Added timer_interrupt example.

This commit is contained in:
Thomas Otto 2010-03-28 16:11:45 +02:00
parent 9dc0af94b0
commit e50b836ada
5 changed files with 304 additions and 2 deletions

View File

@ -24,7 +24,7 @@ Q := @
MAKEFLAGS += --no-print-directory
endif
all: i2c_stts75_sensor adc_temperature_sensor dma_mem2mem
all: i2c_stts75_sensor adc_temperature_sensor dma_mem2mem timer_interrupt
i2c_stts75_sensor:
@printf " BUILD examples/other/i2c_stts75_sensor\n"
@ -38,6 +38,10 @@ dma_mem2mem:
@printf " BUILD examples/other/dma_mem2mem\n"
$(Q)$(MAKE) -C dma_mem2mem
timer_interrupt:
@printf " BUILD examples/other/timer_interrupt\n"
$(Q)$(MAKE) -C timer_interrupt
clean:
@printf " CLEAN examples/other/i2c_stts75_sensor\n"
$(Q)$(MAKE) -C i2c_stts75_sensor clean
@ -45,6 +49,8 @@ clean:
$(Q)$(MAKE) -C adc_temperature_sensor clean
@printf " CLEAN examples/other/dma_mem2mem\n"
$(Q)$(MAKE) -C dma_mem2mem clean
@printf " CLEAN examples/other/timer_interrupt\n"
$(Q)$(MAKE) -C timer_interrupt clean
.PHONY: i2c_stts75_sensor adc_temperature_sensor dma_mem2mem clean
.PHONY: i2c_stts75_sensor adc_temperature_sensor dma_mem2mem timer_interrupt clean

View File

