Cleaned up RF230BB, and refactored FRAME_RETRIES and CSMA_RETRIES

#defines.
This commit is contained in:
Ivan Delamer 2012-09-04 11:12:18 -06:00
parent 2e72ec3594
commit b43dad00b0
8 changed files with 320 additions and 638 deletions

View File

@ -10,6 +10,7 @@
* Kevin Brown kbrown3@uccs.edu * Kevin Brown kbrown3@uccs.edu
* Nate Bohlmann nate@elfwerks.com * Nate Bohlmann nate@elfwerks.com
* David Kopf dak664@embarqmail.com * David Kopf dak664@embarqmail.com
* Ivan Delamer delamer@ieee.com
* *
* All rights reserved. * All rights reserved.
* *
@ -60,10 +61,6 @@
#include "contiki-conf.h" #include "contiki-conf.h"
/*============================ MACROS ========================================*/ /*============================ MACROS ========================================*/
// TEST CODE
#define TRIG1 DDRB |= 0x04, PINB |= 0x04
#define TRIG2 DDRD |= 0x80, PIND |= 0x80
/** \name This is the list of pin configurations needed for a given platform. /** \name This is the list of pin configurations needed for a given platform.
* \brief Change these values to port to other platforms. * \brief Change these values to port to other platforms.
* \{ * \{
@ -97,10 +94,6 @@
# define IRQPIN (0x04) # define IRQPIN (0x04)
# define SLPTRPORT B # define SLPTRPORT B
# define SLPTRPIN (0x04) # define SLPTRPIN (0x04)
# define USART 1
# define USARTVECT USART1_RX_vect
# define TICKTIMER 3
# define HAS_SPARE_TIMER
#elif PLATFORM_TYPE == ZIGBIT #elif PLATFORM_TYPE == ZIGBIT
/* 1281V Zigbit */ /* 1281V Zigbit */
@ -116,12 +109,6 @@
# define IRQPIN (0x05) # define IRQPIN (0x05)
# define SLPTRPORT B # define SLPTRPORT B
# define SLPTRPIN (0x04) # define SLPTRPIN (0x04)
# define TXCWPORT B
# define TXCWPIN (0x07)
# define USART 1
# define USARTVECT USART1_RX_vect
//# define TICKTIMER 3
//# define HAS_SPARE_TIMER // Not used
#elif PLATFORM_TYPE == RAVEN_D #elif PLATFORM_TYPE == RAVEN_D
@ -138,13 +125,6 @@
# define IRQPIN (0x06) # define IRQPIN (0x06)
# define SLPTRPORT B # define SLPTRPORT B
# define SLPTRPIN (0x03) # define SLPTRPIN (0x03)
# define TXCWPORT B
# define TXCWPIN (0x00)
# define USART 1
# define USARTVECT USART1_RX_vect
# define TICKTIMER 3
# define HAS_CW_MODE
# define HAS_SPARE_TIMER
#elif PLATFORM_TYPE == RAVENUSB_C #elif PLATFORM_TYPE == RAVENUSB_C
/* 1287USB raven */ /* 1287USB raven */
@ -160,23 +140,11 @@
# define IRQPIN (0x04) # define IRQPIN (0x04)
# define SLPTRPORT B # define SLPTRPORT B
# define SLPTRPIN (0x04) # define SLPTRPIN (0x04)
# define TXCWPORT B
# define TXCWPIN (0x07)
# define USART 1
# define USARTVECT USART1_RX_vect
# define TICKTIMER 3
# define HAS_CW_MODE
# define HAS_SPARE_TIMER
#elif PLATFORM_TYPE == ATMEGA128RFA1 #elif PLATFORM_TYPE == ATMEGA128RFA1
/* ATmega1281 with internal AT86RF231 radio */ /* ATmega1281 with internal AT86RF231 radio */
# define SLPTRPORT TRXPR # define SLPTRPORT TRXPR
# define SLPTRPIN 1 # define SLPTRPIN 1
# define USART 1
# define USARTVECT USART1_RX_vect
# define TICKTIMER 3
# define HAS_CW_MODE
# define HAS_SPARE_TIMER
#elif CONTIKI_TARGET_MULLE #elif CONTIKI_TARGET_MULLE
/* mulle 5.2 (TODO: move to platform specific) */ /* mulle 5.2 (TODO: move to platform specific) */
@ -194,7 +162,6 @@
# define IRQPIN 3 # define IRQPIN 3
# define SLPTRPORT 0 # define SLPTRPORT 0
# define SLPTRPIN 7 # define SLPTRPIN 7
# define HAS_SPARE_TIMER
#elif PLATFORM_TYPE == IRIS #elif PLATFORM_TYPE == IRIS
/* 1281 IRIS */ /* 1281 IRIS */
@ -210,12 +177,6 @@
# define IRQPIN (0x04) # define IRQPIN (0x04)
# define SLPTRPORT B # define SLPTRPORT B
# define SLPTRPIN (0x07) # define SLPTRPIN (0x07)
//# define TXCWPORT B
//# define TXCWPIN (0x07)
# define USART 1
# define USARTVECT USART1_RX_vect
//# define TICKTIMER 3
//# define HAS_SPARE_TIMER // Not used
#else #else
#error "PLATFORM_TYPE undefined in hal.h" #error "PLATFORM_TYPE undefined in hal.h"
@ -252,63 +213,17 @@
*/ */
#if defined(__AVR__) #if defined(__AVR__)
#define CAT(x, y) x##y #define CAT(x, y) x##y
#define CAT2(x, y, z) x##y##z
#define DDR(x) CAT(DDR, x) #define DDR(x) CAT(DDR, x)
#define PORT(x) CAT(PORT, x) #define PORT(x) CAT(PORT, x)
#define PIN(x) CAT(PIN, x) #define PIN(x) CAT(PIN, 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 #endif
/* TODO: Move to CPU specific */ /* TODO: Move to CPU specific */
#if defined(CONTIKI_TARGET_MULLE) #if defined(CONTIKI_TARGET_MULLE)
#define CAT(x, y) x##y.BYTE #define CAT(x, y) x##y.BYTE
#define CAT2(x, y, z) x##y##z.BYTE
#define DDR(x) CAT(PD, x) #define DDR(x) CAT(PD, x)
#define PORT(x) CAT(P, x) #define PORT(x) CAT(P, x)
#define PIN(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 #endif
/** \} */ /** \} */
@ -325,7 +240,6 @@
#define hal_set_rst_high( ) ( TRXPR |= ( 1 << TRXRST ) ) /**< This macro pulls the RST pin high. */ #define hal_set_rst_high( ) ( TRXPR |= ( 1 << TRXRST ) ) /**< This macro pulls the RST pin high. */
#define hal_set_slptr_high( ) ( TRXPR |= ( 1 << SLPTR ) ) /**< This macro pulls the SLP_TR pin high. */ #define hal_set_slptr_high( ) ( TRXPR |= ( 1 << SLPTR ) ) /**< This macro pulls the SLP_TR pin high. */
#define hal_set_slptr_low( ) ( TRXPR &= ~( 1 << SLPTR ) ) /**< This macro pulls the SLP_TR pin low. */ #define hal_set_slptr_low( ) ( TRXPR &= ~( 1 << SLPTR ) ) /**< This macro pulls the SLP_TR pin low. */
//#define hal_get_slptr( ) ( ( TRXPR & ( 1 << SLPTR ) ) >> SLPTR ) /**< Read current state of the SLP_TR pin (High/Low). */
#define hal_get_slptr( ) ( TRXPR & ( 1 << SLPTR ) ) /**< Read current state of the SLP_TR pin (High/Low). */ #define hal_get_slptr( ) ( TRXPR & ( 1 << SLPTR ) ) /**< Read current state of the SLP_TR pin (High/Low). */
#else #else
@ -335,7 +249,6 @@
#define PIN_SLP_TR PIN( SLPTRPORT ) /**< Pin (Read Access) where SLP_TR is connected. */ #define PIN_SLP_TR PIN( SLPTRPORT ) /**< Pin (Read Access) where SLP_TR is connected. */
#define hal_set_slptr_high( ) ( PORT_SLP_TR |= ( 1 << SLP_TR ) ) /**< This macro pulls the SLP_TR pin high. */ #define hal_set_slptr_high( ) ( PORT_SLP_TR |= ( 1 << SLP_TR ) ) /**< This macro pulls the SLP_TR pin high. */
#define hal_set_slptr_low( ) ( PORT_SLP_TR &= ~( 1 << SLP_TR ) ) /**< This macro pulls the SLP_TR pin low. */ #define hal_set_slptr_low( ) ( PORT_SLP_TR &= ~( 1 << SLP_TR ) ) /**< This macro pulls the SLP_TR pin low. */
//#define hal_get_slptr( ) ( ( PIN_SLP_TR & ( 1 << SLP_TR ) ) >> SLP_TR ) /**< Read current state of the SLP_TR pin (High/Low). */
#define hal_get_slptr( ) ( PIN_SLP_TR & ( 1 << SLP_TR ) ) /**< Read current state of the SLP_TR pin (High/Low). */ #define hal_get_slptr( ) ( PIN_SLP_TR & ( 1 << SLP_TR ) ) /**< Read current state of the SLP_TR pin (High/Low). */
#define RST RSTPIN /**< Pin number that corresponds to the RST pin. */ #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 DDR_RST DDR( RSTPORT ) /**< Data Direction Register that corresponds to the port where RST is */
@ -370,42 +283,7 @@
#define HAL_SS_HIGH( ) (HAL_PORT_SS |= ( 1 << HAL_SS_PIN )) /**< MACRO for pulling SS high. */ #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. */ #define HAL_SS_LOW( ) (HAL_PORT_SS &= ~( 1 << HAL_SS_PIN )) /**< MACRO for pulling SS low. */
/** \brief Macros defined for HAL_TIMER1.
*
* These macros are used to define the correct setupt of the AVR's Timer1, and
* to ensure that the hal_get_system_time function returns the system time in
* symbols (16 us ticks).
*/
#if defined(__AVR__) #if defined(__AVR__)
#if ( F_CPU == 16000000UL )
#define HAL_TCCR1B_CONFIG ( ( 1 << ICES1 ) | ( 1 << CS12 ) )
#define HAL_US_PER_SYMBOL ( 1 )
#define HAL_SYMBOL_MASK ( 0xFFFFffff )
#elif ( F_CPU == 0x800000UL )
#define HAL_TCCR1B_CONFIG ( ( 1 << ICES1 ) | ( 1 << CS11 ) | ( 1 << CS10 ) )
#define HAL_US_PER_SYMBOL ( 2 )
#define HAL_SYMBOL_MASK ( 0x7FFFffff )
#elif ( F_CPU == 8000000UL )
#define HAL_TCCR1B_CONFIG ( ( 1 << ICES1 ) | ( 1 << CS11 ) | ( 1 << CS10 ) )
#define HAL_US_PER_SYMBOL ( 2 )
#define HAL_SYMBOL_MASK ( 0x7FFFffff )
//#elif ( F_CPU == 7953408UL )
#elif ( F_CPU == 7954432UL )
#define HAL_TCCR1B_CONFIG ( ( 1 << ICES1 ) | ( 1 << CS11 ) | ( 1 << CS10 ) )
#define HAL_US_PER_SYMBOL ( 2 )
#define HAL_SYMBOL_MASK ( 0x7FFFffff )
#elif ( F_CPU == 4000000UL )
#define HAL_TCCR1B_CONFIG ( ( 1 << ICES1 ) | ( 1 << CS11 ) | ( 1 << CS10 ) )
#define HAL_US_PER_SYMBOL ( 1 )
#define HAL_SYMBOL_MASK ( 0xFFFFffff )
#elif ( F_CPU == 1000000UL )
#define HAL_TCCR1B_CONFIG ( ( 1 << ICES1 ) | ( 1 << CS11 ) )
#define HAL_US_PER_SYMBOL ( 2 )
#define HAL_SYMBOL_MASK ( 0x7FFFffff )
#else
#error "Clock speed not supported."
#endif
#if PLATFORM_TYPE == ZIGBIT #if PLATFORM_TYPE == ZIGBIT
// IRQ E5 for Zigbit example // IRQ E5 for Zigbit example
@ -485,32 +363,10 @@ typedef struct{
bool crc; /**< Flag - did CRC pass for received frame? */ bool crc; /**< Flag - did CRC pass for received frame? */
} hal_rx_frame_t; } hal_rx_frame_t;
/** RX_START event handler callback type. Is called with timestamp in IEEE 802.15.4 symbols and frame length. See hal_set_rx_start_event_handler(). */
typedef void (*hal_rx_start_isr_event_handler_t)(uint32_t const isr_timestamp, uint8_t const frame_length);
/** RRX_END event handler callback type. Is called with timestamp in IEEE 802.15.4 symbols and frame length. See hal_set_trx_end_event_handler(). */
typedef void (*hal_trx_end_isr_event_handler_t)(uint32_t const isr_timestamp);
typedef void (*rx_callback_t) (uint16_t data);
/*============================ PROTOTYPES ====================================*/ /*============================ PROTOTYPES ====================================*/
void hal_init( void ); void hal_init( void );
void hal_reset_flags( void );
uint8_t hal_get_bat_low_flag( void );
void hal_clear_bat_low_flag( void );
hal_trx_end_isr_event_handler_t hal_get_trx_end_event_handler( void );
void hal_set_trx_end_event_handler( hal_trx_end_isr_event_handler_t trx_end_callback_handle );
void hal_clear_trx_end_event_handler( void );
hal_rx_start_isr_event_handler_t hal_get_rx_start_event_handler( void );
void hal_set_rx_start_event_handler( hal_rx_start_isr_event_handler_t rx_start_callback_handle );
void hal_clear_rx_start_event_handler( void );
uint8_t hal_get_pll_lock_flag( void );
void hal_clear_pll_lock_flag( void );
/* Hack for atmega128rfa1 with integrated radio. Access registers directly, not through SPI */ /* Hack for atmega128rfa1 with integrated radio. Access registers directly, not through SPI */
#if defined(__AVR_ATmega128RFA1__) #if defined(__AVR_ATmega128RFA1__)
//#define hal_register_read(address) _SFR_MEM8((uint16_t)address) //#define hal_register_read(address) _SFR_MEM8((uint16_t)address)
@ -534,8 +390,6 @@ void hal_subregister_write( uint8_t address, uint8_t mask, uint8_t position,
//void hal_frame_read(hal_rx_frame_t *rx_frame, rx_callback_t rx_callback);
/* For speed RF230BB does not use a callback */
void hal_frame_read(hal_rx_frame_t *rx_frame); void hal_frame_read(hal_rx_frame_t *rx_frame);
void hal_frame_write( uint8_t *write_buffer, uint8_t length ); void hal_frame_write( uint8_t *write_buffer, uint8_t length );
void hal_sram_read( uint8_t address, uint8_t length, uint8_t *data ); void hal_sram_read( uint8_t address, uint8_t length, uint8_t *data );

View File

@ -10,6 +10,7 @@
* Kevin Brown kbrown3@uccs.edu * Kevin Brown kbrown3@uccs.edu
* Nate Bohlmann nate@elfwerks.com * Nate Bohlmann nate@elfwerks.com
* David Kopf dak664@embarqmail.com * David Kopf dak664@embarqmail.com
* Ivan Delamer delamer@ieee.com
* *
* All rights reserved. * All rights reserved.
* *
@ -80,66 +81,18 @@ extern uint8_t debugflowsize,debugflow[DEBUGFLOWSIZE];
#endif #endif
/*============================ VARIABLES =====================================*/ /*============================ VARIABLES =====================================*/
/** \brief This is a file internal variable that contains the 16 MSB of the
* system time.
*
* The system time (32-bit) is the current time in microseconds. For the
* AVR microcontroller implementation this is solved by using a 16-bit
* timer (Timer1) with a clock frequency of 1MHz. The hal_system_time is
* incremented when the 16-bit timer overflows, representing the 16 MSB.
* The timer value it self (TCNT1) is then the 16 LSB.
*
* \see hal_get_system_time
*/
static uint16_t hal_system_time = 0;
volatile extern signed char rf230_last_rssi;
//static uint8_t volatile hal_bat_low_flag; volatile extern signed char rf230_last_rssi;
//static uint8_t volatile hal_pll_lock_flag;
/*============================ CALLBACKS =====================================*/ /*============================ CALLBACKS =====================================*/
/** \brief This function is called when a rx_start interrupt is signaled.
*
* If this function pointer is set to something else than NULL, it will
* be called when a RX_START event is signaled. The function takes two
* parameters: timestamp in IEEE 802.15.4 symbols (16 us resolution) and
* frame length. The event handler will be called in the interrupt domain,
* so the function must be kept short and not be blocking! Otherwise the
* system performance will be greatly degraded.
*
* \see hal_set_rx_start_event_handler
*/
//static hal_rx_start_isr_event_handler_t rx_start_callback;
/** \brief This function is called when a trx_end interrupt is signaled.
*
* If this function pointer is set to something else than NULL, it will
* be called when a TRX_END event is signaled. The function takes one
* parameter: timestamp in IEEE 802.15.4 symbols (16 us resolution).
* The event handler will be called in the interrupt domain,
* so the function must not block!
*
* \see hal_set_trx_end_event_handler
*/
//static hal_trx_end_isr_event_handler_t trx_end_callback;
/*============================ IMPLEMENTATION ================================*/ /*============================ IMPLEMENTATION ================================*/
#if defined(__AVR_ATmega128RFA1__) #if defined(__AVR_ATmega128RFA1__)
//#include <avr/io.h>
#include <avr/interrupt.h>
/* AVR1281 with internal RF231 radio */ /* AVR1281 with internal RF231 radio */
#define HAL_SPI_TRANSFER_OPEN() #include <avr/interrupt.h>
//#define HAL_SPI_TRANSFER_WRITE(to_write) (SPDR = (to_write))
#define HAL_SPI_TRANSFER_WAIT()
#define HAL_SPI_TRANSFER_READ() (SPDR)
#define HAL_SPI_TRANSFER_CLOSE()
#if 0
#define HAL_SPI_TRANSFER(to_write) ( \
HAL_SPI_TRANSFER_WRITE(to_write), \
HAL_SPI_TRANSFER_WAIT(), \
HAL_SPI_TRANSFER_READ() )
#endif
#elif defined(__AVR__) #elif defined(__AVR__)
/* /*
* AVR with hardware SPI tranfers (TODO: move to hw spi hal for avr cpu) * AVR with hardware SPI tranfers (TODO: move to hw spi hal for avr cpu)
@ -206,30 +159,22 @@ inline uint8_t spiWrite(uint8_t byte)
/** \brief This function initializes the Hardware Abstraction Layer. /** \brief This function initializes the Hardware Abstraction Layer.
*/ */
#if defined(__AVR_ATmega128RFA1__) #if defined(__AVR_ATmega128RFA1__)
//#define HAL_RF230_ISR() ISR(RADIO_VECT)
#define HAL_TIME_ISR() ISR(TIMER1_OVF_vect)
#define HAL_TICK_UPCNT() (TCNT1)
void void
hal_init(void) hal_init(void)
{ {
/*Reset variables used in file.*/ /*Reset variables used in file.*/
hal_system_time = 0; /* (none at the moment) */
// TCCR1B = HAL_TCCR1B_CONFIG; /* Set clock prescaler */
// TIFR1 |= (1 << ICF1); /* Clear Input Capture Flag. */
// HAL_ENABLE_OVERFLOW_INTERRUPT(); /* Enable Timer1 overflow interrupt. */
//hal_enable_trx_interrupt(); /* NOT USED: Enable interrupt pin from the radio transceiver. */
} }
#elif defined(__AVR__) #elif defined(__AVR__)
#define HAL_RF230_ISR() ISR(RADIO_VECT) #define HAL_RF230_ISR() ISR(RADIO_VECT)
#define HAL_TIME_ISR() ISR(TIMER1_OVF_vect)
#define HAL_TICK_UPCNT() (TCNT1)
void void
hal_init(void) hal_init(void)
{ {
/*Reset variables used in file.*/ /*Reset variables used in file.*/
hal_system_time = 0;
// hal_reset_flags();
/*IO Specific Initialization - sleep and reset pins. */ /*IO Specific Initialization - sleep and reset pins. */
/* Set pins low before they are initialized as output? Does not seem to matter */ /* Set pins low before they are initialized as output? Does not seem to matter */
@ -249,11 +194,8 @@ hal_init(void)
SPCR = (1 << SPE) | (1 << MSTR); /* Enable SPI module and master operation. */ SPCR = (1 << SPE) | (1 << MSTR); /* Enable SPI module and master operation. */
SPSR = (1 << SPI2X); /* Enable doubled SPI speed in master mode. */ SPSR = (1 << SPI2X); /* Enable doubled SPI speed in master mode. */
/*TIMER1 Specific Initialization.*/ /* Enable interrupts from the radio transceiver. */
TCCR1B = HAL_TCCR1B_CONFIG; /* Set clock prescaler */ hal_enable_trx_interrupt();
TIFR1 |= (1 << ICF1); /* Clear Input Capture Flag. */
HAL_ENABLE_OVERFLOW_INTERRUPT(); /* Enable Timer1 overflow interrupt. */
hal_enable_trx_interrupt(); /* Enable interrupts from the radio transceiver. */
} }
#else /* __AVR__ */ #else /* __AVR__ */
@ -266,8 +208,6 @@ void
hal_init(void) hal_init(void)
{ {
/*Reset variables used in file.*/ /*Reset variables used in file.*/
hal_system_time = 0;
// hal_reset_flags();
/*IO Specific Initialization - sleep and reset pins. */ /*IO Specific Initialization - sleep and reset pins. */
DDR_SLP_TR |= (1 << SLP_TR); /* Enable SLP_TR as output. */ DDR_SLP_TR |= (1 << SLP_TR); /* Enable SLP_TR as output. */
@ -295,144 +235,12 @@ hal_init(void)
TBSR.BIT.TB4S = 1; // Start Timer B4 TBSR.BIT.TB4S = 1; // Start Timer B4
INT1IC.BIT.POL = 1; // Select rising edge INT1IC.BIT.POL = 1; // Select rising edge
HAL_ENABLE_OVERFLOW_INTERRUPT(); /* Enable Timer overflow interrupt. */ HAL_ENABLE_OVERFLOW_INTERRUPT(); /* Enable Timer overflow interrupt. */
hal_enable_trx_interrupt(); /* Enable interrupts from the radio transceiver. */
/* Enable interrupts from the radio transceiver. */
hal_enable_trx_interrupt();
} }
#endif /* !__AVR__ */ #endif /* !__AVR__ */
/*----------------------------------------------------------------------------*/
/** \brief This function reset the interrupt flags and interrupt event handlers
* (Callbacks) to their default value.
*/
//void
//hal_reset_flags(void)
//{
// HAL_ENTER_CRITICAL_REGION();
/* Reset Flags. */
// hal_bat_low_flag = 0;
// hal_pll_lock_flag = 0;
/* Reset Associated Event Handlers. */
// rx_start_callback = NULL;
// trx_end_callback = NULL;
// HAL_LEAVE_CRITICAL_REGION();
//}
/*----------------------------------------------------------------------------*/
/** \brief This function returns the current value of the BAT_LOW flag.
*
* The BAT_LOW flag is incremented each time a BAT_LOW event is signaled from the
* radio transceiver. This way it is possible for the end user to poll the flag
* for new event occurances.
*/
//uint8_t
//hal_get_bat_low_flag(void)
//{
// return hal_bat_low_flag;
//}
/*----------------------------------------------------------------------------*/
/** \brief This function clears the BAT_LOW flag.
*/
//void
//hal_clear_bat_low_flag(void)
//{
// HAL_ENTER_CRITICAL_REGION();
// hal_bat_low_flag = 0;
// HAL_LEAVE_CRITICAL_REGION();
//}
/*----------------------------------------------------------------------------*/
/** \brief This function is used to set new TRX_END event handler, overriding
* old handler reference.
*/
//hal_trx_end_isr_event_handler_t
//hal_get_trx_end_event_handler(void)
//{
// return trx_end_callback;
//}
/*----------------------------------------------------------------------------*/
/** \brief This function is used to set new TRX_END event handler, overriding
* old handler reference.
*/
//void
//hal_set_trx_end_event_handler(hal_trx_end_isr_event_handler_t trx_end_callback_handle)
//{
// HAL_ENTER_CRITICAL_REGION();
// trx_end_callback = trx_end_callback_handle;
// HAL_LEAVE_CRITICAL_REGION();
//}
/*----------------------------------------------------------------------------*/
/** \brief Remove event handler reference.
*/
//void
//hal_clear_trx_end_event_handler(void)
//{
// HAL_ENTER_CRITICAL_REGION();
// trx_end_callback = NULL;
// HAL_LEAVE_CRITICAL_REGION();
//}
/*----------------------------------------------------------------------------*/
/** \brief This function returns the active RX_START event handler
*
* \return Current RX_START event handler registered.
*/
//hal_rx_start_isr_event_handler_t
//hal_get_rx_start_event_handler(void)
//{
// return rx_start_callback;
//}
/*----------------------------------------------------------------------------*/
/** \brief This function is used to set new RX_START event handler, overriding
* old handler reference.
*/
//void
//hal_set_rx_start_event_handler(hal_rx_start_isr_event_handler_t rx_start_callback_handle)
//{
// HAL_ENTER_CRITICAL_REGION();
// rx_start_callback = rx_start_callback_handle;
// HAL_LEAVE_CRITICAL_REGION();
//}
/*----------------------------------------------------------------------------*/
/** \brief Remove event handler reference.
*/
//void
//hal_clear_rx_start_event_handler(void)
//{
// HAL_ENTER_CRITICAL_REGION();
// rx_start_callback = NULL;
// HAL_LEAVE_CRITICAL_REGION();
//}
/*----------------------------------------------------------------------------*/
/** \brief This function returns the current value of the PLL_LOCK flag.
*
* The PLL_LOCK flag is incremented each time a PLL_LOCK event is signaled from the
* radio transceiver. This way it is possible for the end user to poll the flag
* for new event occurances.
*/
//uint8_t
//hal_get_pll_lock_flag(void)
//{
// return hal_pll_lock_flag;
//}
/*----------------------------------------------------------------------------*/
/** \brief This function clears the PLL_LOCK flag.
*/
//void
//hal_clear_pll_lock_flag(void)
//{
// HAL_ENTER_CRITICAL_REGION();
// hal_pll_lock_flag = 0;
// HAL_LEAVE_CRITICAL_REGION();
//}
#if defined(__AVR_ATmega128RFA1__) #if defined(__AVR_ATmega128RFA1__)
/* Hack for internal radio registers. hal_register_read and hal_register_write are /* Hack for internal radio registers. hal_register_read and hal_register_write are
@ -459,14 +267,16 @@ void
hal_subregister_write(uint16_t address, uint8_t mask, uint8_t position, hal_subregister_write(uint16_t address, uint8_t mask, uint8_t position,
uint8_t value) uint8_t value)
{ {
cli(); HAL_ENTER_CRITICAL_REGION();
uint8_t register_value = _SFR_MEM8(address); uint8_t register_value = _SFR_MEM8(address);
register_value &= ~mask; register_value &= ~mask;
value <<= position; value <<= position;
value &= mask; value &= mask;
value |= register_value; value |= register_value;
_SFR_MEM8(address) = value; _SFR_MEM8(address) = value;
sei();
HAL_LEAVE_CRITICAL_REGION();
} }
#else /* defined(__AVR_ATmega128RFA1__) */ #else /* defined(__AVR_ATmega128RFA1__) */
@ -597,41 +407,57 @@ hal_frame_read(hal_rx_frame_t *rx_frame)
* Bypassing the length check can result in overrun if buffer is < 256 bytes. * Bypassing the length check can result in overrun if buffer is < 256 bytes.
*/ */
frame_length = TST_RX_LENGTH; frame_length = TST_RX_LENGTH;
if ( 0 || ((frame_length >= HAL_MIN_FRAME_LENGTH) && (frame_length <= HAL_MAX_FRAME_LENGTH))) { if ((frame_length < HAL_MIN_FRAME_LENGTH) || (frame_length > HAL_MAX_FRAME_LENGTH)) {
rx_frame->length = frame_length; /* Length test failed */
rx_frame->length = 0;
rx_frame->lqi = 0;
rx_frame->crc = false;
return;
}
rx_frame->length = frame_length;
/* Start of buffer in I/O space, pointer to RAM buffer */ /* Start of buffer in I/O space, pointer to RAM buffer */
rx_buffer=(uint8_t *)0x180; rx_buffer=(uint8_t *)0x180;
rx_data = (rx_frame->data); rx_data = (rx_frame->data);
do{ do{
*rx_data++ = _SFR_MEM8(rx_buffer++); *rx_data++ = _SFR_MEM8(rx_buffer++);
} while (--frame_length > 0); } while (--frame_length > 0);
/*Read LQI value for this frame.*/ /*Read LQI value for this frame.*/
rx_frame->lqi = *rx_buffer; rx_frame->lqi = *rx_buffer;
/* If crc was calculated set crc field in hal_rx_frame_t accordingly.
* Else show the crc has passed the hardware check.
*/
rx_frame->crc = true;
#else /* defined(__AVR_ATmega128RFA1__) */ #else /* defined(__AVR_ATmega128RFA1__) */
uint8_t *rx_data; uint8_t frame_length, *rx_data;
/*Send frame read (long mode) command.*/ /*Send frame read (long mode) command.*/
HAL_SPI_TRANSFER_OPEN(); HAL_SPI_TRANSFER_OPEN();
HAL_SPI_TRANSFER(0x20); HAL_SPI_TRANSFER(0x20);
/*Read frame length. This includes the checksum. */ /*Read frame length. This includes the checksum. */
uint8_t frame_length = HAL_SPI_TRANSFER(0); frame_length = HAL_SPI_TRANSFER(0);
/*Check for correct frame length. Bypassing this test can result in a buffer overrun! */ /*Check for correct frame length. Bypassing this test can result in a buffer overrun! */
if ( 0 || ((frame_length >= HAL_MIN_FRAME_LENGTH) && (frame_length <= HAL_MAX_FRAME_LENGTH))) { if ((frame_length < HAL_MIN_FRAME_LENGTH) || (frame_length > HAL_MAX_FRAME_LENGTH)) {
/* Length test failed */
rx_frame->length = 0;
rx_frame->lqi = 0;
rx_frame->crc = false;
}
else {
rx_data = (rx_frame->data); rx_data = (rx_frame->data);
rx_frame->length = frame_length; rx_frame->length = frame_length;
/*Transfer frame buffer to RAM buffer */ /*Transfer frame buffer to RAM buffer */
HAL_SPI_TRANSFER_WRITE(0); HAL_SPI_TRANSFER_WRITE(0);
HAL_SPI_TRANSFER_WAIT(); HAL_SPI_TRANSFER_WAIT();
do{ do{
*rx_data++ = HAL_SPI_TRANSFER_READ(); *rx_data++ = HAL_SPI_TRANSFER_READ();
HAL_SPI_TRANSFER_WRITE(0); HAL_SPI_TRANSFER_WRITE(0);
@ -643,7 +469,7 @@ hal_frame_read(hal_rx_frame_t *rx_frame)
* The 802.15.4 standard requires 640us after a greater than 18 byte frame. * The 802.15.4 standard requires 640us after a greater than 18 byte frame.
* With a low interrupt latency overwrites should never occur. * With a low interrupt latency overwrites should never occur.
*/ */
// crc = _crc_ccitt_update(crc, tempData); // crc = _crc_ccitt_update(crc, tempData);
HAL_SPI_TRANSFER_WAIT(); HAL_SPI_TRANSFER_WAIT();
@ -651,23 +477,17 @@ hal_frame_read(hal_rx_frame_t *rx_frame)
/*Read LQI value for this frame.*/ /*Read LQI value for this frame.*/
rx_frame->lqi = HAL_SPI_TRANSFER_READ(); rx_frame->lqi = HAL_SPI_TRANSFER_READ();
#endif /* defined(__AVR_ATmega128RFA1__) */
/* If crc was calculated set crc field in hal_rx_frame_t accordingly. /* If crc was calculated set crc field in hal_rx_frame_t accordingly.
* Else show the crc has passed the hardware check. * Else show the crc has passed the hardware check.
*/ */
rx_frame->crc = true; rx_frame->crc = true;
} else {
/* Length test failed */
rx_frame->length = 0;
rx_frame->lqi = 0;
rx_frame->crc = false;
} }
HAL_SPI_TRANSFER_CLOSE(); HAL_SPI_TRANSFER_CLOSE();
#endif /* defined(__AVR_ATmega128RFA1__) */
} }
/*----------------------------------------------------------------------------*/ /*----------------------------------------------------------------------------*/
@ -765,25 +585,27 @@ hal_sram_read(uint8_t address, uint8_t length, uint8_t *data)
* \param length Length of the write burst * \param length Length of the write burst
* \param data Pointer to an array of bytes that should be written * \param data Pointer to an array of bytes that should be written
*/ */
//void #if 0 //omit unless needed
//hal_sram_write(uint8_t address, uint8_t length, uint8_t *data) void
//{ hal_sram_write(uint8_t address, uint8_t length, uint8_t *data)
// HAL_SPI_TRANSFER_OPEN(); {
HAL_SPI_TRANSFER_OPEN();
/*Send SRAM write command.*/ /*Send SRAM write command.*/
// HAL_SPI_TRANSFER(0x40); HAL_SPI_TRANSFER(0x40);
/*Send address where to start writing to.*/ /*Send address where to start writing to.*/
// HAL_SPI_TRANSFER(address); HAL_SPI_TRANSFER(address);
/*Upload the chosen memory area.*/ /*Upload the chosen memory area.*/
// do{ do{
// HAL_SPI_TRANSFER(*data++); HAL_SPI_TRANSFER(*data++);
// } while (--length > 0); } while (--length > 0);
// HAL_SPI_TRANSFER_CLOSE(); HAL_SPI_TRANSFER_CLOSE();
//} }
#endif
/*----------------------------------------------------------------------------*/ /*----------------------------------------------------------------------------*/
/* This #if compile switch is used to provide a "standard" function body for the */ /* This #if compile switch is used to provide a "standard" function body for the */
@ -862,28 +684,26 @@ ISR(TRX24_PLL_UNLOCK_vect)
DEBUGFLOW('5'); DEBUGFLOW('5');
} }
/* Flag is set by the following interrupts */ /* Flag is set by the following interrupts */
extern volatile uint8_t rf230_interruptwait,rf230_ccawait; extern volatile uint8_t rf230_wakewait, rf230_txendwait,rf230_ccawait;
/* Wake has finished */ /* Wake has finished */
ISR(TRX24_AWAKE_vect) ISR(TRX24_AWAKE_vect)
{ {
// DEBUGFLOW('6'); // DEBUGFLOW('6');
rf230_interruptwait=0; rf230_wakewait=0;
} }
/* Transmission has ended */ /* Transmission has ended */
ISR(TRX24_TX_END_vect) ISR(TRX24_TX_END_vect)
{ {
// DEBUGFLOW('7'); // DEBUGFLOW('7');
rf230_interruptwait=0; rf230_txendwait=0;
} }
/* Frame address has matched ours */ /* Frame address has matched ours */
extern volatile uint8_t rf230_pending;
ISR(TRX24_XAH_AMI_vect) ISR(TRX24_XAH_AMI_vect)
{ {
// DEBUGFLOW('8'); // DEBUGFLOW('8');
rf230_pending=1;
} }
/* CCAED measurement has completed */ /* CCAED measurement has completed */
@ -897,14 +717,6 @@ ISR(TRX24_CCA_ED_DONE_vect)
/* Separate RF230 has a single radio interrupt and the source must be read from the IRQ_STATUS register */ /* Separate RF230 has a single radio interrupt and the source must be read from the IRQ_STATUS register */
HAL_RF230_ISR() 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
hardware counter.
*/
// uint32_t isr_timestamp = hal_system_time;
// isr_timestamp <<= 16;
// isr_timestamp |= HAL_TICK_UPCNT(); // TODO: what if this wraps after reading hal_system_time?
volatile uint8_t state; volatile uint8_t state;
uint8_t interrupt_source; /* used after HAL_SPI_TRANSFER_OPEN/CLOSE block */ uint8_t interrupt_source; /* used after HAL_SPI_TRANSFER_OPEN/CLOSE block */
@ -919,22 +731,10 @@ HAL_RF230_ISR()
/*Send Register address and read register content.*/ /*Send Register address and read register content.*/
HAL_SPI_TRANSFER_WRITE(0x80 | RG_IRQ_STATUS); HAL_SPI_TRANSFER_WRITE(0x80 | RG_IRQ_STATUS);
/* 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
data.
*/
// isr_timestamp /= HAL_US_PER_SYMBOL; /* Divide so that we get time in 16us resolution. */
// isr_timestamp &= HAL_SYMBOL_MASK;
HAL_SPI_TRANSFER_WAIT(); /* AFTER possible interleaved processing */ HAL_SPI_TRANSFER_WAIT(); /* AFTER possible interleaved processing */
#if 0 //dak
interrupt_source = HAL_SPI_TRANSFER_READ(); /* The interrupt variable is used as a dummy read. */
interrupt_source = HAL_SPI_TRANSFER(interrupt_source);
#else
interrupt_source = HAL_SPI_TRANSFER(0); interrupt_source = HAL_SPI_TRANSFER(0);
#endif
HAL_SPI_TRANSFER_CLOSE(); HAL_SPI_TRANSFER_CLOSE();
/*Handle the incomming interrupt. Prioritized.*/ /*Handle the incomming interrupt. Prioritized.*/
@ -950,44 +750,30 @@ HAL_RF230_ISR()
rf230_last_rssi = 3 * hal_subregister_read(SR_RSSI); rf230_last_rssi = 3 * hal_subregister_read(SR_RSSI);
#endif #endif
#endif #endif
// if(rx_start_callback != NULL){
// /* Read Frame length and call rx_start callback. */
// HAL_SPI_TRANSFER_OPEN();
// uint8_t frame_length = HAL_SPI_TRANSFER(0x20);
// frame_length = HAL_SPI_TRANSFER(frame_length);
// HAL_SPI_TRANSFER_CLOSE();
// rx_start_callback(isr_timestamp, frame_length);
// }
} else if (interrupt_source & HAL_TRX_END_MASK){ } else if (interrupt_source & HAL_TRX_END_MASK){
INTERRUPTDEBUG(11); INTERRUPTDEBUG(11);
// if(trx_end_callback != NULL){
// trx_end_callback(isr_timestamp);
// }
state = hal_subregister_read(SR_TRX_STATUS); state = hal_subregister_read(SR_TRX_STATUS);
if((state == BUSY_RX_AACK) || (state == RX_ON) || (state == BUSY_RX) || (state == RX_AACK_ON)){ if((state == BUSY_RX_AACK) || (state == RX_ON) || (state == BUSY_RX) || (state == RX_AACK_ON)){
/* Received packet interrupt */ /* Received packet interrupt */
/* Buffer the frame and call rf230_interrupt to schedule poll for rf230 receive process */ /* Buffer the frame and call rf230_interrupt to schedule poll for rf230 receive process */
// if (rxframe.length) break; //toss packet if last one not processed yet
if (rxframe[rxframe_tail].length) INTERRUPTDEBUG(42); else INTERRUPTDEBUG(12); if (rxframe[rxframe_tail].length) INTERRUPTDEBUG(42); else INTERRUPTDEBUG(12);
#ifdef RF230_MIN_RX_POWER #ifdef RF230_MIN_RX_POWER
/* Discard packets weaker than the minimum if defined. This is for testing miniature meshes.*/ /* Discard packets weaker than the minimum if defined. This is for testing miniature meshes.*/
/* Save the rssi for printing in the main loop */ /* Save the rssi for printing in the main loop */
#if RF230_CONF_AUTOACK #if RF230_CONF_AUTOACK
// rf230_last_rssi=hal_subregister_read(SR_ED_LEVEL); //rf230_last_rssi=hal_subregister_read(SR_ED_LEVEL);
rf230_last_rssi=hal_register_read(RG_PHY_ED_LEVEL); rf230_last_rssi=hal_register_read(RG_PHY_ED_LEVEL);
#endif #endif
if (rf230_last_rssi >= RF230_MIN_RX_POWER) { if (rf230_last_rssi >= RF230_MIN_RX_POWER) {
#endif #endif
hal_frame_read(&rxframe[rxframe_tail]); hal_frame_read(&rxframe[rxframe_tail]);
rxframe_tail++;if (rxframe_tail >= RF230_CONF_RX_BUFFERS) rxframe_tail=0; rxframe_tail++;if (rxframe_tail >= RF230_CONF_RX_BUFFERS) rxframe_tail=0;
rf230_interrupt(); rf230_interrupt();
// trx_end_callback(isr_timestamp);
#ifdef RF230_MIN_RX_POWER #ifdef RF230_MIN_RX_POWER
} }
#endif #endif
} }
@ -1000,7 +786,6 @@ HAL_RF230_ISR()
; ;
} else if (interrupt_source & HAL_PLL_LOCK_MASK){ } else if (interrupt_source & HAL_PLL_LOCK_MASK){
INTERRUPTDEBUG(15); INTERRUPTDEBUG(15);
// hal_pll_lock_flag++;
; ;
} else if (interrupt_source & HAL_BAT_LOW_MASK){ } else if (interrupt_source & HAL_BAT_LOW_MASK){
/* Disable BAT_LOW interrupt to prevent endless interrupts. The interrupt */ /* Disable BAT_LOW interrupt to prevent endless interrupts. The interrupt */
@ -1009,7 +794,6 @@ HAL_RF230_ISR()
uint8_t trx_isr_mask = hal_register_read(RG_IRQ_MASK); uint8_t trx_isr_mask = hal_register_read(RG_IRQ_MASK);
trx_isr_mask &= ~HAL_BAT_LOW_MASK; trx_isr_mask &= ~HAL_BAT_LOW_MASK;
hal_register_write(RG_IRQ_MASK, trx_isr_mask); hal_register_write(RG_IRQ_MASK, trx_isr_mask);
// hal_bat_low_flag++; /* Increment BAT_LOW flag. */
INTERRUPTDEBUG(16); INTERRUPTDEBUG(16);
; ;
} else { } else {
@ -1020,21 +804,6 @@ HAL_RF230_ISR()
#endif /* defined(__AVR_ATmega128RFA1__) */ #endif /* defined(__AVR_ATmega128RFA1__) */
# endif /* defined(DOXYGEN) */ # endif /* defined(DOXYGEN) */
/*----------------------------------------------------------------------------*/
/* This #if compile switch is used to provide a "standard" function body for the */
/* doxygen documentation. */
#if defined(DOXYGEN)
/** \brief Timer Overflow ISR
* This is the interrupt service routine for timer1 overflow.
*/
void TIMER1_OVF_vect(void);
#else /* !DOXYGEN */
HAL_TIME_ISR()
{
hal_system_time++;
}
#endif
/** @} */ /** @} */
/** @} */ /** @} */

View File

@ -2,6 +2,11 @@
* Copyright (c) 2007, Swedish Institute of Computer Science * Copyright (c) 2007, Swedish Institute of Computer Science
* All rights reserved. * All rights reserved.
* *
* Additional fixes for AVR contributed by:
*
* David Kopf dak664@embarqmail.com
* Ivan Delamer delamer@ieee.com
*
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
* are met: * are met:
@ -91,13 +96,17 @@
static bool is_promiscuous; static bool is_promiscuous;
#endif #endif
/* RF230_CONF_AUTORETRIES is 1 plus the number written to the hardware. */ /* RF230_CONF_FRAME_RETRIES is 1 plus the number written to the hardware. */
/* Valid range 1-16, zero disables extended mode. */ /* Valid range 1-16, zero disables extended mode. */
#ifndef RF230_CONF_AUTORETRIES #ifndef RF230_CONF_FRAME_RETRIES
#define RF230_CONF_AUTORETRIES 3 #ifdef RF230_CONF_AUTORETRIES /* Support legacy definition. */
#define RF230_CONF_FRAME_RETRIES RF230_CONF_AUTORETRIES
#else
#define RF230_CONF_FRAME_RETRIES 0 /* Extended mode disabled by default. */
#endif
#endif #endif
/* In extended mode (AUTORETRIES>0) the tx routine waits for hardware /* In extended mode (FRAME_RETRIES>0) the tx routine waits for hardware
* processing of an expected ACK and returns RADIO_TX_OK/NOACK result. * processing of an expected ACK and returns RADIO_TX_OK/NOACK result.
* In non-extended mode the ACK is treated as a normal rx packet. * In non-extended mode the ACK is treated as a normal rx packet.
* If the caller needs the ACK to be returned as an rx packet, * If the caller needs the ACK to be returned as an rx packet,
@ -109,15 +118,19 @@ static bool is_promiscuous;
* that use the TX_OK result to signal a successful ACK. * that use the TX_OK result to signal a successful ACK.
* Adds 100 bytes of program flash and two bytes of RAM. * Adds 100 bytes of program flash and two bytes of RAM.
*/ */
#if RF320_CONF_INSERTACK && RF230_CONF_AUTORETRIES #if RF320_CONF_INSERTACK && RF230_CONF_FRAME_RETRIES
#define RF230_INSERTACK 1 #define RF230_INSERTACK 1
uint8_t ack_pending,ack_seqnum; uint8_t ack_pending,ack_seqnum;
#endif #endif
/* RF230_CONF_CSMARETRIES is number of random-backoff/CCA retries. */ /* RF230_CONF_CSMA_RETRIES is number of random-backoff/CCA retries. */
/* The hardware will accept 0-7, but 802.15.4-2003 only allows 5 maximum */ /* The hardware will accept 0-7, but 802.15.4-2003 only allows 5 maximum */
#ifndef RF230_CONF_CSMARETRIES /* In RF231/128RFA1, a value of 7 means no CSMA bebofe the Tx. */
#define RF230_CONF_CSMARETRIES 5 /* CSMA backoffs are long and can block radio duty cycling
* over several channel check periods! */
/* Used only if RF230_CONF_FRAME_RETRIES > 0. */
#ifndef RF230_CONF_CSMA_RETRIES
#define RF230_CONF_CSMA_RETRIES 5
#endif #endif
//Automatic and manual CRC both append 2 bytes to packets //Automatic and manual CRC both append 2 bytes to packets
@ -191,18 +204,18 @@ extern uint8_t debugflowsize,debugflow[DEBUGFLOWSIZE];
#endif #endif
/* XXX hack: these will be made as Chameleon packet attributes */ /* XXX hack: these will be made as Chameleon packet attributes */
#if RF230_CONF_TIMESTAMPS
rtimer_clock_t rf230_time_of_arrival, rf230_time_of_departure; rtimer_clock_t rf230_time_of_arrival, rf230_time_of_departure;
int rf230_authority_level_of_sender; int rf230_authority_level_of_sender;
#if RF230_CONF_TIMESTAMPS
static rtimer_clock_t setup_time_for_transmission; static rtimer_clock_t setup_time_for_transmission;
static unsigned long total_time_for_transmission, total_transmission_len; static unsigned long total_time_for_transmission, total_transmission_len;
static int num_transmissions; static int num_transmissions;
#endif #endif
#if defined(__AVR_ATmega128RFA1__) #if defined(__AVR_ATmega128RFA1__)
volatile uint8_t rf230_interruptwait,rf230_ccawait; volatile uint8_t rf230_wakewait, rf230_txendwait, rf230_ccawait;
#endif #endif
uint8_t volatile rf230_pending; uint8_t volatile rf230_pending;
@ -226,8 +239,8 @@ typedef enum{
PROCESS(rf230_process, "RF230 driver"); PROCESS(rf230_process, "RF230 driver");
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
int rf230_on(void); static int rf230_on(void);
int rf230_off(void); static int rf230_off(void);
static int rf230_read(void *buf, unsigned short bufsize); static int rf230_read(void *buf, unsigned short bufsize);
@ -340,9 +353,17 @@ static bool radio_is_sleeping(void)
static void static void
radio_reset_state_machine(void) radio_reset_state_machine(void)
{ {
if (hal_get_slptr()) DEBUGFLOW('"'); /* The data sheet is not clear on what happens when slptr is raised in RX on
hal_set_slptr_low(); * states, it "remains in the new state and returns to the preceding state
delay_us(TIME_NOCLK_TO_WAKE); * when slptr is lowered". Possibly that is why there is an undocumented
* TIME_NOCLK_TO_WAKE delay here?
*/
if (hal_get_slptr()) {
DEBUGFLOW('V');
hal_set_slptr_low();
delay_us(TIME_NOCLK_TO_WAKE);
}
hal_subregister_write(SR_TRX_CMD, CMD_FORCE_TRX_OFF); hal_subregister_write(SR_TRX_CMD, CMD_FORCE_TRX_OFF);
delay_us(TIME_CMD_FORCE_TRX_OFF); delay_us(TIME_CMD_FORCE_TRX_OFF);
} }
@ -351,33 +372,36 @@ static char
rf230_isidle(void) rf230_isidle(void)
{ {
uint8_t radio_state; uint8_t radio_state;
/* Contikimac can turn the radio off during an interrupt, so we always check
* slptr before doing the SPI transfer. The caller must also make this test
* if it could otherwise hang waiting for idle! */
if (hal_get_slptr()) { if (hal_get_slptr()) {
DEBUGFLOW(']'); if (RF230_receive_on) DEBUGFLOW('-');
return 1; return 1;
} else { }
radio_state = hal_subregister_read(SR_TRX_STATUS); else {
if (radio_state != BUSY_TX_ARET && radio_state = hal_subregister_read(SR_TRX_STATUS);
if (radio_state != BUSY_TX_ARET &&
radio_state != BUSY_RX_AACK && radio_state != BUSY_RX_AACK &&
radio_state != STATE_TRANSITION && radio_state != STATE_TRANSITION &&
radio_state != BUSY_RX && radio_state != BUSY_RX &&
radio_state != BUSY_TX) { radio_state != BUSY_TX) {
return(1); return(1);
} else { }
// printf(".%u",radio_state); else {
return(0); return(0);
} }
} }
} }
static void static void
rf230_waitidle(void) rf230_waitidle(void)
{ {
int i; /* TX_ARET with multiple csma retries can take a very long time to finish */
for (i=0;i<10000;i++) { //to avoid potential hangs while (1) {
// while (1) { if (hal_get_slptr()) return;
if (rf230_isidle()) break; if (rf230_isidle()) break;
} }
if (i>=10000) {DEBUGFLOW('H');DEBUGFLOW('R');}
} }
/*----------------------------------------------------------------------------*/ /*----------------------------------------------------------------------------*/
@ -402,9 +426,9 @@ int i;
static radio_status_t static radio_status_t
radio_set_trx_state(uint8_t new_state) radio_set_trx_state(uint8_t new_state)
{ {
uint8_t original_state; uint8_t current_state;
/*Check function paramter and current state of the radio transceiver.*/ /*Check function parameter and current state of the radio transceiver.*/
if (!((new_state == TRX_OFF) || if (!((new_state == TRX_OFF) ||
(new_state == RX_ON) || (new_state == RX_ON) ||
(new_state == PLL_ON) || (new_state == PLL_ON) ||
@ -413,23 +437,16 @@ radio_set_trx_state(uint8_t new_state)
return RADIO_INVALID_ARGUMENT; return RADIO_INVALID_ARGUMENT;
} }
if (hal_get_slptr()) { if (hal_get_slptr()) {
DEBUGFLOW('W');
return RADIO_WRONG_STATE; return RADIO_WRONG_STATE;
} }
/* Wait for radio to finish previous operation */ /* Wait for radio to finish previous operation */
rf230_waitidle(); rf230_waitidle();
// for(;;) current_state = radio_get_trx_state();
// {
original_state = radio_get_trx_state();
// if (original_state != BUSY_TX_ARET &&
// original_state != BUSY_RX_AACK &&
// original_state != BUSY_RX &&
// original_state != BUSY_TX)
// break;
// }
if (new_state == original_state){ if (new_state == current_state){
return RADIO_SUCCESS; return RADIO_SUCCESS;
} }
@ -440,14 +457,15 @@ radio_set_trx_state(uint8_t new_state)
/* The radio transceiver can be in one of the following states: */ /* The radio transceiver can be in one of the following states: */
/* TRX_OFF, RX_ON, PLL_ON, RX_AACK_ON, TX_ARET_ON. */ /* TRX_OFF, RX_ON, PLL_ON, RX_AACK_ON, TX_ARET_ON. */
if(new_state == TRX_OFF){ if(new_state == TRX_OFF){
if (hal_get_slptr()) DEBUGFLOW('K');DEBUGFLOW('K');DEBUGFLOW('A'+hal_subregister_read(SR_TRX_STATUS));
radio_reset_state_machine(); /* Go to TRX_OFF from any state. */ radio_reset_state_machine(); /* Go to TRX_OFF from any state. */
} else { } else {
/* It is not allowed to go from RX_AACK_ON or TX_AACK_ON and directly to */ /* It is not allowed to go from RX_AACK_ON or TX_AACK_ON and directly to */
/* TX_AACK_ON or RX_AACK_ON respectively. Need to go via PLL_ON. */ /* TX_AACK_ON or RX_AACK_ON respectively. Need to go via PLL_ON. */
/* (Old datasheets allowed other transitions, but this code complies with */ /* (Old datasheets allowed other transitions, but this code complies with */
/* the current specification for RF230, RF231 and 128RFA1.) */ /* the current specification for RF230, RF231 and 128RFA1.) */
if (((new_state == TX_ARET_ON) && (original_state == RX_AACK_ON)) || if (((new_state == TX_ARET_ON) && (current_state == RX_AACK_ON)) ||
((new_state == RX_AACK_ON) && (original_state == TX_ARET_ON))){ ((new_state == RX_AACK_ON) && (current_state == TX_ARET_ON))){
/* First do intermediate state transition to PLL_ON. */ /* First do intermediate state transition to PLL_ON. */
/* The final state transition is handled after the if-else if. */ /* The final state transition is handled after the if-else if. */
hal_subregister_write(SR_TRX_CMD, PLL_ON); hal_subregister_write(SR_TRX_CMD, PLL_ON);
@ -459,21 +477,28 @@ radio_set_trx_state(uint8_t new_state)
/* When the PLL is active most states can be reached in 1us. However, from */ /* When the PLL is active most states can be reached in 1us. However, from */
/* TRX_OFF the PLL needs time to activate. */ /* TRX_OFF the PLL needs time to activate. */
if (original_state == TRX_OFF){ if (current_state == TRX_OFF){
delay_us(TIME_TRX_OFF_TO_PLL_ACTIVE); delay_us(TIME_TRX_OFF_TO_PLL_ACTIVE);
} else { } else {
delay_us(TIME_STATE_TRANSITION_PLL_ACTIVE); delay_us(TIME_STATE_TRANSITION_PLL_ACTIVE);
} }
} /* end: if(new_state == TRX_OFF) ... */ } /* end: if(new_state == TRX_OFF) ... */
/*Verify state transition.*/ /* Verify state transition.
radio_status_t set_state_status = RADIO_TIMED_OUT; * Radio could have already switched to an RX_BUSY state, at least in cooja.
* Don't know what the hardware does but this would not be an error.*/
if (radio_get_trx_state() == new_state){ current_state = radio_get_trx_state();
set_state_status = RADIO_SUCCESS; if (current_state != new_state) {
if (((new_state == RX_ON) && (current_state == BUSY_RX)) ||
((new_state == RX_AACK_ON) && (current_state == BUSY_RX_AACK))) {
/* This is OK. */
} else {
DEBUGFLOW('N');DEBUGFLOW('A'+new_state);DEBUGFLOW('A'+radio_get_trx_state());DEBUGFLOW('N');
return RADIO_TIMED_OUT;
}
} }
return set_state_status; return RADIO_SUCCESS;
} }
void void
@ -504,7 +529,7 @@ flushrx(void)
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
static void static void
on(void) radio_on(void)
{ {
// ENERGEST_OFF(ENERGEST_TYPE_LISTEN);//testing // ENERGEST_OFF(ENERGEST_TYPE_LISTEN);//testing
ENERGEST_ON(ENERGEST_TYPE_LISTEN); ENERGEST_ON(ENERGEST_TYPE_LISTEN);
@ -520,11 +545,22 @@ on(void)
PORTE|=(1<<PE1); //ledon PORTE|=(1<<PE1); //ledon
#endif #endif
#if defined(__AVR_ATmega128RFA1__) #if defined(__AVR_ATmega128RFA1__)
/* Use the poweron interrupt for delay */ /* Use the poweron interrupt for delay */
rf230_interruptwait=1; rf230_wakewait=1;
sei(); {
hal_set_slptr_low(); uint8_t sreg = SREG;
while (rf230_interruptwait) {} sei();
if (hal_get_slptr() == 0) DEBUGFLOW('$');
hal_set_slptr_low();
{
int i;
for (i=0;i<10000;i++) {
if (!rf230_wakewait) break;
}
if (i>=10000) {DEBUGFLOW('G');DEBUGFLOW('g');DEBUGFLOW('A'+hal_subregister_read(SR_TRX_STATUS));}
}
SREG = sreg;
}
#else #else
/* SPI based radios. The wake time depends on board capacitance. /* SPI based radios. The wake time depends on board capacitance.
* Make sure the delay is long enough, as using SPI too soon will reset the MCU! * Make sure the delay is long enough, as using SPI too soon will reset the MCU!
@ -533,7 +569,6 @@ on(void)
// uint8_t sreg = SREG;cli(); // uint8_t sreg = SREG;cli();
hal_set_slptr_low(); hal_set_slptr_low();
delay_us(2*TIME_SLEEP_TO_TRX_OFF); delay_us(2*TIME_SLEEP_TO_TRX_OFF);
// delay_us(TIME_SLEEP_TO_TRX_OFF+TIME_SLEEP_TO_TRX_OFF/2);
// SREG=sreg; // SREG=sreg;
#endif #endif
} }
@ -547,8 +582,14 @@ on(void)
rf230_waitidle(); rf230_waitidle();
} }
static void static void
off(void) radio_off(void)
{ {
RF230_receive_on = 0;
if (hal_get_slptr()) {
DEBUGFLOW('F');
return;
}
#if RF230BB_CONF_LEDONPORTE1 #if RF230BB_CONF_LEDONPORTE1
PORTE&=~(1<<PE1); //ledoff PORTE&=~(1<<PE1); //ledoff
#endif #endif
@ -563,7 +604,12 @@ off(void)
/* Do not transmit autoacks when stack thinks radio is off */ /* Do not transmit autoacks when stack thinks radio is off */
radio_set_trx_state(RX_ON); radio_set_trx_state(RX_ON);
#else #else
/* Force the device into TRX_OFF. */ /* Force the device into TRX_OFF.
* First make sure an interrupt did not initiate a sleep. */
if (hal_get_slptr()) {
DEBUGFLOW('?');
return;
}
radio_reset_state_machine(); radio_reset_state_machine();
#if RADIOSLEEPSWHENOFF #if RADIOSLEEPSWHENOFF
/* Sleep Radio */ /* Sleep Radio */
@ -572,7 +618,6 @@ off(void)
#endif #endif
#endif /* RADIOALWAYSON */ #endif /* RADIOALWAYSON */
RF230_receive_on = 0;
ENERGEST_OFF(ENERGEST_TYPE_LISTEN); ENERGEST_OFF(ENERGEST_TYPE_LISTEN);
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
@ -586,7 +631,7 @@ set_txpower(uint8_t power)
DEBUGFLOW('f'); DEBUGFLOW('f');
PRINTF("rf230_set_txpower:Sleeping"); //happens with cxmac PRINTF("rf230_set_txpower:Sleeping"); //happens with cxmac
} else { } else {
DEBUGFLOW('g'); //DEBUGFLOW('g');
hal_subregister_write(SR_TX_PWR, power); hal_subregister_write(SR_TX_PWR, power);
} }
} }
@ -718,13 +763,14 @@ rf230_init(void)
// printf_P(PSTR("After calibration OSCCAL=%x\n"),OSCCAL); // printf_P(PSTR("After calibration OSCCAL=%x\n"),OSCCAL);
/* Set receive buffers empty and point to the first */ /* Set receive buffers empty and point to the first */
for (i=0;i<RF230_CONF_RX_BUFFERS;i++) rxframe[i].length=0; for (i=0;i<RF230_CONF_RX_BUFFERS;i++) {
rxframe[i].length=0;
}
rxframe_head=0;rxframe_tail=0; rxframe_head=0;rxframe_tail=0;
/* Do full rf230 Reset */ /* Do full rf230 Reset */
hal_set_rst_low(); hal_set_rst_low();
hal_set_slptr_low(); hal_set_slptr_low();
#if 1
/* On powerup a TIME_RESET delay is needed here, however on some other MCU reset /* On powerup a TIME_RESET delay is needed here, however on some other MCU reset
* (JTAG, WDT, Brownout) the radio may be sleeping. It can enter an uncertain * (JTAG, WDT, Brownout) the radio may be sleeping. It can enter an uncertain
* state (sending wrong hardware FCS for example) unless the full wakeup delay * state (sending wrong hardware FCS for example) unless the full wakeup delay
@ -733,9 +779,7 @@ rf230_init(void)
* See www.avrfreaks.net/index.php?name=PNphpBB2&file=viewtopic&t=78725 * See www.avrfreaks.net/index.php?name=PNphpBB2&file=viewtopic&t=78725
*/ */
delay_us(2*TIME_SLEEP_TO_TRX_OFF); delay_us(2*TIME_SLEEP_TO_TRX_OFF);
#else //delay_us(TIME_RESET); /* Old impl. */
delay_us(TIME_RESET);
#endif
hal_set_rst_high(); hal_set_rst_high();
/* Force transition to TRX_OFF */ /* Force transition to TRX_OFF */
@ -761,7 +805,7 @@ rf230_init(void)
process_start(&rf230_process, NULL); process_start(&rf230_process, NULL);
/* Leave radio in on state (?)*/ /* Leave radio in on state (?)*/
on(); radio_on();
return 1; return 1;
} }
@ -777,11 +821,13 @@ void rf230_warm_reset(void) {
hal_register_write(RG_IRQ_MASK, RF230_SUPPORTED_INTERRUPT_MASK); hal_register_write(RG_IRQ_MASK, RF230_SUPPORTED_INTERRUPT_MASK);
/* Set up number of automatic retries 0-15 (0 implies PLL_ON sends instead of the extended TX_ARET mode */ /* Set up number of automatic retries 0-15
hal_subregister_write(SR_MAX_FRAME_RETRIES, RF230_CONF_AUTORETRIES ); * (0 implies PLL_ON sends instead of the extended TX_ARET mode */
hal_subregister_write(SR_MAX_FRAME_RETRIES,
(RF230_CONF_FRAME_RETRIES > 0) ? (RF230_CONF_FRAME_RETRIES - 1) : 0 );
/* Set up carrier sense/clear channel assesment parameters for extended operating mode */ /* Set up carrier sense/clear channel assesment parameters for extended operating mode */
hal_subregister_write(SR_MAX_CSMA_RETRIES, 5 );//highest allowed retries hal_subregister_write(SR_MAX_CSMA_RETRIES, RF230_CONF_CSMA_RETRIES );//highest allowed retries
hal_register_write(RG_CSMA_BE, 0x80); //min backoff exponent 0, max 8 (highest allowed) hal_register_write(RG_CSMA_BE, 0x80); //min backoff exponent 0, max 8 (highest allowed)
hal_register_write(RG_CSMA_SEED_0,hal_register_read(RG_PHY_RSSI) );//upper two RSSI reg bits RND_VALUE are random in rf231 hal_register_write(RG_CSMA_SEED_0,hal_register_read(RG_PHY_RSSI) );//upper two RSSI reg bits RND_VALUE are random in rf231
// hal_register_write(CSMA_SEED_1,42 ); // hal_register_write(CSMA_SEED_1,42 );
@ -855,20 +901,19 @@ rf230_transmit(unsigned short payload_len)
#if RF230BB_CONF_LEDONPORTE1 #if RF230BB_CONF_LEDONPORTE1
PORTE|=(1<<PE1); //ledon PORTE|=(1<<PE1); //ledon
#endif #endif
rf230_interruptwait=1; rf230_wakewait=1;
hal_set_slptr_low(); hal_set_slptr_low();
// while (rf230_interruptwait) {}
{ {
int i; int i;
for (i=0;i<10000;i++) { for (i=0;i<10000;i++) {
if (!rf230_interruptwait) break; if (!rf230_wakewait) break;
} }
if (i>=10000) {DEBUGFLOW('G');DEBUGFLOW('G');DEBUGFLOW('A'+hal_subregister_read(SR_TRX_STATUS));}
} }
#else #else
hal_set_slptr_low(); hal_set_slptr_low();
DEBUGFLOW('j'); DEBUGFLOW('j');
delay_us(2*TIME_SLEEP_TO_TRX_OFF); //extra delay depends on board capacitance delay_us(2*TIME_SLEEP_TO_TRX_OFF); //extra delay (2x) depends on board capacitance
// delay_us(TIME_SLEEP_TO_TRX_OFF+TIME_SLEEP_TO_TRX_OFF/2);
#endif #endif
} else { } else {
@ -891,7 +936,7 @@ rf230_transmit(unsigned short payload_len)
ENERGEST_OFF(ENERGEST_TYPE_LISTEN); ENERGEST_OFF(ENERGEST_TYPE_LISTEN);
} }
/* Prepare to transmit */ /* Prepare to transmit */
#if RF230_CONF_AUTORETRIES #if RF230_CONF_FRAME_RETRIES
radio_set_trx_state(TX_ARET_ON); radio_set_trx_state(TX_ARET_ON);
DEBUGFLOW('t'); DEBUGFLOW('t');
#else #else
@ -916,20 +961,17 @@ rf230_transmit(unsigned short payload_len)
ENERGEST_ON(ENERGEST_TYPE_TRANSMIT); ENERGEST_ON(ENERGEST_TYPE_TRANSMIT);
#if defined(__AVR_ATmega128RFA1__)
/* No interrupts across frame download! */ /* No interrupts across frame download! */
cli(); HAL_ENTER_CRITICAL_REGION();
/* slow down the transmit? */
// delay_us(500); /* Toggle the SLP_TR pin to initiate the frame transmission */
#endif
/* Toggle the SLP_TR pin to initiate the frame transmission */
hal_set_slptr_high(); hal_set_slptr_high();
hal_set_slptr_low(); hal_set_slptr_low();
hal_frame_write(buffer, total_len); hal_frame_write(buffer, total_len);
#if defined(__AVR_ATmega128RFA1__)
sei(); HAL_LEAVE_CRITICAL_REGION();
#endif
PRINTF("rf230_transmit: %d\n", (int)total_len); PRINTF("rf230_transmit: %d\n", (int)total_len);
#if DEBUG>1 #if DEBUG>1
/* Note the dumped packet will have a zero checksum unless compiled with RF230_CONF_CHECKSUM /* Note the dumped packet will have a zero checksum unless compiled with RF230_CONF_CHECKSUM
* since we don't know what it will be if calculated by the hardware. * since we don't know what it will be if calculated by the hardware.
@ -951,7 +993,7 @@ rf230_transmit(unsigned short payload_len)
rf230_waitidle(); rf230_waitidle();
/* Get the transmission result */ /* Get the transmission result */
#if RF230_CONF_AUTORETRIES #if RF230_CONF_FRAME_RETRIES
tx_result = hal_subregister_read(SR_TRAC_STATUS); tx_result = hal_subregister_read(SR_TRAC_STATUS);
#else #else
tx_result=RADIO_TX_OK; tx_result=RADIO_TX_OK;
@ -981,13 +1023,13 @@ rf230_transmit(unsigned short payload_len)
if(RF230_receive_on) { if(RF230_receive_on) {
DEBUGFLOW('l'); DEBUGFLOW('l');
ENERGEST_ON(ENERGEST_TYPE_LISTEN); ENERGEST_ON(ENERGEST_TYPE_LISTEN);
on(); radio_on();
} else { } else {
#if RADIOALWAYSON #if RADIOALWAYSON
/* Enable reception */ /* Enable reception */
on(); radio_on();
#else #else
off(); radio_off();
PRINTF("rf230_transmit: turning radio off\n"); PRINTF("rf230_transmit: turning radio off\n");
#endif #endif
} }
@ -1123,36 +1165,39 @@ bail:
return ret; return ret;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
int static int
rf230_off(void) rf230_off(void)
{ {
/* Don't do anything if we are already turned off. */ /* Don't do anything if we are already turned off. */
if(RF230_receive_on == 0) { if(RF230_receive_on == 0) {
//if (!hal_get_slptr()) DEBUGFLOW('5');
return 0; return 0;
} }
//if (hal_get_slptr()) DEBUGFLOW('6');
/* If we are currently receiving a packet, we still call off(), /* If we are currently receiving a packet, we still call radio_off(),
as that routine waits until Rx is complete (packet uploaded in ISR as that routine waits until Rx is complete (packet uploaded in ISR
so no worries about losing it). If using RX_AACK_MODE, chances are so no worries about losing it). The transmit routine may also turn
the packet is not for us and will be discarded. */ + the radio off on a return to sleep. rf230_isidle checks for that. */
if (!rf230_isidle()) { if (!rf230_isidle()) {
//DEBUGFLOW('X');DEBUGFLOW('X');DEBUGFLOW('A'+hal_subregister_read(SR_TRX_STATUS));
PRINTF("rf230_off: busy receiving\r\n"); PRINTF("rf230_off: busy receiving\r\n");
//return 1; //return 1;
} }
off(); radio_off();
return 0; return 0;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
int static int
rf230_on(void) rf230_on(void)
{ {
if(RF230_receive_on) { if(RF230_receive_on) {
DEBUGFLOW('q'); //if (hal_get_slptr()) DEBUGFLOW('Q');//Cooja TODO: shows sleeping occasionally
return 1; return 1;
} }
on(); radio_on();
return 1; return 1;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
@ -1296,18 +1341,26 @@ PROCESS_THREAD(rf230_process, ev, data)
TIMETABLE_TIMESTAMP(rf230_timetable, "poll"); TIMETABLE_TIMESTAMP(rf230_timetable, "poll");
#endif /* RF230_TIMETABLE_PROFILING */ #endif /* RF230_TIMETABLE_PROFILING */
rf230_pending = 0;
packetbuf_clear(); packetbuf_clear();
/* Turn off interrupts to avoid ISR writing to the same buffers we are reading. */ /* Turn off interrupts to avoid ISR writing to the same buffers we are reading. */
HAL_ENTER_CRITICAL_REGION(); HAL_ENTER_CRITICAL_REGION();
len = rf230_read(packetbuf_dataptr(), PACKETBUF_SIZE); len = rf230_read(packetbuf_dataptr(), PACKETBUF_SIZE);
/* Restore interrupts. */ /* Restore interrupts. */
HAL_LEAVE_CRITICAL_REGION(); HAL_LEAVE_CRITICAL_REGION();
PRINTF("rf230_read: %u bytes lqi %u\n",len,rf230_last_correlation); PRINTF("rf230_read: %u bytes lqi %u\n",len,rf230_last_correlation);
#if DEBUG>1
{
uint8_t i;
unsigned const char * rxdata = packetbuf_dataptr();
PRINTF("0000");
for (i=0;i<len+AUX_LEN;i++) PRINTF(" %02x",rxdata[i]);
PRINTF("\n");
}
#endif
RF230PROCESSFLAG(1); RF230PROCESSFLAG(1);
if(len > 0) { if(len > 0) {
@ -1372,19 +1425,6 @@ rf230_read(void *buf, unsigned short bufsize)
return 0; return 0;
} }
#if RADIOALWAYSON
if (RF230_receive_on) {
#else
if (hal_get_slptr()) {
DEBUGFLOW('!');
return 0;
}
if (!RF230_receive_on) {
DEBUGFLOW('[');
return 0;
}
#endif
#if RF230_CONF_TIMESTAMPS #if RF230_CONF_TIMESTAMPS
if(interrupt_time_set) { if(interrupt_time_set) {
rf230_time_of_arrival = interrupt_time; rf230_time_of_arrival = interrupt_time;
@ -1395,19 +1435,6 @@ if (!RF230_receive_on) {
rf230_time_of_departure = 0; rf230_time_of_departure = 0;
#endif /* RF230_CONF_TIMESTAMPS */ #endif /* RF230_CONF_TIMESTAMPS */
// can't use PRINTF as interrupts are disabled
// PRINTSHORT("r%d",rxframe[rxframe_head].length);
//PRINTF("rf230_read: %u bytes lqi %u crc %u\n",rxframe[rxframe_head].length,rxframe[rxframe_head].lqi,rxframe[rxframe_head].crc);
#if DEBUG>1
{
//uint8_t i;
//PRINTF("0000");
//for (i=0;i<rxframe[rxframe_head].length;i++) PRINTF(" %02x",rxframe[rxframe_head].data[i]);
//PRINTF("\n");
}
#endif
//if(len > RF230_MAX_PACKET_LEN) {
if(len > RF230_MAX_TX_FRAME_LENGTH) { if(len > RF230_MAX_TX_FRAME_LENGTH) {
/* Oops, we must be out of sync. */ /* Oops, we must be out of sync. */
DEBUGFLOW('u'); DEBUGFLOW('u');
@ -1431,6 +1458,7 @@ if (!RF230_receive_on) {
RIMESTATS_ADD(toolong); RIMESTATS_ADD(toolong);
return 0; return 0;
} }
/* Transfer the frame, stripping the footer, but copying the checksum */ /* Transfer the frame, stripping the footer, but copying the checksum */
framep=&(rxframe[rxframe_head].data[0]); framep=&(rxframe[rxframe_head].data[0]);
memcpy(buf,framep,len-AUX_LEN+CHECKSUM_LEN); memcpy(buf,framep,len-AUX_LEN+CHECKSUM_LEN);
@ -1438,9 +1466,17 @@ if (!RF230_receive_on) {
/* Clear the length field to allow buffering of the next packet */ /* Clear the length field to allow buffering of the next packet */
rxframe[rxframe_head].length=0; rxframe[rxframe_head].length=0;
rxframe_head++;if (rxframe_head >= RF230_CONF_RX_BUFFERS) rxframe_head=0; rxframe_head++;
if (rxframe_head >= RF230_CONF_RX_BUFFERS) {
rxframe_head=0;
}
/* If another packet has been buffered, schedule another receive poll */ /* If another packet has been buffered, schedule another receive poll */
if (rxframe[rxframe_head].length) rf230_interrupt(); if (rxframe[rxframe_head].length) {
rf230_interrupt();
}
else {
rf230_pending = 0;
}
/* Point to the checksum */ /* Point to the checksum */
framep+=len-AUX_LEN; framep+=len-AUX_LEN;
@ -1518,13 +1554,6 @@ if (!RF230_receive_on) {
/* Here return just the data length. The checksum is however still in the buffer for packet sniffing */ /* Here return just the data length. The checksum is however still in the buffer for packet sniffing */
return len - AUX_LEN; return len - AUX_LEN;
#if RADIOALWAYSON
} else {
DEBUGFLOW('y'); //Stack thought radio was off
return 0;
}
#endif
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void void
@ -1589,13 +1618,17 @@ rf230_cca(void)
uint8_t radio_was_off = 0; uint8_t radio_was_off = 0;
/* Turn radio on if necessary. If radio is currently busy return busy channel */ /* Turn radio on if necessary. If radio is currently busy return busy channel */
/* This may happen when testing radio duty cycling with RADIOALWAYSON */ /* This may happen when testing radio duty cycling with RADIOALWAYSON,
* or because a packet just started. */
if(RF230_receive_on) { if(RF230_receive_on) {
if (hal_get_slptr()) { //should not be sleeping! if (hal_get_slptr()) { //should not be sleeping!
DEBUGFLOW('<'); DEBUGFLOW('<');
goto busyexit; goto busyexit;
} else { } else {
if (!rf230_isidle()) {DEBUGFLOW('2');goto busyexit;} if (!rf230_isidle()) {
//DEBUGFLOW('2');
goto busyexit;
}
} }
} else { } else {
radio_was_off = 1; radio_was_off = 1;
@ -1611,18 +1644,30 @@ rf230_cca(void)
/* Note reading the TRX_STATUS register clears both CCA_STATUS and CCA_DONE bits */ /* Note reading the TRX_STATUS register clears both CCA_STATUS and CCA_DONE bits */
#if defined(__AVR_ATmega128RFA1__) #if defined(__AVR_ATmega128RFA1__)
#if 1 //interrupt method #if 1 //interrupt method
sei(); /* Disable rx transitions to busy (RX_PDT_BIT) */
//rf230_waitidle(); /* Note: for speed this resets rx threshold to the compiled default */
//TODO:disable reception for version bug #ifdef RF230_MIN_RX_POWER
radio_set_trx_state(RX_ON); hal_register_write(RG_RX_SYN, RF230_MIN_RX_POWER/6 + 0x81);
// rf230_waitidle(); #else
hal_register_write(RG_RX_SYN, 0x80);
#endif
/* Switch to RX_ON for measurement. This will wait if a packet is being received */
radio_set_trx_state(RX_ON);
rf230_ccawait=1; rf230_ccawait=1;
//CCA_REQUEST is supposed to trigger the interrupt but it doesn't //CCA_REQUEST is supposed to trigger the interrupt but it doesn't
// hal_subregister_write(SR_CCA_REQUEST,1); // hal_subregister_write(SR_CCA_REQUEST,1);
hal_register_write(PHY_ED_LEVEL,0);
// delay_us(TIME_CCA); /* Write to ED_LEVEL register to start CCA */
// if (hal_register_read(RG_PHY_ED_LEVEL)<(91-77)) cca=0xff; {
while (rf230_ccawait) {} uint8_t volatile saved_sreg = SREG;
sei( );
hal_register_write(PHY_ED_LEVEL,0);
while (rf230_ccawait) {}
SREG = saved_sreg;
}
/* Use ED register to determine result. 77dBm is poweron csma default.*/
#ifdef RF230_CONF_CCA_THRES #ifdef RF230_CONF_CCA_THRES
if (hal_register_read(RG_PHY_ED_LEVEL)<(91+RF230_CONF_CCA_THRES) cca=0xff; if (hal_register_read(RG_PHY_ED_LEVEL)<(91+RF230_CONF_CCA_THRES) cca=0xff;
#else #else
@ -1631,8 +1676,17 @@ rf230_cca(void)
//TODO:see if the status register works! //TODO:see if the status register works!
// cca=hal_register_read(RG_TRX_STATUS); // cca=hal_register_read(RG_TRX_STATUS);
#if RF230_CONF_AUTOACK #if RF230_CONF_AUTOACK
radio_set_trx_state(RX_AACK_ON); radio_set_trx_state(RX_AACK_ON);
#endif #endif
/* Enable packet reception */
#ifdef RF230_MIN_RX_POWER
hal_register_write(RG_RX_SYN, RF230_MIN_RX_POWER/6 + 0x01);
#else
hal_register_write(RG_RX_SYN, 0x00);
#endif
#else #else
/* If already in receive mode can read the current ED register without delay */ /* If already in receive mode can read the current ED register without delay */
/* CCA energy threshold = -91dB + 2*SR_CCA_ED_THRESH. Reset defaults to -77dB */ /* CCA energy threshold = -91dB + 2*SR_CCA_ED_THRESH. Reset defaults to -77dB */
@ -1654,6 +1708,10 @@ rf230_cca(void)
hal_subregister_write(SR_CCA_REQUEST,1); hal_subregister_write(SR_CCA_REQUEST,1);
delay_us(TIME_CCA); delay_us(TIME_CCA);
while ((cca & 0x80) == 0 ) { while ((cca & 0x80) == 0 ) {
if (hal_get_slptr()) {
DEBUGFLOW('S');
break;
}
cca=hal_register_read(RG_TRX_STATUS); cca=hal_register_read(RG_TRX_STATUS);
} }
SREG=saved_sreg; SREG=saved_sreg;
@ -1684,7 +1742,6 @@ rf230_receiving_packet(void)
radio_state = hal_subregister_read(SR_TRX_STATUS); radio_state = hal_subregister_read(SR_TRX_STATUS);
if ((radio_state==BUSY_RX) || (radio_state==BUSY_RX_AACK)) { if ((radio_state==BUSY_RX) || (radio_state==BUSY_RX_AACK)) {
// DEBUGFLOW('8'); // DEBUGFLOW('8');
// rf230_pending=1;
return 1; return 1;
} }
} }

View File

@ -10,6 +10,7 @@
* Kevin Brown kbrown3@uccs.edu * Kevin Brown kbrown3@uccs.edu
* Nate Bohlmann nate@elfwerks.com * Nate Bohlmann nate@elfwerks.com
* David Kopf dak664@embarqmail.com * David Kopf dak664@embarqmail.com
* Ivan Delamer delamer@ieee.com
* *
* All rights reserved. * All rights reserved.
* *
@ -82,7 +83,6 @@
#define RF230_MIN_ED_THRESHOLD ( 0 ) #define RF230_MIN_ED_THRESHOLD ( 0 )
#define RF230_MAX_ED_THRESHOLD ( 15 ) #define RF230_MAX_ED_THRESHOLD ( 15 )
#define RF230_MAX_TX_FRAME_LENGTH ( 127 ) /**< 127 Byte PSDU. */ #define RF230_MAX_TX_FRAME_LENGTH ( 127 ) /**< 127 Byte PSDU. */
//#define RF230_MAX_PACKET_LEN 127
#define TX_PWR_3DBM ( 0 ) #define TX_PWR_3DBM ( 0 )
#define TX_PWR_17_2DBM ( 15 ) #define TX_PWR_17_2DBM ( 15 )
@ -166,7 +166,6 @@ typedef enum{
* *
*/ */
typedef enum{ typedef enum{
// CCA_ED = 0, /**< Use energy detection above threshold mode. */ conflicts with atmega128rfa1 mcu definition
CCA_ENERGY_DETECT = 0, /**< Use energy detection above threshold mode. */ CCA_ENERGY_DETECT = 0, /**< Use energy detection above threshold mode. */
CCA_CARRIER_SENSE = 1, /**< Use carrier sense mode. */ CCA_CARRIER_SENSE = 1, /**< Use carrier sense mode. */
CCA_CARRIER_SENSE_WITH_ED = 2 /**< Use a combination of both energy detection and carrier sense. */ CCA_CARRIER_SENSE_WITH_ED = 2 /**< Use a combination of both energy detection and carrier sense. */
@ -210,8 +209,6 @@ const struct radio_driver rf230_driver;
int rf230_init(void); int rf230_init(void);
void rf230_warm_reset(void); void rf230_warm_reset(void);
void rf230_start_sneeze(void); void rf230_start_sneeze(void);
//int rf230_on(void);
//int rf230_off(void);
void rf230_set_channel(uint8_t channel); void rf230_set_channel(uint8_t channel);
void rf230_listen_channel(uint8_t channel); void rf230_listen_channel(uint8_t channel);
uint8_t rf230_get_channel(void); uint8_t rf230_get_channel(void);

View File

@ -137,7 +137,7 @@ typedef unsigned short uip_stats_t;
/* Network setup */ /* Network setup */
/* TX routine passes the cca/ack result in the return parameter */ /* TX routine passes the cca/ack result in the return parameter */
#define RDC_CONF_HARDWARE_ACK 1 #define RDC_CONF_HARDWARE_ACK 1
/* TX routine does automatic cca and optional backoff */ /* TX routine does automatic cca and optional backoffs */
#define RDC_CONF_HARDWARE_CSMA 1 #define RDC_CONF_HARDWARE_CSMA 1
/* Allow MCU sleeping between channel checks */ /* Allow MCU sleeping between channel checks */
#define RDC_CONF_MCU_SLEEP 1 #define RDC_CONF_MCU_SLEEP 1
@ -193,8 +193,10 @@ typedef unsigned short uip_stats_t;
#define RF230_CONF_AUTOACK 1 #define RF230_CONF_AUTOACK 1
/* Request 802.15.4 ACK on all packets sent (else autoretry). This is primarily for testing. */ /* Request 802.15.4 ACK on all packets sent (else autoretry). This is primarily for testing. */
#define SICSLOWPAN_CONF_ACK_ALL 0 #define SICSLOWPAN_CONF_ACK_ALL 0
/* Number of auto retry attempts 0-15 (0 implies don't use extended TX_ARET_ON mode with CCA) */ /* 1 + Number of auto retry attempts 0-15 (0 implies don't use extended TX_ARET_ON mode) */
#define RF230_CONF_AUTORETRIES 2 #define RF230_CONF_FRAME_RETRIES 2
/* Number of csma retry attempts 0-5 in extended tx mode (7 does immediate tx with no csma) */
#define RF230_CONF_CSMA_RETRIES 5
/* Default is one RAM buffer for received packets. More than one may benefit multiple TCP connections or ports */ /* Default is one RAM buffer for received packets. More than one may benefit multiple TCP connections or ports */
#define RF230_CONF_RX_BUFFERS 3 #define RF230_CONF_RX_BUFFERS 3
#define SICSLOWPAN_CONF_FRAG 1 #define SICSLOWPAN_CONF_FRAG 1
@ -250,9 +252,10 @@ typedef unsigned short uip_stats_t;
#define RTIMER_CONF_NESTED_INTERRUPTS 1 #define RTIMER_CONF_NESTED_INTERRUPTS 1
#define RF230_CONF_AUTOACK 1 #define RF230_CONF_AUTOACK 1
/* A 0 here means non-extended mode; 1 means extended mode with no retry, >1 for retrys */ /* A 0 here means non-extended mode; 1 means extended mode with no retry, >1 for retrys */
#define RF230_CONF_AUTORETRIES 1 /* Contikimac strobes on its own, but hardware retries are faster */
/* A 0 here means no cca; 1 means extended mode with cca but no retry, >1 for backoff retrys */ #define RF230_CONF_FRAME_RETRIES 1
#define RF230_CONF_CSMARETRIES 1 /* Long csma backoffs will compromise radio cycling; set to 0 for 1 csma */
#define RF230_CONF_CSMA_RETRIES 0
#define SICSLOWPAN_CONF_FRAG 1 #define SICSLOWPAN_CONF_FRAG 1
#define SICSLOWPAN_CONF_MAXAGE 3 #define SICSLOWPAN_CONF_MAXAGE 3
/* 211 bytes per queue buffer. Contikimac burst mode needs 15 for a 1280 byte MTU */ /* 211 bytes per queue buffer. Contikimac burst mode needs 15 for a 1280 byte MTU */
@ -263,7 +266,7 @@ typedef unsigned short uip_stats_t;
#define UIP_CONF_MAX_CONNECTIONS 2 #define UIP_CONF_MAX_CONNECTIONS 2
#define UIP_CONF_MAX_LISTENPORTS 4 #define UIP_CONF_MAX_LISTENPORTS 4
#define UIP_CONF_UDP_CONNS 5 #define UIP_CONF_UDP_CONNS 5
#define UIP_CONF_DS6_NBR_NBU 4 #define UIP_CONF_DS6_NBR_NBU 20
#define UIP_CONF_DS6_DEFRT_NBU 2 #define UIP_CONF_DS6_DEFRT_NBU 2
#define UIP_CONF_DS6_PREFIX_NBU 3 #define UIP_CONF_DS6_PREFIX_NBU 3
#define UIP_CONF_DS6_ROUTE_NBU 4 #define UIP_CONF_DS6_ROUTE_NBU 4
@ -274,8 +277,10 @@ typedef unsigned short uip_stats_t;
#elif 1 /* cx-mac radio cycling */ #elif 1 /* cx-mac radio cycling */
/* RF230 does clear-channel assessment in extended mode (autoretries>0) */ /* RF230 does clear-channel assessment in extended mode (autoretries>0) */
#define RF230_CONF_AUTORETRIES 1 /* These values are guesses */
#if RF230_CONF_AUTORETRIES #define RF230_CONF_FRAME_RETRIES 10
#define RF230_CONF_CSMA_RETRIES 2
#if RF230_CONF_CSMA_RETRIES
#define NETSTACK_CONF_MAC nullmac_driver #define NETSTACK_CONF_MAC nullmac_driver
#else #else
#define NETSTACK_CONF_MAC csma_driver #define NETSTACK_CONF_MAC csma_driver

View File

@ -204,9 +204,9 @@ typedef unsigned short uip_stats_t;
/* Request 802.15.4 ACK on all packets sent (else autoretry). This is primarily for testing. */ /* Request 802.15.4 ACK on all packets sent (else autoretry). This is primarily for testing. */
#define SICSLOWPAN_CONF_ACK_ALL 0 #define SICSLOWPAN_CONF_ACK_ALL 0
/* Number of auto retry attempts+1, 1-16. Set zero to disable extended TX_ARET_ON mode with CCA) */ /* Number of auto retry attempts+1, 1-16. Set zero to disable extended TX_ARET_ON mode with CCA) */
#define RF230_CONF_AUTORETRIES 3 #define RF230_CONF_FRAME_RETRIES 3
/* Number of CSMA attempts 0-7. 802.15.4 2003 standard max is 5. */ /* Number of CSMA attempts 0-7. 802.15.4 2003 standard max is 5. */
#define RF230_CONF_CSMARETRIES 5 #define RF230_CONF_CSMA_RETRIES 5
/* CCA theshold energy -91 to -61 dBm (default -77). Set this smaller than the expected minimum rssi to avoid packet collisions */ /* CCA theshold energy -91 to -61 dBm (default -77). Set this smaller than the expected minimum rssi to avoid packet collisions */
/* The Jackdaw menu 'm' command is helpful for determining the smallest ever received rssi */ /* The Jackdaw menu 'm' command is helpful for determining the smallest ever received rssi */
#define RF230_CONF_CCA_THRES -85 #define RF230_CONF_CCA_THRES -85
@ -262,9 +262,9 @@ typedef unsigned short uip_stats_t;
#define RTIMER_CONF_NESTED_INTERRUPTS 1 #define RTIMER_CONF_NESTED_INTERRUPTS 1
#define RF230_CONF_AUTOACK 1 #define RF230_CONF_AUTOACK 1
/* A 0 here means non-extended mode; 1 means extended mode with no retry, >1 for retrys */ /* A 0 here means non-extended mode; 1 means extended mode with no retry, >1 for retrys */
#define RF230_CONF_AUTORETRIES 1 #define RF230_CONF_FRAME_RETRIES 1
/* A 0 here means no cca; 1 means extended mode with cca but no retry, >1 for backoff retrys */ /* A 0 here means cca but no retry, >1= for backoff retrys */
#define RF230_CONF_CSMARETRIES 1 #define RF230_CONF_CSMA_RETRIES 1
#define SICSLOWPAN_CONF_FRAG 1 #define SICSLOWPAN_CONF_FRAG 1
#define SICSLOWPAN_CONF_MAXAGE 3 #define SICSLOWPAN_CONF_MAXAGE 3
/* 211 bytes per queue buffer. Contikimac burst mode needs 15 for a 1280 byte MTU */ /* 211 bytes per queue buffer. Contikimac burst mode needs 15 for a 1280 byte MTU */
@ -284,9 +284,9 @@ typedef unsigned short uip_stats_t;
#define UIP_CONF_DS6_AADDR_NBU 0 #define UIP_CONF_DS6_AADDR_NBU 0
#elif 1 /* cx-mac radio cycling */ #elif 1 /* cx-mac radio cycling */
/* RF230 does clear-channel assessment in extended mode (autoretries>0) */ /* RF230 does clear-channel assessment in extended mode (frame retries>0) */
#define RF230_CONF_AUTORETRIES 1 #define RF230_CONF_FRAME_RETRIES 1
#if RF230_CONF_AUTORETRIES #if RF230_CONF_FRAME_RETRIES
#define NETSTACK_CONF_MAC nullmac_driver #define NETSTACK_CONF_MAC nullmac_driver
#else #else
#define NETSTACK_CONF_MAC csma_driver #define NETSTACK_CONF_MAC csma_driver

View File

@ -282,13 +282,13 @@ typedef unsigned short uip_stats_t;
/* Request 802.15.4 ACK on all packets sent by sicslowpan.c (else autoretry) */ /* Request 802.15.4 ACK on all packets sent by sicslowpan.c (else autoretry) */
/* Broadcasts will be duplicated by the retry count, since no one will ACK them! */ /* Broadcasts will be duplicated by the retry count, since no one will ACK them! */
#define SICSLOWPAN_CONF_ACK_ALL 0 #define SICSLOWPAN_CONF_ACK_ALL 0
/* Number of auto retry attempts 0-15 (0 implies don't use extended TX_ARET_ON mode with CCA) */ /* 1 + Number of auto retry attempts 0-15 (0 implies don't use extended TX_ARET_ON mode with CCA) */
#define RF230_CONF_AUTORETRIES 2 #define RF230_CONF_FRAME_RETRIES 2
/* CCA theshold energy -91 to -61 dBm (default -77). Set this smaller than the expected minimum rssi to avoid packet collisions */ /* CCA theshold energy -91 to -61 dBm (default -77). Set this smaller than the expected minimum rssi to avoid packet collisions */
/* The Jackdaw menu 'm' command is helpful for determining the smallest ever received rssi */ /* The Jackdaw menu 'm' command is helpful for determining the smallest ever received rssi */
#define RF230_CONF_CCA_THRES -85 #define RF230_CONF_CCA_THRES -85
/* Number of CSMA attempts 0-7. 802.15.4 2003 standard max is 5. */ /* Number of CSMA attempts 0-7. 802.15.4 2003 standard max is 5. */
#define RF230_CONF_CSMARETRIES 5 #define RF230_CONF_CSMA_RETRIES 5
/* Allow sneeze command from jackdaw menu. Useful for testing CCA on other radios */ /* Allow sneeze command from jackdaw menu. Useful for testing CCA on other radios */
/* During sneezing, any access to an RF230 register will hang the MCU and cause a watchdog reset */ /* During sneezing, any access to an RF230 register will hang the MCU and cause a watchdog reset */
/* The host interface, jackdaw menu and rf230_send routines are temporarily disabled to prevent this */ /* The host interface, jackdaw menu and rf230_send routines are temporarily disabled to prevent this */
@ -310,9 +310,9 @@ typedef unsigned short uip_stats_t;
#define NETSTACK_CONF_RADIO rf230_driver #define NETSTACK_CONF_RADIO rf230_driver
#define CHANNEL_802_15_4 26 #define CHANNEL_802_15_4 26
/* Enable extended mode with autoack, but no csma/autoretry */ /* Enable extended mode with autoack, but no csma/autoretry */
#define RF230_CONF_AUTORETRIES 1 #define RF230_CONF_FRAME_RETRIES 1
#define RF230_CONF_AUTOACK 1 #define RF230_CONF_AUTOACK 1
#define RF230_CONF_CSMARETRIES 0 #define RF230_CONF_CSMA_RETRIES 0
#define SICSLOWPAN_CONF_FRAG 1 #define SICSLOWPAN_CONF_FRAG 1
#define SICSLOWPAN_CONF_MAXAGE 3 #define SICSLOWPAN_CONF_MAXAGE 3
/* Jackdaw has USB power, can be always listening */ /* Jackdaw has USB power, can be always listening */
@ -347,7 +347,7 @@ typedef unsigned short uip_stats_t;
#define NETSTACK_CONF_RADIO rf230_driver #define NETSTACK_CONF_RADIO rf230_driver
#define CHANNEL_802_15_4 26 #define CHANNEL_802_15_4 26
#define RF230_CONF_AUTOACK 1 #define RF230_CONF_AUTOACK 1
#define RF230_CONF_AUTORETRIES 1 #define RF230_CONF_FRAME_RETRIES 1
#define SICSLOWPAN_CONF_FRAG 1 #define SICSLOWPAN_CONF_FRAG 1
#define SICSLOWPAN_CONF_MAXAGE 3 #define SICSLOWPAN_CONF_MAXAGE 3
#define CXMAC_CONF_ANNOUNCEMENTS 0 #define CXMAC_CONF_ANNOUNCEMENTS 0

View File

@ -116,7 +116,7 @@ void clock_adjust_ticks(clock_time_t howmany);
#define NETSTACK_CONF_RADIO rf230_driver #define NETSTACK_CONF_RADIO rf230_driver
#define CHANNEL_802_15_4 26 #define CHANNEL_802_15_4 26
#define RF230_CONF_AUTOACK 1 #define RF230_CONF_AUTOACK 1
#define RF230_CONF_AUTORETRIES 2 #define RF230_CONF_FRAME_RETRIES 2
#define SICSLOWPAN_CONF_FRAG 1 #define SICSLOWPAN_CONF_FRAG 1
//Most browsers reissue GETs after 3 seconds which stops frag reassembly, longer MAXAGE does no good //Most browsers reissue GETs after 3 seconds which stops frag reassembly, longer MAXAGE does no good
#define SICSLOWPAN_CONF_MAXAGE 3 #define SICSLOWPAN_CONF_MAXAGE 3