Added adc_temperature_sensor to examples

This commit is contained in:
Thomas Otto 2010-03-24 20:36:19 +01:00
parent eb3f45dcdb
commit 384a7e688e
5 changed files with 369 additions and 2 deletions

View File

@ -24,15 +24,21 @@ Q := @
MAKEFLAGS += --no-print-directory MAKEFLAGS += --no-print-directory
endif endif
all: i2c_stts75_sensor all: i2c_stts75_sensor adc_temperature_sensor
i2c_stts75_sensor: i2c_stts75_sensor:
@printf " BUILD examples/other/i2c_stts75_sensor\n" @printf " BUILD examples/other/i2c_stts75_sensor\n"
$(Q)$(MAKE) -C i2c_stts75_sensor $(Q)$(MAKE) -C i2c_stts75_sensor
adc_temperature_sensor:
@printf " BUILD examples/other/adc_temperature_sensor\n"
$(Q)$(MAKE) -C adc_temperature_sensor
clean: clean:
@printf " CLEAN examples/other/i2c_stts75_sensor\n" @printf " CLEAN examples/other/i2c_stts75_sensor\n"
$(Q)$(MAKE) -C i2c_stts75_sensor clean $(Q)$(MAKE) -C i2c_stts75_sensor clean
@printf " CLEAN examples/other/adc_temperature_sensor\n"
$(Q)$(MAKE) -C adc_temperature_sensor clean
.PHONY: i2c_stts75_sensor clean .PHONY: i2c_stts75_sensor adc_temperature_sensor 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 = adc
# 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,47 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This example program sends some characters on USART1.
Afterwards it read out the internal temperature sensor of the stm32 and
sends the value read out from the ADC to the USART1.
The terminal settings for the receiving device/PC are 115200 8n1.
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 i2c_stts75_sensor.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,188 @@
/*
* 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/adc.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 usart_setup(void)
{
/* Enable clocks for GPIO port A (for GPIO_USART1_TX) and USART1. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, USART1EN);
/* Setup GPIO pin GPIO_USART1_TX/GPIO9 on GPIO port A for transmit. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART1_TX);
/* Setup UART parameters. */
usart_set_baudrate(USART1, 115200);
usart_set_databits(USART1, 8);
usart_set_stopbits(USART1, USART_STOPBITS_1);
usart_set_mode(USART1, USART_MODE_TX_RX);
usart_set_parity(USART1, USART_PARITY_NONE);
usart_set_flow_control(USART1, USART_FLOWCONTROL_NONE);
/* Finally enable the USART. */
usart_enable(USART1);
}
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 adc_setup(void)
{
int i;
rcc_peripheral_enable_clock(&RCC_APB2ENR, ADC1EN);
/* make shure it didnt run during config */
adc_off(ADC1);
/* we configure everything for one single conversion */
adc_disable_scan_mode(ADC1);
adc_set_single_conversion_mode(ADC1);
adc_enable_discontinous_mode_regular(ADC1);
adc_disable_external_trigger_regular(ADC1);
adc_set_right_aligned(ADC1);
/* we want read out the temperature sensor so we have to enable it */
adc_enable_temperature_sensor(ADC1);
adc_set_conversion_time_on_all_channels(ADC1, ADC_SMPR_SMP_28DOT5CYC);
adc_on(ADC1);
/* wait for adc starting up*/
for (i = 0; i < 80000; i++); /* Wait (needs -O0 CFLAGS). */
adc_reset_calibration(ADC1);
adc_calibration(ADC1);
}
void my_usart_print_int(u32 usart, int value)
{
s8 i;
u8 nr_digits = 0;
char buffer[25];
if (value < 0) {
usart_send(usart, '-');
value = value * -1;
}
while (value > 0) {
buffer[nr_digits++] = "0123456789"[value%10];
value = value/10;
}
for (i=nr_digits; i>=0; i--) {
usart_send(usart, buffer[i]);
}
}
int main(void)
{
u8 channel_array[16];
u16 temperature;
clock_setup();
gpio_setup();
usart_setup();
adc_setup();
gpio_clear(GPIOB, GPIO7); /* LED1 on */
gpio_set(GPIOB, GPIO6); /* LED2 off */
/* Send a message on USART1. */
usart_send(USART1, 's');
usart_send(USART1, 't');
usart_send(USART1, 'm');
usart_send(USART1, '\r');
usart_send(USART1, '\n');
/* Select the channel we want to convert. 16=temperature_sensor */
channel_array[0] = 16;
adc_set_regular_sequence(ADC1, 1, channel_array);
/* If the ADC_CR2_ON bit is already set -> setting it another time starts the conversion */
adc_on(ADC1);
/* Waiting for end of conversion */
while (!(ADC_SR(ADC1) & ADC_SR_EOC));
temperature = ADC_DR(ADC1);
/* thats actually not the real temparature - you have to compute it like described in the datasheet */
my_usart_print_int(USART1, temperature);
gpio_clear(GPIOB, GPIO6); /* LED2 on */
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