@ -0,0 +1,95 @@
##
## This file is part of the libopenstm32 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This program is free software: you can redistribute it and/or modify
## it under the terms of the GNU General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This program is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU General Public License for more details.
##
## You should have received a copy of the GNU General Public License
## along with this program. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = timer
# PREFIX ?= arm-none-eabi
PREFIX ?= arm-elf
CC = $(PREFIX)-gcc
LD = $(PREFIX)-ld
OBJCOPY = $(PREFIX)-objcopy
OBJDUMP = $(PREFIX)-objdump
# Uncomment this line if you want to use the installed (not local) library.
#TOOLCHAIN_DIR = `dirname \`which $(CC)\``/..
TOOLCHAIN_DIR = ../../..
CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
-mcpu=cortex-m3 -mthumb
LDSCRIPT = $(BINARY).ld
LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
OBJS = $(BINARY).o
OPENOCD_BASE = /usr
OPENOCD = $(OPENOCD_BASE)/bin/openocd
OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/jtagkey.cfg
OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/target/stm32.cfg
# Be silent per default, but 'make V=1' will show all compiler calls.
ifneq ($(V),1)
Q := @
NULL := 2>/dev/null
endif
all: images
images: $(BINARY)
@printf " OBJCOPY $(BINARY).bin\n"
$(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
@printf " OBJCOPY $(BINARY).hex\n"
$(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
@printf " OBJCOPY $(BINARY).srec\n"
$(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
@printf " OBJDUMP $(BINARY).list\n"
$(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
$(BINARY): $(OBJS) $(LDSCRIPT)
@printf " LD $(subst $(shell pwd)/,,$(@))\n"
$(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
%.o: %.c Makefile
@printf " CC $(subst $(shell pwd)/,,$(@))\n"
$(Q)$(CC) $(CFLAGS) -o $@ -c $<
clean:
@printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
$(Q)rm -f *.o
@printf " CLEAN $(BINARY)\n"
$(Q)rm -f $(BINARY)
@printf " CLEAN $(BINARY).bin\n"
$(Q)rm -f $(BINARY).bin
@printf " CLEAN $(BINARY).hex\n"
$(Q)rm -f $(BINARY).hex
@printf " CLEAN $(BINARY).srec\n"
$(Q)rm -f $(BINARY).srec
@printf " CLEAN $(BINARY).list\n"
$(Q)rm -f $(BINARY).list
flash: images
@printf " FLASH $(BINARY).bin\n"
@# IMPORTANT: Don't use "resume", only "reset" will work correctly!
$(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
-f $(OPENOCD_FLASHER) \
-f $(OPENOCD_BOARD) \
-c "init" -c "reset halt" \
-c "flash write_image erase $(BINARY).hex" \
-c "reset" \
-c "shutdown" $(NULL)
.PHONY: images clean

View File

@ -0,0 +1,43 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This example program blinks a LED on PortB Pin 6. 1 second on / 1 second off.
Blinking is made only with timer interrupt from TIM2 timer.
Building
--------
$ make
Running 'make' on the top-level libopenstm32 directory will automatically
also build this example. Or you can build the library "manually" and
then run 'make' in this directory.
You may want to override the toolchain (e.g., arm-elf or arm-none-eabi):
$ PREFIX=arm-none-eabi make
For a more verbose build you can use
$ make V=1
Flashing
--------
You can flash the generated code using OpenOCD:
$ make flash
Or you can do the same manually via:
$ openocd -f interface/jtagkey-tiny.cfg -f target/stm32.cfg
$ telnet localhost 4444
> reset halt
> flash write_image erase timer.hex
> reset
Replace the "jtagkey-tiny.cfg" with whatever JTAG device you are using, and/or
replace "stm.cfg" with your respective config file.

View File

@ -0,0 +1,127 @@
/*
* This file is part of the libopenstm32 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopenstm32/rcc.h>
#include <libopenstm32/flash.h>
#include <libopenstm32/gpio.h>
#include <libopenstm32/usart.h>
#include <libopenstm32/timer.h>
#include <libopenstm32/nvic.h>
/* Set STM32 to 72 MHz. HSE 16MHz */
void clock_setup(void)
{
/* enable Internal High Speed Oscillator */
rcc_osc_on(HSI);
rcc_wait_for_osc_ready(HSI);
/* Select HSI as SYSCLK source. */
rcc_set_sysclk_source(SW_SYSCLKSEL_HSICLK);
/* enable External High Speed Oscillator 16MHz */
rcc_osc_on(HSE);
rcc_wait_for_osc_ready(HSE);
rcc_set_sysclk_source(SW_SYSCLKSEL_HSECLK);
/* set prescalers for ADC, ABP1, ABP2... make this before touching the PLL */
rcc_set_hpre(HPRE_SYSCLK_NODIV); //prescales the AHB clock from the SYSCLK
rcc_set_adcpre(ADCPRE_PLCK2_DIV6); //prescales the ADC from the APB2 clock; max 14MHz
rcc_set_ppre1(PPRE1_HCLK_DIV2); //prescales the APB1 from the AHB clock; max 36MHz
rcc_set_ppre2(PPRE2_HCLK_NODIV); //prescales the APB2 from the AHB clock; max 72MHz
/* sysclk should run with 72MHz -> 2 Waitstates ; choose 0WS from 0-24MHz, 1WS from 24-48MHz, 2WS from 48-72MHz */
flash_set_ws(FLASH_LATENCY_2WS);
/* Set the PLL multiplication factor to 9. -> 16MHz (external) * 9 (multiplier) / 2 (PLLXTPRE_HSE_CLK_DIV2) = 72MHz */
rcc_set_pll_multiplication_factor(PLLMUL_PLL_CLK_MUL9);
/* Select HSI as PLL source. */
rcc_set_pll_source(PLLSRC_HSE_CLK);
/* divide external frequency by 2 before entering pll (only valid/needed for HSE) */
rcc_set_pllxtpre(PLLXTPRE_HSE_CLK_DIV2);
/* Enable PLL oscillator and wait for it to stabilize. */
rcc_osc_on(PLL);
rcc_wait_for_osc_ready(PLL);
/* Select PLL as SYSCLK source. */
rcc_set_sysclk_source(SW_SYSCLKSEL_PLLCLK);
}
void gpio_setup(void)
{
/* Enable GPIOB clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, IOPBEN);
/* Set GPIO6/7 (in GPIO port B) to 'output push-pull' for the LEDs. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO6);
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO7);
}
void nvic_setup()
{
/* without this the timer intterrupt routing will newer be called */
nvic_enable_irq(NVIC_TIM2_IRQ);
nvic_set_priority(NVIC_TIM2_IRQ, 1);
}
void tim2_isr()
{
/* LED2 on/off */
gpio_toggle(GPIOB, GPIO6);
/* clear interrrupt flag */
TIM_SR(TIM2) &= ~TIM_SR_UIF;
}
int main(void)
{
clock_setup();
gpio_setup();
nvic_setup();
gpio_clear(GPIOB, GPIO7); /* LED1 on */
gpio_set(GPIOB, GPIO6); /* LED2 off */
rcc_peripheral_enable_clock(&RCC_APB1ENR, TIM2EN);
/* the goal is to let the LED2 glow for a second and then be off for a second */
/* Set timer start value */
TIM_CNT(TIM2) = 1;
/* Set timer prescaler. 72MHz/1440 => 50000 counts per second */
TIM_PSC(TIM2) = 1440;
/* End timer value. If this value is reached an interrupt is generated */
TIM_ARR(TIM2) = 50000;
/* Update interrupt enable */
TIM_DIER(TIM2) |= TIM_DIER_UIE;
/* Start timer */
TIM_CR1(TIM2) |= TIM_CR1_CEN;
while(1); /* Halt. */
return 0;
}

View File

@ -0,0 +1,31 @@
/*
* This file is part of the libopenstm32 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/* Linker script for an STM32F103RBT6 board (128K flash, 20K RAM). */
/* Define memory regions. */
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
}
/* Include the common ld script from libopenstm32. */
INCLUDE libopenstm32.ld