1
0
mirror of https://github.com/RIOT-OS/RIOT.git synced 2024-12-29 04:50:03 +01:00

boards: initial import of iot-lab_M3

This commit is contained in:
Thomas Eichinger 2014-07-03 10:36:46 +02:00
parent 37611db41c
commit aaa2c2e8ba
42 changed files with 1083 additions and 1630 deletions

View File

@ -1,3 +1,4 @@
ifneq (,$(findstring at86rf231,$(USEMODULE)))
USEMODULE += at86rf231
ifneq (,$(filter defaulttransceiver,$(USEMODULE)))
USEMODULE += at86rf231
USEMODULE += transceiver
endif

View File

@ -3,7 +3,7 @@ export CPU = stm32f1
export CPU_MODEL = stm32f103re
# set the default port
export PORT ?= /dev/ttyUSB2
export PORT ?= /dev/ttyUSB0
# define tools used for building the project
export PREFIX = arm-none-eabi-
@ -21,14 +21,14 @@ export DEBUGGER = $(RIOTBOARD)/$(BOARD)/dist/debug.sh
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 CFLAGS += -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
export FFLAGS = $(HEXFILE)
export DEBUGGER_FLAGS = $(ELFFILE)
# 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)
@ -36,15 +36,6 @@ export LINKFLAGS += -specs=nano.specs -lc -lnosys
endif
# export board specific includes to the global includes-listing
export INCLUDES += -I$(RIOTBOARD)/$(BOARD)/include/
export INCLUDES += -I$(RIOTBOARD)/$(BOARD)/include/ -I$(RIOTBASE)/drivers/at86rf231/include -I$(RIOTBASE)/sys/net/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
include $(RIOTBOARD)/$(BOARD)/Makefile.dep

View File

@ -13,7 +13,7 @@
* @file board.c
* @brief Board specific implementations for the iot-lab_M3 board
*
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
*
* @}
*/
@ -53,13 +53,13 @@ static void leds_init(void)
{
/* green pin */
RCC->APB2ENR |= RCC_APB2ENR_IOPBEN;
GPIOB->CRL = (0x3 << (5*4));
LED_GREEN_PORT->CRL = (0x3 << (LED_GREEN_PIN*4));
/* orange pin */
RCC->APB2ENR |= RCC_APB2ENR_IOPCEN;
GPIOC->CRH = (0x3 << ((10-8)*4));
LED_ORANGE_PORT->CRH = (0x3 << ((LED_ORANGE_PIN-8)*4));
/* red pin */
RCC->APB2ENR |= RCC_APB2ENR_IOPDEN;
GPIOD->CRL = (0x3 << (2*4));
LED_RED_PORT->CRL = (0x3 << (LED_RED_PIN*4));
}

File diff suppressed because it is too large Load Diff

View File

@ -10,8 +10,8 @@ BIN_FOLDER=$(dirname "${FILE}")
openocd -f "${BIN_FOLDER}/${BOARD}_jtag.cfg" \
-f "target/stm32f1x.cfg" \
-c "tcl_port 6333"
-c "telnet_port 4444"
-c "tcl_port 6333" \
-c "telnet_port 4444" \
-c "init" \
-c "targets" \
-c "reset halt"

View File

@ -1,7 +1,7 @@
#!/bin/bash
if [ -L "$0" ]; then
FILE=$(readlink "$0")
FILE=$(readlink -e "$0")
else
FILE="$0"
fi

View File

@ -8,7 +8,7 @@ fi
BIN_FOLDER=$(dirname "${FILE}")
openocd -f "${BIN_FOLDER}/iot-lab_m3_jtag.cfg" \
openocd -f "${BIN_FOLDER}/${BOARD}_jtag.cfg" \
-f "target/stm32f1x.cfg" \
-c "init" \
-c "reset run" \

View File

@ -1,34 +1,5 @@
SRC = $(wildcard *.c)
#BINDIR = $(RIOTBOARD)/$(BOARD)/bin/
OBJ = $(SRC:%.c=$(BINDIR)%.o)
DEP = $(SRC:%.c=$(BINDIR)%.d)
MODULE =$(BOARD)_base
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
include $(RIOTBOARD)/$(BOARD)/Makefile.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)
include $(RIOTBASE)/Makefile.base

View File

@ -1,19 +1,36 @@
/*
* 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 at86rf231_driver.c
* @brief Board specific implementations for the at86rf231 radio driver
*
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
*
* @}
*/
#include <stdio.h>
#include <stddef.h>
#include "cpu.h"
#include "sched.h"
#include "vtimer.h"
#include "arch/thread_arch.h"
#include "periph/gpio.h"
#include "spi.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
@ -29,25 +46,25 @@ GPIO
SLEEP : PA2 : control sleep, tx & rx state
*/
inline static void RESET_CLR(void)
static inline void RESET_CLR(void)
{
GPIOC->BRR = 1 << 1;
SPI_0_RESET_PORT->BRR = (1 << SPI_0_RESET_PIN);
}
inline static void RESET_SET(void)
static inline void RESET_SET(void)
{
GPIOC->BSRR = 1 << 1;
SPI_0_RESET_PORT->BSRR = (1 << SPI_0_RESET_PIN);
}
inline static void CSn_SET(void)
static inline void CSn_SET(void)
{
GPIOA->BSRR = 1 << 4;
SPI_0_CS_PORT->BSRR = (1 << SPI_0_CS_PIN);
}
inline static void CSn_CLR(void)
static inline void CSn_CLR(void)
{
GPIOA->BRR = 1 << 4;
SPI_0_CS_PORT->BRR = (1 << SPI_0_CS_PIN);
}
inline static void SLEEP_CLR(void)
static inline void SLEEP_CLR(void)
{
GPIOA->BRR = 1 << 2;
SPI_0_SLEEP_PORT->BRR = (1 << SPI_0_SLEEP_PIN);
}
uint8_t at86rf231_get_status(void)
@ -57,82 +74,46 @@ uint8_t at86rf231_get_status(void)
}
extern void at86rf231_rx_irq(void);
static
void enable_exti_interrupt(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
gpio_irq_enable(SPI_0_IRQ0_GPIO);
}
static void disable_exti_interrupt(void)
{
gpio_irq_disable(SPI_0_IRQ0_GPIO);
}
void at86rf231_gpio_spi_interrupts_init(void)
{
/* SPI1 init */
at86rf231_spi1_init();
/* set up GPIO pins */
/* SCLK and MOSI*/
GPIOA->CRL &= ~(0xf << (5 * 4));
GPIOA->CRL |= (0xb << (5 * 4));
GPIOA->CRL &= ~(0xf << (7 * 4));
GPIOA->CRL |= (0xb << (7 * 4));
/* MISO */
gpio_init_in(SPI_0_MISO_GPIO, GPIO_NOPULL);
/* IRQ0 : PC4, INPUT and IRQ */
// RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE);
/* SPI init */
spi_init_master(SPI_0, SPI_CONF_FIRST_RISING, 4500000);
// 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);
spi_poweron(SPI_0);
/* Enable AFIO clock */
// RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
/* IRQ0 */
gpio_init_in(SPI_0_IRQ0_GPIO, GPIO_NOPULL);
gpio_init_int(SPI_0_IRQ0_GPIO, GPIO_NOPULL, GPIO_RISING, at86rf231_rx_irq);
/* 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);
/* CS */
gpio_init_out(SPI_0_CS_GPIO, GPIO_NOPULL);
/* SLEEP */
gpio_init_out(SPI_0_SLEEP_GPIO, GPIO_NOPULL);
/* RESET */
// RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE);
gpio_init_out(SPI_0_RESET_GPIO, GPIO_NOPULL);
// 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)
@ -165,17 +146,18 @@ void at86rf231_reset(void)
vtimer_usleep(10);
if (!--max_wait) {
printf("at86rf231 : ERROR : could not enter TRX_OFF mode");
printf("at86rf231 : ERROR : could not enter TRX_OFF mode\n");
break;
}
}
while ((status & AT86RF231_TRX_STATUS_MASK__TRX_STATUS) != AT86RF231_TRX_STATUS__TRX_OFF);
} 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();
@ -185,28 +167,8 @@ 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();
// }

View File

