diff --git a/cpu/avr/radio/rf230bb/hal.h b/cpu/avr/radio/rf230bb/hal.h index f813d0236..c9b0553a5 100644 --- a/cpu/avr/radio/rf230bb/hal.h +++ b/cpu/avr/radio/rf230bb/hal.h @@ -47,7 +47,7 @@ * \file * \brief This file contains low-level radio driver code. * - * $Id: hal.h,v 1.4 2010/11/30 19:47:40 dak664 Exp $ + * $Id: hal.h,v 1.5 2010/12/03 20:42:01 dak664 Exp $ */ #ifndef HAL_AVR_H @@ -55,9 +55,7 @@ /*============================ INCLUDE =======================================*/ #include #include -#include -#include -#include +//#include #include "contiki-conf.h" /*============================ MACROS ========================================*/ @@ -82,7 +80,7 @@ - +/* TODO: Move to platform (or CPU specific) */ #if RCB_REVISION == RCB_B /* 1281 rcb */ # define SSPORT B @@ -168,12 +166,49 @@ # define HAS_CW_MODE # define HAS_SPARE_TIMER +#elif CONTIKI_TARGET_MULLE +/* mulle 5.2 (TODO: move to platform specific) */ + +# define SSPORT 3 +# define SSPIN 5 +# define MOSIPORT 1 +# define MOSIPIN 1 +# define MISOPORT 1 +# define MISOPIN 0 +# define SCKPORT 3 +# define SCKPIN 3 +# define RSTPORT 4 +# define RSTPIN 3 +# define IRQPORT 8 +# define IRQPIN 3 +# define SLPTRPORT 0 +# define SLPTRPIN 7 +# define HAS_SPARE_TIMER + + #else #error "Platform undefined in hal.h" #endif +/* For architectures that have all SPI signals on the same port */ +#ifndef SSPORT +#define SSPORT SPIPORT +#endif + +#ifndef SCKPORT +#define SCKPORT SPIPORT +#endif + +#ifndef MOSIPORT +#define MOSIPORT SPIPORT +#endif + +#ifndef MISOPORT +#define MISOPORT SPIPORT +#endif + /** \} */ /** @@ -185,6 +220,7 @@ * if TICKTIMER is defined as 0. * \{ */ +#if defined(__AVR__) #define CAT(x, y) x##y #define CAT2(x, y, z) x##y##z #define DDR(x) CAT(DDR, x) @@ -212,6 +248,39 @@ #define COMPVECT(x) CAT2(TIMER,x,_COMPA_vect) #define UDREVECT(x) CAT2(USART,x,_UDRE_vect) #define RXVECT(x) CAT2(USART,x,_RX_vect) +#endif + +/* TODO: Move to CPU specific */ +#if defined(CONTIKI_TARGET_MULLE) +#define CAT(x, y) x##y.BYTE +#define CAT2(x, y, z) x##y##z.BYTE +#define DDR(x) CAT(PD, x) +#define PORT(x) CAT(P, x) +#define PIN(x) CAT(P, x) +#define UCSR(num, let) CAT2(UCSR,num,let) +#define RXEN(x) CAT(RXEN,x) +#define TXEN(x) CAT(TXEN,x) +#define TXC(x) CAT(TXC,x) +#define RXC(x) CAT(RXC,x) +#define RXCIE(x) CAT(RXCIE,x) +#define UCSZ(x,y) CAT2(UCSZ,x,y) +#define UBRR(x,y) CAT2(UBRR,x,y) +#define UDRE(x) CAT(UDRE,x) +#define UDRIE(x) CAT(UDRIE,x) +#define UDR(x) CAT(UDR,x) +#define TCNT(x) CAT(TCNT,x) +#define TIMSK(x) CAT(TIMSK,x) +#define TCCR(x,y) CAT2(TCCR,x,y) +#define COM(x,y) CAT2(COM,x,y) +#define OCR(x,y) CAT2(OCR,x,y) +#define CS(x,y) CAT2(CS,x,y) +#define WGM(x,y) CAT2(WGM,x,y) +#define OCIE(x,y) CAT2(OCIE,x,y) +#define COMPVECT(x) CAT2(TIMER,x,_COMPA_vect) +#define UDREVECT(x) CAT2(USART,x,_UDRE_vect) +#define RXVECT(x) CAT2(USART,x,_RX_vect) +#endif + /** \} */ /** @@ -230,13 +299,24 @@ #define RST RSTPIN /**< Pin number that corresponds to the RST pin. */ #define DDR_RST DDR( RSTPORT ) /**< Data Direction Register that corresponds to the port where RST is */ #define PORT_RST PORT( RSTPORT ) /**< Port (Write Access) where RST is connected. */ -#define PIN_RST PIN( RSTPORT ) /**< Pin (Read Access) where RST is connected. */ +#define PIN_RST PIN( RSTPORT /* BUG? */) /**< Pin (Read Access) where RST is connected. */ #define hal_set_rst_high( ) ( PORT_RST |= ( 1 << RST ) ) /**< This macro pulls the RST pin high. */ #define hal_set_rst_low( ) ( PORT_RST &= ~( 1 << RST ) ) /**< This macro pulls the RST pin low. */ #define hal_get_rst( ) ( ( PIN_RST & ( 1 << RST ) ) >> RST ) /**< Read current state of the RST pin (High/Low). */ #define HAL_SS_PIN SSPIN /**< The slave select pin. */ +#define HAL_SCK_PIN SCKPIN /**< Data bit for SCK. */ +#define HAL_MOSI_PIN MOSIPIN +#define HAL_MISO_PIN MISOPIN #define HAL_PORT_SPI PORT( SPIPORT ) /**< The SPI module is located on PORTB. */ +#define HAL_PORT_SS PORT( SSPORT ) +#define HAL_PORT_SCK PORT( SCKPORT ) +#define HAL_PORT_MOSI PORT( MOSIPORT ) /**< The SPI module uses GPIO might be split on different ports. */ +#define HAL_PORT_MISO PORT( MISOPORT ) /**< The SPI module uses GPIO might be split on different ports. */ #define HAL_DDR_SPI DDR( SPIPORT ) /**< Data Direction Register for PORTB. */ +#define HAL_DDR_SS DDR( SSPORT ) /**< Data Direction Register for MISO GPIO pin. */ +#define HAL_DDR_SCK DDR( SCKPORT ) /**< Data Direction Register for MISO GPIO pin. */ +#define HAL_DDR_MOSI DDR( MOSIPORT ) /**< Data Direction Register for MISO GPIO pin. */ +#define HAL_DDR_MISO DDR( MISOPORT ) /**< Data Direction Register for MOSI GPIO pin. */ #define HAL_DD_SS SSPIN /**< Data Direction bit for SS. */ #define HAL_DD_SCK SCKPIN /**< Data Direction bit for SCK. */ #define HAL_DD_MOSI MOSIPIN /**< Data Direction bit for MOSI. */ @@ -244,8 +324,8 @@ /** \} */ -#define HAL_SS_HIGH( ) (HAL_PORT_SPI |= ( 1 << HAL_SS_PIN )) /**< MACRO for pulling SS high. */ -#define HAL_SS_LOW( ) (HAL_PORT_SPI &= ~( 1 << HAL_SS_PIN )) /**< MACRO for pulling SS low. */ +#define HAL_SS_HIGH( ) (HAL_PORT_SS |= ( 1 << HAL_SS_PIN )) /**< MACRO for pulling SS high. */ +#define HAL_SS_LOW( ) (HAL_PORT_SS &= ~( 1 << HAL_SS_PIN )) /**< MACRO for pulling SS low. */ /** \brief Macros defined for HAL_TIMER1. * @@ -254,6 +334,7 @@ * symbols (16 us ticks). */ +#if defined(__AVR__) #if ( F_CPU == 16000000UL ) #define HAL_TCCR1B_CONFIG ( ( 1 << ICES1 ) | ( 1 << CS12 ) ) #define HAL_US_PER_SYMBOL ( 1 ) @@ -290,11 +371,28 @@ #define HAL_DISABLE_OVERFLOW_INTERRUPT( ) ( TIMSK1 &= ~( 1 << TOIE1 ) ) /** This macro will protect the following code from interrupts.*/ -#define AVR_ENTER_CRITICAL_REGION( ) {uint8_t volatile saved_sreg = SREG; cli( ) +#define HAL_ENTER_CRITICAL_REGION( ) {uint8_t volatile saved_sreg = SREG; cli( ) -/** This macro must always be used in conjunction with AVR_ENTER_CRITICAL_REGION +/** This macro must always be used in conjunction with HAL_ENTER_CRITICAL_REGION so that interrupts are enabled again.*/ -#define AVR_LEAVE_CRITICAL_REGION( ) SREG = saved_sreg;} +#define HAL_LEAVE_CRITICAL_REGION( ) SREG = saved_sreg;} + +#else /* MULLE */ + +#define HAL_ENABLE_RADIO_INTERRUPT( ) ( INT1IC.BYTE |= 1 ) +#define HAL_DISABLE_RADIO_INTERRUPT( ) ( INT1IC.BYTE &= ~(1) ) + +#define HAL_ENABLE_OVERFLOW_INTERRUPT( ) ( TB4IC.BYTE = 1 ) +#define HAL_DISABLE_OVERFLOW_INTERRUPT( ) ( TB4IC.BYTE = 0 ) + +/** This macro will protect the following code from interrupts.*/ +#define HAL_ENTER_CRITICAL_REGION( ) MULLE_ENTER_CRITICAL_REGION( ) + +/** This macro must always be used in conjunction with HAL_ENTER_CRITICAL_REGION + so that interrupts are enabled again.*/ +#define HAL_LEAVE_CRITICAL_REGION( ) MULLE_LEAVE_CRITICAL_REGION( ) + +#endif /* !__AVR__ */ /** \brief Enable the interrupt from the radio transceiver. diff --git a/cpu/avr/radio/rf230bb/halbb.c b/cpu/avr/radio/rf230bb/halbb.c index 5b05d6067..9229fa56f 100644 --- a/cpu/avr/radio/rf230bb/halbb.c +++ b/cpu/avr/radio/rf230bb/halbb.c @@ -132,44 +132,74 @@ static uint16_t hal_system_time = 0; /*============================ PROTOTYPES ====================================*/ /*============================ IMPLEMENTATION ================================*/ -#ifndef RF230BB_HARDWARE_SPI -#define RF230BB_HARDWARE_SPI 1 -#endif +#if defined(__AVR__) +/* + * AVR with hardware SPI tranfers (TODO: move to hw spi hal for avr cpu) + */ +#include +#include -#if RF230BB_HARDWARE_SPI -// AVR with hardware spi tranfers #define HAL_SPI_TRANSFER_OPEN() { \ - AVR_ENTER_CRITICAL_REGION(); \ + HAL_ENTER_CRITICAL_REGION(); \ HAL_SS_LOW(); /* Start the SPI transaction by pulling the Slave Select low. */ -#define HAL_SPI_TRANSFER_WRITE(to_write) SPDR = to_write +#define HAL_SPI_TRANSFER_WRITE(to_write) (SPDR = (to_write)) #define HAL_SPI_TRANSFER_WAIT() ({while ((SPSR & (1 << SPIF)) == 0) {;}}) /* gcc extension, alternative inline function */ #define HAL_SPI_TRANSFER_READ() (SPDR) #define HAL_SPI_TRANSFER_CLOSE() \ HAL_SS_HIGH(); /* End the transaction by pulling the Slave Select High. */ \ - AVR_LEAVE_CRITICAL_REGION(); \ + HAL_LEAVE_CRITICAL_REGION(); \ } #define HAL_SPI_TRANSFER(to_write) ( \ HAL_SPI_TRANSFER_WRITE(to_write), \ HAL_SPI_TRANSFER_WAIT(), \ HAL_SPI_TRANSFER_READ() ) -#else /* RF230BB_HARDWARE_SPI */ -// Software SPI transfers (Mulle, for reference) +#else /* __AVR__ */ +/* + * Other SPI architecture (parts to core, parts to m16c6Xp + */ +#include "contiki-mulle.h" // MULLE_ENTER_CRITICAL_REGION + +// Software SPI transfers #define HAL_SPI_TRANSFER_OPEN() { uint8_t spiTemp; \ - AVR_ENTER_CRITICAL_REGION(); \ + HAL_ENTER_CRITICAL_REGION(); \ HAL_SS_LOW(); /* Start the SPI transaction by pulling the Slave Select low. */ #define HAL_SPI_TRANSFER_WRITE(to_write) (spiTemp = spiWrite(to_write)) -#define HAL_SPI_TRANSFER_WAIT() (0) +#define HAL_SPI_TRANSFER_WAIT() ({0;}) #define HAL_SPI_TRANSFER_READ() (spiTemp) #define HAL_SPI_TRANSFER_CLOSE() \ HAL_SS_HIGH(); /* End the transaction by pulling the Slave Select High. */ \ - AVR_LEAVE_CRITICAL_REGION(); \ + HAL_LEAVE_CRITICAL_REGION(); \ } #define HAL_SPI_TRANSFER(to_write) (spiTemp = spiWrite(to_write)) -#endif /* RF230BB_HARDWARE_SPI */ + +inline uint8_t spiWrite(uint8_t byte) +{ + uint8_t data = 0; + uint8_t mask = 0x80; + do + { + if( (byte & mask) != 0 ) + HAL_PORT_MOSI |= (1 << HAL_MOSI_PIN); //call MOSI.set(); + else + HAL_PORT_MOSI &= ~(1 << HAL_MOSI_PIN); //call MOSI.clr(); + + HAL_PORT_SCK &= ~(1 << HAL_SCK_PIN); //call SCLK.clr(); + if( (HAL_PORT_MISO & (1 << HAL_MISO_PIN)) > 0) //call MISO.get() ) + data |= mask; + HAL_PORT_SCK |= (1 << HAL_SCK_PIN); //call SCLK.set(); + } while( (mask >>= 1) != 0 ); + return data; +} + +#endif /* !__AVR__ */ /** \brief This function initializes the Hardware Abstraction Layer. */ +#if defined(__AVR__) +#define HAL_RF230_ISR() ISR(RADIO_VECT) +#define HAL_TIME_ISR() ISR(TIMER1_OVF_vect) +#define HAL_TICK_UPCNT() (TCNT1) void hal_init(void) { @@ -177,7 +207,7 @@ hal_init(void) hal_system_time = 0; // hal_reset_flags(); - /*IO Specific Initialization.*/ + /*IO Specific Initialization - sleep and reset pins. */ DDR_SLP_TR |= (1 << SLP_TR); /* Enable SLP_TR as output. */ DDR_RST |= (1 << RST); /* Enable RST as output. */ @@ -196,6 +226,49 @@ hal_init(void) hal_enable_trx_interrupt(); /* Enable interrupts from the radio transceiver. */ } +#else /* __AVR__ */ + +#define HAL_RF230_ISR() M16C_INTERRUPT(M16C_INT1) +#define HAL_TIME_ISR() M16C_INTERRUPT(M16C_TMRB4) +#define HAL_TICK_UPCNT() (0xFFFF-TB4) // TB4 counts down so we need to convert it to upcounting + +void +hal_init(void) +{ + /*Reset variables used in file.*/ + hal_system_time = 0; +// hal_reset_flags(); + + /*IO Specific Initialization - sleep and reset pins. */ + DDR_SLP_TR |= (1 << SLP_TR); /* Enable SLP_TR as output. */ + DDR_RST |= (1 << RST); /* Enable RST as output. */ + + /*SPI Specific Initialization.*/ + /* Set SS, CLK and MOSI as output. */ + HAL_DDR_SS |= (1 << HAL_SS_PIN); + HAL_DDR_SCK |= (1 << HAL_SCK_PIN); + HAL_DDR_MOSI |= (1 << HAL_MOSI_PIN); + HAL_DDR_MISO &= ~(1 << HAL_MISO_PIN); + + /* Set SS */ + HAL_PORT_SS |= (1 << HAL_SS_PIN); // HAL_SS_HIGH() + HAL_PORT_SCK |= (1 << HAL_SCK_PIN); + + /*TIMER Specific Initialization.*/ + // Init count source (Timer B3) + TB3 = ((16*10) - 1); // 16 us ticks + TB3MR.BYTE = 0b00000000; // Timer mode, F1 + TBSR.BIT.TB3S = 1; // Start Timer B3 + + TB4 = 0xFFFF; // + TB4MR.BYTE = 0b10000001; // Counter mode, count TB3 + TBSR.BIT.TB4S = 1; // Start Timer B4 + INT1IC.BIT.POL = 1; // Select rising edge + HAL_ENABLE_OVERFLOW_INTERRUPT(); /* Enable Timer overflow interrupt. */ + hal_enable_trx_interrupt(); /* Enable interrupts from the radio transceiver. */ +} +#endif /* !__AVR__ */ + /*----------------------------------------------------------------------------*/ /** \brief This function reset the interrupt flags and interrupt event handlers * (Callbacks) to their default value. @@ -203,7 +276,7 @@ hal_init(void) //void //hal_reset_flags(void) //{ -// AVR_ENTER_CRITICAL_REGION(); +// HAL_ENTER_CRITICAL_REGION(); /* Reset Flags. */ // hal_bat_low_flag = 0; @@ -213,7 +286,7 @@ hal_init(void) // rx_start_callback = NULL; // trx_end_callback = NULL; -// AVR_LEAVE_CRITICAL_REGION(); +// HAL_LEAVE_CRITICAL_REGION(); //} /*----------------------------------------------------------------------------*/ @@ -235,9 +308,9 @@ hal_init(void) //void //hal_clear_bat_low_flag(void) //{ -// AVR_ENTER_CRITICAL_REGION(); +// HAL_ENTER_CRITICAL_REGION(); // hal_bat_low_flag = 0; -// AVR_LEAVE_CRITICAL_REGION(); +// HAL_LEAVE_CRITICAL_REGION(); //} /*----------------------------------------------------------------------------*/ @@ -257,9 +330,9 @@ hal_init(void) //void //hal_set_trx_end_event_handler(hal_trx_end_isr_event_handler_t trx_end_callback_handle) //{ -// AVR_ENTER_CRITICAL_REGION(); +// HAL_ENTER_CRITICAL_REGION(); // trx_end_callback = trx_end_callback_handle; -// AVR_LEAVE_CRITICAL_REGION(); +// HAL_LEAVE_CRITICAL_REGION(); //} /*----------------------------------------------------------------------------*/ @@ -268,9 +341,9 @@ hal_init(void) //void //hal_clear_trx_end_event_handler(void) //{ -// AVR_ENTER_CRITICAL_REGION(); +// HAL_ENTER_CRITICAL_REGION(); // trx_end_callback = NULL; -// AVR_LEAVE_CRITICAL_REGION(); +// HAL_LEAVE_CRITICAL_REGION(); //} /*----------------------------------------------------------------------------*/ @@ -291,9 +364,9 @@ hal_init(void) //void //hal_set_rx_start_event_handler(hal_rx_start_isr_event_handler_t rx_start_callback_handle) //{ -// AVR_ENTER_CRITICAL_REGION(); +// HAL_ENTER_CRITICAL_REGION(); // rx_start_callback = rx_start_callback_handle; -// AVR_LEAVE_CRITICAL_REGION(); +// HAL_LEAVE_CRITICAL_REGION(); //} /*----------------------------------------------------------------------------*/ @@ -302,9 +375,9 @@ hal_init(void) //void //hal_clear_rx_start_event_handler(void) //{ -// AVR_ENTER_CRITICAL_REGION(); +// HAL_ENTER_CRITICAL_REGION(); // rx_start_callback = NULL; -// AVR_LEAVE_CRITICAL_REGION(); +// HAL_LEAVE_CRITICAL_REGION(); //} /*----------------------------------------------------------------------------*/ @@ -326,9 +399,9 @@ hal_init(void) //void //hal_clear_pll_lock_flag(void) //{ -// AVR_ENTER_CRITICAL_REGION(); +// HAL_ENTER_CRITICAL_REGION(); // hal_pll_lock_flag = 0; -// AVR_LEAVE_CRITICAL_REGION(); +// HAL_LEAVE_CRITICAL_REGION(); //} /*----------------------------------------------------------------------------*/ @@ -488,7 +561,6 @@ hal_frame_read(hal_rx_frame_t *rx_frame) do{ *rx_data++ = HAL_SPI_TRANSFER_READ(); HAL_SPI_TRANSFER_WRITE(0); - HAL_SPI_TRANSFER_WAIT(); // if (rx_frame){ // *rx_data++ = tempData; @@ -500,13 +572,15 @@ hal_frame_read(hal_rx_frame_t *rx_frame) /* A full buffer should be read in 320us at 2x spi clocking, so with a low interrupt latency overwrites should not occur */ // crc = _crc_ccitt_update(crc, tempData); + HAL_SPI_TRANSFER_WAIT(); + } while (--frame_length > 0); /*Read LQI value for this frame.*/ // if (rx_frame){ rx_frame->lqi = HAL_SPI_TRANSFER_READ(); // } else { -// rx_callback(SPDR); +// rx_callback(HAL_SPI_TRANSFER_READ()); // } @@ -567,31 +641,21 @@ hal_frame_write(uint8_t *write_buffer, uint8_t length) //void //hal_sram_read(uint8_t address, uint8_t length, uint8_t *data) //{ -// AVR_ENTER_CRITICAL_REGION(); - -// HAL_SS_LOW(); /* Initiate the SPI transaction. */ +// HAL_SPI_TRANSFER_OPEN(); /*Send SRAM read command.*/ -// SPDR = HAL_TRX_CMD_SR; -// while ((SPSR & (1 << SPIF)) == 0) {;} -// uint8_t dummy_read = SPDR; +// uint8_t dummy_read = HAL_SPI_TRANSFER(HAL_TRX_CMD_SR); /*Send address where to start reading.*/ -// SPDR = address; -// while ((SPSR & (1 << SPIF)) == 0) {;} - -// dummy_read = SPDR; +// dummy_read = HAL_SPI_TRANSFER(address); /*Upload the chosen memory area.*/ // do{ -// SPDR = HAL_DUMMY_READ; -// while ((SPSR & (1 << SPIF)) == 0) {;} -// *data++ = SPDR; +// *data++ = HAL_SPI_TRANSFER(HAL_DUMMY_READ); // } while (--length > 0); -// HAL_SS_HIGH(); +// HAL_SPI_TRANSFER_CLOSE(); -// AVR_LEAVE_CRITICAL_REGION(); //} /*----------------------------------------------------------------------------*/ @@ -606,30 +670,21 @@ hal_frame_write(uint8_t *write_buffer, uint8_t length) //void //hal_sram_write(uint8_t address, uint8_t length, uint8_t *data) //{ -// AVR_ENTER_CRITICAL_REGION(); - -// HAL_SS_LOW(); +// HAL_SPI_TRANSFER_OPEN(); /*Send SRAM write command.*/ -// SPDR = HAL_TRX_CMD_SW; -// while ((SPSR & (1 << SPIF)) == 0) {;} -// uint8_t dummy_read = SPDR; +// uint8_t dummy_read = HAL_SPI_TRANSFER(HAL_TRX_CMD_SW); /*Send address where to start writing to.*/ -// SPDR = address; -// while ((SPSR & (1 << SPIF)) == 0) {;} -// dummy_read = SPDR; +// dummy_read = HAL_SPI_TRANSFER(address); /*Upload the chosen memory area.*/ // do{ -// SPDR = *data++; -// while ((SPSR & (1 << SPIF)) == 0) {;} -// dummy_read = SPDR; +// dummy_read = HAL_SPI_TRANSFER(*data++); // } while (--length > 0); -// HAL_SS_HIGH(); +// HAL_SPI_TRANSFER_CLOSE(); -// AVR_LEAVE_CRITICAL_REGION(); //} /*----------------------------------------------------------------------------*/ @@ -654,24 +709,29 @@ volatile char rf230interruptflag; #define INTERRUPTDEBUG(arg) #endif -ISR(RADIO_VECT) +HAL_RF230_ISR() { /*The following code reads the current system time. This is done by first reading the hal_system_time and then adding the 16 LSB directly from the - TCNT1 register. Not implented in RF230BB for speed + hardware counter. */ // uint32_t isr_timestamp = hal_system_time; // isr_timestamp <<= 16; -// isr_timestamp |= TCNT1; +// isr_timestamp |= HAL_TICK_UPCNT(); // TODO: what if this wraps after reading hal_system_time? + volatile uint8_t state; - + uint8_t interrupt_source; /* used after HAL_SPI_TRANSFER_OPEN/CLOSE block */ + INTERRUPTDEBUG(1); + /* Using SPI bus from ISR is generally a bad idea... */ + /* Note: all IRQ are not always automatically disabled when running in ISR */ + HAL_SPI_TRANSFER_OPEN(); + /*Read Interrupt source.*/ - HAL_SS_LOW(); /*Send Register address and read register content.*/ - SPDR = RG_IRQ_STATUS | HAL_TRX_CMD_RR; + HAL_SPI_TRANSFER_WRITE(RG_IRQ_STATUS | HAL_TRX_CMD_RR); /* This is the second part of the convertion of system time to a 16 us time base. The division is moved here so we can spend less time waiting for SPI @@ -680,31 +740,26 @@ ISR(RADIO_VECT) // isr_timestamp /= HAL_US_PER_SYMBOL; /* Divide so that we get time in 16us resolution. */ // isr_timestamp &= HAL_SYMBOL_MASK; - while ((SPSR & (1 << SPIF)) == 0) {;} - uint8_t interrupt_source = SPDR; /* The interrupt variable is used as a dummy read. */ + HAL_SPI_TRANSFER_WAIT(); /* AFTER possible interleaved processing */ - SPDR = interrupt_source; - while ((SPSR & (1 << SPIF)) == 0) {;} - interrupt_source = SPDR; /* The interrupt source is read. */ + interrupt_source = HAL_SPI_TRANSFER_READ(); /* The interrupt variable is used as a dummy read. */ + + interrupt_source = HAL_SPI_TRANSFER(interrupt_source); + + HAL_SPI_TRANSFER_CLOSE(); - HAL_SS_HIGH(); - /*Handle the incomming interrupt. Prioritized.*/ if ((interrupt_source & HAL_RX_START_MASK)){ INTERRUPTDEBUG(10); // if(rx_start_callback != NULL){ // /* Read Frame length and call rx_start callback. */ -// HAL_SS_LOW(); +// HAL_SPI_TRANSFER_OPEN(); -// SPDR = HAL_TRX_CMD_FR; -// while ((SPSR & (1 << SPIF)) == 0) {;} -// uint8_t frame_length = SPDR; +// uint8_t frame_length = HAL_SPI_TRANSFER(HAL_TRX_CMD_FR); -// SPDR = frame_length; /* frame_length used for dummy data */ -// while ((SPSR & (1 << SPIF)) == 0) {;} -// frame_length = SPDR; +// frame_length = HAL_SPI_TRANSFER(frame_length); -// HAL_SS_HIGH(); +// HAL_SPI_TRANSFER_CLOSE(); // rx_start_callback(isr_timestamp, frame_length); // } @@ -728,10 +783,8 @@ ISR(RADIO_VECT) #if RF230_CONF_AUTOACK rf230_last_rssi=hal_subregister_read(SR_ED_LEVEL); if (rf230_last_rssi >= RF230_MIN_RX_POWER) { -// if (hal_subregister_read(SR_ED_LEVEL) >= RF230_MIN_RX_POWER) { #else rf230_last_rssi=hal_subregister_read(SR_RSSI); - // if (hal_subregister_read(SR_RSSI) >= RF230_MIN_RX_POWER/3) { if (rf230_last_rssi >= RF230_MIN_RX_POWER/3) { #endif #endif @@ -789,7 +842,7 @@ ISR(RADIO_VECT) */ void TIMER1_OVF_vect(void); #else /* !DOXYGEN */ -ISR(TIMER1_OVF_vect) +HAL_TIME_ISR() { hal_system_time++; } diff --git a/cpu/avr/radio/rf230bb/rf230bb.c b/cpu/avr/radio/rf230bb/rf230bb.c index fd7ddefa7..0bdeeb061 100644 --- a/cpu/avr/radio/rf230bb/rf230bb.c +++ b/cpu/avr/radio/rf230bb/rf230bb.c @@ -28,7 +28,7 @@ * * This file is part of the Contiki operating system. * - * @(#)$Id: rf230bb.c,v 1.14 2010/11/26 20:39:15 dak664 Exp $ + * @(#)$Id: rf230bb.c,v 1.15 2010/12/03 20:42:01 dak664 Exp $ */ /* * This code is almost device independent and should be easy to port. @@ -43,6 +43,7 @@ #if defined(__AVR__) #include #include +#define delay_us( us ) ( _delay_us( ( us ) ) ) #include #elif defined(__MSP430__) #include diff --git a/cpu/avr/radio/rf230bb/rf230bb.h b/cpu/avr/radio/rf230bb/rf230bb.h index 1e2d0f96b..b0b6f8eb5 100644 --- a/cpu/avr/radio/rf230bb/rf230bb.h +++ b/cpu/avr/radio/rf230bb/rf230bb.h @@ -45,7 +45,7 @@ * \file * \brief This file contains radio driver code. * - * $Id: rf230bb.h,v 1.3 2010/09/17 21:59:09 dak664 Exp $ + * $Id: rf230bb.h,v 1.4 2010/12/03 20:42:01 dak664 Exp $ */ #ifndef RADIO_H @@ -211,8 +211,6 @@ uint8_t rf230_get_raw_rssi(void); #define rf230_rssi rf230_get_raw_rssi -#define delay_us( us ) ( _delay_loop_2( ( F_CPU / 4000000UL ) * ( us ) ) ) - #endif /** @} */ /*EOF*/ diff --git a/platform/avr-raven/contiki-conf.h b/platform/avr-raven/contiki-conf.h index 495bb8318..066186251 100644 --- a/platform/avr-raven/contiki-conf.h +++ b/platform/avr-raven/contiki-conf.h @@ -102,6 +102,7 @@ #define NETSTACK_CONF_RDC sicslowmac_driver #define NETSTACK_CONF_FRAMER framer_802154 #define NETSTACK_CONF_RADIO rf230_driver +#define CHANNEL_802_15_4 26 #define RF230_CONF_AUTOACK 1 #define RF230_CONF_AUTORETRIES 2 #define SICSLOWPAN_CONF_FRAG 1 @@ -116,6 +117,7 @@ #define NETSTACK_CONF_RDC contikimac_driver #define NETSTACK_CONF_FRAMER framer_802154 #define NETSTACK_CONF_RADIO rf230_driver +#define CHANNEL_802_15_4 26 #define RF230_CONF_AUTOACK 0 #define RF230_CONF_AUTORETRIES 0 @@ -125,6 +127,7 @@ #define NETSTACK_CONF_RDC cxmac_driver #define NETSTACK_CONF_FRAMER framer_802154 #define NETSTACK_CONF_RADIO rf230_driver +#define CHANNEL_802_15_4 26 #define RF230_CONF_AUTOACK 0 #define RF230_CONF_AUTORETRIES 0 #define MAC_CONF_CHANNEL_CHECK_RATE 8 @@ -189,7 +192,6 @@ //#define RF230_MIN_RX_POWER 30 #define UIP_CONF_ROUTER 1 -#define UIP_CONF_IPV6_RPL 1 /* Handle 10 neighbors */ #define UIP_CONF_DS6_NBR_NBU 10 diff --git a/platform/avr-raven/contiki-raven-main.c b/platform/avr-raven/contiki-raven-main.c index 21dc8f676..1bfd91433 100644 --- a/platform/avr-raven/contiki-raven-main.c +++ b/platform/avr-raven/contiki-raven-main.c @@ -126,7 +126,12 @@ static uint8_t get_channel_from_eeprom() { if(eeprom_channel==~eeprom_check) return eeprom_channel; + +#ifdef CHANNEL_802_15_4 + return(CHANNEL_802_15_4); +#else return 26; +#endif } static bool get_mac_from_eeprom(uint8_t* macptr) { diff --git a/platform/avr-ravenusb/cdc_task.c b/platform/avr-ravenusb/cdc_task.c index 554bac8d5..83fb8956b 100644 --- a/platform/avr-ravenusb/cdc_task.c +++ b/platform/avr-ravenusb/cdc_task.c @@ -298,11 +298,9 @@ void menu_process(char c) if(settings_set_uint8(SETTINGS_KEY_CHANNEL, tempchannel)!=SETTINGS_STATUS_OK) { PRINTF_P(PSTR("\n\rChannel changed to %d, but unable to store in EEPROM!\n\r"),tempchannel); } else -#else - AVR_ENTER_CRITICAL_REGION(); +#else eeprom_write_byte((uint8_t *) 9, tempchannel); //Write channel eeprom_write_byte((uint8_t *)10, ~tempchannel); //Bit inverse as check - AVR_LEAVE_CRITICAL_REGION(); #endif PRINTF_P(PSTR("\n\rChannel changed to %d and stored in EEPROM.\n\r"),tempchannel); } @@ -446,8 +444,16 @@ void menu_process(char c) #include "rpl.h" extern uip_ds6_nbr_t uip_ds6_nbr_cache[]; extern uip_ds6_route_t uip_ds6_routing_table[]; +extern uip_ds6_netif_t uip_ds6_if; case 'N': { uint8_t i,j; + PRINTF_P(PSTR("\n\rAddresses [%u max]\n\r"),UIP_DS6_ADDR_NB); + for (i=0;isout); PSOCK_GENERATOR_SEND(&s->sout, generate_string_P, TOP1); @@ -262,6 +262,8 @@ PT_THREAD(generate_routes(struct httpd_state *s)) #if UIP_CONF_IPV6 //allow ip4 builds blen = 0; ADD("

