Merge pull request #1736 from haukepetersen/fix_stm32f1_somecleanup

board/iot-lab_M3: cleanup of SPI and radio driver
This commit is contained in:
Hauke Petersen 2014-09-30 12:02:42 +02:00
commit 25c891ecdd
14 changed files with 304 additions and 342 deletions

View File

@ -1,5 +1,3 @@
MODULE =$(BOARD)_base
DIRS = drivers
include $(RIOTBASE)/Makefile.base

View File

@ -1,5 +0,0 @@
MODULE =$(BOARD)_base
include $(RIOTBOARD)/$(BOARD)/Makefile.include
include $(RIOTBASE)/Makefile.base

View File

@ -1,171 +0,0 @@
/*
* 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 "cpu.h"
#include "sched.h"
#include "vtimer.h"
#include "arch/thread_arch.h"
#include "periph/gpio.h"
#include "periph/spi.h"
#include "periph_conf.h"
#include "at86rf231.h"
#include "at86rf231_spi.h"
/*
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
*/
uint8_t at86rf231_get_status(void)
{
return at86rf231_reg_read(AT86RF231_REG__TRX_STATUS)
& AT86RF231_TRX_STATUS_MASK__TRX_STATUS;
}
void at86rf231_spi_select(void)
{
gpio_clear(SPI_0_CS_GPIO);
}
void at86rf231_spi_unselect(void)
{
gpio_set(SPI_0_CS_GPIO);
}
void at86rf231_slp_set(void)
{
gpio_set(SPI_0_SLEEP_GPIO);
}
void at86rf231_slp_clear(void)
{
gpio_clear(SPI_0_SLEEP_GPIO);
}
void at86rf231_rst_set(void)
{
gpio_clear(SPI_0_RESET_GPIO);
}
void at86rf231_rst_clear(void)
{
gpio_set(SPI_0_RESET_GPIO);
}
void at86rf231_enable_interrupts(void)
{
gpio_irq_enable(SPI_0_IRQ0_GPIO);
}
void at86rf231_disable_interrupts(void)
{
gpio_irq_disable(SPI_0_IRQ0_GPIO);
}
void at86rf231_gpio_spi_interrupts_init(void)
{
/* 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);
/* SPI init */
spi_init_master(SPI_0, SPI_CONF_FIRST_RISING, SPI_SPEED_5MHZ);
spi_poweron(SPI_0);
/* IRQ0 */
gpio_init_in(SPI_0_IRQ0_GPIO, GPIO_NOPULL);
gpio_init_int(SPI_0_IRQ0_GPIO, GPIO_NOPULL, GPIO_RISING, (gpio_cb_t)at86rf231_rx_irq, NULL);
/* Connect EXTI4 Line to PC4 pin */
at86rf231_enable_interrupts();
/* CS */
gpio_init_out(SPI_0_CS_GPIO, GPIO_NOPULL);
/* SLEEP */
gpio_init_out(SPI_0_SLEEP_GPIO, GPIO_NOPULL);
/* RESET */
gpio_init_out(SPI_0_RESET_GPIO, GPIO_NOPULL);
}
void at86rf231_reset(void)
{
/* force reset */
at86rf231_rst_set();
/* put pins to default values */
at86rf231_spi_unselect();
at86rf231_slp_clear();
/* additional waiting to comply to min rst pulse width */
uint8_t delay = 50;
while (delay--){}
at86rf231_rst_clear();
/* Send a FORCE TRX OFF command */
at86rf231_reg_write(AT86RF231_REG__TRX_STATE, AT86RF231_TRX_STATE__FORCE_TRX_OFF);
/* busy wait for TRX_OFF state */
uint8_t status;
uint8_t max_wait = 100;
do {
status = at86rf231_get_status();
if (!--max_wait) {
printf("at86rf231 : ERROR : could not enter TRX_OFF mode\n");
break;
}
} while ((status & AT86RF231_TRX_STATUS_MASK__TRX_STATUS)
!= AT86RF231_TRX_STATUS__TRX_OFF);
}
uint8_t at86rf231_spi_transfer_byte(uint8_t byte)
{
char ret;
spi_transfer_byte(SPI_0, byte, &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);
}

View File