@ -1,66 +1,45 @@
#include <stdio.h>
#include <stddef.h>
/*
* 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 at86rf231_spi1.c
* @brief Board specific implementations for the at86rf231 SPI interface
*
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
*
* @}
*/
#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;
/*
SPI1
SCLK : PA5
MISO : PA6
MOSI : PA7
CS : PA4
/* 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);
}
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
*/
uint8_t at86rf231_spi_transfer_byte(uint8_t byte)
{
char ret;
spi_transfer_byte(SPI_0, byte?byte:0, byte?0:&ret );
spi_transfer_byte(SPI_0, byte, &ret);
return ret;
}

View File

@ -1,22 +0,0 @@
/**
* 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;
}

View File

@ -1,6 +0,0 @@
#ifndef AT86RF231_SPI1_H_
#define AT86RF231_SPI1_H_
void at86rf231_spi1_init(void);
#endif

View File

@ -1,8 +1,8 @@
/*
* Copyright (C) 2014 Thomas Eichinger <thomas.eichinger@fu-berlin.de>
* 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
* Public License v2.1. See the file LICENSE in the top level directory for more
* details.
*/
@ -50,29 +50,29 @@
* @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)
#define LED_RED_PORT (GPIOD)
#define LED_RED_PIN (2)
#define LED_GREEN_PORT (GPIOB)
#define LED_GREEN_PIN (5)
#define LED_ORANGE_PORT (GPIOC)
#define LED_ORANGE_PIN (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_RED_ON (LED_RED_PORT->ODR &= ~(1<<LED_RED_PIN))
#define LED_RED_OFF (LED_RED_PORT->ODR |= (1<<LED_RED_PIN))
#define LED_RED_TOGGLE (LED_RED_PORT->ODR ^= (1<<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_GREEN_ON (LED_GREEN_PORT->ODR &= ~(1<<LED_GREEN_PIN))
#define LED_GREEN_OFF (LED_GREEN_PORT->ODR |= (1<<LED_GREEN_PIN))
#define LED_GREEN_TOGGLE (LED_GREEN_PORT->ODR ^= (1<<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 LED_ORANGE_ON (LED_ORANGE_PORT->ODR &= ~(1<<LED_ORANGE_PIN))
#define LED_ORANGE_OFF (LED_ORANGE_PORT->ODR |= (1<<LED_ORANGE_PIN))
#define LED_ORANGE_TOGGLE (LED_ORANGE_PORT->ODR ^= (1<<LED_ORANGE_PIN))
/** @} */
/**

View File

@ -2,7 +2,7 @@
* 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
* Public License v2.1. See the file LICENSE in the top level directory for more
* details.
*/
@ -24,7 +24,7 @@
*/
#define TIMER_NUMOF (2U)
#define TIMER_0_EN 1
#define TIMER_1_EN 2
#define TIMER_1_EN 1
/* Timer 0 configuration */
#define TIMER_0_DEV TIM2
@ -60,6 +60,7 @@
#define UART_0_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_USART1EN)
#define UART_0_IRQ USART1_IRQn
#define UART_0_ISR isr_usart1
#define UART_0_BUS_FREQ 72000000
/* UART 0 pin configuration */
#define UART_0_PORT GPIOA
#define UART_0_PORT_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPAEN)
@ -72,6 +73,7 @@
#define UART_1_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_USART2EN)
#define UART_1_IRQ USART2_IRQn
#define UART_1_ISR isr_usart2
#define UART_1_BUS_FREQ 36000000
/* UART 1 pin configuration */
#define UART_1_PORT GPIOA
#define UART_1_PORT_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPAEN)
@ -82,7 +84,7 @@
/**
* @brief GPIO configuration
*/
#define GPIO_NUMOF 12
#define GPIO_NUMOF 16
#define GPIO_0_EN 1
#define GPIO_1_EN 1
#define GPIO_2_EN 1
@ -95,6 +97,10 @@
#define GPIO_9_EN 1
#define GPIO_10_EN 1
#define GPIO_11_EN 1
#define GPIO_12_EN 1
#define GPIO_13_EN 1
#define GPIO_14_EN 1
#define GPIO_15_EN 0 /* not configured */
#define GPIO_IRQ_PRIO 1
/* IRQ config */
@ -110,83 +116,123 @@
#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_12 GPIO_4
#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_PIN 3
#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
#define GPIO_0_EXTI_CFG() (AFIO->EXTICR[0] |= AFIO_EXTICR1_EXTI3_PA)
#define GPIO_0_EXTI_LINE 4
#define GPIO_0_IRQ EXTI4_IRQn
/* GPIO channel 1 config */
#define GPIO_1_PORT GPIOA
#define GPIO_1_PIN 1
#define GPIO_1_PIN 8
#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
#define GPIO_1_EXTI_CFG() (AFIO->EXTICR[2] |= AFIO_EXTICR3_EXTI8_PA)
#define GPIO_1_EXTI_LINE 4
#define GPIO_1_IRQ EXTI4_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_PORT GPIOA
#define GPIO_2_PIN 12
#define GPIO_2_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPAEN)
#define GPIO_2_EXTI_CFG() (AFIO->EXTICR[3] |= AFIO_EXTICR4_EXTI12_PA)
#define GPIO_2_EXTI_LINE 4
#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_PORT GPIOB
#define GPIO_3_PIN 8
#define GPIO_3_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPBEN)
#define GPIO_3_EXTI_CFG() (AFIO->EXTICR[2] |= AFIO_EXTICR3_EXTI8_PB)
#define GPIO_3_EXTI_LINE 4
#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_PORT GPIOB
#define GPIO_4_PIN 9
#define GPIO_4_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPBEN)
#define GPIO_4_EXTI_CFG() (AFIO->EXTICR[2] |= AFIO_EXTICR3_EXTI9_PB)
#define GPIO_4_EXTI_LINE 4
#define GPIO_4_IRQ EXTI4_IRQn
/* GPIO channel 5 config */
#define GPIO_5_PORT GPIOF
#define GPIO_5_PORT GPIOC
#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_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPCEN)
#define GPIO_5_EXTI_CFG() (AFIO->EXTICR[1] |= AFIO_EXTICR2_EXTI7_PC)
#define GPIO_5_EXTI_LINE 4
#define GPIO_5_IRQ EXTI4_IRQn
/* GPIO channel 6 config */
#define GPIO_6_PORT GPIOC
#define GPIO_6_PIN 4
#define GPIO_6_PIN 8
#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_EXTI_CFG() (AFIO->EXTICR[2] |= AFIO_EXTICR3_EXTI8_PC)
#define GPIO_6_EXTI_LINE 4
#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_EXTI_CFG() (AFIO->EXTICR[2] |= AFIO_EXTICR3_EXTI11_PC)
#define GPIO_7_EXTI_LINE 4
#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
#define GPIO_8_PORT GPIOA
#define GPIO_8_PIN 5
#define GPIO_8_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPAEN)
#define GPIO_8_EXTI_CFG() (AFIO->EXTICR[1] |= AFIO_EXTICR2_EXTI5_PA)
#define GPIO_8_EXTI_LINE 4
#define GPIO_8_IRQ EXTI4_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
#define GPIO_9_PORT GPIOA
#define GPIO_9_PIN 6
#define GPIO_9_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPAEN)
#define GPIO_9_EXTI_CFG() (AFIO->EXTICR[1] |= AFIO_EXTICR2_EXTI6_PA)
#define GPIO_9_EXTI_LINE 4
#define GPIO_9_IRQ EXTI4_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
#define GPIO_10_PORT GPIOA
#define GPIO_10_PIN 7
#define GPIO_10_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPAEN)
#define GPIO_10_EXTI_CFG() (AFIO->EXTICR[1] |= AFIO_EXTICR2_EXTI7_PA)
#define GPIO_10_EXTI_LINE 4
#define GPIO_10_IRQ EXTI4_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
#define GPIO_11_PORT GPIOA
#define GPIO_11_PIN 4
#define GPIO_11_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPAEN)
#define GPIO_11_EXTI_CFG() (AFIO->EXTICR[1] |= AFIO_EXTICR2_EXTI4_PA)
#define GPIO_11_EXTI_LINE 4
#define GPIO_11_IRQ EXTI4_IRQn
/* GPIO channel 12 config */
#define GPIO_12_PORT GPIOC
#define GPIO_12_PIN 4
#define GPIO_12_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPCEN)
#define GPIO_12_EXTI_CFG() (AFIO->EXTICR[1] |= AFIO_EXTICR2_EXTI4_PC)
#define GPIO_12_EXTI_LINE 4
#define GPIO_12_IRQ EXTI4_IRQn
/* GPIO channel 13 config */
#define GPIO_13_PORT GPIOC
#define GPIO_13_PIN 1
#define GPIO_13_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPCEN)
#define GPIO_13_EXTI_CFG() (AFIO->EXTICR[0] |= AFIO_EXTICR1_EXTI1_PC)
#define GPIO_13_EXTI_LINE 4
#define GPIO_13_IRQ EXTI4_IRQn
/* GPIO channel 14 config */
#define GPIO_14_PORT GPIOA
#define GPIO_14_PIN 2
#define GPIO_14_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPAEN)
#define GPIO_14_EXTI_CFG() (AFIO->EXTICR[0] |= AFIO_EXTICR1_EXTI2_PA)
#define GPIO_14_EXTI_LINE 4
#define GPIO_14_IRQ EXTI4_IRQn
/* GPIO channel 15 config */
#define GPIO_15_PORT GPIOC
#define GPIO_15_PIN 15
#define GPIO_15_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPCEN)
#define GPIO_15_EXTI_CFG() (AFIO->EXTICR[3] |= AFIO_EXTICR4_EXTI15_PC)
#define GPIO_15_EXTI_LINE 4
#define GPIO_15_IRQ EXTI4_IRQn
/**
* @brief SPI configuration
@ -194,14 +240,43 @@
#define SPI_NUM_OF 1
#define SPI_0_EN 1
#define SPI_0_DEV SPI1
#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
#define SPI_0_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_SPI1EN)
#define SPI_0_CLKDIS() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI1EN))
#define SPI_0_SCLK_GPIO GPIO_8
#define SPI_0_SCLK_PIN GPIO_8_PIN
#define SPI_0_SCLK_PORT GPIO_8_PORT
#define SPI_0_MISO_GPIO GPIO_9
#define SPI_0_MISO_PIN GPIO_9_PIN
#define SPI_0_MISO_PORT GPIO_9_PORT
#define SPI_0_MOSI_GPIO GPIO_10
#define SPI_0_MOSI_PIN GPIO_10_PIN
#define SPI_0_MOSI_PORT GPIO_10_PORT
#define SPI_0_CS_GPIO GPIO_11
#define SPI_0_CS_PIN GPIO_11_PIN
#define SPI_0_CS_PORT GPIO_11_PORT
#define SPI_0_IRQ0_GPIO GPIO_12
#define SPI_0_IRQ0_PIN GPIO_12_PIN
#define SPI_0_IRQ0_PORT GPIO_12_PORT
#define SPI_0_RESET_GPIO GPIO_13
#define SPI_0_RESET_PIN GPIO_13_PIN
#define SPI_0_RESET_PORT GPIO_13_PORT
#define SPI_0_SLEEP_GPIO GPIO_14
#define SPI_0_SLEEP_PIN GPIO_14_PIN
#define SPI_0_SLEEP_PORT GPIO_14_PORT
#define SPI_2_LINES_FULL_DUPLEX (0x0000)
#define SPI_MASTER_MODE (0x0104)
#define SPI_DATA_SIZE_8B (0x0000)
#define SPI_CPOL_LOW (0x0000)
#define SPI_CPHA_1_EDGE (0x0000)
#define SPI_NSS_SOFT (0x0200)
#define SPI_BR_PRESCALER_16 (0x0018)
#define SPI_1ST_BIT_MSB (0x0000)
#endif /* __PERIPH_CONF_H */
/** @} */