Neighbors [%u max]

",UIP_DS6_NBR_NB); + PSOCK_GENERATOR_SEND(&s->sout, generate_string, buf); + blen = 0; for(i = 0; i < UIP_DS6_NBR_NB; i++) { if(uip_ds6_nbr_cache[i].isused) { ipaddr_add(&uip_ds6_nbr_cache[i].ipaddr); @@ -284,6 +286,8 @@ PT_THREAD(generate_routes(struct httpd_state *s)) blen=0; ipaddr_add(&uip_ds6_routing_table[i].nexthop); if(uip_ds6_routing_table[i].state.lifetime < 600) { + PSOCK_GENERATOR_SEND(&s->sout, generate_string, buf); + blen=0; ADD(") %lus
", uip_ds6_routing_table[i].state.lifetime); } else { ADD(")
"); diff --git a/platform/avr-zigbit/contiki-avr-zigbit-main.c b/platform/avr-zigbit/contiki-avr-zigbit-main.c index 8f63439fb..7eead3ff8 100644 --- a/platform/avr-zigbit/contiki-avr-zigbit-main.c +++ b/platform/avr-zigbit/contiki-avr-zigbit-main.c @@ -122,15 +122,17 @@ init_lowlevel(void) rimeaddr_t addr; memset(&addr, 0, sizeof(rimeaddr_t)); - AVR_ENTER_CRITICAL_REGION(); eeprom_read_block ((void *)&addr.u8, &mac_address, 8); - AVR_LEAVE_CRITICAL_REGION(); #if UIP_CONF_IPV6 memcpy(&uip_lladdr.addr, &addr.u8, 8); #endif rf230_set_pan_addr(IEEE802154_PANID, 0, (uint8_t *)&addr.u8); - rf230_set_channel(24); +#ifdef CHANNEL_802_15_4 + rf230_set_channel(CHANNEL_802_15_4); +#else + rf230_set_channel(26); +#endif rimeaddr_set_node_addr(&addr); diff --git a/platform/avr-zigbit/contiki-conf.h b/platform/avr-zigbit/contiki-conf.h index fb219cb97..c9f67fe9f 100644 --- a/platform/avr-zigbit/contiki-conf.h +++ b/platform/avr-zigbit/contiki-conf.h @@ -43,7 +43,6 @@ #define __CONTIKI_CONF_H__ /* MCU and clock rate */ -#define MCU_MHZ 8 #define PLATFORM PLATFORM_AVR #define HARWARE_REVISION ZIGBIT @@ -97,6 +96,7 @@ #define NETSTACK_CONF_RDC sicslowmac_driver #define NETSTACK_CONF_FRAMER framer_802154 #define NETSTACK_CONF_RADIO rf230_driver +#define CHANNEL_802_15_4 26 #define RF230_CONF_AUTOACK 1 #define RF230_CONF_AUTORETRIES 2 #define SICSLOWPAN_CONF_FRAG 1