@ -48,6 +48,17 @@
*/
#define HW_TIMER TIMER_0
/**
* @name Define the interface to the AT86RF231 radio
* @{
*/
#define AT86RF231_SPI SPI_0
#define AT86RF231_CS GPIO_11
#define AT86RF231_INT GPIO_12
#define AT86RF231_RESET GPIO_13
#define AT86RF231_SLEEP GPIO_14
/** @} */
/**
* @name LED pin definitions
* @{

View File

@ -14,7 +14,9 @@
* @brief Peripheral MCU configuration for the iot-lab_M3 board
*
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*/
#ifndef __PERIPH_CONF_H
#define __PERIPH_CONF_H
@ -254,51 +256,27 @@
/**
* @brief SPI configuration
* @{
*/
#define SPI_NUMOF 1
#define SPI_0_EN 1
#define SPI_NUMOF (1U)
#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_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_8 (0x0010)
#define SPI_BR_PRESCALER_16 (0x0018)
#define SPI_BR_PRESCALER_64 (0x0028)
#define SPI_BR_PRESCALER_128 (0x0030)
#define SPI_BR_PRESCALER_256 (0x0038)
#define SPI_1ST_BIT_MSB (0x0000)
/* SPI 0 device configuration */
#define SPI_0_DEV SPI1
#define SPI_0_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_SPI1EN)
#define SPI_0_CLKDIS() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI1EN))
#define SPI_0_BUS_DIV 1 /* 1 -> SPI runs with full CPU clock, 0 -> half CPU clock */
/* SPI 0 pin configuration */
#define SPI_0_CLK_PORT GPIOA
#define SPI_0_CLK_PIN 5
#define SPI_0_CLK_PORT_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPAEN)
#define SPI_0_MOSI_PORT GPIOA
#define SPI_0_MOSI_PIN 7
#define SPI_0_MOSI_PORT_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPAEN)
#define SPI_0_MISO_PORT GPIOA
#define SPI_0_MISO_PIN 6
#define SPI_0_MISO_PORT_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_IOPAEN)
/** @} */
#endif /* __PERIPH_CONF_H */
/** @} */

View File