View File

@ -0,0 +1,128 @@
/*
* 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 system_stm32f1.c
* @brief Board specific clock setup
*
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
*
* @}
*/
#include "stm32f10x.h"
#include "board.h"
uint32_t SystemCoreClock = F_CPU;
#define VECT_TAB_OFFSET 0x0
static void set_system_clock(void)
{
volatile uint32_t startup_counter = 0, HSE_status = 0;
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration */
/* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do {
HSE_status = RCC->CR & RCC_CR_HSERDY;
startup_counter++;
}
while ((HSE_status == 0) && (startup_counter != HSE_STARTUP_TIMEOUT));
if ((RCC->CR & RCC_CR_HSERDY) != RESET) {
HSE_status = (uint32_t)0x01;
}
else {
HSE_status = (uint32_t)0x00;
}
if (HSE_status == (uint32_t)0x01) {
/* Enable Prefetch Buffer */
FLASH->ACR |= FLASH_ACR_PRFTBE;
/* Flash 2 wait state */
FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2;
/* HCLK = SYSCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
/* PCLK2 = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
/* PCLK1 = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
/* NOTE : agilefox : modified to take into account the 16MHz
crystal instead of 8MHz */
/* PLL configuration: PLLCLK = HSE / 2 * 9 = 72 MHz */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC
| RCC_CFGR_PLLXTPRE
| RCC_CFGR_PLLMULL));
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE
| RCC_CFGR_PLLXTPRE_HSE_Div2
| RCC_CFGR_PLLMULL9);
/* Enable PLL */
RCC->CR |= RCC_CR_PLLON;
/* Wait till PLL is ready */
while ((RCC->CR & RCC_CR_PLLRDY) == 0) {
}
/* Select PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
/* Wait till PLL is used as system clock source */
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08) {
}
}
else {
/* If HSE fails to start-up, the application will have wrong clock
configuration. User can add here some code to deal with this error */
}
}
void SystemInit(void)
{
/* Reset the RCC clock configuration to the default reset state(for debug purpose) */
/* Set HSION bit */
RCC->CR |= (uint32_t)0x00000001;
/* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */
RCC->CFGR &= (uint32_t)0xF0FF0000;
/* Reset HSEON, CSSON and PLLON bits */
RCC->CR &= (uint32_t)0xFEF6FFFF;
/* Reset HSEBYP bit */
RCC->CR &= (uint32_t)0xFFFBFFFF;
/* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */
RCC->CFGR &= (uint32_t)0xFF80FFFF;
/* Disable all interrupts and clear pending bits */
RCC->CIR = 0x009F0000;
/* Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers */
/* Configure the Flash Latency cycles and enable prefetch buffer */
set_system_clock();
/* Vector Table Relocation in Internal FLASH. */
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET;
}

View File

