mirror of
https://github.com/RIOT-OS/RIOT.git
synced 2025-01-18 12:52:44 +01:00
cpu: initial import of stm32f1
This commit is contained in:
parent
78041ea15d
commit
37611db41c
5
boards/iot-lab_M3/Makefile
Normal file
5
boards/iot-lab_M3/Makefile
Normal file
@ -0,0 +1,5 @@
|
||||
MODULE =$(BOARD)_base
|
||||
|
||||
DIRS = drivers
|
||||
|
||||
include $(RIOTBASE)/Makefile.base
|
3
boards/iot-lab_M3/Makefile.dep
Normal file
3
boards/iot-lab_M3/Makefile.dep
Normal file
@ -0,0 +1,3 @@
|
||||
ifneq (,$(findstring at86rf231,$(USEMODULE)))
|
||||
USEMODULE += at86rf231
|
||||
endif
|
50
boards/iot-lab_M3/Makefile.include
Normal file
50
boards/iot-lab_M3/Makefile.include
Normal file
@ -0,0 +1,50 @@
|
||||
## the cpu to build for
|
||||
export CPU = stm32f1
|
||||
export CPU_MODEL = stm32f103re
|
||||
|
||||
# set the default port
|
||||
export PORT ?= /dev/ttyUSB2
|
||||
|
||||
# define tools used for building the project
|
||||
export PREFIX = arm-none-eabi-
|
||||
export CC = $(PREFIX)gcc
|
||||
export AR = $(PREFIX)ar
|
||||
export AS = $(PREFIX)as
|
||||
export LINK = $(PREFIX)gcc
|
||||
export SIZE = $(PREFIX)size
|
||||
export OBJCOPY = $(PREFIX)objcopy
|
||||
export TERMPROG = $(RIOTBASE)/dist/tools/pyterm/pyterm.py
|
||||
export FLASHER = $(RIOTBOARD)/$(BOARD)/dist/flash.sh
|
||||
export DEBUGGER = $(RIOTBOARD)/$(BOARD)/dist/debug.sh
|
||||
|
||||
# define build specific options
|
||||
export CPU_USAGE = -mcpu=cortex-m3
|
||||
export FPU_USAGE =
|
||||
export CFLAGS += -ggdb -g3 -std=gnu99 -Os -Wall -Wstrict-prototypes $(CPU_USAGE) $(FPU_USAGE) -mlittle-endian -mthumb -mthumb-interwork -nostartfiles
|
||||
export CFLAGS += -flto -ffunction-sections -fdata-sections -fno-builtin
|
||||
export ASFLAGS += -ggdb -g3 $(CPU_USAGE) $(FPU_USAGE) -mlittle-endian
|
||||
export LINKFLAGS += -ggdb -g3 -std=gnu99 $(CPU_USAGE) $(FPU_USAGE) -mlittle-endian -static -lgcc -mthumb -mthumb-interwork -nostartfiles
|
||||
# $(LINKERSCRIPT) is specified in cpu/Makefile.include
|
||||
export LINKFLAGS += -T$(LINKERSCRIPT)
|
||||
export OFLAGS = -O ihex
|
||||
export FFLAGS = $(BINDIR)/$(APPLICATION).hex
|
||||
export DEBUGGER_FLAGS = $(BINDIR)/$(APPLICATION).elf
|
||||
|
||||
# use the nano-specs of the NewLib when available
|
||||
ifeq ($(shell $(LINK) -specs=nano.specs -E - 2>/dev/null >/dev/null </dev/null ; echo $$?),0)
|
||||
export LINKFLAGS += -specs=nano.specs -lc -lnosys
|
||||
endif
|
||||
|
||||
# export board specific includes to the global includes-listing
|
||||
export INCLUDES += -I$(RIOTBOARD)/$(BOARD)/include/
|
||||
|
||||
|
||||
|
||||
# TODO -> move this to the appropriate Makefile.dep!!!
|
||||
ifneq (,$(filter defaulttransceiver,$(USEMODULE)))
|
||||
USEMODULE += at86rf231
|
||||
USEMODULE += transceiver
|
||||
endif
|
||||
|
||||
# TODO -> is this needed?
|
||||
TERM = miniterm.py -b 115200
|
65
boards/iot-lab_M3/board.c
Normal file
65
boards/iot-lab_M3/board.c
Normal file
@ -0,0 +1,65 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License v2.1. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup board_iot-lab_M3
|
||||
* @{
|
||||
*
|
||||
* @file board.c
|
||||
* @brief Board specific implementations for the iot-lab_M3 board
|
||||
*
|
||||
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include "cmsis_system.h"
|
||||
#include "board.h"
|
||||
#include "cpu.h"
|
||||
|
||||
|
||||
static void leds_init(void);
|
||||
|
||||
|
||||
void board_init(void)
|
||||
{
|
||||
/* initialize core clocks via CMSIS function provided by ST */
|
||||
SystemInit();
|
||||
|
||||
/* initialize the CPU */
|
||||
cpu_init();
|
||||
|
||||
/* initialize the boards LEDs */
|
||||
leds_init();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initialize the boards on-board LEDs
|
||||
*
|
||||
* The LEDs initialization is hard-coded in this function. As the LED is soldered
|
||||
* onto the board it is fixed to its CPU pins.
|
||||
*
|
||||
* The LEDs are connected to the following pin:
|
||||
* - Green: PB5
|
||||
* - Orange: PC10
|
||||
* - Red: PD2
|
||||
*/
|
||||
static void leds_init(void)
|
||||
{
|
||||
/* green pin */
|
||||
RCC->APB2ENR |= RCC_APB2ENR_IOPBEN;
|
||||
GPIOB->CRL = (0x3 << (5*4));
|
||||
|
||||
/* orange pin */
|
||||
RCC->APB2ENR |= RCC_APB2ENR_IOPCEN;
|
||||
GPIOC->CRH = (0x3 << ((10-8)*4));
|
||||
|
||||
/* red pin */
|
||||
RCC->APB2ENR |= RCC_APB2ENR_IOPDEN;
|
||||
GPIOD->CRL = (0x3 << (2*4));
|
||||
}
|
1067
boards/iot-lab_M3/board_init.c
Normal file
1067
boards/iot-lab_M3/board_init.c
Normal file
File diff suppressed because it is too large
Load Diff
13
boards/iot-lab_M3/dist/agilefox_jtag.cfg
vendored
Normal file
13
boards/iot-lab_M3/dist/agilefox_jtag.cfg
vendored
Normal file
@ -0,0 +1,13 @@
|
||||
jtag_khz 1000
|
||||
|
||||
# comstick ftdi device
|
||||
interface ft2232
|
||||
ft2232_layout "usbjtag"
|
||||
ft2232_device_desc "HiKoB FOX JTAG"
|
||||
ft2232_vid_pid 0x0403 0x6010
|
||||
|
||||
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
|
17
boards/iot-lab_M3/dist/debug.sh
vendored
Executable file
17
boards/iot-lab_M3/dist/debug.sh
vendored
Executable file
@ -0,0 +1,17 @@
|
||||
#!/bin/bash
|
||||
|
||||
if [ -L "$0" ]; then
|
||||
FILE=$(readlink "$0")
|
||||
else
|
||||
FILE="$0"
|
||||
fi
|
||||
|
||||
BIN_FOLDER=$(dirname "${FILE}")
|
||||
|
||||
openocd -f "${BIN_FOLDER}/${BOARD}_jtag.cfg" \
|
||||
-f "target/stm32f1x.cfg" \
|
||||
-c "tcl_port 6333"
|
||||
-c "telnet_port 4444"
|
||||
-c "init" \
|
||||
-c "targets" \
|
||||
-c "reset halt"
|
20
boards/iot-lab_M3/dist/flash.sh
vendored
Executable file
20
boards/iot-lab_M3/dist/flash.sh
vendored
Executable file
@ -0,0 +1,20 @@
|
||||
#!/bin/bash
|
||||
|
||||
if [ -L "$0" ]; then
|
||||
FILE=$(readlink "$0")
|
||||
else
|
||||
FILE="$0"
|
||||
fi
|
||||
|
||||
BIN_FOLDER=$(dirname "${FILE}")
|
||||
|
||||
openocd -f "${BIN_FOLDER}/${BOARD}_jtag.cfg" \
|
||||
-f "target/stm32f1x.cfg" \
|
||||
-c "init" \
|
||||
-c "targets" \
|
||||
-c "reset halt" \
|
||||
-c "reset init" \
|
||||
-c "flash write_image erase $1" \
|
||||
-c "verify_image $1" \
|
||||
-c "reset run"\
|
||||
-c "shutdown"
|
13
boards/iot-lab_M3/dist/iot-lab_M3_jtag.cfg
vendored
Normal file
13
boards/iot-lab_M3/dist/iot-lab_M3_jtag.cfg
vendored
Normal file
@ -0,0 +1,13 @@
|
||||
jtag_khz 1000
|
||||
|
||||
# comstick ftdi device
|
||||
interface ft2232
|
||||
ft2232_layout "usbjtag"
|
||||
ft2232_device_desc "FITECO M3"
|
||||
ft2232_vid_pid 0x0403 0x6010
|
||||
|
||||
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
|
15
boards/iot-lab_M3/dist/reset.sh
vendored
Executable file
15
boards/iot-lab_M3/dist/reset.sh
vendored
Executable file
@ -0,0 +1,15 @@
|
||||
#!/bin/bash
|
||||
|
||||
if [ -L "$0" ]; then
|
||||
FILE=$(readlink "$0")
|
||||
else
|
||||
FILE="$0"
|
||||
fi
|
||||
|
||||
BIN_FOLDER=$(dirname "${FILE}")
|
||||
|
||||
openocd -f "${BIN_FOLDER}/iot-lab_m3_jtag.cfg" \
|
||||
-f "target/stm32f1x.cfg" \
|
||||
-c "init" \
|
||||
-c "reset run" \
|
||||
-c "shutdown"
|
34
boards/iot-lab_M3/drivers/Makefile
Normal file
34
boards/iot-lab_M3/drivers/Makefile
Normal file
@ -0,0 +1,34 @@
|
||||
SRC = $(wildcard *.c)
|
||||
#BINDIR = $(RIOTBOARD)/$(BOARD)/bin/
|
||||
OBJ = $(SRC:%.c=$(BINDIR)%.o)
|
||||
DEP = $(SRC:%.c=$(BINDIR)%.d)
|
||||
|
||||
INCLUDES += -I../include
|
||||
INCLUDES += -I$(RIOTCPU)/STM32F10x_StdPeriph_Lib_V3.5.0/Libraries/CMSIS/Include
|
||||
INCLUDES += -I$(RIOTCPU)/STM32F10x_StdPeriph_Lib_V3.5.0/Libraries/CMSIS/CM3/DeviceSupport/ST/STM32F10x
|
||||
INCLUDES += -I$(RIOTCPU)/STM32F10x_StdPeriph_Lib_V3.5.0/Libraries/STM32F10x_StdPeriph_Driver/inc
|
||||
INCLUDES += -I$(RIOTCPU)/stm32f103rey6/include
|
||||
|
||||
INCLUDES += -I$(RIOTBASE)/drivers/at86rf231/include
|
||||
INCLUDES += -I$(RIOTBASE)/sys/include
|
||||
INCLUDES += -I$(RIOTBASE)/sys/net/include
|
||||
|
||||
|
||||
.PHONY: $(BINDIR)iot-lab_M3_drivers.a
|
||||
|
||||
$(BINDIR)iot-lab_M3_drivers.a: $(OBJ)
|
||||
$(AD) $(AR) rcs $(BINDIR)iot-lab_M3_base.a $(OBJ)
|
||||
|
||||
# pull in dependency info for *existing* .o files
|
||||
-include $(OBJ:.o=.d)
|
||||
|
||||
# compile and generate dependency info
|
||||
$(BINDIR)%.o: %.c
|
||||
$(AD) $(CC) $(CFLAGS) $(INCLUDES) $(BOARDINCLUDE) $(APPLICATIONINCLUDE) $(CPUINCLUDE) -c $*.c -o $(BINDIR)$*.o
|
||||
$(AD) $(CC) $(CFLAGS) $(INCLUDES) $(BOARDINCLUDE) $(APPLICATIONINCLUDE) $(CPUINCLUDE) -MM $*.c > $(BINDIR)$*.d
|
||||
@printf "$(BINDIR)" | cat - $(BINDIR)$*.d > /tmp/fw_out && mv /tmp/fw_out $(BINDIR)$*.d
|
||||
|
||||
# remove compilation products
|
||||
|
||||
clean:
|
||||
rm -f $(OBJ) $(DEP)
|
212
boards/iot-lab_M3/drivers/at86rf231_driver.c
Normal file
212
boards/iot-lab_M3/drivers/at86rf231_driver.c
Normal file
@ -0,0 +1,212 @@
|
||||
#include <stdio.h>
|
||||
#include <stddef.h>
|
||||
|
||||
#include "cpu.h"
|
||||
#include "sched.h"
|
||||
#include "vtimer.h"
|
||||
|
||||
#include "periph/gpio.h"
|
||||
#include "periph_conf.h"
|
||||
#include "board.h"
|
||||
|
||||
#include "at86rf231.h"
|
||||
#include "at86rf231_spi.h"
|
||||
#include "at86rf231_spi1.h"
|
||||
|
||||
extern volatile unsigned int sched_context_switch_request;
|
||||
|
||||
/*
|
||||
SPI1
|
||||
SCLK : PA5
|
||||
MISO : PA6
|
||||
MOSI : PA7
|
||||
CS : PA4
|
||||
|
||||
GPIO
|
||||
IRQ0 : PC4 : Frame buff empty indicator
|
||||
DIG2 : ? : RX Frame Time stamping XXX : NOT USED
|
||||
Reset : PC1 : active low, enable chip
|
||||
SLEEP : PA2 : control sleep, tx & rx state
|
||||
*/
|
||||
|
||||
inline static void RESET_CLR(void)
|
||||
{
|
||||
GPIOC->BRR = 1 << 1;
|
||||
}
|
||||
inline static void RESET_SET(void)
|
||||
{
|
||||
GPIOC->BSRR = 1 << 1;
|
||||
}
|
||||
inline static void CSn_SET(void)
|
||||
{
|
||||
GPIOA->BSRR = 1 << 4;
|
||||
}
|
||||
inline static void CSn_CLR(void)
|
||||
{
|
||||
GPIOA->BRR = 1 << 4;
|
||||
}
|
||||
inline static void SLEEP_CLR(void)
|
||||
{
|
||||
GPIOA->BRR = 1 << 2;
|
||||
}
|
||||
|
||||
uint8_t at86rf231_get_status(void)
|
||||
{
|
||||
return at86rf231_reg_read(AT86RF231_REG__TRX_STATUS)
|
||||
& AT86RF231_TRX_STATUS_MASK__TRX_STATUS;
|
||||
}
|
||||
|
||||
|
||||
extern void at86rf231_rx_irq(void);
|
||||
static
|
||||
void enable_exti_interrupt(void)
|
||||
{
|
||||
// EXTI_InitTypeDef EXTI_InitStructure;
|
||||
|
||||
// EXTI_InitStructure.EXTI_Line = EXTI_Line4;
|
||||
// EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
|
||||
// EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
|
||||
// EXTI_InitStructure.EXTI_LineCmd = ENABLE;
|
||||
// EXTI_Init(&EXTI_InitStructure);
|
||||
gpio_init_int(GPIO_6, GPIO_NOPULL, GPIO_RISING, at86rf231_rx_irq);
|
||||
}
|
||||
static
|
||||
void disable_exti_interrupt(void)
|
||||
{
|
||||
// EXTI_InitTypeDef EXTI_InitStructure;
|
||||
|
||||
// EXTI_InitStructure.EXTI_Line = EXTI_Line4;
|
||||
// EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
|
||||
// EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
|
||||
// EXTI_InitStructure.EXTI_LineCmd = DISABLE;
|
||||
// EXTI_Init(&EXTI_InitStructure);
|
||||
#warning not implemented yet
|
||||
}
|
||||
|
||||
|
||||
void at86rf231_gpio_spi_interrupts_init(void)
|
||||
{
|
||||
/* SPI1 init */
|
||||
at86rf231_spi1_init();
|
||||
|
||||
/* IRQ0 : PC4, INPUT and IRQ */
|
||||
// RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE);
|
||||
|
||||
// GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;
|
||||
// GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
|
||||
// GPIO_Init(GPIOC, &GPIO_InitStructure);
|
||||
gpio_init_in(GPIO_4, GPIO_NOPULL);
|
||||
|
||||
/* Enable AFIO clock */
|
||||
// RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
|
||||
|
||||
/* Connect EXTI4 Line to PC4 pin */
|
||||
// GPIO_EXTILineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource4);
|
||||
|
||||
/* Configure EXTI4 line */
|
||||
enable_exti_interrupt();
|
||||
|
||||
/* Enable and set EXTI4 Interrupt to the lowest priority */
|
||||
// NVIC_InitStructure.NVIC_IRQChannel = EXTI4_IRQn;
|
||||
// NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0x01;
|
||||
// NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0x0F;
|
||||
// NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
// NVIC_Init(&NVIC_InitStructure);
|
||||
|
||||
/* Init GPIOs */
|
||||
|
||||
/* CS & SLEEP */
|
||||
// RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
|
||||
|
||||
// GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2 | GPIO_Pin_4;
|
||||
// GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
// GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
|
||||
// GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
gpio_init_out(GPIO_2, GPIO_NOPULL);
|
||||
gpio_init_out(GPIO_4, GPIO_NOPULL);
|
||||
|
||||
/* RESET */
|
||||
// RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE);
|
||||
|
||||
// GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1;
|
||||
// GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
// GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
|
||||
// GPIO_Init(GPIOC, &GPIO_InitStructure);
|
||||
gpio_init_out(GPIO_1, GPIO_NOPULL);
|
||||
}
|
||||
|
||||
void at86rf231_reset(void)
|
||||
{
|
||||
/* force reset */
|
||||
RESET_CLR();
|
||||
CSn_SET();
|
||||
SLEEP_CLR();
|
||||
|
||||
vtimer_usleep(AT86RF231_TIMING__RESET);
|
||||
|
||||
RESET_SET();
|
||||
|
||||
/* Wait until TRX_OFF is entered */
|
||||
vtimer_usleep(AT86RF231_TIMING__RESET_TO_TRX_OFF);
|
||||
|
||||
/* Send a FORCE TRX OFF command */
|
||||
at86rf231_reg_write(AT86RF231_REG__TRX_STATE, AT86RF231_TRX_STATE__FORCE_TRX_OFF);
|
||||
|
||||
/* Wait until TRX_OFF state is entered from P_ON */
|
||||
vtimer_usleep(AT86RF231_TIMING__SLEEP_TO_TRX_OFF);
|
||||
|
||||
/* busy wait for TRX_OFF state */
|
||||
uint8_t status;
|
||||
uint8_t max_wait = 100; // TODO : move elsewhere, this is in 10us
|
||||
|
||||
do {
|
||||
status = at86rf231_get_status();
|
||||
|
||||
vtimer_usleep(10);
|
||||
|
||||
if (!--max_wait) {
|
||||
printf("at86rf231 : ERROR : could not enter TRX_OFF mode");
|
||||
break;
|
||||
}
|
||||
}
|
||||
while ((status & AT86RF231_TRX_STATUS_MASK__TRX_STATUS) != AT86RF231_TRX_STATUS__TRX_OFF);
|
||||
}
|
||||
|
||||
void at86rf231_spi_select(void)
|
||||
{
|
||||
CSn_CLR();
|
||||
}
|
||||
void at86rf231_spi_unselect(void)
|
||||
{
|
||||
CSn_SET();
|
||||
}
|
||||
|
||||
void at86rf231_enable_interrupts(void)
|
||||
{
|
||||
enable_exti_interrupt();
|
||||
}
|
||||
void at86rf231_disable_interrupts(void)
|
||||
{
|
||||
disable_exti_interrupt();
|
||||
}
|
||||
|
||||
// extern void at86rf231_rx_irq(void);
|
||||
// __attribute__((naked))
|
||||
// void EXTI4_IRQHandler(void)
|
||||
// {
|
||||
// save_context();
|
||||
|
||||
// if (EXTI_GetITStatus(EXTI_Line4) != RESET) {
|
||||
// /* IRQ_3 (TRX_END), read Frame Buffer */
|
||||
// EXTI_ClearITPendingBit(EXTI_Line4);
|
||||
|
||||
// at86rf231_rx_irq();
|
||||
|
||||
// if (sched_context_switch_request) {
|
||||
// /* scheduler */
|
||||
// thread_yield();
|
||||
// }
|
||||
// }
|
||||
|
||||
// restore_context();
|
||||
// }
|
70
boards/iot-lab_M3/drivers/at86rf231_spi1.c
Normal file
70
boards/iot-lab_M3/drivers/at86rf231_spi1.c
Normal file
@ -0,0 +1,70 @@
|
||||
#include <stdio.h>
|
||||
#include <stddef.h>
|
||||
|
||||
#include "cpu.h"
|
||||
#include "periph/gpio.h"
|
||||
#include "spi.h"
|
||||
#include "periph_conf.h"
|
||||
#include "at86rf231_spi1.h"
|
||||
|
||||
void at86rf231_spi1_init(void)
|
||||
{
|
||||
// SPI_InitTypeDef SPI_InitStructure;
|
||||
/* RCC */
|
||||
// RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
|
||||
// RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE);
|
||||
// RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE);
|
||||
// RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;
|
||||
|
||||
/* GPIO */
|
||||
|
||||
/* Configure SPI MASTER pins */
|
||||
// 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);
|
||||
GPIOA->CRL &= ~(0xf << (5 * 4));
|
||||
GPIOA->CRL |= (0xB << (5 * 4));
|
||||
GPIOA->CRL &= ~(0xf << (7 * 4));
|
||||
GPIOA->CRL |= (0xB << (7 * 4));
|
||||
|
||||
// GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
|
||||
// GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
|
||||
// GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
// GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
gpio_init_in(GPIO_6, GPIO_NOPULL);
|
||||
|
||||
/* SPI
|
||||
* NOTE: APB2 is 72MHz, prescaler 16 => SPI @ 4.5 MHz, radio spi max is 7.5MHz
|
||||
* Clock idle low, rising edge
|
||||
*/
|
||||
// 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_1Edge;
|
||||
// SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
|
||||
// SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_16;
|
||||
// SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
|
||||
// SPI_InitStructure.SPI_CRCPolynomial = 7;
|
||||
//SPI_Init(SPI1, &SPI_InitStructure);
|
||||
#warning implement spi
|
||||
/* Enable interrupt */
|
||||
//SPI_I2S_ITConfig(SPI1, SPI_I2S_IT_TXE, ENABLE);
|
||||
/* Enable SPI */
|
||||
// SPI_Cmd(SPI1, ENABLE);
|
||||
}
|
||||
|
||||
uint8_t at86rf231_spi_transfer_byte(uint8_t byte)
|
||||
{
|
||||
char ret;
|
||||
|
||||
spi_transfer_byte(SPI_0, byte?byte:0, byte?0:&ret );
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
void at86rf231_spi_transfer(const uint8_t *data_out, uint8_t *data_in, uint16_t length)
|
||||
{
|
||||
spi_transfer_bytes(SPI_0, (char*)data_out, (char*)data_in, length);
|
||||
}
|
22
boards/iot-lab_M3/drivers/iot-lab_M3-uart.c
Normal file
22
boards/iot-lab_M3/drivers/iot-lab_M3-uart.c
Normal file
@ -0,0 +1,22 @@
|
||||
/**
|
||||
* Copyright (C) 2014 Oliver Hahm <oliver.hahm@inria.fr>
|
||||
*
|
||||
* This file subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*
|
||||
* @file iot-lab_M3-uart.c
|
||||
* @author Oliver Hahm <oliver.hahm@inria.fr>
|
||||
*/
|
||||
|
||||
#include "stm32f10x.h"
|
||||
#include "periph/uart.h"
|
||||
|
||||
int fw_puts(char *astring, int length)
|
||||
{
|
||||
for (int i = 0; i < length; i++) {
|
||||
uart_write_blocking(UART_0, astring[i]);
|
||||
}
|
||||
|
||||
return length;
|
||||
}
|
6
boards/iot-lab_M3/include/at86rf231_spi1.h
Normal file
6
boards/iot-lab_M3/include/at86rf231_spi1.h
Normal file
@ -0,0 +1,6 @@
|
||||
#ifndef AT86RF231_SPI1_H_
|
||||
#define AT86RF231_SPI1_H_
|
||||
|
||||
void at86rf231_spi1_init(void);
|
||||
|
||||
#endif
|
89
boards/iot-lab_M3/include/board.h
Normal file
89
boards/iot-lab_M3/include/board.h
Normal file
@ -0,0 +1,89 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Thomas Eichinger <thomas.eichinger@fu-berlin.de>
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @defgroup board_iot-lab_M3 iot-lab_M3
|
||||
* @ingroup boards
|
||||
* @brief Board specific files for the iot-lab_M3 board.
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Board specific definitions for the iot-lab_M3 board.
|
||||
*
|
||||
* @author Alaeddine Weslati <alaeddine.weslati@inria.fr>
|
||||
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
|
||||
* @author Oliver Hahm <oliver.hahm@inria.fr>
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
*/
|
||||
|
||||
#ifndef BOARD_H_
|
||||
#define BOARD_H_
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "cpu.h"
|
||||
|
||||
/**
|
||||
* Define the nominal CPU core clock in this board
|
||||
*/
|
||||
#define F_CPU (72000000UL)
|
||||
|
||||
/**
|
||||
* @name Define the UART to be used as stdio and its baudrate
|
||||
* @{
|
||||
*/
|
||||
#define STDIO UART_0
|
||||
#define STDIO_BAUDRATE (115200)
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* Assign the hardware timer
|
||||
*/
|
||||
#define HW_TIMER TIMER_0
|
||||
|
||||
/**
|
||||
* @name LED pin definitions
|
||||
* @{
|
||||
*/
|
||||
#define LED_RED_PORT (GPIOD->ODR)
|
||||
#define LED_RED_PIN (1<<2)
|
||||
#define LED_GREEN_PORT (GPIOB->ODR)
|
||||
#define LED_GREEN_PIN (1<<5)
|
||||
#define LED_ORANGE_PORT (GPIOC->ODR)
|
||||
#define LED_ORANGE_PIN (1<<10)
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @name Macros for controlling the on-board LEDs.
|
||||
* @{
|
||||
*/
|
||||
#define LED_RED_ON (LED_RED_PORT &= ~LED_RED_PIN)
|
||||
#define LED_RED_OFF (LED_RED_PORT |= LED_RED_PIN)
|
||||
#define LED_RED_TOGGLE (LED_RED_PORT ^= LED_RED_PIN)
|
||||
|
||||
#define LED_GREEN_ON (LED_GREEN_PORT &= ~LED_GREEN_PIN)
|
||||
#define LED_GREEN_OFF (LED_GREEN_PORT |= LED_GREEN_PIN)
|
||||
#define LED_GREEN_TOGGLE (LED_GREEN_PORT ^= LED_GREEN_PIN)
|
||||
|
||||
#define LED_ORANGE_ON (LED_ORANGE_PORT &= ~LED_ORANGE_PIN)
|
||||
#define LED_ORANGE_OFF (LED_ORANGE_PORT |= LED_ORANGE_PIN)
|
||||
#define LED_ORANGE_TOGGLE (LED_ORANGE_PORT ^= LED_ORANGE_PIN)
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* Define the type for the radio packet length for the transceiver
|
||||
*/
|
||||
typedef uint8_t radio_packet_length_t;
|
||||
|
||||
/**
|
||||
* @brief Initialize board specific hardware, including clock, LEDs and std-IO
|
||||
*/
|
||||
void board_init(void);
|
||||
|
||||
#endif /* BOARD_H_ */
|
||||
/** @} */
|
207
boards/iot-lab_M3/include/periph_conf.h
Normal file
207
boards/iot-lab_M3/include/periph_conf.h
Normal file
@ -0,0 +1,207 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup board_iot-lab_M3
|
||||
* @{
|
||||
*
|
||||
* @file periph_conf.h
|
||||
* @brief Peripheral MCU configuration for the iot-lab_M3 board
|
||||
*
|
||||
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
|
||||
*/
|
||||
#ifndef __PERIPH_CONF_H
|
||||
#define __PERIPH_CONF_H
|
||||
|
||||
/**
|
||||
* @brief Timer configuration
|
||||
* @{
|
||||
*/
|
||||
#define TIMER_NUMOF (2U)
|
||||
#define TIMER_0_EN 1
|
||||
#define TIMER_1_EN 2
|
||||
|
||||
/* Timer 0 configuration */
|
||||
#define TIMER_0_DEV TIM2
|
||||
#define TIMER_0_CHANNELS 4
|
||||
#define TIMER_0_PRESCALER (36000U)
|
||||
#define TIMER_0_MAX_VALUE (0xffff)
|
||||
#define TIMER_0_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_TIM2EN)
|
||||
#define TIMER_0_ISR isr_tim2
|
||||
#define TIMER_0_IRQ_CHAN TIM2_IRQn
|
||||
#define TIMER_0_IRQ_PRIO 1
|
||||
|
||||
/* Timer 1 configuration */
|
||||
#define TIMER_1_DEV TIM3
|
||||
#define TIMER_1_CHANNELS 2
|
||||
#define TIMER_1_PRESCALER (36000U)
|
||||
#define TIMER_1_MAX_VALUE (0xffff)
|
||||
#define TIMER_1_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_TIM3EN)
|
||||
#define TIMER_1_ISR isr_tim3
|
||||
#define TIMER_1_IRQ_CHAN TIM3_IRQn
|
||||
#define TIMER_1_IRQ_PRIO 1
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @brief UART configuration
|
||||
*/
|
||||
#define UART_NUMOF (2U)
|
||||
#define UART_0_EN 1
|
||||
#define UART_1_EN 0
|
||||
#define UART_IRQ_PRIO 1
|
||||
|
||||
/* UART 0 device configuration */
|
||||
#define UART_0_DEV USART1
|
||||
#define UART_0_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_USART1EN)
|
||||
#define UART_0_IRQ USART1_IRQn
|
||||
#define UART_0_ISR isr_usart1
|
||||
/* UART 0 pin configuration */
|
||||
#define UART_0_PORT GPIOA
|
||||
#define UART_0_PORT_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPAEN)
|
||||
#define UART_0_RX_PIN 10
|
||||
#define UART_0_TX_PIN 9
|
||||
#define UART_0_AF 0
|
||||
|
||||
/* UART 1 device configuration */
|
||||
#define UART_1_DEV USART2
|
||||
#define UART_1_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_USART2EN)
|
||||
#define UART_1_IRQ USART2_IRQn
|
||||
#define UART_1_ISR isr_usart2
|
||||
/* UART 1 pin configuration */
|
||||
#define UART_1_PORT GPIOA
|
||||
#define UART_1_PORT_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPAEN)
|
||||
#define UART_1_RX_PIN 3
|
||||
#define UART_1_TX_PIN 2
|
||||
#define UART_1_AF 1
|
||||
|
||||
/**
|
||||
* @brief GPIO configuration
|
||||
*/
|
||||
#define GPIO_NUMOF 12
|
||||
#define GPIO_0_EN 1
|
||||
#define GPIO_1_EN 1
|
||||
#define GPIO_2_EN 1
|
||||
#define GPIO_3_EN 1
|
||||
#define GPIO_4_EN 1
|
||||
#define GPIO_5_EN 1
|
||||
#define GPIO_6_EN 1
|
||||
#define GPIO_7_EN 1
|
||||
#define GPIO_8_EN 1
|
||||
#define GPIO_9_EN 1
|
||||
#define GPIO_10_EN 1
|
||||
#define GPIO_11_EN 1
|
||||
#define GPIO_IRQ_PRIO 1
|
||||
|
||||
/* IRQ config */
|
||||
#define GPIO_IRQ_0 GPIO_0
|
||||
#define GPIO_IRQ_1 GPIO_1
|
||||
#define GPIO_IRQ_2 GPIO_0 /* not configured */
|
||||
#define GPIO_IRQ_3 GPIO_0 /* not configured */
|
||||
#define GPIO_IRQ_4 GPIO_2
|
||||
#define GPIO_IRQ_5 GPIO_3
|
||||
#define GPIO_IRQ_6 GPIO_4
|
||||
#define GPIO_IRQ_7 GPIO_5
|
||||
#define GPIO_IRQ_8 GPIO_0 /* not configured */
|
||||
#define GPIO_IRQ_9 GPIO_0 /* not configured */
|
||||
#define GPIO_IRQ_10 GPIO_6
|
||||
#define GPIO_IRQ_11 GPIO_7
|
||||
#define GPIO_IRQ_12 GPIO_8
|
||||
#define GPIO_IRQ_13 GPIO_9
|
||||
#define GPIO_IRQ_14 GPIO_10
|
||||
#define GPIO_IRQ_15 GPIO_11
|
||||
|
||||
/* GPIO channel 0 config */
|
||||
#define GPIO_0_PORT GPIOA /* Used for user button 1 */
|
||||
#define GPIO_0_PIN 0
|
||||
#define GPIO_0_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPAEN)
|
||||
#define GPIO_0_EXTI_CFG() (AFIO->EXTICR[GPIO_0_PIN>>0x02] |= (((uint32_t)0x00) << (0x04 * (GPIO_0_PIN & (uint8_t)0x03))))
|
||||
#define GPIO_0_IRQ EXTI0_IRQn
|
||||
/* GPIO channel 1 config */
|
||||
#define GPIO_1_PORT GPIOA
|
||||
#define GPIO_1_PIN 1
|
||||
#define GPIO_1_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPAEN)
|
||||
#define GPIO_1_EXTI_CFG() (AFIO->EXTICR[GPIO_1_PIN>>0x02] |= (((uint32_t)0x00) << (0x04 * (GPIO_1_PIN & (uint8_t)0x03))))
|
||||
#define GPIO_1_IRQ EXTI0_IRQn
|
||||
/* GPIO channel 2 config */
|
||||
#define GPIO_2_PORT GPIOF
|
||||
#define GPIO_2_PIN 4
|
||||
#define GPIO_2_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPFEN)
|
||||
#define GPIO_2_EXTI_CFG() (AFIO->EXTICR[GPIO_2_PIN>>0x02] |= (((uint32_t)0x05) << (0x04 * (GPIO_2_PIN & (uint8_t)0x03))))
|
||||
#define GPIO_2_IRQ EXTI4_IRQn
|
||||
/* GPIO channel 3 config */
|
||||
#define GPIO_3_PORT GPIOF
|
||||
#define GPIO_3_PIN 5
|
||||
#define GPIO_3_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPFEN)
|
||||
#define GPIO_3_EXTI_CFG() (AFIO->EXTICR[GPIO_3_PIN>>0x02] |= (((uint32_t)0x05) << (0x04 * (GPIO_3_PIN & (uint8_t)0x03))))
|
||||
#define GPIO_3_IRQ EXTI4_IRQn
|
||||
/* GPIO channel 4 config */
|
||||
#define GPIO_4_PORT GPIOF
|
||||
#define GPIO_4_PIN 6
|
||||
#define GPIO_4_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPFEN)
|
||||
#define GPIO_4_EXTI_CFG() (AFIO->EXTICR[GPIO_3_PIN>>0x02] |= (((uint32_t)0x05) << (0x04 * (GPIO_3_PIN & (uint8_t)0x03))))
|
||||
#define GPIO_4_IRQ EXTI4_IRQn
|
||||
/* GPIO channel 5 config */
|
||||
#define GPIO_5_PORT GPIOF
|
||||
#define GPIO_5_PIN 7
|
||||
#define GPIO_5_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPFEN)
|
||||
#define GPIO_5_EXTI_CFG() (AFIO->EXTICR[GPIO_5_PIN>>0x02] |= (((uint32_t)0x05) << (0x04 * (GPIO_5_PIN & (uint8_t)0x03))))
|
||||
#define GPIO_5_IRQ EXTI4_IRQn
|
||||
/* GPIO channel 6 config */
|
||||
#define GPIO_6_PORT GPIOC
|
||||
#define GPIO_6_PIN 4
|
||||
#define GPIO_6_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPCEN)
|
||||
#define GPIO_6_EXTI_CFG() (AFIO->EXTICR[GPIO_6_PIN>>0x02] |= (((uint32_t)0x02) << (0x04 * (GPIO_6_PIN & (uint8_t)0x03))))
|
||||
#define GPIO_6_IRQ EXTI3_IRQn
|
||||
/* GPIO channel 7 config */
|
||||
#define GPIO_7_PORT GPIOC
|
||||
#define GPIO_7_PIN 11
|
||||
#define GPIO_7_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPCEN)
|
||||
#define GPIO_7_EXTI_CFG() (AFIO->EXTICR[GPIO_7_PIN>>0x02] |= (((uint32_t)0x02) << (0x04 * (GPIO_7_PIN & (uint8_t)0x03))))
|
||||
#define GPIO_7_IRQ EXTI3_IRQn
|
||||
/* GPIO channel 8 config */
|
||||
#define GPIO_8_PORT GPIOC
|
||||
#define GPIO_8_PIN 12
|
||||
#define GPIO_8_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPCEN)
|
||||
#define GPIO_8_EXTI_CFG() (AFIO->EXTICR[GPIO_8_PIN>>0x02] |= (((uint32_t)0x02) << (0x04 * (GPIO_8_PIN & (uint8_t)0x03))))
|
||||
#define GPIO_8_IRQ EXTI3_IRQn
|
||||
/* GPIO channel 9 config */
|
||||
#define GPIO_9_PORT GPIOC
|
||||
#define GPIO_9_PIN 13
|
||||
#define GPIO_9_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPCEN)
|
||||
#define GPIO_9_EXTI_CFG() (AFIO->EXTICR[GPIO_9_PIN>>0x02] |= (((uint32_t)0x02) << (0x04 * (GPIO_9_PIN & (uint8_t)0x03))))
|
||||
#define GPIO_9_IRQ EXTI3_IRQn
|
||||
/* GPIO channel 10 config */
|
||||
#define GPIO_10_PORT GPIOC
|
||||
#define GPIO_10_PIN 14
|
||||
#define GPIO_10_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPCEN)
|
||||
#define GPIO_10_EXTI_CFG() (AFIO->EXTICR[GPIO_10_PIN>>0x02] |= (((uint32_t)0x02) << (0x04 * (GPIO_10_PIN & (uint8_t)0x03))))
|
||||
#define GPIO_10_IRQ EXTI3_IRQn
|
||||
/* GPIO channel 11 config */
|
||||
#define GPIO_11_PORT GPIOC
|
||||
#define GPIO_11_PIN 15
|
||||
#define GPIO_11_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPCEN)
|
||||
#define GPIO_11_EXTI_CFG() (AFIO->EXTICR[GPIO_11_PIN>>0x02] |= (((uint32_t)0x02) << (0x04 * (GPIO_11_PIN & (uint8_t)0x03))))
|
||||
#define GPIO_11_IRQ EXTI3_IRQn
|
||||
|
||||
/**
|
||||
* @brief SPI configuration
|
||||
*/
|
||||
#define SPI_NUM_OF 1
|
||||
#define SPI_0_EN 1
|
||||
|
||||
#define SPI_IRQ_0 SPI_0
|
||||
|
||||
#define SPI_0_BR_PRESC 16
|
||||
|
||||
#define SPI_0_SCLK GPIO_5_PIN
|
||||
#define SPI_0_MISO GPIO_6_PIN
|
||||
#define SPI_0_MOSI GPIO_7_PIN
|
||||
#define SPI_0_CS GPIO_4_PIN
|
||||
|
||||
#endif /* __PERIPH_CONF_H */
|
||||
/** @} */
|
4
boards/iot-lab_M3/tools/openocd.cfg
Normal file
4
boards/iot-lab_M3/tools/openocd.cfg
Normal file
@ -0,0 +1,4 @@
|
||||
# openocd.cfg file for STM32F4Discovery board via integrated ST-Link/V2.
|
||||
source [find interface/stlink-v2.cfg]
|
||||
source [find target/stm32f4x_stlink.cfg]
|
||||
reset_config srst_only srst_nogate
|
44
cpu/cortex-m3_common/include/cmsis_system.h
Normal file
44
cpu/cortex-m3_common/include/cmsis_system.h
Normal file
@ -0,0 +1,44 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License v2.1. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_cortexm3_common
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief CMSIS system header definitions for the Cortex-M0
|
||||
*
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
*/
|
||||
|
||||
#ifndef __CMSIS_SYSTEM_H
|
||||
#define __CMSIS_SYSTEM_H
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
/**
|
||||
* @brief This variable holds the current CPU core clock frequency in Hz
|
||||
*/
|
||||
extern uint32_t SystemCoreClock;
|
||||
|
||||
/**
|
||||
* @brief Initialize the system's clock system
|
||||
*
|
||||
* This function sets up the system's clock tree, concerning all options
|
||||
* regarding PLL setup, external clock source configuration and prescaler
|
||||
* setup for peripheral buses.
|
||||
*/
|
||||
void SystemInit(void);
|
||||
|
||||
/**
|
||||
* @brief Update the `SystemCoreClock` variable with the current core clock value
|
||||
*/
|
||||
void SystemCoreClockUpdate(void);
|
||||
|
||||
|
||||
#endif /* __CMSIS_SYSTEM_H */
|
@ -7,10 +7,10 @@
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_cortex-m3
|
||||
* @ingroup cpu_cortexm4_common
|
||||
* @{
|
||||
*
|
||||
* @file thread_arch.c
|
||||
* @file
|
||||
* @brief Implementation of the kernel's architecture dependent thread interface
|
||||
*
|
||||
* @author Stefan Pfeiffer <stefan.pfeiffer@fu-berlin.de>
|
||||
@ -25,6 +25,7 @@
|
||||
#include "arch/thread_arch.h"
|
||||
#include "thread.h"
|
||||
#include "sched.h"
|
||||
#include "thread.h"
|
||||
#include "irq.h"
|
||||
#include "cpu.h"
|
||||
#include "kernel_internal.h"
|
||||
@ -46,7 +47,14 @@ static void context_save(void);
|
||||
static void context_restore(void) NORETURN;
|
||||
|
||||
/**
|
||||
* Cortex-M3 knows stacks and handles register backups, so use different stack frame layout
|
||||
* Cortex-M knows stacks and handles register backups, so use different stack frame layout
|
||||
*
|
||||
* TODO: How to handle different Cortex-Ms? Code is so far valid for M3 and M4 without FPU
|
||||
*
|
||||
* Layout with storage of floating point registers (applicable for Cortex-M4):
|
||||
* ------------------------------------------------------------------------------------------------------------------------------------
|
||||
* | R0 | R1 | R2 | R3 | LR | PC | xPSR | S0 | S1 | S2 | S3 | S4 | S5 | S6 | S7 | S8 | S9 | S10 | S11 | S12 | S13 | S14 | S15 | FPSCR |
|
||||
* ------------------------------------------------------------------------------------------------------------------------------------
|
||||
*
|
||||
* Layout without floating point registers:
|
||||
* --------------------------------------
|
||||
@ -61,23 +69,37 @@ char *thread_arch_stack_init(void *(*task_func)(void *), void *arg, void *stack_
|
||||
|
||||
/* marker */
|
||||
stk--;
|
||||
*stk = (uint32_t)STACK_MARKER;
|
||||
*stk = STACK_MARKER;
|
||||
|
||||
/* TODO: fix FPU handling for Cortex-M4 */
|
||||
/*
|
||||
stk--;
|
||||
*stk = (unsigned int) 0;
|
||||
*/
|
||||
|
||||
/* S0 - S15 */
|
||||
/*
|
||||
for (int i = 15; i >= 0; i--) {
|
||||
stk--;
|
||||
*stk = i;
|
||||
}
|
||||
*/
|
||||
|
||||
/* FIXME xPSR */
|
||||
stk--;
|
||||
*stk = (uint32_t)0x01000200;
|
||||
*stk = (unsigned int) 0x01000200;
|
||||
|
||||
/* program counter */
|
||||
stk--;
|
||||
*stk = (uint32_t)task_func;
|
||||
*stk = (unsigned int) task_func;
|
||||
|
||||
/* link register, jumped to when thread exits */
|
||||
stk--;
|
||||
*stk = (uint32_t)sched_task_exit;
|
||||
*stk = (unsigned int) sched_task_exit;
|
||||
|
||||
/* r12 */
|
||||
stk--;
|
||||
*stk = (uint32_t) 0;
|
||||
*stk = (unsigned int) 0;
|
||||
|
||||
/* r1 - r3 */
|
||||
for (int i = 3; i >= 1; i--) {
|
||||
|
67
cpu/cortexm_common/crash.c
Normal file
67
cpu/cortexm_common/crash.c
Normal file
@ -0,0 +1,67 @@
|
||||
/*
|
||||
* Copyright (C) 2014 INRIA
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup core_util
|
||||
* @{
|
||||
*
|
||||
* @file crash.c
|
||||
* @brief Crash handling functions implementation for ARM Cortex-based MCUs
|
||||
*
|
||||
* @author Oliver Hahm <oliver.hahm@inria.fr>
|
||||
*/
|
||||
|
||||
#include "cpu.h"
|
||||
#include "lpm.h"
|
||||
#include "crash.h"
|
||||
|
||||
#include <string.h>
|
||||
#include <stdio.h>
|
||||
|
||||
/* "public" variables holding the crash data */
|
||||
char panic_str[80];
|
||||
int panic_code;
|
||||
|
||||
/* flag preventing "recursive crash printing loop" */
|
||||
static int crashed = 0;
|
||||
|
||||
/* WARNING: this function NEVER returns! */
|
||||
NORETURN void core_panic(int crash_code, const char *message)
|
||||
{
|
||||
/* copy panic datas to "public" global variables */
|
||||
panic_code = crash_code;
|
||||
strncpy(panic_str, message, 80);
|
||||
/* print panic message to console (if possible) */
|
||||
if (crashed == 0) {
|
||||
crashed = 1;
|
||||
puts("******** SYSTEM FAILURE ********\n");
|
||||
puts(message);
|
||||
#if DEVELHELP
|
||||
puts("******** RIOT HALTS HERE ********\n");
|
||||
#else
|
||||
puts("******** RIOT WILL REBOOT ********\n");
|
||||
#endif
|
||||
puts("\n\n");
|
||||
}
|
||||
/* disable watchdog and all possible sources of interrupts */
|
||||
//TODO
|
||||
dINT();
|
||||
#if DEVELHELP
|
||||
/* enter infinite loop, into deepest possible sleep mode */
|
||||
while (1) {
|
||||
lpm_set(LPM_OFF);
|
||||
}
|
||||
#else
|
||||
/* DEVELHELP not set => reboot system */
|
||||
(void) reboot(RB_AUTOBOOT);
|
||||
#endif
|
||||
|
||||
/* tell the compiler that we won't return from this function
|
||||
(even if we actually won't even get here...) */
|
||||
UNREACHABLE();
|
||||
}
|
7
cpu/stm32f1/Makefile
Normal file
7
cpu/stm32f1/Makefile
Normal file
@ -0,0 +1,7 @@
|
||||
# define the module that is build
|
||||
MODULE =cpu
|
||||
|
||||
# add a list of subdirectories, that should also be build
|
||||
DIRS += periph $(CORTEXM_COMMON)
|
||||
|
||||
include $(RIOTBASE)/Makefile.base
|
26
cpu/stm32f1/Makefile.include
Normal file
26
cpu/stm32f1/Makefile.include
Normal file
@ -0,0 +1,26 @@
|
||||
# this CPU implementation is using the new core/CPU interface
|
||||
export CFLAGS += -DCOREIF_NG=1
|
||||
|
||||
# tell the build system that the CPU depends on the Cortex-M common files
|
||||
export USEMODULE += cortex-m3_common
|
||||
|
||||
# define path to cortex-m common module, which is needed for this CPU
|
||||
export CORTEXM_COMMON = $(RIOTCPU)/cortex-m3_common/
|
||||
|
||||
# define the linker script to use for this CPU
|
||||
export LINKERSCRIPT = $(RIOTCPU)/$(CPU)/$(CPU_MODEL)_linkerscript.ld
|
||||
|
||||
# include CPU specific includes
|
||||
export INCLUDES += -I$(RIOTCPU)/$(CPU)/include/components
|
||||
export INCLUDES += -I$(RIOTCPU)/$(CPU)/include
|
||||
|
||||
# explicitly tell the linker to link the syscalls and startup code.
|
||||
# Without this the interrupt vectors will not be linked correctly!
|
||||
export UNDEF += $(BINDIR)cpu/syscalls.o
|
||||
export UNDEF += $(BINDIR)cpu/startup.o
|
||||
|
||||
# export the peripheral drivers to be linked into the final binary
|
||||
export USEMODULE += periph
|
||||
|
||||
# CPU depends on the cortex-m common module, so include it
|
||||
include $(CORTEXM_COMMON)Makefile.include
|
30
cpu/stm32f1/cpu.c
Normal file
30
cpu/stm32f1/cpu.c
Normal file
@ -0,0 +1,30 @@
|
||||
/*
|
||||
* Copyright (C) 2013 INRIA
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License v2.1. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_stm32f1
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Implementation of the kernel cpu functions
|
||||
*
|
||||
* @author Stefan Pfeiffer <stefan.pfeiffer@fu-berlin.de>
|
||||
* @author Alaeddine Weslati <alaeddine.weslati@inria.fr>
|
||||
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include "cpu.h"
|
||||
|
||||
void cpu_init(void)
|
||||
{
|
||||
/* set PendSV priority to the lowest possible priority */
|
||||
NVIC_SetPriority(PendSV_IRQn, 0xff);
|
||||
}
|
76
cpu/stm32f1/hwtimer_arch.c
Normal file
76
cpu/stm32f1/hwtimer_arch.c
Normal file
@ -0,0 +1,76 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License v2.1. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_stm32f1
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Implementation of the kernels hwtimer interface
|
||||
*
|
||||
* The hardware timer implementation uses the Coretex build-in system timer as backend.
|
||||
*
|
||||
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include "hwtimer_arch.h"
|
||||
#include "thread.h"
|
||||
#include "board.h"
|
||||
#include "periph/timer.h"
|
||||
|
||||
#define ENABLE_DEBUG (0)
|
||||
#include "debug.h"
|
||||
|
||||
|
||||
void irq_handler(int channel);
|
||||
void (*timeout_handler)(int);
|
||||
|
||||
|
||||
void hwtimer_arch_init(void (*handler)(int), uint32_t fcpu)
|
||||
{
|
||||
timeout_handler = handler;
|
||||
timer_init(HW_TIMER, 1, &irq_handler);
|
||||
}
|
||||
|
||||
void hwtimer_arch_enable_interrupt(void)
|
||||
{
|
||||
timer_irq_enable(HW_TIMER);
|
||||
}
|
||||
|
||||
void hwtimer_arch_disable_interrupt(void)
|
||||
{
|
||||
timer_irq_disable(HW_TIMER);
|
||||
}
|
||||
|
||||
void hwtimer_arch_set(unsigned long offset, short timer)
|
||||
{
|
||||
timer_set(HW_TIMER, timer, offset);
|
||||
}
|
||||
|
||||
void hwtimer_arch_set_absolute(unsigned long value, short timer)
|
||||
{
|
||||
timer_set_absolute(HW_TIMER, timer, value);
|
||||
}
|
||||
|
||||
void hwtimer_arch_unset(short timer)
|
||||
{
|
||||
timer_clear(HW_TIMER, timer);
|
||||
}
|
||||
|
||||
unsigned long hwtimer_arch_now(void)
|
||||
{
|
||||
return timer_read(HW_TIMER);
|
||||
}
|
||||
|
||||
void irq_handler(int channel)
|
||||
{
|
||||
timeout_handler((short)channel);
|
||||
thread_yield();
|
||||
}
|
73
cpu/stm32f1/include/cpu-conf.h
Normal file
73
cpu/stm32f1/include/cpu-conf.h
Normal file
@ -0,0 +1,73 @@
|
||||
/*
|
||||
* Copyright (C) 2013 INRIA
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License v2.1. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @defgroup cpu_stm32f1 STM32F1
|
||||
* @addtogroup cpu
|
||||
* @brief CPU specific implementations for the STM32F1
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Implementation specific CPU configuration options
|
||||
*
|
||||
* @author Alaeddine Weslati <alaeddine.weslati@intia.fr>
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
*/
|
||||
|
||||
#ifndef CPUCONF_H_
|
||||
#define CPUCONF_H_
|
||||
|
||||
#include "stm32f10x.h"
|
||||
|
||||
/**
|
||||
* @name Kernel configuration
|
||||
*
|
||||
* TODO: measure and adjust for the cortex-m3
|
||||
* @{
|
||||
*/
|
||||
#define KERNEL_CONF_STACKSIZE_PRINTF (2500)
|
||||
|
||||
#ifndef KERNEL_CONF_STACKSIZE_DEFAULT
|
||||
#define KERNEL_CONF_STACKSIZE_DEFAULT (2500)
|
||||
#endif
|
||||
|
||||
#define KERNEL_CONF_STACKSIZE_IDLE (512)
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @name UART0 buffer size definition for compatibility reasons
|
||||
*
|
||||
* TODO: remove once the remodeling of the uart0 driver is done
|
||||
* @{
|
||||
*/
|
||||
#ifndef UART0_BUFSIZE
|
||||
#define UART0_BUFSIZE (128)
|
||||
#endif
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @name Macro for reading CPU_ID
|
||||
*/
|
||||
#define GET_CPU_ID(id) memcpy(&id, (void *)(0x1ffff7e8), CPU_ID_LEN)
|
||||
|
||||
/**
|
||||
* @name Definition of different panic modes
|
||||
*/
|
||||
typedef enum {
|
||||
HARD_FAULT,
|
||||
WATCHDOG,
|
||||
BUS_FAULT,
|
||||
USAGE_FAULT,
|
||||
DUMMY_HANDLER
|
||||
} panic_t;
|
||||
|
||||
void cpu_clock_scale(uint32_t source, uint32_t target, uint32_t *prescale);
|
||||
|
||||
#endif /* __CPU_CONF_H */
|
||||
/** @} */
|
32
cpu/stm32f1/include/hwtimer_cpu.h
Normal file
32
cpu/stm32f1/include/hwtimer_cpu.h
Normal file
@ -0,0 +1,32 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_stm32f0
|
||||
* @{
|
||||
*
|
||||
* @file hwtimer_cpu.h
|
||||
* @brief CPU specific hwtimer configuration options
|
||||
*
|
||||
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
|
||||
*/
|
||||
|
||||
#ifndef HWTIMER_CPU_H_
|
||||
#define HWTIMER_CPU_H_
|
||||
|
||||
/**
|
||||
* @name Hardware timer configuration
|
||||
* @{
|
||||
*/
|
||||
#define HWTIMER_MAXTIMERS (4) /**< the CPU implementation supports 3 HW timers */
|
||||
#define HWTIMER_SPEED (2000U) /**< the HW timer runs with 2KHz */
|
||||
#define HWTIMER_MAXTICKS (0xFFFF) /**< 16-bit timer */
|
||||
/** @} */
|
||||
|
||||
#endif /* HWTIMER_CPU_H_ */
|
||||
/** @} */
|
176
cpu/stm32f1/include/spi.h
Normal file
176
cpu/stm32f1/include/spi.h
Normal file
@ -0,0 +1,176 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License v2.1. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup driver_periph
|
||||
* @brief Low-level SPI peripheral driver
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Low-level SPI peripheral driver interface definitions
|
||||
*
|
||||
* TODO: optimize interface for master AND slave usage, interface is focused on master mode so far...
|
||||
*
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
*/
|
||||
|
||||
#ifndef __SPI_H
|
||||
#define __SPI_H
|
||||
|
||||
#include "periph_conf.h"
|
||||
|
||||
|
||||
/**
|
||||
* @brief Definition available SPI devices
|
||||
*/
|
||||
typedef enum {
|
||||
#if SPI_0_EN
|
||||
SPI_0 = 0, /**< SPI device 0 */
|
||||
#endif
|
||||
#if SPI_1_EN
|
||||
SPI_1, /**< SPI device 1 */
|
||||
#endif
|
||||
#if SPI_2_EN
|
||||
SPI_2, /**< SPI device 2 */
|
||||
#endif
|
||||
#if SPI_3_EN
|
||||
SPI_3, /**< SPI device 3 */
|
||||
#endif
|
||||
SPI_UNDEFINED
|
||||
} spi_t;
|
||||
|
||||
/**
|
||||
* @brief The SPI mode is defined by the four possible combinations of clock polarity and
|
||||
* clock phase.
|
||||
*/
|
||||
typedef enum {
|
||||
SPI_CONF_FIRST_RISING = 0, /**< first data bit is transacted on the first rising SCK edge */
|
||||
SPI_CONF_SECOND_RISING, /**< first data bit is transacted on the second rising SCK edge */
|
||||
SPI_CONF_FIRST_FALLING, /**< first data bit is transacted on the first falling SCK edge */
|
||||
SPI_CONF_SECOND_FALLING /**< first data bit is transacted on the second falling SCK edge */
|
||||
} spi_conf_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Initialize the given SPI device to work in master mode
|
||||
*
|
||||
* In master mode the SPI device is configured to control the SPI bus. This means the device
|
||||
* will start and end all communication on the bus and control the CLK line. For transferring
|
||||
* data on the bus the below defined transfer functions should be used.
|
||||
*
|
||||
* @param[in] dev SPI device to initialize
|
||||
* @param[in] conf Mode of clock phase and clock polarity
|
||||
* @param[in] speed SPI bus speed in Hz
|
||||
*
|
||||
* @return 0 on success
|
||||
* @return -1 on undefined SPI device
|
||||
* @return -2 on unavailable speed value
|
||||
*/
|
||||
int spi_init_master(spi_t dev, spi_conf_t conf, uint32_t speed);
|
||||
|
||||
/**
|
||||
* @brief Initialize the given SPI device to work in slave mode
|
||||
*
|
||||
* In slave mode the SPI device is purely reacting to the bus. Transaction will be started and
|
||||
* ended by a connected SPI master. When a byte is received, the callback is called in interrupt
|
||||
* context with this byte as argument. The return byte of the callback is transferred to the
|
||||
* master in the next transmission cycle. This interface enables easy implementation of a register
|
||||
* based access paradigm for the SPI slave.
|
||||
*
|
||||
* @param[in] dev The SPI device to initialize as SPI slave
|
||||
* @param[in] conf Mode of clock phase and polarity
|
||||
* @param[in] cb callback on received byte
|
||||
*
|
||||
* @return 0 on success
|
||||
* @return -1 on undefined SPI device
|
||||
* @return -2 on unavailable speed value
|
||||
*/
|
||||
int spi_init_slave(spi_t dev, spi_conf_t conf, char (*cb)(char));
|
||||
|
||||
/**
|
||||
* @brief Transfer one byte on the given SPI bus
|
||||
*
|
||||
* @param[in] dev SPI device to use
|
||||
* @param[in] out Byte to send out, set NULL if only receiving
|
||||
* @param[out] in Byte to read, set NULL if only sending
|
||||
*
|
||||
* @return Number of bytes that were transfered
|
||||
* @return -1 on error
|
||||
*/
|
||||
int spi_transfer_byte(spi_t dev, char out, char *in);
|
||||
|
||||
/**
|
||||
* @brief Transfer a number bytes on the given SPI bus
|
||||
*
|
||||
* @param[in] dev SPI device to use
|
||||
* @param[in] out Array of bytes to send, set NULL if only receiving
|
||||
* @param[out] in Buffer to receive bytes to, set NULL if only sending
|
||||
* @param[in] length Number of bytes to transfer
|
||||
*
|
||||
* @return Number of bytes that were transfered
|
||||
* @return -1 on error
|
||||
*/
|
||||
int spi_transfer_bytes(spi_t dev, char *out, char *in, int length);
|
||||
|
||||
/**
|
||||
* @brief Transfer one byte to/from a given register address
|
||||
*
|
||||
* This function is a shortcut function for easier handling of register based SPI devices. As
|
||||
* many SPI devices use a register based addressing scheme, this function is a convenient short-
|
||||
* cut for interfacing with such devices.
|
||||
*
|
||||
* @param[in] dev SPI device to use
|
||||
* @param[in] reg Register address to transfer data to/from
|
||||
* @param[in] out Byte to send, set NULL if only receiving data
|
||||
* @param[out] in Byte to read, set NULL if only sending
|
||||
*
|
||||
* @return Number of bytes that were transfered
|
||||
* @return -1 on error
|
||||
*/
|
||||
int spi_transfer_reg(spi_t dev, uint8_t reg, char *out, char *in);
|
||||
|
||||
/**
|
||||
* @brief Transfer a number of bytes from/to a given register address
|
||||
*
|
||||
* This function is a shortcut function for easier handling of register based SPI devices. As
|
||||
* many SPI devices use a register based addressing scheme, this function is a convenient short-
|
||||
* cut for interfacing with such devices.
|
||||
*
|
||||
* @param[in] dev SPI device to use
|
||||
* @param[in] reg Register address to transfer data to/from
|
||||
* @param[in] out Byte array to send data from, set NULL if only receiving
|
||||
* @param[out] in Byte buffer to read into, set NULL if only sending
|
||||
* @param[in] length Number of bytes to transfer
|
||||
*
|
||||
* @return Number of bytes that were transfered
|
||||
* @return -1 on error
|
||||
*/
|
||||
int spi_transfer_regs(spi_t dev, uint8_t reg, char *out, char *in, int length);
|
||||
|
||||
/**
|
||||
* @brief Power on the given SPI device
|
||||
*
|
||||
* @param[in] dev SPI device to power on
|
||||
*
|
||||
* @return 0 on success
|
||||
* @return -1 on undefined device
|
||||
*/
|
||||
int spi_poweron(spi_t dev);
|
||||
|
||||
/**
|
||||
* @brief Power off the given SPI device
|
||||
*
|
||||
* @param[in] dev SPI device to power off
|
||||
*
|
||||
* @return 0 on success
|
||||
* @return -1 on undefined device
|
||||
*/
|
||||
int spi_poweroff(spi_t dev);
|
||||
|
||||
#endif /* __SPI_H */
|
||||
/** @} */
|
8337
cpu/stm32f1/include/stm32f10x.h
Normal file
8337
cpu/stm32f1/include/stm32f10x.h
Normal file
File diff suppressed because it is too large
Load Diff
32
cpu/stm32f1/io_arch.c
Normal file
32
cpu/stm32f1/io_arch.c
Normal file
@ -0,0 +1,32 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_stm32f1
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Implementation of the kernel's architecture dependent IO interface
|
||||
*
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
#include "arch/io_arch.h"
|
||||
|
||||
int io_arch_puts(char *data, int size)
|
||||
{
|
||||
int i = 0;
|
||||
for (; i < size; i++) {
|
||||
putchar(data[i]);
|
||||
}
|
||||
return i;
|
||||
}
|
55
cpu/stm32f1/lpm_arch.c
Normal file
55
cpu/stm32f1/lpm_arch.c
Normal file
@ -0,0 +1,55 @@
|
||||
/*
|
||||
* Copyright (C) 2013 INRIA
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_stm32f1
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Implementation of the kernel's lpm interface
|
||||
*
|
||||
* @author Alaeddine Weslati <alaeddine.weslati@inria.fr>
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include "arch/lpm_arch.h"
|
||||
|
||||
void lpm_arch_init(void)
|
||||
{
|
||||
/* TODO */
|
||||
}
|
||||
|
||||
enum lpm_mode lpm_arch_set(enum lpm_mode target)
|
||||
{
|
||||
/* TODO */
|
||||
return 0;
|
||||
}
|
||||
|
||||
enum lpm_mode lpm_arch_get(void)
|
||||
{
|
||||
/* TODO */
|
||||
return 0;
|
||||
}
|
||||
|
||||
void lpm_arch_awake(void)
|
||||
{
|
||||
/* TODO */
|
||||
}
|
||||
|
||||
void lpm_arch_begin_awake(void)
|
||||
{
|
||||
/* TODO */
|
||||
}
|
||||
|
||||
void lpm_arch_end_awake(void)
|
||||
{
|
||||
/* TODO */
|
||||
}
|
5
cpu/stm32f1/periph/Makefile
Normal file
5
cpu/stm32f1/periph/Makefile
Normal file
@ -0,0 +1,5 @@
|
||||
# define the module name
|
||||
MODULE = periph
|
||||
|
||||
# include RIOTs generic Makefile
|
||||
include $(RIOTBASE)/Makefile.base
|
736
cpu/stm32f1/periph/gpio.c
Normal file
736
cpu/stm32f1/periph/gpio.c
Normal file
@ -0,0 +1,736 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License v2.1. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_stm32f1
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Low-level GPIO driver implementation
|
||||
*
|
||||
* @author Hauke Petersen <mail@haukepetersen.de>
|
||||
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include "cpu.h"
|
||||
#include "periph/gpio.h"
|
||||
#include "periph_conf.h"
|
||||
|
||||
typedef struct {
|
||||
void (*cb)(void);
|
||||
} gpio_state_t;
|
||||
|
||||
static gpio_state_t config[GPIO_NUMOF];
|
||||
|
||||
int gpio_init_out(gpio_t dev, gpio_pp_t pullup)
|
||||
{
|
||||
GPIO_TypeDef *port;
|
||||
uint32_t pin;
|
||||
|
||||
switch (dev) {
|
||||
#ifdef GPIO_0_EN
|
||||
case GPIO_0:
|
||||
GPIO_0_CLKEN();
|
||||
port = GPIO_0_PORT;
|
||||
pin = GPIO_0_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_1_EN
|
||||
case GPIO_1:
|
||||
GPIO_1_CLKEN();
|
||||
port = GPIO_1_PORT;
|
||||
pin = GPIO_1_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_2_EN
|
||||
case GPIO_2:
|
||||
GPIO_2_CLKEN();
|
||||
port = GPIO_2_PORT;
|
||||
pin = GPIO_2_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_3_EN
|
||||
case GPIO_3:
|
||||
GPIO_3_CLKEN();
|
||||
port = GPIO_3_PORT;
|
||||
pin = GPIO_3_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_4_EN
|
||||
case GPIO_4:
|
||||
GPIO_4_CLKEN();
|
||||
port = GPIO_4_PORT;
|
||||
pin = GPIO_4_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_5_EN
|
||||
case GPIO_5:
|
||||
GPIO_5_CLKEN();
|
||||
port = GPIO_5_PORT;
|
||||
pin = GPIO_5_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_6_EN
|
||||
case GPIO_6:
|
||||
GPIO_6_CLKEN();
|
||||
port = GPIO_6_PORT;
|
||||
pin = GPIO_6_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_7_EN
|
||||
case GPIO_7:
|
||||
GPIO_7_CLKEN();
|
||||
port = GPIO_7_PORT;
|
||||
pin = GPIO_7_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_8_EN
|
||||
case GPIO_8:
|
||||
GPIO_8_CLKEN();
|
||||
port = GPIO_8_PORT;
|
||||
pin = GPIO_8_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_9_EN
|
||||
case GPIO_9:
|
||||
GPIO_9_CLKEN();
|
||||
port = GPIO_9_PORT;
|
||||
pin = GPIO_9_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_10_EN
|
||||
case GPIO_10:
|
||||
GPIO_10_CLKEN();
|
||||
port = GPIO_10_PORT;
|
||||
pin = GPIO_10_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_11_EN
|
||||
case GPIO_11:
|
||||
GPIO_11_CLKEN();
|
||||
port = GPIO_11_PORT;
|
||||
pin = GPIO_11_PIN;
|
||||
break;
|
||||
#endif
|
||||
case GPIO_UNDEFINED:
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (pin < 8) {
|
||||
port->CRL &= ~(0xf << (4 * pin));
|
||||
port->CRL |= (0x3 << (4* pin)); /* Output mode, 50 MHz */
|
||||
/* general purpose push-pull set implicitly */
|
||||
port->ODR |= (1 << pin); /* set pin to low signal */
|
||||
}
|
||||
else {
|
||||
port->CRH &= ~(0xf << (4 * (pin-8)));
|
||||
port->CRH |= (0x3 << (4* (pin-8))); /* Output mode, 50 MHz */
|
||||
/* general purpose push-pull set implicitly */
|
||||
port->ODR |= (1 << pin); /* set pin to low signal */
|
||||
}
|
||||
|
||||
return 0; /* all OK */
|
||||
}
|
||||
|
||||
int gpio_init_in(gpio_t dev, gpio_pp_t pullup)
|
||||
{
|
||||
GPIO_TypeDef *port;
|
||||
uint32_t pin;
|
||||
|
||||
switch (dev) {
|
||||
#ifdef GPIO_0_EN
|
||||
case GPIO_0:
|
||||
GPIO_0_CLKEN();
|
||||
port = GPIO_0_PORT;
|
||||
pin = GPIO_0_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_1_EN
|
||||
case GPIO_1:
|
||||
GPIO_1_CLKEN();
|
||||
port = GPIO_1_PORT;
|
||||
pin = GPIO_1_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_2_EN
|
||||
case GPIO_2:
|
||||
GPIO_2_CLKEN();
|
||||
port = GPIO_2_PORT;
|
||||
pin = GPIO_2_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_3_EN
|
||||
case GPIO_3:
|
||||
GPIO_3_CLKEN();
|
||||
port = GPIO_3_PORT;
|
||||
pin = GPIO_3_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_4_EN
|
||||
case GPIO_4:
|
||||
GPIO_4_CLKEN();
|
||||
port = GPIO_4_PORT;
|
||||
pin = GPIO_4_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_5_EN
|
||||
case GPIO_5:
|
||||
GPIO_5_CLKEN();
|
||||
port = GPIO_5_PORT;
|
||||
pin = GPIO_5_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_6_EN
|
||||
case GPIO_6:
|
||||
GPIO_6_CLKEN();
|
||||
port = GPIO_6_PORT;
|
||||
pin = GPIO_6_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_7_EN
|
||||
case GPIO_7:
|
||||
GPIO_7_CLKEN();
|
||||
port = GPIO_7_PORT;
|
||||
pin = GPIO_7_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_8_EN
|
||||
case GPIO_8:
|
||||
GPIO_8_CLKEN();
|
||||
port = GPIO_8_PORT;
|
||||
pin = GPIO_8_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_9_EN
|
||||
case GPIO_9:
|
||||
GPIO_9_CLKEN();
|
||||
port = GPIO_9_PORT;
|
||||
pin = GPIO_9_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_10_EN
|
||||
case GPIO_10:
|
||||
GPIO_10_CLKEN();
|
||||
port = GPIO_10_PORT;
|
||||
pin = GPIO_10_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_11_EN
|
||||
case GPIO_11:
|
||||
GPIO_11_CLKEN();
|
||||
port = GPIO_11_PORT;
|
||||
pin = GPIO_11_PIN;
|
||||
break;
|
||||
#endif
|
||||
case GPIO_UNDEFINED:
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (pin < 8) {
|
||||
port->CRL &= ~(0xf << (4 * pin));
|
||||
}
|
||||
else {
|
||||
port->CRH &= ~(0xf << (4 * (pin-8)));
|
||||
}
|
||||
|
||||
return 0; /* everything alright here */
|
||||
}
|
||||
|
||||
int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, void (*cb)(void))
|
||||
{
|
||||
int res;
|
||||
uint32_t pin;
|
||||
|
||||
/* configure pin as input */
|
||||
res = gpio_init_in(dev, pullup);
|
||||
if (res < 0) {
|
||||
return res;
|
||||
}
|
||||
|
||||
/* set interrupt priority (its the same for all EXTI interrupts) */
|
||||
NVIC_SetPriority(EXTI0_IRQn, GPIO_IRQ_PRIO);
|
||||
NVIC_SetPriority(EXTI1_IRQn, GPIO_IRQ_PRIO);
|
||||
NVIC_SetPriority(EXTI2_IRQn, GPIO_IRQ_PRIO);
|
||||
NVIC_SetPriority(EXTI4_IRQn, GPIO_IRQ_PRIO);
|
||||
|
||||
/* enable clock of the SYSCFG module for EXTI configuration */
|
||||
//RCC->APB2ENR |= RCC_APB2ENR_SYSCFGCOMPEN;
|
||||
|
||||
/* read pin number, set EXIT channel and enable global interrupt for EXTI channel */
|
||||
switch (dev) {
|
||||
#ifdef GPIO_0_EN
|
||||
case GPIO_0:
|
||||
pin = GPIO_0_PIN;
|
||||
GPIO_0_EXTI_CFG();
|
||||
NVIC_SetPriority(GPIO_0_IRQ, GPIO_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(GPIO_0_IRQ);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_1_EN
|
||||
case GPIO_1:
|
||||
pin = GPIO_1_PIN;
|
||||
GPIO_1_EXTI_CFG();
|
||||
NVIC_SetPriority(GPIO_1_IRQ, GPIO_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(GPIO_1_IRQ);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_2_EN
|
||||
case GPIO_2:
|
||||
pin = GPIO_2_PIN;
|
||||
GPIO_2_EXTI_CFG();
|
||||
NVIC_SetPriority(GPIO_2_IRQ, GPIO_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(GPIO_2_IRQ);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_3_EN
|
||||
case GPIO_3:
|
||||
pin = GPIO_3_PIN;
|
||||
GPIO_3_EXTI_CFG();
|
||||
NVIC_SetPriority(GPIO_3_IRQ, GPIO_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(GPIO_3_IRQ);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_4_EN
|
||||
case GPIO_4:
|
||||
pin = GPIO_4_PIN;
|
||||
GPIO_4_EXTI_CFG();
|
||||
NVIC_SetPriority(GPIO_4_IRQ, GPIO_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(GPIO_4_IRQ);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_5_EN
|
||||
case GPIO_5:
|
||||
pin = GPIO_5_PIN;
|
||||
GPIO_5_EXTI_CFG();
|
||||
NVIC_SetPriority(GPIO_5_IRQ, GPIO_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(GPIO_5_IRQ);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_6_EN
|
||||
case GPIO_6:
|
||||
pin = GPIO_6_PIN;
|
||||
GPIO_6_EXTI_CFG();
|
||||
NVIC_SetPriority(GPIO_6_IRQ, GPIO_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(GPIO_6_IRQ);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_7_EN
|
||||
case GPIO_7:
|
||||
pin = GPIO_7_PIN;
|
||||
GPIO_7_EXTI_CFG();
|
||||
NVIC_SetPriority(GPIO_7_IRQ, GPIO_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(GPIO_7_IRQ);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_8_EN
|
||||
case GPIO_8:
|
||||
pin = GPIO_8_PIN;
|
||||
GPIO_8_EXTI_CFG();
|
||||
NVIC_SetPriority(GPIO_8_IRQ, GPIO_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(GPIO_8_IRQ);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_9_EN
|
||||
case GPIO_9:
|
||||
pin = GPIO_9_PIN;
|
||||
GPIO_9_EXTI_CFG();
|
||||
NVIC_SetPriority(GPIO_9_IRQ, GPIO_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(GPIO_9_IRQ);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_10_EN
|
||||
case GPIO_10:
|
||||
pin = GPIO_10_PIN;
|
||||
GPIO_10_EXTI_CFG();
|
||||
NVIC_SetPriority(GPIO_10_IRQ, GPIO_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(GPIO_10_IRQ);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_11_EN
|
||||
case GPIO_11:
|
||||
pin = GPIO_11_PIN;
|
||||
GPIO_11_EXTI_CFG();
|
||||
NVIC_SetPriority(GPIO_11_IRQ, GPIO_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(GPIO_11_IRQ);
|
||||
break;
|
||||
#endif
|
||||
case GPIO_UNDEFINED:
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* set callback */
|
||||
config[dev].cb = cb;
|
||||
|
||||
/* configure the event that triggers an interrupt */
|
||||
switch (flank) {
|
||||
case GPIO_RISING:
|
||||
EXTI->RTSR |= (1 << pin);
|
||||
EXTI->FTSR &= ~(1 << pin);
|
||||
break;
|
||||
case GPIO_FALLING:
|
||||
EXTI->RTSR &= ~(1 << pin);
|
||||
EXTI->FTSR |= (1 << pin);
|
||||
break;
|
||||
case GPIO_BOTH:
|
||||
EXTI->RTSR |= (1 << pin);
|
||||
EXTI->FTSR |= (1 << pin);
|
||||
break;
|
||||
}
|
||||
|
||||
/* unmask the pins interrupt channel */
|
||||
EXTI->IMR |= (1 << pin);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int gpio_read(gpio_t dev)
|
||||
{
|
||||
GPIO_TypeDef *port;
|
||||
uint32_t pin;
|
||||
|
||||
switch (dev) {
|
||||
#ifdef GPIO_0_EN
|
||||
case GPIO_0:
|
||||
port = GPIO_0_PORT;
|
||||
pin = GPIO_0_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_1_EN
|
||||
case GPIO_1:
|
||||
port = GPIO_1_PORT;
|
||||
pin = GPIO_1_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_2_EN
|
||||
case GPIO_2:
|
||||
port = GPIO_2_PORT;
|
||||
pin = GPIO_2_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_3_EN
|
||||
case GPIO_3:
|
||||
port = GPIO_3_PORT;
|
||||
pin = GPIO_3_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_4_EN
|
||||
case GPIO_4:
|
||||
port = GPIO_4_PORT;
|
||||
pin = GPIO_4_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_5_EN
|
||||
case GPIO_5:
|
||||
port = GPIO_5_PORT;
|
||||
pin = GPIO_5_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_6_EN
|
||||
case GPIO_6:
|
||||
port = GPIO_6_PORT;
|
||||
pin = GPIO_6_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_7_EN
|
||||
case GPIO_7:
|
||||
port = GPIO_7_PORT;
|
||||
pin = GPIO_7_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_8_EN
|
||||
case GPIO_8:
|
||||
port = GPIO_8_PORT;
|
||||
pin = GPIO_8_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_9_EN
|
||||
case GPIO_9:
|
||||
port = GPIO_9_PORT;
|
||||
pin = GPIO_9_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_10_EN
|
||||
case GPIO_10:
|
||||
port = GPIO_10_PORT;
|
||||
pin = GPIO_10_PIN;
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_11_EN
|
||||
case GPIO_11:
|
||||
port = GPIO_11_PORT;
|
||||
pin = GPIO_11_PIN;
|
||||
break;
|
||||
#endif
|
||||
case GPIO_UNDEFINED:
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (pin < 8) {
|
||||
if (port->CRL & (0x3 << (pin * 4))) { /* if configured as output */
|
||||
return port->ODR & (1 << pin); /* read output data register */
|
||||
} else {
|
||||
return port->IDR & (1 << pin); /* else read input data register */
|
||||
}
|
||||
}
|
||||
else {
|
||||
if (port->CRH & (0x3 << ((pin-8) * 4))) { /* if configured as output */
|
||||
return port->ODR & (1 << pin); /* read output data register */
|
||||
} else {
|
||||
return port->IDR & (1 << pin); /* else read input data register */
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int gpio_set(gpio_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#ifdef GPIO_0_EN
|
||||
case GPIO_0:
|
||||
GPIO_0_PORT->ODR |= (1 << GPIO_0_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_1_EN
|
||||
case GPIO_1:
|
||||
GPIO_1_PORT->ODR |= (1 << GPIO_1_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_2_EN
|
||||
case GPIO_2:
|
||||
GPIO_2_PORT->ODR |= (1 << GPIO_2_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_3_EN
|
||||
case GPIO_3:
|
||||
GPIO_3_PORT->ODR |= (1 << GPIO_3_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_4_EN
|
||||
case GPIO_4:
|
||||
GPIO_4_PORT->ODR |= (1 << GPIO_4_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_5_EN
|
||||
case GPIO_5:
|
||||
GPIO_5_PORT->ODR |= (1 << GPIO_5_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_6_EN
|
||||
case GPIO_6:
|
||||
GPIO_6_PORT->ODR |= (1 << GPIO_6_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_7_EN
|
||||
case GPIO_7:
|
||||
GPIO_7_PORT->ODR |= (1 << GPIO_7_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_8_EN
|
||||
case GPIO_8:
|
||||
GPIO_8_PORT->ODR |= (1 << GPIO_8_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_9_EN
|
||||
case GPIO_9:
|
||||
GPIO_9_PORT->ODR |= (1 << GPIO_9_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_10_EN
|
||||
case GPIO_10:
|
||||
GPIO_10_PORT->ODR |= (1 << GPIO_10_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_11_EN
|
||||
case GPIO_11:
|
||||
GPIO_11_PORT->ODR |= (1 << GPIO_11_PIN);
|
||||
break;
|
||||
#endif
|
||||
case GPIO_UNDEFINED:
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int gpio_clear(gpio_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#ifdef GPIO_0_EN
|
||||
case GPIO_0:
|
||||
GPIO_0_PORT->ODR &= ~(1 << GPIO_0_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_1_EN
|
||||
case GPIO_1:
|
||||
GPIO_1_PORT->ODR &= ~(1 << GPIO_1_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_2_EN
|
||||
case GPIO_2:
|
||||
GPIO_2_PORT->ODR &= ~(1 << GPIO_2_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_3_EN
|
||||
case GPIO_3:
|
||||
GPIO_3_PORT->ODR &= ~(1 << GPIO_3_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_4_EN
|
||||
case GPIO_4:
|
||||
GPIO_4_PORT->ODR &= ~(1 << GPIO_4_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_5_EN
|
||||
case GPIO_5:
|
||||
GPIO_5_PORT->ODR &= ~(1 << GPIO_5_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_6_EN
|
||||
case GPIO_6:
|
||||
GPIO_6_PORT->ODR &= ~(1 << GPIO_6_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_7_EN
|
||||
case GPIO_7:
|
||||
GPIO_7_PORT->ODR &= ~(1 << GPIO_7_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_8_EN
|
||||
case GPIO_8:
|
||||
GPIO_8_PORT->ODR &= ~(1 << GPIO_8_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_9_EN
|
||||
case GPIO_9:
|
||||
GPIO_9_PORT->ODR &= ~(1 << GPIO_9_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_10_EN
|
||||
case GPIO_10:
|
||||
GPIO_10_PORT->ODR &= ~(1 << GPIO_10_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef GPIO_11_EN
|
||||
case GPIO_11:
|
||||
GPIO_11_PORT->ODR &= ~(1 << GPIO_11_PIN);
|
||||
break;
|
||||
#endif
|
||||
case GPIO_UNDEFINED:
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
int gpio_toggle(gpio_t dev)
|
||||
{
|
||||
if (gpio_read(dev)) {
|
||||
return gpio_clear(dev);
|
||||
} else {
|
||||
return gpio_set(dev);
|
||||
}
|
||||
}
|
||||
|
||||
int gpio_write(gpio_t dev, int value)
|
||||
{
|
||||
if (value) {
|
||||
return gpio_set(dev);
|
||||
} else {
|
||||
return gpio_clear(dev);
|
||||
}
|
||||
}
|
||||
|
||||
__attribute__((naked)) void isr_exti0_1(void)
|
||||
{
|
||||
ISR_ENTER();
|
||||
if (EXTI->PR & EXTI_PR_PR0) {
|
||||
EXTI->PR |= EXTI_PR_PR0; /* clear status bit by writing a 1 to it */
|
||||
config[GPIO_IRQ_0].cb();
|
||||
}
|
||||
else if (EXTI->PR & EXTI_PR_PR1) {
|
||||
EXTI->PR |= EXTI_PR_PR1; /* clear status bit by writing a 1 to it */
|
||||
config[GPIO_IRQ_1].cb();
|
||||
}
|
||||
ISR_EXIT();
|
||||
}
|
||||
|
||||
__attribute__((naked)) void isr_exti2_3(void)
|
||||
{
|
||||
ISR_ENTER();
|
||||
if (EXTI->PR & EXTI_PR_PR2) {
|
||||
EXTI->PR |= EXTI_PR_PR2; /* clear status bit by writing a 1 to it */
|
||||
config[GPIO_IRQ_2].cb();
|
||||
}
|
||||
else if (EXTI->PR & EXTI_PR_PR3) {
|
||||
EXTI->PR |= EXTI_PR_PR3; /* clear status bit by writing a 1 to it */
|
||||
config[GPIO_IRQ_3].cb();
|
||||
}
|
||||
ISR_EXIT();
|
||||
}
|
||||
|
||||
__attribute__((naked)) void isr_exti4_15(void)
|
||||
{
|
||||
ISR_ENTER();
|
||||
if (EXTI->PR & EXTI_PR_PR4) {
|
||||
EXTI->PR |= EXTI_PR_PR4; /* clear status bit by writing a 1 to it */
|
||||
config[GPIO_IRQ_4].cb();
|
||||
}
|
||||
else if (EXTI->PR & EXTI_PR_PR5) {
|
||||
EXTI->PR |= EXTI_PR_PR5; /* clear status bit by writing a 1 to it */
|
||||
config[GPIO_IRQ_5].cb();
|
||||
}
|
||||
else if (EXTI->PR & EXTI_PR_PR6) {
|
||||
EXTI->PR |= EXTI_PR_PR6; /* clear status bit by writing a 1 to it */
|
||||
config[GPIO_IRQ_6].cb();
|
||||
}
|
||||
else if (EXTI->PR & EXTI_PR_PR7) {
|
||||
EXTI->PR |= EXTI_PR_PR7; /* clear status bit by writing a 1 to it */
|
||||
config[GPIO_IRQ_7].cb();
|
||||
}
|
||||
else if (EXTI->PR & EXTI_PR_PR8) {
|
||||
EXTI->PR |= EXTI_PR_PR8; /* clear status bit by writing a 1 to it */
|
||||
config[GPIO_IRQ_8].cb();
|
||||
}
|
||||
else if (EXTI->PR & EXTI_PR_PR9) {
|
||||
EXTI->PR |= EXTI_PR_PR9; /* clear status bit by writing a 1 to it */
|
||||
config[GPIO_IRQ_9].cb();
|
||||
}
|
||||
else if (EXTI->PR & EXTI_PR_PR10) {
|
||||
EXTI->PR |= EXTI_PR_PR10; /* clear status bit by writing a 1 to it */
|
||||
config[GPIO_IRQ_10].cb();
|
||||
}
|
||||
else if (EXTI->PR & EXTI_PR_PR11) {
|
||||
EXTI->PR |= EXTI_PR_PR11; /* clear status bit by writing a 1 to it */
|
||||
config[GPIO_IRQ_11].cb();
|
||||
}
|
||||
else if (EXTI->PR & EXTI_PR_PR12) {
|
||||
EXTI->PR |= EXTI_PR_PR12; /* clear status bit by writing a 1 to it */
|
||||
config[GPIO_IRQ_12].cb();
|
||||
}
|
||||
else if (EXTI->PR & EXTI_PR_PR13) {
|
||||
EXTI->PR |= EXTI_PR_PR13; /* clear status bit by writing a 1 to it */
|
||||
config[GPIO_IRQ_13].cb();
|
||||
}
|
||||
else if (EXTI->PR & EXTI_PR_PR14) {
|
||||
EXTI->PR |= EXTI_PR_PR14; /* clear status bit by writing a 1 to it */
|
||||
config[GPIO_IRQ_14].cb();
|
||||
}
|
||||
else if (EXTI->PR & EXTI_PR_PR15) {
|
||||
EXTI->PR |= EXTI_PR_PR15; /* clear status bit by writing a 1 to it */
|
||||
config[GPIO_IRQ_15].cb();
|
||||
}
|
||||
ISR_EXIT();
|
||||
}
|
109
cpu/stm32f1/periph/spi.c
Normal file
109
cpu/stm32f1/periph/spi.c
Normal file
@ -0,0 +1,109 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Thomas Eichinger <thomas.eichinger@fu-berlin.de>
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License v2.1. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
#include "stm32f10x.h"
|
||||
#include "spi.h"
|
||||
#include "periph_conf.h"
|
||||
|
||||
int spi_init_master(spi_t dev, spi_conf_t conf, uint32_t speed)
|
||||
{
|
||||
RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int spi_init_slave(spi_t dev, spi_conf_t conf, char (*cb)(char))
|
||||
{
|
||||
/* TODO */
|
||||
return 0;
|
||||
}
|
||||
|
||||
int spi_transfer_byte(spi_t dev, char out, char *in)
|
||||
{
|
||||
SPI_TypeDef *SPI_dev;
|
||||
int transfered = 0;
|
||||
|
||||
switch(dev) {
|
||||
#ifdef SPI_0_EN
|
||||
case SPI_0:
|
||||
SPI_dev = SPI1;
|
||||
#endif
|
||||
case SPI_UNDEFINED:
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (out != 0) {
|
||||
/* wait for empty tx buffer */
|
||||
while ((SPI_dev->SR & 0x2) == 0);
|
||||
/* write out data to buffer */
|
||||
SPI_dev->DR = out;
|
||||
/* increase transfered bytes counter */
|
||||
transfered++;
|
||||
}
|
||||
|
||||
if (in != 0) {
|
||||
/* wait for not empty rx buffer */
|
||||
while ((SPI_dev->SR & 0x1) == 0);
|
||||
/* read out data to in buffer */
|
||||
*in = SPI_dev->DR;
|
||||
/* increase transfered bytes counter */
|
||||
transfered++;
|
||||
}
|
||||
|
||||
while ((SPI_dev->SR & 0x80) == SET);
|
||||
|
||||
return transfered;
|
||||
}
|
||||
|
||||
int spi_transfer_bytes(spi_t dev, char *out, char *in, int length)
|
||||
{
|
||||
int transfered = 0;
|
||||
int ret = 0;
|
||||
|
||||
if (out != 0) {
|
||||
while (length--) {
|
||||
ret += spi_transfer_byte(dev, *(out)++, 0);
|
||||
if (ret < 0) {
|
||||
return ret;
|
||||
}
|
||||
transfered += ret;
|
||||
}
|
||||
}
|
||||
if (in != 0) {
|
||||
while (length--) {
|
||||
ret += spi_transfer_byte(dev, 0, in++);
|
||||
if (ret < 0) {
|
||||
return ret;
|
||||
}
|
||||
transfered += ret;
|
||||
}
|
||||
}
|
||||
|
||||
return transfered;
|
||||
}
|
||||
|
||||
int spi_transfer_reg(spi_t dev, uint8_t reg, char *out, char *in)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
int spi_transfer_regs(spi_t dev, uint8_t reg, char *out, char *in, int length)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
int spi_poweron(spi_t dev)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
int spi_poweroff(spi_t dev)
|
||||
{
|
||||
return -1;
|
||||
}
|
345
cpu/stm32f1/periph/timer.c
Normal file
345
cpu/stm32f1/periph/timer.c
Normal file
@ -0,0 +1,345 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License v2.1. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_stm32f0
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Low-level timer driver implementation
|
||||
*
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "cpu.h"
|
||||
#include "board.h"
|
||||
#include "periph_conf.h"
|
||||
#include "periph/timer.h"
|
||||
|
||||
#define ENABLE_DEBUG (0)
|
||||
#include "debug.h"
|
||||
|
||||
|
||||
static inline void irq_handler(tim_t timer, TIM_TypeDef *dev);
|
||||
|
||||
typedef struct {
|
||||
void (*cb)(int);
|
||||
} timer_conf_t;
|
||||
|
||||
/**
|
||||
* Timer state memory
|
||||
*/
|
||||
timer_conf_t config[TIMER_NUMOF];
|
||||
|
||||
|
||||
|
||||
int timer_init(tim_t dev, unsigned int ticks_per_us, void (*callback)(int))
|
||||
{
|
||||
TIM_TypeDef *timer;
|
||||
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
case TIMER_0:
|
||||
/* enable timer peripheral clock */
|
||||
TIMER_0_CLKEN();
|
||||
/* set timer's IRQ priority */
|
||||
NVIC_SetPriority(TIMER_0_IRQ_CHAN, TIMER_0_IRQ_PRIO);
|
||||
/* select timer */
|
||||
timer = TIMER_0_DEV;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
case TIMER_1:
|
||||
/* enable timer peripheral clock */
|
||||
TIMER_1_CLKEN();
|
||||
/* set timer's IRQ priority */
|
||||
NVIC_SetPriority(TIMER_1_IRQ_CHAN, TIMER_1_IRQ_PRIO);
|
||||
/* select timer */
|
||||
timer = TIMER_1_DEV;
|
||||
break;
|
||||
#endif
|
||||
case TIMER_UNDEFINED:
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* set callback function */
|
||||
config[dev].cb = callback;
|
||||
|
||||
/* set timer to run in counter mode */
|
||||
timer->CR1 |= TIM_CR1_URS;
|
||||
|
||||
/* set auto-reload and prescaler values and load new values */
|
||||
timer->ARR = TIMER_0_MAX_VALUE;
|
||||
timer->PSC = TIMER_0_PRESCALER * ticks_per_us;
|
||||
timer->EGR |= TIM_EGR_UG;
|
||||
|
||||
/* enable the timer's interrupt */
|
||||
timer_irq_enable(dev);
|
||||
|
||||
/* start the timer */
|
||||
timer_start(dev);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int timer_set(tim_t dev, int channel, unsigned int timeout)
|
||||
{
|
||||
int now = timer_read(dev);
|
||||
return timer_set_absolute(dev, channel, now + timeout - 1);
|
||||
}
|
||||
|
||||
int timer_set_absolute(tim_t dev, int channel, unsigned int value)
|
||||
{
|
||||
TIM_TypeDef *timer = NULL;
|
||||
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
case TIMER_0:
|
||||
timer = TIMER_0_DEV;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
case TIMER_1:
|
||||
timer = TIMER_1_DEV;
|
||||
break;
|
||||
#endif
|
||||
case TIMER_UNDEFINED:
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
switch (channel) {
|
||||
case 0:
|
||||
timer->CCR1 = value;
|
||||
timer->SR &= ~TIM_SR_CC1IF;
|
||||
timer->DIER |= TIM_DIER_CC1IE;
|
||||
break;
|
||||
case 1:
|
||||
timer->CCR2 = value;
|
||||
timer->SR &= ~TIM_SR_CC2IF;
|
||||
timer->DIER |= TIM_DIER_CC2IE;
|
||||
break;
|
||||
case 2:
|
||||
timer->CCR3 = value;
|
||||
timer->SR &= ~TIM_SR_CC3IF;
|
||||
timer->DIER |= TIM_DIER_CC3IE;
|
||||
break;
|
||||
case 3:
|
||||
timer->CCR4 = value;
|
||||
timer->SR &= ~TIM_SR_CC4IF;
|
||||
timer->DIER |= TIM_DIER_CC4IE;
|
||||
break;
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int timer_clear(tim_t dev, int channel)
|
||||
{
|
||||
TIM_TypeDef *timer;
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
case TIMER_0:
|
||||
timer = TIMER_0_DEV;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
case TIMER_1:
|
||||
timer = TIMER_1_DEV;
|
||||
break;
|
||||
#endif
|
||||
case TIMER_UNDEFINED:
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
switch (channel) {
|
||||
case 0:
|
||||
timer->DIER &= ~TIM_DIER_CC1IE;
|
||||
break;
|
||||
case 1:
|
||||
timer->DIER &= ~TIM_DIER_CC2IE;
|
||||
break;
|
||||
case 2:
|
||||
timer->DIER &= ~TIM_DIER_CC3IE;
|
||||
break;
|
||||
case 3:
|
||||
timer->DIER &= ~TIM_DIER_CC4IE;
|
||||
break;
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
unsigned int timer_read(tim_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
case TIMER_0:
|
||||
return TIMER_0_DEV->CNT;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
case TIMER_1:
|
||||
return TIMER_1_DEV->CNT;
|
||||
break;
|
||||
#endif
|
||||
case TIMER_UNDEFINED:
|
||||
default:
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
void timer_start(tim_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
case TIMER_0:
|
||||
TIMER_0_DEV->CR1 |= TIM_CR1_CEN;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
case TIMER_1:
|
||||
TIMER_1_DEV->CR1 |= TIM_CR1_CEN;
|
||||
break;
|
||||
#endif
|
||||
case TIMER_UNDEFINED:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void timer_stop(tim_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
case TIMER_0:
|
||||
TIMER_0_DEV->CR1 &= ~TIM_CR1_CEN;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
case TIMER_1:
|
||||
TIMER_1_DEV->CR1 &= ~TIM_CR1_CEN;
|
||||
break;
|
||||
#endif
|
||||
case TIMER_UNDEFINED:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void timer_irq_enable(tim_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
case TIMER_0:
|
||||
NVIC_EnableIRQ(TIMER_0_IRQ_CHAN);
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
case TIMER_1:
|
||||
NVIC_EnableIRQ(TIMER_1_IRQ_CHAN);
|
||||
break;
|
||||
#endif
|
||||
case TIMER_UNDEFINED:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void timer_irq_disable(tim_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
case TIMER_0:
|
||||
NVIC_DisableIRQ(TIMER_0_IRQ_CHAN);
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
case TIMER_1:
|
||||
NVIC_DisableIRQ(TIMER_1_IRQ_CHAN);
|
||||
break;
|
||||
#endif
|
||||
case TIMER_UNDEFINED:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void timer_reset(tim_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if TIMER_0_EN
|
||||
case TIMER_0:
|
||||
TIMER_0_DEV->CNT = 0;
|
||||
break;
|
||||
#endif
|
||||
#if TIMER_1_EN
|
||||
case TIMER_1:
|
||||
TIMER_1_DEV->CNT = 0;
|
||||
break;
|
||||
#endif
|
||||
case TIMER_UNDEFINED:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#if TIMER_0_EN
|
||||
__attribute__ ((naked)) void TIMER_0_ISR(void)
|
||||
{
|
||||
ISR_ENTER();
|
||||
DEBUG("enter ISR\n");
|
||||
irq_handler(TIMER_0, TIMER_0_DEV);
|
||||
DEBUG("leave ISR\n");
|
||||
ISR_EXIT();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if TIMER_1_EN
|
||||
__attribute__ ((naked)) void TIMER_1_ISR(void)
|
||||
{
|
||||
ISR_ENTER();
|
||||
irq_handler(TIMER_1, TIMER_1_DEV);
|
||||
ISR_EXIT();
|
||||
}
|
||||
#endif
|
||||
|
||||
static inline void irq_handler(tim_t timer, TIM_TypeDef *dev)
|
||||
{
|
||||
if (dev->SR & TIM_SR_CC1IF) {
|
||||
DEBUG("1\n");
|
||||
dev->DIER &= ~TIM_DIER_CC1IE;
|
||||
dev->SR &= ~TIM_SR_CC1IF;
|
||||
config[timer].cb(0);
|
||||
DEBUG("-1\n");
|
||||
}
|
||||
else if (dev->SR & TIM_SR_CC2IF) {
|
||||
DEBUG("2\n");
|
||||
dev->DIER &= ~TIM_DIER_CC2IE;
|
||||
dev->SR &= ~TIM_SR_CC2IF;
|
||||
config[timer].cb(1);
|
||||
}
|
||||
else if (dev->SR & TIM_SR_CC3IF) {
|
||||
DEBUG("3\n");
|
||||
dev->DIER &= ~TIM_DIER_CC3IE;
|
||||
dev->SR &= ~TIM_SR_CC3IF;
|
||||
config[timer].cb(2);
|
||||
DEBUG("-3\n");
|
||||
}
|
||||
else if (dev->SR & TIM_SR_CC4IF) {
|
||||
DEBUG("4\n");
|
||||
dev->DIER &= ~TIM_DIER_CC4IE;
|
||||
dev->SR &= ~TIM_SR_CC4IF;
|
||||
config[timer].cb(3);
|
||||
DEBUG("-4\n");
|
||||
}
|
||||
}
|
307
cpu/stm32f1/periph/uart.c
Normal file
307
cpu/stm32f1/periph/uart.c
Normal file
@ -0,0 +1,307 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License v2.1. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_stm32f1
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Low-level UART driver implementation
|
||||
*
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <math.h>
|
||||
|
||||
#include "cpu.h"
|
||||
#include "board.h"
|
||||
#include "periph_conf.h"
|
||||
#include "periph/uart.h"
|
||||
|
||||
|
||||
/**
|
||||
* @brief Each UART device has to store two callbacks.
|
||||
*/
|
||||
typedef struct {
|
||||
void (*rx_cb)(char);
|
||||
void (*tx_cb)(void);
|
||||
} uart_conf_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Unified interrupt handler for all UART devices
|
||||
*
|
||||
* @param uartnum the number of the UART that triggered the ISR
|
||||
* @param uart the UART device that triggered the ISR
|
||||
*/
|
||||
static inline void irq_handler(uart_t uartnum, USART_TypeDef *uart);
|
||||
|
||||
|
||||
/**
|
||||
* @brief Allocate memory to store the callback functions.
|
||||
*/
|
||||
static uart_conf_t config[UART_NUMOF];
|
||||
|
||||
|
||||
int uart_init(uart_t uart, uint32_t baudrate, void (*rx_cb)(char), void (*tx_cb)(void))
|
||||
{
|
||||
int res;
|
||||
|
||||
/* initialize UART in blocking mode first */
|
||||
res = uart_init_blocking(uart, baudrate);
|
||||
if (res < 0) {
|
||||
return res;
|
||||
}
|
||||
|
||||
/* enable global interrupt and configure the interrupts priority */
|
||||
switch (uart) {
|
||||
#if UART_0_EN
|
||||
case UART_0:
|
||||
NVIC_SetPriority(UART_0_IRQ, UART_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(UART_0_IRQ);
|
||||
UART_0_DEV->CR1 |= USART_CR1_RXNEIE;
|
||||
break;
|
||||
#endif
|
||||
#if UART_1_EN
|
||||
case UART_1:
|
||||
NVIC_SetPriority(UART_1_IRQ, UART_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(UART_1_IRQ);
|
||||
UART_1_DEV->CR1 |= USART_CR1_RXNEIE;
|
||||
break;
|
||||
#endif
|
||||
case UART_UNDEFINED:
|
||||
default:
|
||||
return -2;
|
||||
}
|
||||
|
||||
/* register callbacks */
|
||||
config[uart].rx_cb = rx_cb;
|
||||
config[uart].tx_cb = tx_cb;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int uart_init_blocking(uart_t uart, uint32_t baudrate)
|
||||
{
|
||||
USART_TypeDef *dev;
|
||||
GPIO_TypeDef *port;
|
||||
uint32_t rx_pin, tx_pin;
|
||||
float divider;
|
||||
uint16_t mantissa;
|
||||
uint8_t fraction;
|
||||
|
||||
/* enable UART and port clocks and select devices */
|
||||
switch (uart) {
|
||||
#if UART_0_EN
|
||||
case UART_0:
|
||||
dev = UART_0_DEV;
|
||||
port = UART_0_PORT;
|
||||
rx_pin = UART_0_RX_PIN;
|
||||
tx_pin = UART_0_TX_PIN;
|
||||
/* enable clocks */
|
||||
UART_0_CLKEN();
|
||||
UART_0_PORT_CLKEN();
|
||||
break;
|
||||
#endif
|
||||
#if UART_1_EN
|
||||
case UART_1:
|
||||
dev = UART_1_DEV;
|
||||
port = UART_1_PORT;
|
||||
tx_pin = UART_1_TX_PIN;
|
||||
rx_pin = UART_1_RX_PIN;
|
||||
/* enable clocks */
|
||||
UART_1_CLKEN();
|
||||
UART_1_PORT_CLKEN();
|
||||
break;
|
||||
#endif
|
||||
case UART_UNDEFINED:
|
||||
default:
|
||||
return -2;
|
||||
}
|
||||
/* Configure USART Tx as alternate function push-pull and 50MHz*/
|
||||
if (tx_pin < 8) {
|
||||
port->CRL &= ~(0xf << (tx_pin * 4));
|
||||
port->CRL |= (0xB << (tx_pin * 4));
|
||||
}
|
||||
else {
|
||||
port->CRH &= ~(0xf << ((tx_pin-8) * 4));
|
||||
port->CRH |= (0xB << ((tx_pin-8) * 4));
|
||||
}
|
||||
/* Configure USART Rx as floating input */
|
||||
if (rx_pin < 8) {
|
||||
port->CRL &= ~(0xf << (rx_pin * 4));
|
||||
port->CRL |= (0x4 << (rx_pin * 4));
|
||||
}
|
||||
else {
|
||||
port->CRH &= ~(0xf << ((rx_pin-8) * 4));
|
||||
port->CRH |= (0x4 << ((rx_pin-8) * 4));
|
||||
}
|
||||
|
||||
/* configure UART to mode 8N1 with given baudrate */
|
||||
divider = ((float)F_CPU) / (16 * baudrate);
|
||||
mantissa = (uint16_t)floorf(divider);
|
||||
fraction = (uint8_t)floorf((divider - mantissa) * 16);
|
||||
dev->BRR = 0;
|
||||
dev->BRR |= ((mantissa & 0x0fff) << 4) | (0x0f & fraction);
|
||||
|
||||
/* enable receive and transmit mode */
|
||||
dev->CR1 |= USART_CR1_UE | USART_CR1_TE | USART_CR1_RE;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void uart_tx_begin(uart_t uart)
|
||||
{
|
||||
switch (uart) {
|
||||
#if UART_0_EN
|
||||
case UART_0:
|
||||
UART_0_DEV->CR1 |= USART_CR1_TXEIE;
|
||||
break;
|
||||
#endif
|
||||
#if UART_1_EN
|
||||
case UART_1:
|
||||
UART_1_DEV->CR1 |= USART_CR1_TXEIE;
|
||||
break;
|
||||
#endif
|
||||
case UART_UNDEFINED:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void uart_tx_end(uart_t uart)
|
||||
{
|
||||
switch (uart) {
|
||||
#if UART_0_EN
|
||||
case UART_0:
|
||||
UART_0_DEV->CR1 &= ~USART_CR1_TXEIE;
|
||||
break;
|
||||
#endif
|
||||
#if UART_1_EN
|
||||
case UART_1:
|
||||
UART_1_DEV->CR1 &= ~USART_CR1_TXEIE;
|
||||
break;
|
||||
#endif
|
||||
case UART_UNDEFINED:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
int uart_write(uart_t uart, char data)
|
||||
{
|
||||
USART_TypeDef *dev;
|
||||
|
||||
switch (uart) {
|
||||
#if UART_0_EN
|
||||
case UART_0:
|
||||
dev = UART_0_DEV;
|
||||
break;
|
||||
#endif
|
||||
#if UART_1_EN
|
||||
case UART_1:
|
||||
dev = UART_1_DEV;
|
||||
break;
|
||||
#endif
|
||||
case UART_UNDEFINED:
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (dev->SR & USART_SR_TXE) {
|
||||
dev->DR = (uint8_t)data;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int uart_read_blocking(uart_t uart, char *data)
|
||||
{
|
||||
USART_TypeDef *dev;
|
||||
|
||||
switch (uart) {
|
||||
#if UART_0_EN
|
||||
case UART_0:
|
||||
dev = UART_0_DEV;
|
||||
break;
|
||||
#endif
|
||||
#if UART_1_EN
|
||||
case UART_1:
|
||||
dev = UART_1_DEV;
|
||||
break;
|
||||
#endif
|
||||
case UART_UNDEFINED:
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
while (!(dev->SR & USART_SR_RXNE));
|
||||
*data = (char)dev->DR;
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
int uart_write_blocking(uart_t uart, char data)
|
||||
{
|
||||
USART_TypeDef *dev;
|
||||
|
||||
switch (uart) {
|
||||
#if UART_0_EN
|
||||
case UART_0:
|
||||
dev = UART_0_DEV;
|
||||
break;
|
||||
#endif
|
||||
#if UART_1_EN
|
||||
case UART_1:
|
||||
dev = UART_1_DEV;
|
||||
break;
|
||||
#endif
|
||||
case UART_UNDEFINED:
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
while (!(dev->SR & USART_SR_TXE));
|
||||
dev->DR = (uint8_t)data;
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
#if UART_0_EN
|
||||
__attribute__((naked)) void UART_0_ISR(void)
|
||||
{
|
||||
ISR_ENTER();
|
||||
irq_handler(UART_0, UART_0_DEV);
|
||||
ISR_EXIT();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if UART_1_EN
|
||||
__attribute__((naked)) void UART_1_ISR(void)
|
||||
{
|
||||
ISR_ENTER();
|
||||
irq_handler(UART_1, UART_1_DEV);
|
||||
ISR_EXIT();
|
||||
}
|
||||
#endif
|
||||
|
||||
static inline void irq_handler(uint8_t uartnum, USART_TypeDef *dev)
|
||||
{
|
||||
if (dev->SR & USART_SR_RXNE) {
|
||||
char data = (char)dev->DR;
|
||||
config[uartnum].rx_cb(data);
|
||||
}
|
||||
else if (dev->SR & USART_SR_ORE) {
|
||||
/* ORE is cleared by reading SR and DR sequentially */
|
||||
dev->DR;
|
||||
}
|
||||
else if (dev->SR & USART_SR_TXE) {
|
||||
config[uartnum].tx_cb();
|
||||
}
|
||||
}
|
34
cpu/stm32f1/reboot_arch.c
Normal file
34
cpu/stm32f1/reboot_arch.c
Normal file
@ -0,0 +1,34 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_stm32f1
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Implementation of the kernels reboot interface
|
||||
*
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
#include "arch/reboot_arch.h"
|
||||
#include "cpu.h"
|
||||
|
||||
|
||||
int reboot_arch(int mode)
|
||||
{
|
||||
printf("Going into reboot, mode %i\n", mode);
|
||||
|
||||
NVIC_SystemReset();
|
||||
|
||||
return 0;
|
||||
}
|
271
cpu/stm32f1/startup.c
Normal file
271
cpu/stm32f1/startup.c
Normal file
@ -0,0 +1,271 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_sam3x8e
|
||||
* @{
|
||||
*
|
||||
* @file startup.c
|
||||
* @brief Startup code and interrupt vector definition
|
||||
*
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include "crash.h"
|
||||
|
||||
|
||||
/**
|
||||
* memory markers as defined in the linker script
|
||||
*/
|
||||
extern uint32_t _sfixed;
|
||||
extern uint32_t _efixed;
|
||||
extern uint32_t _etext;
|
||||
extern uint32_t _srelocate;
|
||||
extern uint32_t _erelocate;
|
||||
extern uint32_t _szero;
|
||||
extern uint32_t _ezero;
|
||||
extern uint32_t _sstack;
|
||||
extern uint32_t _estack;
|
||||
|
||||
|
||||
/**
|
||||
* @brief functions for initializing the board, std-lib and kernel
|
||||
*/
|
||||
extern void board_init(void);
|
||||
extern void kernel_init(void);
|
||||
extern void __libc_init_array(void);
|
||||
|
||||
/**
|
||||
* @brief This function is the entry point after a system reset
|
||||
*
|
||||
* After a system reset, the following steps are necessary and carried out:
|
||||
* 1. load data section from flash to ram
|
||||
* 2. overwrite uninitialized data section (BSS) with zeros
|
||||
* 3. initialize the newlib
|
||||
* 4. initialize the board (sync clock, setup std-IO)
|
||||
* 5. initialize and start RIOTs kernel
|
||||
*/
|
||||
void reset_handler(void)
|
||||
{
|
||||
uint32_t *dst;
|
||||
uint32_t *src = &_etext;
|
||||
|
||||
/* load data section from flash to ram */
|
||||
for (dst = &_srelocate; dst < &_erelocate; ) {
|
||||
*(dst++) = *(src++);
|
||||
}
|
||||
|
||||
/* default bss section to zero */
|
||||
for (dst = &_szero; dst < &_ezero; ) {
|
||||
*(dst++) = 0;
|
||||
}
|
||||
|
||||
/* initialize the board and startup the kernel */
|
||||
board_init();
|
||||
/* initialize std-c library (this should be done after board_init) */
|
||||
__libc_init_array();
|
||||
/* startup the kernel */
|
||||
kernel_init();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Default handler is called in case no interrupt handler was defined
|
||||
*/
|
||||
void dummy_handler(void)
|
||||
{
|
||||
core_panic(DUMMY_HANDLER, "DUMMY HANDLER");
|
||||
while (1) {asm ("nop");}
|
||||
}
|
||||
|
||||
void isr_nmi(void)
|
||||
{
|
||||
while (1) {asm ("nop");}
|
||||
}
|
||||
|
||||
void isr_mem_manage(void)
|
||||
{
|
||||
while (1) {asm ("nop");}
|
||||
}
|
||||
|
||||
void isr_debug_mon(void)
|
||||
{
|
||||
while (1) {asm ("nop");}
|
||||
}
|
||||
|
||||
void isr_hard_fault(void)
|
||||
{
|
||||
core_panic(HARD_FAULT, "HARD FAULT");
|
||||
while (1) {asm ("nop");}
|
||||
}
|
||||
|
||||
void isr_bus_fault(void)
|
||||
{
|
||||
core_panic(BUS_FAULT, "BUS FAULT");
|
||||
while (1) {asm ("nop");}
|
||||
}
|
||||
|
||||
void isr_usage_fault(void)
|
||||
{
|
||||
core_panic(USAGE_FAULT, "USAGE FAULT");
|
||||
while (1) {asm ("nop");}
|
||||
}
|
||||
|
||||
/* Cortex-M specific interrupt vectors */
|
||||
void isr_svc(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_pendsv(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_systick(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
|
||||
/* stm32f1 specific interrupt vector */
|
||||
void isr_wwdg(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_pvd(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_tamper(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_rtc(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_flash(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_rcc(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_exti0(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_exti1(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_exti2(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_exti3(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_exti4(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_dma1_ch1(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_dma1_ch2(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_dma1_ch3(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_dma1_ch4(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_dma1_ch5(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_dma1_ch6(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_dma1_ch7(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_adc1_2(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_usb_hp_can1_tx(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_usb_lp_can1_rx0(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_can1_rx1(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_can1_sce(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_exti9_5(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_tim1_brk(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_tim1_up(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_tim1_trg_com(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_tim1_cc(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_tim2(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_tim3(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_tim4(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_i2c1_ev(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_i2c1_er(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_i2c2_ev(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_i2c2_er(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_spi1(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_spi2(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_usart1(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_usart2(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_usart3(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_exti15_10(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_rtc_alarm(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_usb_wakeup(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_tim8_brk(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_tim8_up(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_tim8_trg_com(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_tim8_cc(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_adc3(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_fsmc(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_sdio(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_tim5(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_spi3(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_uart4(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_uart5(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_tim6(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_tim7(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_dma2_ch1(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_dma2_ch2(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_dma2_ch3(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
void isr_dma2_ch4_5(void) __attribute__ ((weak, alias("dummy_handler")));
|
||||
|
||||
|
||||
/* interrupt vector table */
|
||||
__attribute__ ((section(".vectors")))
|
||||
const void *interrupt_vector[] = {
|
||||
/* Stack pointer */
|
||||
(void*) (&_estack), /* pointer to the top of the empty stack */
|
||||
/* Cortex-M handlers */
|
||||
(void*) reset_handler, /* entry point of the program */
|
||||
(void*) isr_nmi, /* non maskable interrupt handler */
|
||||
(void*) isr_hard_fault, /* if you end up here its not good */
|
||||
(void*) isr_mem_manage, /* memory controller interrupt */
|
||||
(void*) isr_bus_fault, /* also not good to end up here */
|
||||
(void*) isr_usage_fault, /* autsch */
|
||||
(void*) (0UL), /* Reserved */
|
||||
(void*) (0UL), /* Reserved */
|
||||
(void*) (0UL), /* Reserved */
|
||||
(void*) (0UL), /* Reserved */
|
||||
(void*) isr_svc, /* system call interrupt */
|
||||
(void*) isr_debug_mon, /* debug interrupt */
|
||||
(void*) (0UL), /* Reserved */
|
||||
(void*) isr_pendsv, /* pendSV interrupt, used for task switching in RIOT */
|
||||
(void*) isr_systick, /* SysTick interrupt, not used in RIOT */
|
||||
/* STM specific peripheral handlers */
|
||||
(void*) isr_wwdg,
|
||||
(void*) isr_pvd,
|
||||
(void*) isr_tamper,
|
||||
(void*) isr_rtc,
|
||||
(void*) isr_flash,
|
||||
(void*) isr_rcc,
|
||||
(void*) isr_exti0,
|
||||
(void*) isr_exti1,
|
||||
(void*) isr_exti2,
|
||||
(void*) isr_exti3,
|
||||
(void*) isr_exti4,
|
||||
(void*) isr_dma1_ch1,
|
||||
(void*) isr_dma1_ch2,
|
||||
(void*) isr_dma1_ch3,
|
||||
(void*) isr_dma1_ch4,
|
||||
(void*) isr_dma1_ch5,
|
||||
(void*) isr_dma1_ch6,
|
||||
(void*) isr_dma1_ch7,
|
||||
(void*) isr_adc1_2,
|
||||
(void*) isr_usb_hp_can1_tx,
|
||||
(void*) isr_usb_lp_can1_rx0,
|
||||
(void*) isr_can1_rx1,
|
||||
(void*) isr_can1_sce,
|
||||
(void*) isr_exti9_5,
|
||||
(void*) isr_tim1_brk,
|
||||
(void*) isr_tim1_up,
|
||||
(void*) isr_tim1_trg_com,
|
||||
(void*) isr_tim1_cc,
|
||||
(void*) isr_tim2,
|
||||
(void*) isr_tim3,
|
||||
(void*) isr_tim4,
|
||||
(void*) isr_i2c1_ev,
|
||||
(void*) isr_i2c1_er,
|
||||
(void*) isr_i2c2_ev,
|
||||
(void*) isr_i2c2_er,
|
||||
(void*) isr_spi1,
|
||||
(void*) isr_spi2,
|
||||
(void*) isr_usart1,
|
||||
(void*) isr_usart2,
|
||||
(void*) isr_usart3,
|
||||
(void*) isr_exti15_10,
|
||||
(void*) isr_rtc_alarm,
|
||||
(void*) isr_usb_wakeup,
|
||||
(void*) isr_tim8_brk,
|
||||
(void*) isr_tim8_up,
|
||||
(void*) isr_tim8_trg_com,
|
||||
(void*) isr_tim8_cc,
|
||||
(void*) isr_adc3,
|
||||
(void*) isr_fsmc,
|
||||
(void*) isr_sdio,
|
||||
(void*) isr_tim5,
|
||||
(void*) isr_spi3,
|
||||
(void*) isr_uart4,
|
||||
(void*) isr_uart5,
|
||||
(void*) isr_tim6,
|
||||
(void*) isr_tim7,
|
||||
(void*) isr_dma2_ch1,
|
||||
(void*) isr_dma2_ch2,
|
||||
(void*) isr_dma2_ch3,
|
||||
(void*) isr_dma2_ch4_5,
|
||||
};
|
142
cpu/stm32f1/stm32f103re_linkerscript.ld
Normal file
142
cpu/stm32f1/stm32f103re_linkerscript.ld
Normal file
@ -0,0 +1,142 @@
|
||||
/* ----------------------------------------------------------------------------
|
||||
* SAM Software Package License
|
||||
* ----------------------------------------------------------------------------
|
||||
* Copyright (c) 2012, Atmel Corporation
|
||||
*
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following condition is met:
|
||||
*
|
||||
* - Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the disclaimer below.
|
||||
*
|
||||
* Atmel's name may not be used to endorse or promote products derived from
|
||||
* this software without specific prior written permission.
|
||||
*
|
||||
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
|
||||
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
|
||||
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
|
||||
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
|
||||
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
|
||||
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
|
||||
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
* ----------------------------------------------------------------------------
|
||||
*/
|
||||
|
||||
/*OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm")
|
||||
OUTPUT_ARCH(arm)
|
||||
SEARCH_DIR(.)*/
|
||||
|
||||
/* Memory Spaces Definitions */
|
||||
MEMORY
|
||||
{
|
||||
rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K
|
||||
ram (xrw) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
}
|
||||
|
||||
/* The stack size used by the application. NOTE: you need to adjust */
|
||||
STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : 0x800 ;
|
||||
|
||||
/* Section Definitions */
|
||||
SECTIONS
|
||||
{
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sfixed = .;
|
||||
KEEP(*(.vectors .vectors.*))
|
||||
*(.text .text.* .gnu.linkonce.t.*)
|
||||
*(.glue_7t) *(.glue_7)
|
||||
*(.rodata .rodata* .gnu.linkonce.r.*)
|
||||
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||
|
||||
/* Support C constructors, and C destructors in both user code
|
||||
and the C library. This also provides support for C++ code. */
|
||||
. = 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);
|
||||
_efixed = .; /* End of text section */
|
||||
} > rom
|
||||
|
||||
/* .ARM.exidx is sorted, so has to go in its own output section. */
|
||||
PROVIDE_HIDDEN (__exidx_start = .);
|
||||
.ARM.exidx :
|
||||
{
|
||||
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
|
||||
} > rom
|
||||
PROVIDE_HIDDEN (__exidx_end = .);
|
||||
|
||||
. = ALIGN(4);
|
||||
_etext = .;
|
||||
|
||||
.relocate : AT (_etext)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_srelocate = .;
|
||||
*(.ramfunc .ramfunc.*);
|
||||
*(.data .data.*);
|
||||
. = ALIGN(4);
|
||||
_erelocate = .;
|
||||
} > ram
|
||||
|
||||
/* .bss section which is used for uninitialized data */
|
||||
.bss (NOLOAD) :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sbss = . ;
|
||||
_szero = .;
|
||||
*(.bss .bss.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = . ;
|
||||
_ezero = .;
|
||||
} > ram
|
||||
|
||||
/* stack section */
|
||||
.stack (NOLOAD) :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sstack = .;
|
||||
. = . + STACK_SIZE;
|
||||
. = ALIGN(4);
|
||||
_estack = .;
|
||||
} > ram
|
||||
|
||||
. = ALIGN(4);
|
||||
_end = . ;
|
||||
}
|
276
cpu/stm32f1/syscalls.c
Normal file
276
cpu/stm32f1/syscalls.c
Normal file
@ -0,0 +1,276 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_stm32f1
|
||||
* @{
|
||||
*
|
||||
* @file syscalls.c
|
||||
* @brief NewLib system calls implementations for SAM3X8E
|
||||
*
|
||||
* @author Michael Baar <michael.baar@fu-berlin.de>
|
||||
* @author Stefan Pfeiffer <pfeiffer@inf.fu-berlin.de>
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <sys/stat.h>
|
||||
#include <sys/unistd.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "thread.h"
|
||||
#include "kernel.h"
|
||||
#include "irq.h"
|
||||
#include "periph/uart.h"
|
||||
|
||||
/**
|
||||
* manage the heap
|
||||
*/
|
||||
extern uint32_t _end; /* address of last used memory cell */
|
||||
caddr_t heap_top = (caddr_t)&_end + 4;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Initialize NewLib, called by __libc_init_array() from the startup script
|
||||
*/
|
||||
void _init(void)
|
||||
{
|
||||
uart_init_blocking(UART_0, 115200);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Free resources on NewLib de-initialization, not used for RIOT
|
||||
*/
|
||||
void _fini(void)
|
||||
{
|
||||
/* nothing to do here */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Exit a program without cleaning up files
|
||||
*
|
||||
* If your system doesn't provide this, it is best to avoid linking with subroutines that
|
||||
* require it (exit, system).
|
||||
*
|
||||
* @param n the exit code, 0 for all OK, >0 for not OK
|
||||
*/
|
||||
void _exit(int n)
|
||||
{
|
||||
printf("#! exit %i: resetting\n", n);
|
||||
NVIC_SystemReset();
|
||||
while(1);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Allocate memory from the heap.
|
||||
*
|
||||
* The current heap implementation is very rudimentary, it is only able to allocate
|
||||
* memory. But it does not
|
||||
* - check if the returned address is valid (no check if the memory very exists)
|
||||
* - have any means to free memory again
|
||||
*
|
||||
* TODO: check if the requested memory is really available
|
||||
*
|
||||
* @return [description]
|
||||
*/
|
||||
caddr_t _sbrk_r(struct _reent *r, size_t incr)
|
||||
{
|
||||
unsigned int state = disableIRQ();
|
||||
caddr_t res = heap_top;
|
||||
heap_top += incr;
|
||||
restoreIRQ(state);
|
||||
return res;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get the process-ID of the current thread
|
||||
*
|
||||
* @return the process ID of the current thread
|
||||
*/
|
||||
int _getpid(void)
|
||||
{
|
||||
return sched_active_thread->pid;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a signal to a given thread
|
||||
*
|
||||
* @param r TODO
|
||||
* @param pid TODO
|
||||
* @param sig TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _kill_r(struct _reent *r, int pid, int sig)
|
||||
{
|
||||
r->_errno = ESRCH; /* not implemented yet */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Open a file
|
||||
*
|
||||
* @param r TODO
|
||||
* @param name TODO
|
||||
* @param mode TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _open_r(struct _reent *r, const char *name, int mode)
|
||||
{
|
||||
r->_errno = ENODEV; /* not implemented yet */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Read from a file
|
||||
*
|
||||
* All input is read from UART_0. The function will block until a byte is actually read.
|
||||
*
|
||||
* Note: the read function does not buffer - data will be lost if the function is not
|
||||
* called fast enough.
|
||||
*
|
||||
* TODO: implement more sophisticated read call.
|
||||
*
|
||||
* @param r TODO
|
||||
* @param fd TODO
|
||||
* @param buffer TODO
|
||||
* @param int TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _read_r(struct _reent *r, int fd, void *buffer, unsigned int count)
|
||||
{
|
||||
char c;
|
||||
char *buff = (char*)buffer;
|
||||
uart_read_blocking(UART_0, &c);
|
||||
buff[0] = c;
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Write characters to a file
|
||||
*
|
||||
* All output is currently directed to UART_0, independent of the given file descriptor.
|
||||
* The write call will further block until the byte is actually written to the UART.
|
||||
*
|
||||
* TODO: implement more sophisticated write call.
|
||||
*
|
||||
* @param r TODO
|
||||
* @param fd TODO
|
||||
* @param data TODO
|
||||
* @param int TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _write_r(struct _reent *r, int fd, const void *data, unsigned int count)
|
||||
{
|
||||
char *c = (char*)data;
|
||||
for (int i = 0; i < count; i++) {
|
||||
uart_write_blocking(UART_0, c[i]);
|
||||
}
|
||||
return count;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Close a file
|
||||
*
|
||||
* @param r TODO
|
||||
* @param fd TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _close_r(struct _reent *r, int fd)
|
||||
{
|
||||
r->_errno = ENODEV; /* not implemented yet */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Set position in a file
|
||||
*
|
||||
* @param r TODO
|
||||
* @param fd TODO
|
||||
* @param pos TODO
|
||||
* @param dir TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
_off_t _lseek_r(struct _reent *r, int fd, _off_t pos, int dir)
|
||||
{
|
||||
r->_errno = ENODEV; /* not implemented yet */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Status of an open file
|
||||
*
|
||||
* @param r TODO
|
||||
* @param fd TODO
|
||||
* @param stat TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _fstat_r(struct _reent *r, int fd, struct stat * st)
|
||||
{
|
||||
r->_errno = ENODEV; /* not implemented yet */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Status of a file (by name)
|
||||
*
|
||||
* @param r TODO
|
||||
* @param name TODO
|
||||
* @param stat TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _stat_r(struct _reent *r, char *name, struct stat *st)
|
||||
{
|
||||
r->_errno = ENODEV; /* not implemented yet */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Query whether output stream is a terminal
|
||||
*
|
||||
* @param r TODO
|
||||
* @param fd TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _isatty_r(struct _reent *r, int fd)
|
||||
{
|
||||
r->_errno = 0;
|
||||
if(fd == STDOUT_FILENO || fd == STDERR_FILENO) {
|
||||
return 1;
|
||||
}
|
||||
else {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Remove a file's directory entry
|
||||
*
|
||||
* @param r TODO
|
||||
* @param path TODO
|
||||
*
|
||||
* @return TODO
|
||||
*/
|
||||
int _unlink_r(struct _reent *r, char* path)
|
||||
{
|
||||
r->_errno = ENODEV; /* not implemented yet */
|
||||
return -1;
|
||||
}
|
@ -142,5 +142,7 @@ void timer_irq_disable(tim_t dev);
|
||||
*/
|
||||
void timer_reset(tim_t dev);
|
||||
|
||||
int timer_set_absolute(tim_t dev, int channel, unsigned int value);
|
||||
|
||||
#endif /* __TIMER_H */
|
||||
/** @} */
|
||||
|
@ -16,3 +16,6 @@ CFLAGS += -DDEVELHELP
|
||||
QUIET ?= 1
|
||||
|
||||
include $(RIOTBASE)/Makefile.include
|
||||
|
||||
reset:
|
||||
$(RIOTBASE)/cpu/$(CPU)/tools/reset.sh
|
||||
|
@ -16,3 +16,6 @@ CFLAGS += -DDEVELHELP
|
||||
QUIET ?= 1
|
||||
|
||||
include $(RIOTBASE)/Makefile.include
|
||||
|
||||
reset:
|
||||
$(RIOTBOARD)/$(BOARD)/dist/reset.sh
|
||||
|
@ -4,3 +4,6 @@ include ../Makefile.tests_common
|
||||
DISABLE_MODULE += auto_init
|
||||
|
||||
include $(RIOTBASE)/Makefile.include
|
||||
|
||||
reset:
|
||||
$(RIOTBOARD)/$(BOARD)/dist/reset.sh
|
||||
|
@ -6,3 +6,6 @@ BOARD_INSUFFICIENT_RAM := stm32f0discovery
|
||||
DISABLE_MODULE += auto_init
|
||||
|
||||
include $(RIOTBASE)/Makefile.include
|
||||
|
||||
reset:
|
||||
$(RIOTCPU)/$(CPU)/tools/reset.sh
|
||||
|
Loading…
Reference in New Issue
Block a user