@ -29,13 +29,23 @@
int spi_init_master(spi_t dev, spi_conf_t conf, spi_speed_t speed)
{
SPI_TypeDef *SPIx;
uint16_t br_div = 0;
SPI_TypeDef *spi;
GPIO_TypeDef *clk_port, *mosi_port, *miso_port;
int clk_pin, mosi_pin, miso_pin;
uint16_t br_div;
uint8_t bus_div;
switch(dev) {
#ifdef SPI_0_EN
case SPI_0:
SPIx = SPI_0_DEV;
spi = SPI_0_DEV;
clk_port = SPI_0_CLK_PORT;
clk_pin = SPI_0_CLK_PIN;
mosi_port = SPI_0_MOSI_PORT;
mosi_pin = SPI_0_MOSI_PIN;
miso_port = SPI_0_MISO_PORT;
miso_pin = SPI_0_MISO_PIN;
bus_div = SPI_0_BUS_DIV;
SPI_0_CLKEN();
break;
#endif
@ -43,37 +53,60 @@ int spi_init_master(spi_t dev, spi_conf_t conf, spi_speed_t speed)
return -1;
}
/* configure CLK pin */
if (clk_pin < 8) {
clk_port->CRL &= ~(0xf << (clk_pin * 4));
clk_port->CRL |= (0xb << (clk_pin * 4));
}
else {
clk_port->CRH &= ~(0xf << ((clk_pin - 8) * 4));
clk_port->CRH &= (0xb << ((clk_pin - 8) * 4));
}
/* configure the MOSI pin */
if (mosi_pin < 8) {
mosi_port->CRL &= ~(0xf << (mosi_pin * 4));
mosi_port->CRL |= (0xb << (mosi_pin * 4));
}
else {
mosi_port->CRH &= ~(0xf << ((mosi_pin - 8) * 4));
mosi_port->CRH &= (0xb << ((mosi_pin - 8) * 4));
}
/* configure MISO pin */
if (miso_pin < 8) {
miso_port->CRL &= ~(0xf << (miso_pin * 4));
miso_port->CRL |= (0x4 << (miso_pin * 4));
}
else {
miso_port->CRH &= ~(0xf << ((miso_pin - 8) * 4));
miso_port->CRH &= (0x4 << ((miso_pin - 8) * 4));
}
/* configure SPI bus speed */
switch(speed) {
case SPI_SPEED_10MHZ:
br_div = SPI_BR_PRESCALER_8; /* actual speed: 9MHz */
br_div = 0x01 + bus_div; /* actual speed: 9MHz */
break;
case SPI_SPEED_5MHZ:
br_div = SPI_BR_PRESCALER_16; /* actual speed: 4.5MHz */
br_div = 0x02 + bus_div; /* actual speed: 4.5MHz */
break;
case SPI_SPEED_1MHZ:
br_div = SPI_BR_PRESCALER_64; /* actual speed: 1.1MHz */
br_div = 0x04 + bus_div; /* actual speed: 1.1MHz */
break;
case SPI_SPEED_400KHZ:
br_div = SPI_BR_PRESCALER_128; /* actual speed: 500kHz */
br_div = 0x05 + bus_div; /* actual speed: 560kHz */
break;
case SPI_SPEED_100KHZ:
br_div = SPI_BR_PRESCALER_256; /* actual speed: 200kHz */
br_div = 0x07; /* actual speed: 280kHz on APB2, 140KHz on APB1 */
default:
return -2;
}
/* set up SPI */
SPIx->CR1 = SPI_2_LINES_FULL_DUPLEX \
| SPI_MASTER_MODE \
| SPI_DATA_SIZE_8B \
| (conf & 0x3) \
| SPI_NSS_SOFT \
| br_div \
| SPI_1ST_BIT_MSB;
SPIx->I2SCFGR &= 0xF7FF; /* select SPI mode */
SPIx->CRCPR = 0x7; /* reset CRC polynomial */
SPIx->CR2 |= (uint16_t)(1<<7);
spi->CR1 = SPI_CR1_SSM | SPI_CR1_SSI | SPI_CR1_MSTR | (conf & 0x3) | (br_div << 3);
spi->I2SCFGR &= 0xF7FF; /* select SPI mode */
spi->CRCPR = 0x7; /* reset CRC polynomial */
/* enable the SPI device */
spi->CR1 |= SPI_CR1_SPE;
return 0;
}
@ -86,34 +119,34 @@ int spi_init_slave(spi_t dev, spi_conf_t conf, char (*cb)(char))
int spi_transfer_byte(spi_t dev, char out, char *in)
{
SPI_TypeDef *SPI_dev;
SPI_TypeDef *spi;
int transfered = 0;
switch(dev) {
#ifdef SPI_0_EN
case SPI_0:
SPI_dev = SPI_0_DEV;
spi = SPI_0_DEV;
break;
#endif
default:
return -1;
}
while ((SPI_dev->SR & SPI_SR_TXE) == RESET);
SPI_dev->DR = out;
while ((spi->SR & SPI_SR_TXE) == RESET);
spi->DR = out;
transfered++;
while ((SPI_dev->SR & SPI_SR_RXNE) == RESET);
while ((spi->SR & SPI_SR_RXNE) == RESET);
if (in != NULL) {
*in = SPI_dev->DR;
*in = spi->DR;
transfered++;
}
else {
SPI_dev->DR;
spi->DR;
}
/* SPI busy */
while ((SPI_dev->SR & 0x80));
while ((spi->SR & 0x80));
DEBUG("\nout: %x in: %x transfered: %x\n", out, *in, transfered);
@ -172,7 +205,7 @@ void spi_poweron(spi_t dev)
#ifdef SPI_0_EN
case SPI_0:
SPI_0_CLKEN();
SPI_0_DEV->CR1 |= 0x0040; /* turn SPI peripheral on */
SPI_0_DEV->CR1 |= SPI_CR1_SPE; /* turn SPI peripheral on */
break;
#endif
}
@ -183,8 +216,8 @@ void spi_poweroff(spi_t dev)
switch(dev) {
#ifdef SPI_0_EN
case SPI_0:
SPI_0_DEV->CR1 &= ~(SPI_CR1_SPE); /* turn SPI peripheral off */
SPI_0_CLKDIS();
SPI_0_DEV->CR1 &= ~(0x0040); /* turn SPI peripheral off */
break;
#endif
}

View File