@ -11,7 +11,7 @@
* @{
*
* @file
* @brief CMSIS system header definitions for the Cortex-M0
* @brief CMSIS system header definitions for the Cortex-M3
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*/

View File

@ -7,10 +7,10 @@
*/
/**
* @ingroup cpu_cortexm4_common
* @ingroup cpu_cortex-m3
* @{
*
* @file
* @file thread_arch.c
* @brief Implementation of the kernel's architecture dependent thread interface
*
* @author Stefan Pfeiffer <stefan.pfeiffer@fu-berlin.de>
@ -25,7 +25,6 @@
#include "arch/thread_arch.h"
#include "thread.h"
#include "sched.h"
#include "thread.h"
#include "irq.h"
#include "cpu.h"
#include "kernel_internal.h"
@ -47,14 +46,7 @@ static void context_save(void);
static void context_restore(void) NORETURN;
/**
* 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 |
* ------------------------------------------------------------------------------------------------------------------------------------
* Cortex-M3 knows stacks and handles register backups, so use different stack frame layout
*
* Layout without floating point registers:
* --------------------------------------
@ -69,37 +61,23 @@ char *thread_arch_stack_init(void *(*task_func)(void *), void *arg, void *stack_
/* marker */
stk--;
*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;
}
*/
*stk = (uint32_t)STACK_MARKER;
/* FIXME xPSR */
stk--;
*stk = (unsigned int) 0x01000200;
*stk = (uint32_t)0x01000200;
/* program counter */
stk--;
*stk = (unsigned int) task_func;
*stk = (uint32_t)task_func;
/* link register, jumped to when thread exits */
stk--;
*stk = (unsigned int) sched_task_exit;
*stk = (uint32_t)sched_task_exit;
/* r12 */
stk--;
*stk = (unsigned int) 0;
*stk = (uint32_t) 0;
/* r1 - r3 */
for (int i = 3; i >= 1; i--) {

View File

@ -1,67 +0,0 @@
/*
* 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();
}

View File

@ -11,7 +11,7 @@
* @ingroup cpu_stm32f1
* @{
*
* @file
* @file cpu.c
* @brief Implementation of the kernel cpu functions
*
* @author Stefan Pfeiffer <stefan.pfeiffer@fu-berlin.de>

View File

@ -10,7 +10,7 @@
* @ingroup cpu_stm32f1
* @{
*
* @file
* @file hwtimer_arch.c
* @brief Implementation of the kernels hwtimer interface
*
* The hardware timer implementation uses the Coretex build-in system timer as backend.
@ -20,7 +20,7 @@
* @}
*/
#include "hwtimer_arch.h"
#include "arch/hwtimer_arch.h"
#include "thread.h"
#include "board.h"
#include "periph/timer.h"
@ -72,5 +72,4 @@ unsigned long hwtimer_arch_now(void)
void irq_handler(int channel)
{
timeout_handler((short)channel);
thread_yield();
}

View File

@ -31,13 +31,13 @@
* TODO: measure and adjust for the cortex-m3
* @{
*/
#define KERNEL_CONF_STACKSIZE_PRINTF (2500)
#define KERNEL_CONF_STACKSIZE_PRINTF (1024)
#ifndef KERNEL_CONF_STACKSIZE_DEFAULT
#define KERNEL_CONF_STACKSIZE_DEFAULT (2500)
#define KERNEL_CONF_STACKSIZE_DEFAULT (1024)
#endif
#define KERNEL_CONF_STACKSIZE_IDLE (512)
#define KERNEL_CONF_STACKSIZE_IDLE (256)
/** @} */
/**
@ -69,5 +69,7 @@ typedef enum {
void cpu_clock_scale(uint32_t source, uint32_t target, uint32_t *prescale);
#define TRANSCEIVER_BUFFER_SIZE (3)
#endif /* __CPU_CONF_H */
/** @} */

View File

@ -2,12 +2,12 @@
* 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
* Public License v2.1. See the file LICENSE in the top level directory for more
* details.
*/
/**
* @ingroup cpu_stm32f0
* @ingroup cpu_stm32f1
* @{
*
* @file hwtimer_cpu.h

View File

@ -2,7 +2,7 @@
* 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
* Public License v2.1. See the file LICENSE in the top level directory for more
* details.
*/
@ -10,7 +10,7 @@
* @ingroup cpu_stm32f1
* @{
*
* @file
* @file io_arch.c
* @brief Implementation of the kernel's architecture dependent IO interface
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>

View File

@ -3,7 +3,7 @@
* 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
* Public License v2.1. See the file LICENSE in the top level directory for more
* details.
*/
@ -11,7 +11,7 @@
* @ingroup cpu_stm32f1
* @{
*
* @file
* @file lpm_arch.c
* @brief Implementation of the kernel's lpm interface
*
* @author Alaeddine Weslati <alaeddine.weslati@inria.fr>

View File

@ -10,7 +10,7 @@
* @ingroup cpu_stm32f1
* @{
*
* @file
* @file gpio.c
* @brief Low-level GPIO driver implementation
*
* @author Hauke Petersen <mail@haukepetersen.de>
@ -20,8 +20,15 @@
*/
#include "cpu.h"
#include "stm32f10x.h"
#include "periph/gpio.h"
#include "periph_conf.h"
#include "board.h"
#include "thread.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
typedef struct {
void (*cb)(void);
@ -119,6 +126,35 @@ int gpio_init_out(gpio_t dev, gpio_pp_t pullup)
pin = GPIO_11_PIN;
break;
#endif
#ifdef GPIO_12_EN
case GPIO_12:
GPIO_12_CLKEN();
port = GPIO_12_PORT;
pin = GPIO_12_PIN;
break;
#endif
#ifdef GPIO_13_EN
case GPIO_13:
GPIO_13_CLKEN();
port = GPIO_13_PORT;
pin = GPIO_13_PIN;
break;
#endif
#ifdef GPIO_14_EN
case GPIO_14:
GPIO_14_CLKEN();
port = GPIO_14_PORT;
pin = GPIO_14_PIN;
break;
#endif
#ifdef GPIO_15_EN
case GPIO_15:
GPIO_15_CLKEN();
port = GPIO_15_PORT;
pin = GPIO_15_PIN;
break;
#endif
case GPIO_UNDEFINED:
default:
return -1;
@ -128,13 +164,11 @@ int gpio_init_out(gpio_t dev, gpio_pp_t pullup)
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 */
@ -229,6 +263,34 @@ int gpio_init_in(gpio_t dev, gpio_pp_t pullup)
port = GPIO_11_PORT;
pin = GPIO_11_PIN;
break;
#endif
#ifdef GPIO_12_EN
case GPIO_12:
GPIO_12_CLKEN();
port = GPIO_12_PORT;
pin = GPIO_12_PIN;
break;
#endif
#ifdef GPIO_13_EN
case GPIO_13:
GPIO_13_CLKEN();
port = GPIO_13_PORT;
pin = GPIO_13_PIN;
break;
#endif
#ifdef GPIO_14_EN
case GPIO_14:
GPIO_14_CLKEN();
port = GPIO_14_PORT;
pin = GPIO_14_PIN;
break;
#endif
#ifdef GPIO_15_EN
case GPIO_15:
GPIO_15_CLKEN();
port = GPIO_15_PORT;
pin = GPIO_15_PIN;
break;
#endif
case GPIO_UNDEFINED:
default:
@ -237,9 +299,11 @@ int gpio_init_in(gpio_t dev, gpio_pp_t pullup)
if (pin < 8) {
port->CRL &= ~(0xf << (4 * pin));
port->CRL |= (0x4 << (4 * pin));
}
else {
port->CRH &= ~(0xf << (4 * (pin-8)));
port->CRL &= ~(0xf << (4 * pin));
port->CRH |= (0x4 << (4 * (pin-8)));
}
return 0; /* everything alright here */
@ -248,7 +312,8 @@ int gpio_init_in(gpio_t dev, gpio_pp_t pullup)
int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, void (*cb)(void))
{
int res;
uint32_t pin;
uint8_t exti_line;
uint8_t gpio_irq;
/* configure pin as input */
res = gpio_init_in(dev, pullup);
@ -262,14 +327,14 @@ int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, void (*cb)(v
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;
RCC->APB2ENR |= RCC_APB2ENR_AFIOEN;
/* read pin number, set EXIT channel and enable global interrupt for EXTI channel */
/* read pin number, set EXTI channel and enable global interrupt for EXTI channel */
switch (dev) {
#ifdef GPIO_0_EN
case GPIO_0:
pin = GPIO_0_PIN;
exti_line = GPIO_0_EXTI_LINE;
gpio_irq = GPIO_IRQ_0;
GPIO_0_EXTI_CFG();
NVIC_SetPriority(GPIO_0_IRQ, GPIO_IRQ_PRIO);
NVIC_EnableIRQ(GPIO_0_IRQ);
@ -277,7 +342,8 @@ int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, void (*cb)(v
#endif
#ifdef GPIO_1_EN
case GPIO_1:
pin = GPIO_1_PIN;
exti_line = GPIO_1_EXTI_LINE;
gpio_irq = GPIO_IRQ_1;
GPIO_1_EXTI_CFG();
NVIC_SetPriority(GPIO_1_IRQ, GPIO_IRQ_PRIO);
NVIC_EnableIRQ(GPIO_1_IRQ);
@ -285,7 +351,8 @@ int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, void (*cb)(v
#endif
#ifdef GPIO_2_EN
case GPIO_2:
pin = GPIO_2_PIN;
exti_line = GPIO_2_EXTI_LINE;
gpio_irq = GPIO_IRQ_2;
GPIO_2_EXTI_CFG();
NVIC_SetPriority(GPIO_2_IRQ, GPIO_IRQ_PRIO);
NVIC_EnableIRQ(GPIO_2_IRQ);
@ -293,7 +360,8 @@ int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, void (*cb)(v
#endif
#ifdef GPIO_3_EN
case GPIO_3:
pin = GPIO_3_PIN;
exti_line = GPIO_3_EXTI_LINE;
gpio_irq = GPIO_IRQ_3;
GPIO_3_EXTI_CFG();
NVIC_SetPriority(GPIO_3_IRQ, GPIO_IRQ_PRIO);
NVIC_EnableIRQ(GPIO_3_IRQ);
@ -301,7 +369,8 @@ int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, void (*cb)(v
#endif
#ifdef GPIO_4_EN
case GPIO_4:
pin = GPIO_4_PIN;
exti_line = GPIO_4_EXTI_LINE;
gpio_irq = GPIO_IRQ_4;
GPIO_4_EXTI_CFG();
NVIC_SetPriority(GPIO_4_IRQ, GPIO_IRQ_PRIO);
NVIC_EnableIRQ(GPIO_4_IRQ);
@ -309,7 +378,8 @@ int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, void (*cb)(v
#endif
#ifdef GPIO_5_EN
case GPIO_5:
pin = GPIO_5_PIN;
exti_line = GPIO_5_EXTI_LINE;
gpio_irq = GPIO_IRQ_5;
GPIO_5_EXTI_CFG();
NVIC_SetPriority(GPIO_5_IRQ, GPIO_IRQ_PRIO);
NVIC_EnableIRQ(GPIO_5_IRQ);
@ -317,7 +387,8 @@ int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, void (*cb)(v
#endif
#ifdef GPIO_6_EN
case GPIO_6:
pin = GPIO_6_PIN;
exti_line = GPIO_6_EXTI_LINE;
gpio_irq = GPIO_IRQ_6;
GPIO_6_EXTI_CFG();
NVIC_SetPriority(GPIO_6_IRQ, GPIO_IRQ_PRIO);
NVIC_EnableIRQ(GPIO_6_IRQ);
@ -325,7 +396,8 @@ int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, void (*cb)(v
#endif
#ifdef GPIO_7_EN
case GPIO_7:
pin = GPIO_7_PIN;
exti_line = GPIO_7_EXTI_LINE;
gpio_irq = GPIO_IRQ_7;
GPIO_7_EXTI_CFG();
NVIC_SetPriority(GPIO_7_IRQ, GPIO_IRQ_PRIO);
NVIC_EnableIRQ(GPIO_7_IRQ);
@ -333,7 +405,8 @@ int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, void (*cb)(v
#endif
#ifdef GPIO_8_EN
case GPIO_8:
pin = GPIO_8_PIN;
exti_line = GPIO_8_EXTI_LINE;
gpio_irq = GPIO_IRQ_8;
GPIO_8_EXTI_CFG();
NVIC_SetPriority(GPIO_8_IRQ, GPIO_IRQ_PRIO);
NVIC_EnableIRQ(GPIO_8_IRQ);
@ -341,7 +414,8 @@ int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, void (*cb)(v
#endif
#ifdef GPIO_9_EN
case GPIO_9:
pin = GPIO_9_PIN;
exti_line = GPIO_9_EXTI_LINE;
gpio_irq = GPIO_IRQ_9;
GPIO_9_EXTI_CFG();
NVIC_SetPriority(GPIO_9_IRQ, GPIO_IRQ_PRIO);
NVIC_EnableIRQ(GPIO_9_IRQ);
@ -349,7 +423,8 @@ int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, void (*cb)(v
#endif
#ifdef GPIO_10_EN
case GPIO_10:
pin = GPIO_10_PIN;
exti_line = GPIO_10_EXTI_LINE;
gpio_irq = GPIO_IRQ_10;
GPIO_10_EXTI_CFG();
NVIC_SetPriority(GPIO_10_IRQ, GPIO_IRQ_PRIO);
NVIC_EnableIRQ(GPIO_10_IRQ);
@ -357,11 +432,48 @@ int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, void (*cb)(v
#endif
#ifdef GPIO_11_EN
case GPIO_11:
pin = GPIO_11_PIN;
exti_line = GPIO_11_EXTI_LINE;
gpio_irq = GPIO_IRQ_11;
GPIO_11_EXTI_CFG();
NVIC_SetPriority(GPIO_11_IRQ, GPIO_IRQ_PRIO);
NVIC_EnableIRQ(GPIO_11_IRQ);
break;
#endif
#ifdef GPIO_12_EN
case GPIO_12:
exti_line = GPIO_12_EXTI_LINE;
gpio_irq = GPIO_IRQ_12;
GPIO_12_EXTI_CFG();
NVIC_SetPriority(GPIO_12_IRQ, GPIO_IRQ_PRIO);
NVIC_EnableIRQ(GPIO_12_IRQ);
break;
#endif
#ifdef GPIO_13_EN
case GPIO_13:
exti_line = GPIO_13_EXTI_LINE;
gpio_irq = GPIO_IRQ_13;
GPIO_13_EXTI_CFG();
NVIC_SetPriority(GPIO_13_IRQ, GPIO_IRQ_PRIO);
NVIC_EnableIRQ(GPIO_13_IRQ);
break;
#endif
#ifdef GPIO_14_EN
case GPIO_14:
exti_line = GPIO_14_EXTI_LINE;
gpio_irq = GPIO_IRQ_14;
GPIO_14_EXTI_CFG();
NVIC_SetPriority(GPIO_14_IRQ, GPIO_IRQ_PRIO);
NVIC_EnableIRQ(GPIO_14_IRQ);
break;
#endif
#ifdef GPIO_15_EN
case GPIO_15:
exti_line = GPIO_15_EXTI_LINE;
gpio_irq = GPIO_IRQ_15;
GPIO_15_EXTI_CFG();
NVIC_SetPriority(GPIO_15_IRQ, GPIO_IRQ_PRIO);
NVIC_EnableIRQ(GPIO_15_IRQ);
break;
#endif
case GPIO_UNDEFINED:
default:
@ -369,30 +481,229 @@ int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, void (*cb)(v
}
/* set callback */
config[dev].cb = cb;
config[gpio_irq].cb = cb;
/* configure the event that triggers an interrupt */
switch (flank) {
case GPIO_RISING:
EXTI->RTSR |= (1 << pin);
EXTI->FTSR &= ~(1 << pin);
EXTI->RTSR |= (1 << exti_line);
EXTI->FTSR &= ~(1 << exti_line);
break;
case GPIO_FALLING:
EXTI->RTSR &= ~(1 << pin);
EXTI->FTSR |= (1 << pin);
EXTI->RTSR &= ~(1 << exti_line);
EXTI->FTSR |= (1 << exti_line);
break;
case GPIO_BOTH:
EXTI->RTSR |= (1 << pin);
EXTI->FTSR |= (1 << pin);
EXTI->RTSR |= (1 << exti_line);
EXTI->FTSR |= (1 << exti_line);
break;
}
/* clear event mask */
EXTI->EMR &= ~(1 << exti_line);
/* unmask the pins interrupt channel */
EXTI->IMR |= (1 << pin);
EXTI->IMR |= (1 << exti_line);
return 0;
}
int gpio_irq_enable(gpio_t dev)
{
uint8_t exti_line;
switch(dev) {
#ifdef GPIO_0_EN
case GPIO_0:
exti_line = GPIO_0_EXTI_LINE;
break;
#endif
#ifdef GPIO_1_EN
case GPIO_1:
exti_line = GPIO_1_EXTI_LINE;
break;
#endif
#ifdef GPIO_2_EN
case GPIO_2:
exti_line = GPIO_2_EXTI_LINE;
break;
#endif
#ifdef GPIO_3_EN
case GPIO_3:
exti_line = GPIO_3_EXTI_LINE;
break;
#endif
#ifdef GPIO_4_EN
case GPIO_4:
exti_line = GPIO_4_EXTI_LINE;
break;
#endif
#ifdef GPIO_5_EN
case GPIO_5:
exti_line = GPIO_5_EXTI_LINE;
break;
#endif
#ifdef GPIO_6_EN
case GPIO_6:
exti_line = GPIO_6_EXTI_LINE;
break;
#endif
#ifdef GPIO_7_EN
case GPIO_7:
exti_line = GPIO_7_EXTI_LINE;
break;
#endif
#ifdef GPIO_8_EN
case GPIO_8:
exti_line = GPIO_8_EXTI_LINE;
break;
#endif
#ifdef GPIO_9_EN
case GPIO_9:
exti_line = GPIO_9_EXTI_LINE;
break;
#endif
#ifdef GPIO_10_EN
case GPIO_10:
exti_line = GPIO_10_EXTI_LINE;
break;
#endif
#ifdef GPIO_11_EN
case GPIO_11:
exti_line = GPIO_11_EXTI_LINE;
break;
#endif
#ifdef GPIO_12_EN
case GPIO_12:
exti_line = GPIO_12_EXTI_LINE;
break;
#endif
#ifdef GPIO_13_EN
case GPIO_13:
exti_line = GPIO_13_EXTI_LINE;
break;
#endif
#ifdef GPIO_14_EN
case GPIO_14:
exti_line = GPIO_14_EXTI_LINE;
break;
#endif
#ifdef GPIO_15_EN
case GPIO_15:
exti_line = GPIO_15_EXTI_LINE;
break;
#endif
case GPIO_UNDEFINED:
default:
return -1;
}
/* save state */
int state = (EXTI->IMR & (1 << exti_line) >> exti_line);
/* unmask the pins interrupt channel */
EXTI->IMR |= (1 << exti_line);
return state;
}
int gpio_irq_disable(gpio_t dev)
{
uint8_t exti_line;
switch(dev) {
#ifdef GPIO_0_EN
case GPIO_0:
exti_line = GPIO_0_EXTI_LINE;
break;
#endif
#ifdef GPIO_1_EN
case GPIO_1:
exti_line = GPIO_1_EXTI_LINE;
break;
#endif
#ifdef GPIO_2_EN
case GPIO_2:
exti_line = GPIO_2_EXTI_LINE;
break;
#endif
#ifdef GPIO_3_EN
case GPIO_3:
exti_line = GPIO_3_EXTI_LINE;
break;
#endif
#ifdef GPIO_4_EN
case GPIO_4:
exti_line = GPIO_4_EXTI_LINE;
break;
#endif
#ifdef GPIO_5_EN
case GPIO_5:
exti_line = GPIO_5_EXTI_LINE;
break;
#endif
#ifdef GPIO_6_EN
case GPIO_6:
exti_line = GPIO_6_EXTI_LINE;
break;
#endif
#ifdef GPIO_7_EN
case GPIO_7:
exti_line = GPIO_7_EXTI_LINE;
break;
#endif
#ifdef GPIO_8_EN
case GPIO_8:
exti_line = GPIO_8_EXTI_LINE;
break;
#endif
#ifdef GPIO_9_EN
case GPIO_9:
exti_line = GPIO_9_EXTI_LINE;
break;
#endif
#ifdef GPIO_10_EN
case GPIO_10:
exti_line = GPIO_10_EXTI_LINE;
break;
#endif
#ifdef GPIO_11_EN
case GPIO_11:
exti_line = GPIO_11_EXTI_LINE;
break;
#endif
#ifdef GPIO_12_EN
case GPIO_12:
exti_line = GPIO_12_EXTI_LINE;
break;
#endif
#ifdef GPIO_13_EN
case GPIO_13:
exti_line = GPIO_13_EXTI_LINE;
break;
#endif
#ifdef GPIO_14_EN
case GPIO_14:
exti_line = GPIO_14_EXTI_LINE;
break;
#endif
#ifdef GPIO_15_EN
case GPIO_15:
exti_line = GPIO_15_EXTI_LINE;
break;
#endif
case GPIO_UNDEFINED:
default:
return -1;
}
/* save state */
int state = ((EXTI->IMR & (1 << exti_line)) >> exti_line);
/* unmask the pins interrupt channel */
EXTI->IMR &= ~(1 << exti_line);
return state;
}
int gpio_read(gpio_t dev)
{
GPIO_TypeDef *port;
@ -470,6 +781,30 @@ int gpio_read(gpio_t dev)
port = GPIO_11_PORT;
pin = GPIO_11_PIN;
break;
#endif
#ifdef GPIO_12_EN
case GPIO_12:
port = GPIO_12_PORT;
pin = GPIO_12_PIN;
break;
#endif
#ifdef GPIO_13_EN
case GPIO_13:
port = GPIO_13_PORT;
pin = GPIO_13_PIN;
break;
#endif
#ifdef GPIO_14_EN
case GPIO_14:
port = GPIO_14_PORT;
pin = GPIO_14_PIN;
break;
#endif
#ifdef GPIO_15_EN
case GPIO_15:
port = GPIO_15_PORT;
pin = GPIO_15_PIN;
break;
#endif
case GPIO_UNDEFINED:
default:
@ -554,6 +889,26 @@ int gpio_set(gpio_t dev)
case GPIO_11:
GPIO_11_PORT->ODR |= (1 << GPIO_11_PIN);
break;
#endif
#ifdef GPIO_12_EN
case GPIO_12:
GPIO_12_PORT->ODR |= (1 << GPIO_12_PIN);
break;
#endif
#ifdef GPIO_13_EN
case GPIO_13:
GPIO_13_PORT->ODR |= (1 << GPIO_13_PIN);
break;
#endif
#ifdef GPIO_14_EN
case GPIO_14:
GPIO_14_PORT->ODR |= (1 << GPIO_14_PIN);
break;
#endif
#ifdef GPIO_15_EN
case GPIO_15:
GPIO_15_PORT->ODR |= (1 << GPIO_15_PIN);
break;
#endif
case GPIO_UNDEFINED:
default:
@ -625,6 +980,26 @@ int gpio_clear(gpio_t dev)
case GPIO_11:
GPIO_11_PORT->ODR &= ~(1 << GPIO_11_PIN);
break;
#endif
#ifdef GPIO_12_EN
case GPIO_12:
GPIO_12_PORT->ODR &= ~(1 << GPIO_12_PIN);
break;
#endif
#ifdef GPIO_13_EN
case GPIO_13:
GPIO_13_PORT->ODR &= ~(1 << GPIO_13_PIN);
break;
#endif
#ifdef GPIO_14_EN
case GPIO_14:
GPIO_14_PORT->ODR &= ~(1 << GPIO_14_PIN);
break;
#endif
#ifdef GPIO_15_EN
case GPIO_15:
GPIO_15_PORT->ODR &= ~(1 << GPIO_15_PIN);
break;
#endif
case GPIO_UNDEFINED:
default:
@ -639,7 +1014,8 @@ int gpio_toggle(gpio_t dev)
{
if (gpio_read(dev)) {
return gpio_clear(dev);
} else {
}
else {
return gpio_set(dev);
}
}
@ -648,89 +1024,142 @@ int gpio_write(gpio_t dev, int value)
{
if (value) {
return gpio_set(dev);
} else {
}
else {
return gpio_clear(dev);
}
}
__attribute__((naked)) void isr_exti0_1(void)
__attribute__((naked)) void isr_exti0(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();
config[GPIO_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();
if (sched_context_switch_request) {
thread_yield();
}
ISR_EXIT();
}
__attribute__((naked)) void isr_exti2_3(void)
__attribute__((naked)) void isr_exti1(void)
{
ISR_ENTER();
if (EXTI->PR & EXTI_PR_PR1) {
EXTI->PR |= EXTI_PR_PR1; /* clear status bit by writing a 1 to it */
config[GPIO_1].cb();
}
if (sched_context_switch_request) {
thread_yield();
}
ISR_EXIT();
}
__attribute__((naked)) void isr_exti2(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();
config[GPIO_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();
if (sched_context_switch_request) {
thread_yield();
}
ISR_EXIT();
}
__attribute__((naked)) void isr_exti4_15(void)
__attribute__((naked)) void isr_exti3(void)
{
ISR_ENTER();
if (EXTI->PR & EXTI_PR_PR3) {
EXTI->PR |= EXTI_PR_PR3; /* clear status bit by writing a 1 to it */
config[GPIO_3].cb();
}
if (sched_context_switch_request) {
thread_yield();
}
ISR_EXIT();
}
__attribute__((naked)) void isr_exti4(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();
config[GPIO_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();
if (sched_context_switch_request) {
thread_yield();
}
ISR_EXIT();
}
__attribute__((naked)) void isr_exti9_5(void)
{
ISR_ENTER();
if (EXTI->PR & EXTI_PR_PR5) {
EXTI->PR |= EXTI_PR_PR5; /* clear status bit by writing a 1 to it */
config[GPIO_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_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_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_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_9].cb();
}
if (sched_context_switch_request) {
thread_yield();
}
ISR_EXIT();
}
__attribute__((naked)) void isr_exti15_10(void)
{
ISR_ENTER();
if (EXTI->PR & EXTI_PR_PR10) {
EXTI->PR |= EXTI_PR_PR10; /* clear status bit by writing a 1 to it */
config[GPIO_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_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_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_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_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_15].cb();
}
if (sched_context_switch_request) {
thread_yield();
}
ISR_EXIT();
}

View File

@ -1,18 +1,68 @@
/*
* Copyright (C) 2014 Thomas Eichinger <thomas.eichinger@fu-berlin.de>
* 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 spi.c
* @brief Low-level SPI driver implementation
*
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
*
* @}
*/
#include "stm32f10x.h"
#include "periph/gpio.h"
#include "spi.h"
#include "periph_conf.h"
#include "board.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
/* TODO: parse and use conf and speed parameter */
int spi_init_master(spi_t dev, spi_conf_t conf, uint32_t speed)
{
RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;
SPI_TypeDef *SPIx;
switch(dev) {
#ifdef SPI_0_EN
case SPI_0:
SPIx = SPI_0_DEV;
SPI_0_CLKEN();
break;
#endif
case SPI_UNDEFINED:
default:
return -1;
}
/* set up SPI */
uint16_t tmp = SPIx->CR1;
tmp &= 0x3040; /* reset value */
tmp |= SPI_2_LINES_FULL_DUPLEX;
tmp |= SPI_MASTER_MODE;
tmp |= SPI_DATA_SIZE_8B;
tmp |= SPI_CPOL_LOW;
tmp |= SPI_CPHA_1_EDGE;
tmp |= SPI_NSS_SOFT;
tmp |= SPI_BR_PRESCALER_16;
tmp |= SPI_1ST_BIT_MSB;
SPIx->CR1 = tmp;
SPIx->I2SCFGR &= 0xF7FF; /* select SPI mode */
SPIx->CRCPR = 0x7; /* reset CRC polynomial */
SPIx->CR2 |= (uint16_t)(1<<7);
return 0;
}
@ -31,32 +81,30 @@ int spi_transfer_byte(spi_t dev, char out, char *in)
switch(dev) {
#ifdef SPI_0_EN
case SPI_0:
SPI_dev = SPI1;
SPI_dev = SPI_0_DEV;
break;
#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++;
}
while ((SPI_dev->SR & SPI_SR_TXE) == RESET);
SPI_dev->DR = out;
transfered += (out) ? 1 : 0;
if (in != 0) {
/* wait for not empty rx buffer */
while ((SPI_dev->SR & 0x1) == 0);
/* read out data to in buffer */
while ((SPI_dev->SR & SPI_SR_RXNE) == RESET);
if (in != NULL) {
*in = SPI_dev->DR;
/* increase transfered bytes counter */
transfered++;
transfered += (*in) ? 1 : 0;
}
else {
SPI_dev->DR;
}
while ((SPI_dev->SR & 0x80) == SET);
while ((SPI_dev->SR & 0x80) == 1);
DEBUG("\nout: %x in: %x transfered: %x\n", out, *in, transfered);
return transfered;
}
@ -66,7 +114,8 @@ int spi_transfer_bytes(spi_t dev, char *out, char *in, int length)
int transfered = 0;
int ret = 0;
if (out != 0) {
if (out != NULL) {
DEBUG("out*: %p out: %x length: %x\n", out, *out, length);
while (length--) {
ret += spi_transfer_byte(dev, *(out)++, 0);
if (ret < 0) {
@ -75,7 +124,7 @@ int spi_transfer_bytes(spi_t dev, char *out, char *in, int length)
transfered += ret;
}
}
if (in != 0) {
if (in != NULL) {
while (length--) {
ret += spi_transfer_byte(dev, 0, in++);
if (ret < 0) {
@ -83,27 +132,53 @@ int spi_transfer_bytes(spi_t dev, char *out, char *in, int length)
}
transfered += ret;
}
DEBUG("in*: %p in: %x transfered: %x\n", in, *(in-transfered), transfered);
}
DEBUG("sent %x byte(s)\n", transfered);
return transfered;
}
int spi_transfer_reg(spi_t dev, uint8_t reg, char *out, char *in)
{
/* TODO */
return -1;
}
int spi_transfer_regs(spi_t dev, uint8_t reg, char *out, char *in, int length)
{
/* TODO */
return -1;
}
int spi_poweron(spi_t dev)
{
return -1;
switch(dev) {
#ifdef SPI_0_EN
case SPI_0:
SPI_0_CLKEN();
SPI_0_DEV->CR1 |= 0x0040; /* turn SPI peripheral on */
break;
#endif
case SPI_UNDEFINED:
default:
return -1;
}
return 0;
}
int spi_poweroff(spi_t dev)
{
return -1;
switch(dev) {
#ifdef SPI_0_EN
case SPI_0:
SPI_0_CLKDIS();
SPI_0_DEV->CR1 &= ~(0x0040); /* turn SPI peripheral off */
break;
#endif
case SPI_UNDEFINED:
default:
return -1;
}
return 0;
}

View File

@ -7,10 +7,10 @@
*/
/**
* @ingroup cpu_stm32f0
* @ingroup cpu_stm32f1
* @{
*
* @file
* @file timer.c
* @brief Low-level timer driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
@ -26,6 +26,8 @@
#include "periph_conf.h"
#include "periph/timer.h"
#include "thread.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
@ -39,9 +41,7 @@ typedef struct {
/**
* Timer state memory
*/
timer_conf_t config[TIMER_NUMOF];
static timer_conf_t config[TIMER_NUMOF];
int timer_init(tim_t dev, unsigned int ticks_per_us, void (*callback)(int))
{
@ -124,6 +124,7 @@ int timer_set_absolute(tim_t dev, int channel, unsigned int value)
timer->CCR1 = value;
timer->SR &= ~TIM_SR_CC1IF;
timer->DIER |= TIM_DIER_CC1IE;
DEBUG("Timer 1 set to %x\n", value);
break;
case 1:
timer->CCR2 = value;
@ -315,6 +316,11 @@ __attribute__ ((naked)) void TIMER_1_ISR(void)
static inline void irq_handler(tim_t timer, TIM_TypeDef *dev)
{
if (dev->SR & TIM_SR_UIF) {
DEBUG("Overflow.\n");
dev->SR &= ~(TIM_SR_UIF|TIM_SR_CC1IF|TIM_SR_CC2IF|TIM_SR_CC3IF|TIM_SR_CC4IF);
return;
}
if (dev->SR & TIM_SR_CC1IF) {
DEBUG("1\n");
dev->DIER &= ~TIM_DIER_CC1IE;
@ -327,6 +333,7 @@ static inline void irq_handler(tim_t timer, TIM_TypeDef *dev)
dev->DIER &= ~TIM_DIER_CC2IE;
dev->SR &= ~TIM_SR_CC2IF;
config[timer].cb(1);
DEBUG("-2\n");
}
else if (dev->SR & TIM_SR_CC3IF) {
DEBUG("3\n");
@ -342,4 +349,8 @@ static inline void irq_handler(tim_t timer, TIM_TypeDef *dev)
config[timer].cb(3);
DEBUG("-4\n");
}
if (sched_context_switch_request) {
thread_yield();
}
}

View File

@ -10,7 +10,7 @@
* @ingroup cpu_stm32f1
* @{
*
* @file
* @file uart.c
* @brief Low-level UART driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
@ -26,6 +26,9 @@
#include "periph_conf.h"
#include "periph/uart.h"
#include "sched.h"
#include "thread.h"
/**
* @brief Each UART device has to store two callbacks.
@ -93,7 +96,7 @@ int uart_init_blocking(uart_t uart, uint32_t baudrate)
{
USART_TypeDef *dev;
GPIO_TypeDef *port;
uint32_t rx_pin, tx_pin;
uint32_t rx_pin, tx_pin, bus_freq;
float divider;
uint16_t mantissa;
uint8_t fraction;
@ -106,6 +109,7 @@ int uart_init_blocking(uart_t uart, uint32_t baudrate)
port = UART_0_PORT;
rx_pin = UART_0_RX_PIN;
tx_pin = UART_0_TX_PIN;
bus_freq = UART_0_BUS_FREQ;
/* enable clocks */
UART_0_CLKEN();
UART_0_PORT_CLKEN();
@ -117,6 +121,7 @@ int uart_init_blocking(uart_t uart, uint32_t baudrate)
port = UART_1_PORT;
tx_pin = UART_1_TX_PIN;
rx_pin = UART_1_RX_PIN;
bus_freq = UART_1_BUS_FREQ;
/* enable clocks */
UART_1_CLKEN();
UART_1_PORT_CLKEN();
@ -146,7 +151,7 @@ int uart_init_blocking(uart_t uart, uint32_t baudrate)
}
/* configure UART to mode 8N1 with given baudrate */
divider = ((float)F_CPU) / (16 * baudrate);
divider = ((float)bus_freq) / (16 * baudrate);
mantissa = (uint16_t)floorf(divider);
fraction = (uint8_t)floorf((divider - mantissa) * 16);
dev->BRR = 0;
@ -304,4 +309,8 @@ static inline void irq_handler(uint8_t uartnum, USART_TypeDef *dev)
else if (dev->SR & USART_SR_TXE) {
config[uartnum].tx_cb();
}
if (sched_context_switch_request) {
thread_yield();
}
}

View File

@ -2,7 +2,7 @@
* 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
* Public License v2.1. See the file LICENSE in the top level directory for more
* details.
*/
@ -10,7 +10,7 @@
* @ingroup cpu_stm32f1
* @{
*
* @file
* @file reboot_arch.c
* @brief Implementation of the kernels reboot interface
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>

View File

@ -2,18 +2,19 @@
* 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
* Public License v2.1. See the file LICENSE in the top level directory for more
* details.
*/
/**
* @ingroup cpu_sam3x8e
* @ingroup cpu_stm32f1
* @{
*
* @file startup.c
* @brief Startup code and interrupt vector definition
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
*
* @}
*/

View File

@ -39,7 +39,7 @@ MEMORY
}
/* The stack size used by the application. NOTE: you need to adjust */
STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : 0x800 ;
STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : 0x200 ;
/* Section Definitions */
SECTIONS

View File

@ -2,7 +2,7 @@
* 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
* Public License v2.1. See the file LICENSE in the top level directory for more
* details.
*/
@ -11,7 +11,7 @@
* @{
*
* @file syscalls.c
* @brief NewLib system calls implementations for SAM3X8E
* @brief NewLib system calls implementations for stm32f1
*
* @author Michael Baar <michael.baar@fu-berlin.de>
* @author Stefan Pfeiffer <pfeiffer@inf.fu-berlin.de>

View File

@ -1,4 +1,4 @@
/**
/*
* at86rf231.c - Implementation of at86rf231 functions.
* Copyright (C) 2013 Alaeddine Weslati <alaeddine.weslati@inria.fr>
*
@ -10,6 +10,18 @@
#include "kernel_types.h"
#include "transceiver.h"
/**
* @ingroup drivers_at86rf231
* @{
*
* @file at86rf231.c
* @brief Driver implementation for at86rf231 chip
*
* @author Alaeddine Weslati <alaeddine.weslati@inria.fr>
*
* @}
*/
#include "at86rf231.h"
#include "at86rf231_arch.h"
#include "at86rf231_spi.h"
@ -82,7 +94,7 @@ void at86rf231_switch_to_rx(void)
vtimer_usleep(10);
if (!--max_wait) {
printf("at86rf231 : ERROR : could not enter RX_ON mode");
printf("at86rf231 : ERROR : could not enter RX_ON mode\n");
break;
}
}

View File

@ -35,6 +35,7 @@ void at86rf231_init(kernel_pid_t tpid);
//void at86rf231_reset(void);
void at86rf231_rx(void);
void at86rf231_rx_handler(void);
void at86rf231_rx_irq(void);
int16_t at86rf231_send(at86rf231_packet_t *packet);

View File

@ -1,8 +1,9 @@
/*
* Copyright (C) 2014 Freie Universität Berlin
*
* This file is subject to the terms and conditions of the LGPLv2 License.
* See the file LICENSE in the top level directory for more details.
* 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.
*/
/**
@ -142,7 +143,5 @@ 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 */
/** @} */

View File

@ -29,7 +29,8 @@ QUIET ?= 1
BOARD_INSUFFICIENT_RAM := chronos msb-430h telosb wsn430-v1_3b wsn430-v1_4 z1 redbee-econotag
BOARD_BLACKLIST := arduino-due mbed_lpc1768 msb-430 pttu udoo qemu-i386 \
stm32f0discovery stm32f3discovery stm32f4discovery pca10000 pca10005
stm32f0discovery stm32f3discovery stm32f4discovery pca10000 pca10005 \
iot-lab_M3
# mbed_lpc1768: see https://github.com/RIOT-OS/RIOT/issues/675
# msb-430: see https://github.com/RIOT-OS/RIOT/issues/658
# pttu: see https://github.com/RIOT-OS/RIOT/issues/659
@ -39,6 +40,7 @@ BOARD_BLACKLIST := arduino-due mbed_lpc1768 msb-430 pttu udoo qemu-i386 \
# stm32f4discovery: no transceiver, yet
# pca10000: no transceiver, yet
# pca10005: no transceiver, yet
# iot-lab_M3: no RTC implementation, yet
# Modules to include:

View File

@ -30,7 +30,7 @@ QUIET ?= 1
BOARD_INSUFFICIENT_RAM := chronos msb-430h telosb wsn430-v1_3b wsn430-v1_4 z1 redbee-econotag
BOARD_BLACKLIST := arduino-due mbed_lpc1768 msb-430 pttu udoo qemu-i386 \
stm32f0discovery stm32f3discovery stm32f4discovery \
pca10000 pca10005
pca10000 pca10005 iot-lab_M3
# mbed_lpc1768: see https://github.com/RIOT-OS/RIOT/issues/675
# msb-430: see https://github.com/RIOT-OS/RIOT/issues/658
# pttu: see https://github.com/RIOT-OS/RIOT/issues/659
@ -39,7 +39,7 @@ BOARD_BLACKLIST := arduino-due mbed_lpc1768 msb-430 pttu udoo qemu-i386 \
# stm32f3discovery: no transceiver, yet
# stm32f4discovery: no transceiver, yet
# pca10000/5: no transceiver, yet
# iot-lab_M3: no RTC implementation, yet
# Modules to include:
USEMODULE += posix

View File

@ -16,6 +16,3 @@ CFLAGS += -DDEVELHELP
QUIET ?= 1
include $(RIOTBASE)/Makefile.include
reset:
$(RIOTBASE)/cpu/$(CPU)/tools/reset.sh

View File

@ -16,6 +16,3 @@ CFLAGS += -DDEVELHELP
QUIET ?= 1
include $(RIOTBASE)/Makefile.include
reset:
$(RIOTBOARD)/$(BOARD)/dist/reset.sh

View File

@ -30,7 +30,8 @@ QUIET ?= 1
# Blacklist boards
BOARD_BLACKLIST := arduino-due avsextrem chronos mbed_lpc1768 msb-430h msba2 redbee-econotag \
telosb wsn430-v1_3b wsn430-v1_4 msb-430 pttu udoo qemu-i386 z1 stm32f0discovery \
stm32f3discovery stm32f4discovery pca10000 pca10005
stm32f3discovery stm32f4discovery pca10000 pca10005 iot-lab_M3
# This example only works with native for now.
# msb430-based boards: msp430-g++ is not provided in mspgcc.
# (People who want use c++ can build c++ compiler from source, or get binaries from Energia http://energia.nu/)
@ -40,6 +41,7 @@ BOARD_BLACKLIST := arduino-due avsextrem chronos mbed_lpc1768 msb-430h msba2 red
# stm32f4discovery: g++ does not support some used flags (e.g. -mthumb...)
# pca10000: g++ does not support some used flags (e.g. -mthumb...)
# pca10005: g++ does not support some used flags (e.g. -mthumb...)
# iot-lab_M3: g++ does not support some used flags (e.g. -mthumb...)
# others: untested.
# If you want to add some extra flags when compile c++ files, add these flags

View File

@ -4,6 +4,3 @@ include ../Makefile.tests_common
DISABLE_MODULE += auto_init
include $(RIOTBASE)/Makefile.include
reset:
$(RIOTBOARD)/$(BOARD)/dist/reset.sh

View File

@ -6,6 +6,3 @@ BOARD_INSUFFICIENT_RAM := stm32f0discovery
DISABLE_MODULE += auto_init
include $(RIOTBASE)/Makefile.include
reset:
$(RIOTCPU)/$(CPU)/tools/reset.sh