@ -1,5 +1,4 @@
/*
* at86rf231.c - Implementation of at86rf231 functions.
* Copyright (C) 2013 Alaeddine Weslati <alaeddine.weslati@inria.fr>
*
* This file is subject to the terms and conditions of the GNU Lesser
@ -7,15 +6,12 @@
* directory for more details.
*/
#include "kernel_types.h"
#include "transceiver.h"
/**
* @ingroup drivers_at86rf231
* @{
*
* @file at86rf231.c
* @brief Driver implementation for at86rf231 chip
* @file
* @brief Driver implementation of the AT86RF231 device driver
*
* @author Alaeddine Weslati <alaeddine.weslati@inria.fr>
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
@ -24,8 +20,13 @@
*/
#include "at86rf231.h"
#include "at86rf231_arch.h"
#include "at86rf231_spi.h"
#include "board.h"
#include "periph/gpio.h"
#include "periph/spi.h"
#include "kernel_types.h"
#include "transceiver.h"
#include "vtimer.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
@ -37,6 +38,11 @@ static uint64_t radio_address_long;
uint8_t driver_state;
uint8_t at86rf231_get_status(void);
void at86rf231_gpio_spi_interrupts_init(void);
void at86rf231_reset(void);
void at86rf231_init(kernel_pid_t tpid)
{
transceiver_pid = tpid;
@ -71,7 +77,8 @@ void at86rf231_init(kernel_pid_t tpid)
void at86rf231_switch_to_rx(void)
{
at86rf231_disable_interrupts();
gpio_irq_disable(AT86RF231_INT);
// Send a FORCE TRX OFF command
at86rf231_reg_write(AT86RF231_REG__TRX_STATE, AT86RF231_TRX_STATE__FORCE_TRX_OFF);
@ -82,7 +89,7 @@ void at86rf231_switch_to_rx(void)
at86rf231_reg_read(AT86RF231_REG__IRQ_STATUS);
// Enable IRQ interrupt
at86rf231_enable_interrupts();
gpio_irq_enable(AT86RF231_INT);
// Start RX
at86rf231_reg_write(AT86RF231_REG__TRX_STATE, AT86RF231_TRX_STATE__RX_ON);
@ -104,8 +111,10 @@ void at86rf231_switch_to_rx(void)
while ((status & AT86RF231_TRX_STATUS_MASK__TRX_STATUS) != AT86RF231_TRX_STATUS__RX_ON);
}
void at86rf231_rx_irq(void)
void at86rf231_rx_irq(void *arg)
{
(void)arg;
/* check if we are in sending state */
if (driver_state == AT_DRIVER_STATE_SENDING) {
/* Read IRQ to clear it */
@ -202,3 +211,51 @@ void at86rf231_set_monitor(uint8_t mode)
(void) mode;
// TODO
}
void at86rf231_gpio_spi_interrupts_init(void)
{
/* SPI init */
spi_init_master(AT86RF231_SPI, SPI_CONF_FIRST_RISING, SPI_SPEED_5MHZ);
/* IRQ0 */
gpio_init_int(AT86RF231_INT, GPIO_NOPULL, GPIO_RISING, at86rf231_rx_irq, NULL);
/* CS */
gpio_init_out(AT86RF231_CS, GPIO_NOPULL);
/* SLEEP */
gpio_init_out(AT86RF231_SLEEP, GPIO_NOPULL);
/* RESET */
gpio_init_out(AT86RF231_RESET, GPIO_NOPULL);
}
void at86rf231_reset(void)
{
/* force reset */
gpio_clear(AT86RF231_RESET);
/* put pins to default values */
gpio_set(AT86RF231_CS);
gpio_clear(AT86RF231_SLEEP);
/* additional waiting to comply to min rst pulse width */
uint8_t delay = 50;
while (delay--){}
gpio_set(AT86RF231_RESET);
/* Send a FORCE TRX OFF command */
at86rf231_reg_write(AT86RF231_REG__TRX_STATE, AT86RF231_TRX_STATE__FORCE_TRX_OFF);
/* busy wait for TRX_OFF state */
uint8_t status;
uint8_t max_wait = 100;
do {
status = at86rf231_get_status();
if (!--max_wait) {
printf("at86rf231 : ERROR : could not enter TRX_OFF mode\n");
break;
}
} while ((status & AT86RF231_TRX_STATUS_MASK__TRX_STATUS)
!= AT86RF231_TRX_STATUS__TRX_OFF);
}

View File

@ -6,8 +6,20 @@
* directory for more details.
*/
/**
* @ingroup drivers_at86rf231
* @{
*
* @file
* @brief RX related functionality for the AT86RF231 device driver
*
* @author Alaeddine Weslati <alaeddine.weslati@inria.fr>
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
*
* @}
*/
#include "at86rf231.h"
#include "at86rf231_arch.h"
#include "at86rf231_spi.h"
#include "kernel_types.h"

View File

@ -6,68 +6,72 @@
* directory for more details.
*/
/**
* @ingroup drivers_at86rf231
* @{
*
* @file
* @brief Register access functions for the AT86RF231 device driver
*
* @author Alaeddine Weslati <alaeddine.weslati@inria.fr>
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
*
* @}
*/
#include "at86rf231_spi.h"
#include "at86rf231_arch.h"
#include "at86rf231.h"
#include "board.h"
#include "periph/spi.h"
#include "periph/gpio.h"
void at86rf231_reg_write(uint8_t addr, uint8_t value)
{
// Start the SPI transfer
at86rf231_spi_select();
// Send first byte being the command and address
at86rf231_spi_transfer_byte(AT86RF231_ACCESS_REG | AT86RF231_ACCESS_WRITE | addr);
// Send value
at86rf231_spi_transfer_byte(value);
// End the SPI transfer
at86rf231_spi_unselect();
/* Start the SPI transfer */
gpio_clear(AT86RF231_CS);
/* write to register */
spi_transfer_reg(AT86RF231_SPI, AT86RF231_ACCESS_REG | AT86RF231_ACCESS_WRITE | addr, value, 0);
/* End the SPI transfer */
gpio_set(AT86RF231_CS);
}
uint8_t at86rf231_reg_read(uint8_t addr)
{
uint8_t value;
char value;
// Start the SPI transfer
at86rf231_spi_select();
// Send first byte being the command and address
at86rf231_spi_transfer_byte(AT86RF231_ACCESS_REG | AT86RF231_ACCESS_READ | addr);
// Send value
value = at86rf231_spi_transfer_byte(0);
// End the SPI transfer
at86rf231_spi_unselect();
return value;
/* Start the SPI transfer */
gpio_clear(AT86RF231_CS);
/* read from register */
spi_transfer_reg(AT86RF231_SPI, AT86RF231_ACCESS_REG | AT86RF231_ACCESS_READ | addr, 0, &value);
/* End the SPI transfer */
gpio_set(AT86RF231_CS);
return (uint8_t)value;
}
void at86rf231_read_fifo(uint8_t *data, radio_packet_length_t length)
{
// Start the SPI transfer
at86rf231_spi_select();
// Send Frame Buffer Write access
at86rf231_spi_transfer_byte(AT86RF231_ACCESS_FRAMEBUFFER | AT86RF231_ACCESS_READ);
at86rf231_spi_transfer(0, data, length);
// End the SPI transfer
at86rf231_spi_unselect();
/* Start the SPI transfer */
gpio_clear(AT86RF231_CS);
/* Read a number of bytes from the devices frame buffer */
spi_transfer_regs(AT86RF231_SPI, AT86RF231_ACCESS_FRAMEBUFFER | AT86RF231_ACCESS_READ,
0, (char*)data, length);
/* End the SPI transfer */
gpio_set(AT86RF231_CS);
}
void at86rf231_write_fifo(const uint8_t *data, radio_packet_length_t length)
{
// Start the SPI transfer
at86rf231_spi_select();
// Send Frame Buffer Write access
at86rf231_spi_transfer_byte(AT86RF231_ACCESS_FRAMEBUFFER | AT86RF231_ACCESS_WRITE);
at86rf231_spi_transfer(data, 0, length);
// End the SPI transfer
at86rf231_spi_unselect();
/* Start the SPI transfer */
gpio_clear(AT86RF231_CS);
/* Send Frame Buffer Write access */
spi_transfer_regs(AT86RF231_SPI, AT86RF231_ACCESS_FRAMEBUFFER | AT86RF231_ACCESS_WRITE,
(char*)data, 0, length);
/* End the SPI transfer */
gpio_set(AT86RF231_CS);
}
uint8_t at86rf231_get_status(void)
{
return at86rf231_reg_read(AT86RF231_REG__TRX_STATUS)
& AT86RF231_TRX_STATUS_MASK__TRX_STATUS;
}

View File

@ -6,9 +6,22 @@
* directory for more details.
*/
/**
* @ingroup drivers_at86rf231
* @{
*
* @file
* @brief RX related functionality for the AT86RF231 device driver
*
* @author Alaeddine Weslati <alaeddine.weslati@inria.fr>
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
*
* @}
*/
#include "at86rf231.h"
#include "at86rf231_arch.h"
#include "at86rf231_spi.h"
#include "vtimer.h"
#define ENABLE_DEBUG (0)
#include "debug.h"

View File

@ -1,22 +0,0 @@
#ifndef AT86RF231_ARCH_H_
#define AT86RF231_ARCH_H_
#include <stdint.h>
#include "vtimer.h"
void at86rf231_gpio_spi_interrupts_init(void);
void at86rf231_reset(void);
uint8_t at86rf231_get_status(void);
void at86rf231_spi_select(void);
void at86rf231_spi_unselect(void);
void at86rf231_spi_transfer(const uint8_t *data_out, uint8_t *data_in, radio_packet_length_t length);
uint8_t at86rf231_spi_transfer_byte(uint8_t byte);
void at86rf231_init_interrupts(void);
void at86rf231_enable_interrupts(void);
void at86rf231_disable_interrupts(void);
#endif

View File

@ -1,3 +1,22 @@
/*
* 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 drivers_at86rf231
* @{
*
* @file
* @brief Register access function definitions for the AT86RF231 device driver
*
* @author Alaeddine Weslati <alaeddine.weslati@inria.fr>
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
*/
#ifndef AT86RF231_SPI_H_
#define AT86RF231_SPI_H_
@ -10,4 +29,8 @@ void at86rf231_reg_write(uint8_t addr, uint8_t value);
void at86rf231_read_fifo(uint8_t *data, radio_packet_length_t length);
void at86rf231_write_fifo(const uint8_t *data, radio_packet_length_t length);
#endif
uint8_t at86rf231_get_status(void);
#endif /* AT86RF231_SPI_H_ */
/** @} */

View File

@ -6,6 +6,19 @@
* directory for more details.
*/
/**
* @defgroup drivers_at86rf231
* @ingroup drivers
* @brief Device driver for the Atmel AT86RF231 radio
* @{
*
* @file
* @brief Interface definition for the AT86RF231 device driver
*
* @author Alaeddine Weslati <alaeddine.weslati@inria.fr>
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
*/
#ifndef AT86RF231_H_
#define AT86RF231_H_
@ -13,21 +26,20 @@
#include <stdint.h>
#include "kernel_types.h"
#include "board.h"
#include "radio/types.h"
#include "ieee802154_frame.h"
#include "at86rf231/at86rf231_settings.h"
#include "periph/gpio.h"
#define AT86RF231_MAX_PKT_LENGTH 127
#define AT86RF231_MAX_DATA_LENGTH 118
#define AT86RF231_MAX_PKT_LENGTH 127
#define AT86RF231_MAX_DATA_LENGTH 118
/**
* Structure to represent a at86rf231 packet.
*/
typedef struct __attribute__((packed))
typedef struct __attribute__((packed)) /* TODO: do we need the packed here? it leads to an
unaligned pointer -> trouble for M0 systems... */
{
/* @{ */
uint8_t length; /** < the length of the frame of the frame including fcs*/
@ -53,10 +65,10 @@ extern volatile kernel_pid_t transceiver_pid;
extern uint8_t driver_state;
void at86rf231_init(kernel_pid_t tpid);
//void at86rf231_reset(void);
/* void at86rf231_reset(void); */
void at86rf231_rx(void);
void at86rf231_rx_handler(void);
void at86rf231_rx_irq(void);
void at86rf231_rx_irq(void *arg);
int16_t at86rf231_send(at86rf231_packet_t *packet);
@ -84,4 +96,5 @@ enum {
extern at86rf231_packet_t at86rf231_rx_buffer[AT86RF231_RX_BUF_SIZE];
#endif
#endif /* AT86RF231_H_ */
/** @} */

View File

@ -1,3 +1,21 @@
/*
* Copyright (C) 2014 INRIA
*
* 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 drivers_at86rf231
* @{
*
* @file
* @brief Register and command definitions for the AT86RF231 radio
*
* @author Alaeddine Weslati <alaeddine.weslati@inria.fr>
*/
#ifndef AT86AT86RF231_SETTINGS_H
#define AT86AT86RF231_SETTINGS_H