Add combined MCU and radio ATmega128rfa1
This commit is contained in:
parent
ee65d0d887
commit
f1f32c8e6a
|
@ -36,7 +36,43 @@
|
||||||
*/ \
|
*/ \
|
||||||
TIMSK = _BV (OCIE0);
|
TIMSK = _BV (OCIE0);
|
||||||
|
|
||||||
#elif defined (__AVR_ATmega1284P__) || (__AVR_AT90USB1287__) || (__AVR_ATmega1281__)
|
#elif defined (__AVR_ATmega128RFA1__) && 0
|
||||||
|
|
||||||
|
#define AVR_OUTPUT_COMPARE_INT TIMER0_COMPA_vect
|
||||||
|
#define OCRSetup() \
|
||||||
|
/* Select internal clock */ \
|
||||||
|
ASSR = 0x00; \
|
||||||
|
\
|
||||||
|
/* Set counter to zero */ \
|
||||||
|
TCNT0 = 0; \
|
||||||
|
\
|
||||||
|
/* \
|
||||||
|
* Set comparison register: \
|
||||||
|
* Crystal freq. is 8000000,\
|
||||||
|
* pre-scale factor is 1024, we want 125 ticks / sec: \
|
||||||
|
* 8000000 = 1024 * 126.01 * 62, less 1 for CTC mode \
|
||||||
|
*/ \
|
||||||
|
OCR0A = 61; \
|
||||||
|
\
|
||||||
|
/* \
|
||||||
|
* Set timer control register: \
|
||||||
|
* - prescale: 1024 (CS00 - CS02) \
|
||||||
|
* - counter reset via comparison register (WGM01) \
|
||||||
|
*/ \
|
||||||
|
TCCR0A = _BV(WGM01); \
|
||||||
|
TCCR0B = _BV(CS00) | _BV(CS02); \
|
||||||
|
\
|
||||||
|
/* Clear interrupt flag register */ \
|
||||||
|
TIFR0 = TIFR0; \
|
||||||
|
\
|
||||||
|
/* \
|
||||||
|
* Raise interrupt when value in OCR0 is reached. Note that the \
|
||||||
|
* counter value in TCNT0 is cleared automatically. \
|
||||||
|
*/ \
|
||||||
|
TIMSK0 = _BV (OCIE0A);
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined (__AVR_ATmega1284P__) || (__AVR_AT90USB1287__) || (__AVR_ATmega1281__) || defined (__AVR_ATmega128RFA1__)
|
||||||
/*
|
/*
|
||||||
The Raven has a 32768Hz watch crystal that can be used to clock the timer
|
The Raven has a 32768Hz watch crystal that can be used to clock the timer
|
||||||
while the 1284p is sleeping. The Jackdaw has pads for a crystal. The crystal
|
while the 1284p is sleeping. The Jackdaw has pads for a crystal. The crystal
|
||||||
|
|
|
@ -46,19 +46,42 @@ void clock_adjust_seconds(uint8_t howmany) {
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
|
/* These routines increment the second counters.
|
||||||
|
* Calling these avoids the interrupt overhead of pushing many registers on the stack.
|
||||||
|
*/
|
||||||
|
static void increment_seconds(void) __attribute__ ((noinline));
|
||||||
|
static void increment_seconds(void)
|
||||||
|
{
|
||||||
|
seconds++;
|
||||||
|
}
|
||||||
|
#if RADIOSTATS
|
||||||
|
extern volatile uint8_t rf230_calibrate;
|
||||||
|
static void increment_radioontime(void) __attribute__ ((noinline));
|
||||||
|
static void increment_radioontime(void)
|
||||||
|
{
|
||||||
|
static uint8_t calibrate_interval;
|
||||||
|
radioontime++;
|
||||||
|
if (++calibrate_interval==0) {
|
||||||
|
rf230_calibrate=1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
//SIGNAL(SIG_OUTPUT_COMPARE0)
|
//SIGNAL(SIG_OUTPUT_COMPARE0)
|
||||||
ISR(AVR_OUTPUT_COMPARE_INT)
|
ISR(AVR_OUTPUT_COMPARE_INT)
|
||||||
{
|
{
|
||||||
count++;
|
count++;
|
||||||
if(++scount == CLOCK_SECOND) {
|
if(++scount == CLOCK_SECOND) {
|
||||||
scount = 0;
|
scount = 0;
|
||||||
seconds++;
|
increment_seconds();
|
||||||
|
// seconds++;
|
||||||
}
|
}
|
||||||
#if RADIOSTATS
|
#if RADIOSTATS
|
||||||
if (RF230_receive_on) {
|
if (RF230_receive_on) {
|
||||||
if (++rcount == CLOCK_SECOND) {
|
if (++rcount == CLOCK_SECOND) {
|
||||||
rcount=0;
|
rcount=0;
|
||||||
radioontime++;
|
increment_radioontime();
|
||||||
|
// radioontime++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -52,7 +52,7 @@
|
||||||
#define ADD_CARRAGE_RETURNS_TO_SERIAL_OUTPUT 1
|
#define ADD_CARRAGE_RETURNS_TO_SERIAL_OUTPUT 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined (__AVR_ATmega128__) || defined(__AVR_ATmega1284P__) || defined(__AVR_ATmega1281__)
|
#if defined (__AVR_ATmega128__) || defined(__AVR_ATmega1284P__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega128RFA1__)
|
||||||
typedef struct {
|
typedef struct {
|
||||||
volatile uint8_t * UDR;
|
volatile uint8_t * UDR;
|
||||||
volatile uint8_t * UBRRH;
|
volatile uint8_t * UBRRH;
|
||||||
|
|
|
@ -48,6 +48,8 @@
|
||||||
#include "dev/rs232_atmega1284.h"
|
#include "dev/rs232_atmega1284.h"
|
||||||
#elif defined (__AVR_AT90USB1287__)
|
#elif defined (__AVR_AT90USB1287__)
|
||||||
#include "dev/rs232_at90usb1287.h"
|
#include "dev/rs232_at90usb1287.h"
|
||||||
|
#elif defined (__AVR_ATmega128RFA1__)
|
||||||
|
#include "dev/rs232_atmega128rfa1.h"
|
||||||
#else
|
#else
|
||||||
#error "Please implement a rs232 header for your MCU (or set the MCU type \
|
#error "Please implement a rs232 header for your MCU (or set the MCU type \
|
||||||
in contiki-conf.h)."
|
in contiki-conf.h)."
|
||||||
|
|
|
@ -73,10 +73,12 @@
|
||||||
// RAVENUSB_C : used for USB key or Raven card
|
// RAVENUSB_C : used for USB key or Raven card
|
||||||
// RCB_B : RZ200 kit from Atmel based on 1281V
|
// RCB_B : RZ200 kit from Atmel based on 1281V
|
||||||
// ZIGBIT : Zigbit module from Meshnetics
|
// ZIGBIT : Zigbit module from Meshnetics
|
||||||
|
// ATMEGA128RFA1 : Bare chip with internal radio
|
||||||
#define RAVEN_D 4
|
#define RAVEN_D 4
|
||||||
#define RAVENUSB_C 1
|
#define RAVENUSB_C 1
|
||||||
#define RCB_B 2
|
#define RCB_B 2
|
||||||
#define ZIGBIT 3
|
#define ZIGBIT 3
|
||||||
|
#define ATMEGA128RFA1 4
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -166,6 +168,32 @@
|
||||||
# define HAS_CW_MODE
|
# define HAS_CW_MODE
|
||||||
# define HAS_SPARE_TIMER
|
# define HAS_SPARE_TIMER
|
||||||
|
|
||||||
|
#elif HARWARE_REVISION == ATMEGA128RFA1
|
||||||
|
/* ATmega1281 with internal AT86RF231 radio */
|
||||||
|
#if 0
|
||||||
|
# define SSPORT B
|
||||||
|
# define SSPIN (0x04)
|
||||||
|
# define SPIPORT B
|
||||||
|
# define MOSIPIN (0x05)
|
||||||
|
# define MISOPIN (0x06)
|
||||||
|
# define SCKPIN (0x07)
|
||||||
|
# define RSTPORT B
|
||||||
|
# define RSTPIN (0x01)
|
||||||
|
# define IRQPORT D
|
||||||
|
# define IRQPIN (0x06)
|
||||||
|
# define SLPTRPORT B
|
||||||
|
# define SLPTRPIN (0x03)
|
||||||
|
# define TXCWPORT B
|
||||||
|
# define TXCWPIN (0x00)
|
||||||
|
#endif
|
||||||
|
# define SLPTRPORT TRXPR
|
||||||
|
# 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) */
|
||||||
|
|
||||||
|
@ -289,6 +317,15 @@
|
||||||
* that the source code can directly use.
|
* that the source code can directly use.
|
||||||
* \{
|
* \{
|
||||||
*/
|
*/
|
||||||
|
#if defined(__AVR_ATmega128RFA1__)
|
||||||
|
|
||||||
|
#define hal_set_rst_low( ) ( TRXPR &= ~( 1 << TRXRST ) ) /**< This macro pulls the RST pin low. */
|
||||||
|
#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_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). */
|
||||||
|
|
||||||
|
#else
|
||||||
#define SLP_TR SLPTRPIN /**< Pin number that corresponds to the SLP_TR pin. */
|
#define SLP_TR SLPTRPIN /**< Pin number that corresponds to the SLP_TR pin. */
|
||||||
#define DDR_SLP_TR DDR( SLPTRPORT ) /**< Data Direction Register that corresponds to the port where SLP_TR is connected. */
|
#define DDR_SLP_TR DDR( SLPTRPORT ) /**< Data Direction Register that corresponds to the port where SLP_TR is connected. */
|
||||||
#define PORT_SLP_TR PORT( SLPTRPORT ) /**< Port (Write Access) where SLP_TR is connected. */
|
#define PORT_SLP_TR PORT( SLPTRPORT ) /**< Port (Write Access) where SLP_TR is connected. */
|
||||||
|
@ -321,6 +358,8 @@
|
||||||
#define HAL_DD_SCK SCKPIN /**< Data Direction bit for SCK. */
|
#define HAL_DD_SCK SCKPIN /**< Data Direction bit for SCK. */
|
||||||
#define HAL_DD_MOSI MOSIPIN /**< Data Direction bit for MOSI. */
|
#define HAL_DD_MOSI MOSIPIN /**< Data Direction bit for MOSI. */
|
||||||
#define HAL_DD_MISO MISOPIN /**< Data Direction bit for MISO. */
|
#define HAL_DD_MISO MISOPIN /**< Data Direction bit for MISO. */
|
||||||
|
#endif /* defined(__AVR_ATmega128RFA1__) */
|
||||||
|
|
||||||
/** \} */
|
/** \} */
|
||||||
|
|
||||||
|
|
||||||
|
@ -459,17 +498,39 @@ void hal_clear_rx_start_event_handler( void );
|
||||||
uint8_t hal_get_pll_lock_flag( void );
|
uint8_t hal_get_pll_lock_flag( void );
|
||||||
void hal_clear_pll_lock_flag( void );
|
void hal_clear_pll_lock_flag( void );
|
||||||
|
|
||||||
|
/* Hack for atmega128rfa1 with integrated radio. Access registers directly, not through SPI */
|
||||||
|
#if defined(__AVR_ATmega128RFA1__)
|
||||||
|
//#define hal_register_read(address) _SFR_MEM8((uint16_t)address)
|
||||||
|
#define hal_register_read(address) address
|
||||||
|
uint8_t hal_subregister_read( uint16_t address, uint8_t mask, uint8_t position );
|
||||||
|
void hal_subregister_write( uint16_t address, uint8_t mask, uint8_t position,
|
||||||
|
uint8_t value );
|
||||||
|
|
||||||
|
//#define hal_register_write(address, value) _SFR_MEM8((uint16_t)address)=value
|
||||||
|
#define hal_register_write(address, value) address=value
|
||||||
|
//#define hal_subregister_read( address, mask, position ) (_SFR_MEM8((uint16_t)address)&mask)>>position
|
||||||
|
//#define hal_subregister_read1( address, mask, position ) (address&mask)>>position
|
||||||
|
//#define hal_subregister_write( address, mask, position, value ) address=(address<<position)&mask
|
||||||
|
#else
|
||||||
uint8_t hal_register_read( uint8_t address );
|
uint8_t hal_register_read( uint8_t address );
|
||||||
void hal_register_write( uint8_t address, uint8_t value );
|
void hal_register_write( uint8_t address, uint8_t value );
|
||||||
uint8_t hal_subregister_read( uint8_t address, uint8_t mask, uint8_t position );
|
uint8_t hal_subregister_read( uint8_t address, uint8_t mask, uint8_t position );
|
||||||
void hal_subregister_write( uint8_t address, uint8_t mask, uint8_t position,
|
void hal_subregister_write( uint8_t address, uint8_t mask, uint8_t position,
|
||||||
uint8_t value );
|
uint8_t value );
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//void hal_frame_read(hal_rx_frame_t *rx_frame, rx_callback_t rx_callback);
|
//void hal_frame_read(hal_rx_frame_t *rx_frame, rx_callback_t rx_callback);
|
||||||
/* For speed RF230BB does not use a 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 );
|
||||||
void 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 );
|
||||||
|
/* Number of receive buffers in RAM. */
|
||||||
|
#ifndef RF230_CONF_RX_BUFFERS
|
||||||
|
#define RF230_CONF_RX_BUFFERS 1
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
/** @} */
|
/** @} */
|
||||||
|
|
|
@ -65,26 +65,14 @@
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
|
|
||||||
#include "hal.h"
|
#include "hal.h"
|
||||||
|
|
||||||
|
#if defined(__AVR_ATmega128RFA1__)
|
||||||
|
#include <avr/io.h>
|
||||||
|
#include "atmega128rfa1_registermap.h"
|
||||||
|
#else
|
||||||
#include "at86rf230_registermap.h"
|
#include "at86rf230_registermap.h"
|
||||||
/*============================ MACROS ========================================*/
|
#endif
|
||||||
|
|
||||||
/*
|
|
||||||
* Macros defined for the radio transceiver's access modes.
|
|
||||||
*
|
|
||||||
* These functions are implemented as macros since they are used very often.
|
|
||||||
*/
|
|
||||||
#define HAL_DUMMY_READ (0x00) /**< Dummy value for the SPI. */
|
|
||||||
|
|
||||||
#define HAL_TRX_CMD_RW (0xC0) /**< Register Write (short mode). */
|
|
||||||
#define HAL_TRX_CMD_RR (0x80) /**< Register Read (short mode). */
|
|
||||||
#define HAL_TRX_CMD_FW (0x60) /**< Frame Transmit Mode (long mode). */
|
|
||||||
#define HAL_TRX_CMD_FR (0x20) /**< Frame Receive Mode (long mode). */
|
|
||||||
#define HAL_TRX_CMD_SW (0x40) /**< SRAM Write. */
|
|
||||||
#define HAL_TRX_CMD_SR (0x00) /**< SRAM Read. */
|
|
||||||
#define HAL_TRX_CMD_RADDRM (0x7F) /**< Register Address Mask. */
|
|
||||||
|
|
||||||
#define HAL_CALCULATED_CRC_OK (0) /**< CRC calculated over the frame including the CRC field should be 0. */
|
|
||||||
/*============================ TYPDEFS =======================================*/
|
|
||||||
/*============================ VARIABLES =====================================*/
|
/*============================ VARIABLES =====================================*/
|
||||||
/** \brief This is a file internal variable that contains the 16 MSB of the
|
/** \brief This is a file internal variable that contains the 16 MSB of the
|
||||||
* system time.
|
* system time.
|
||||||
|
@ -100,11 +88,10 @@
|
||||||
static uint16_t hal_system_time = 0;
|
static uint16_t hal_system_time = 0;
|
||||||
volatile extern signed char rf230_last_rssi;
|
volatile extern signed char rf230_last_rssi;
|
||||||
|
|
||||||
/*Flag section.*/
|
//static uint8_t volatile hal_bat_low_flag;
|
||||||
//static uint8_t volatile hal_bat_low_flag; /**< BAT_LOW flag. */
|
//static uint8_t volatile hal_pll_lock_flag;
|
||||||
//static uint8_t volatile hal_pll_lock_flag; /**< PLL_LOCK flag. */
|
|
||||||
|
|
||||||
/*Callbacks.*/
|
/*============================ CALLBACKS =====================================*/
|
||||||
|
|
||||||
/** \brief This function is called when a rx_start interrupt is signaled.
|
/** \brief This function is called when a rx_start interrupt is signaled.
|
||||||
*
|
*
|
||||||
|
@ -130,10 +117,24 @@ volatile extern signed char rf230_last_rssi;
|
||||||
* \see hal_set_trx_end_event_handler
|
* \see hal_set_trx_end_event_handler
|
||||||
*/
|
*/
|
||||||
//static hal_trx_end_isr_event_handler_t trx_end_callback;
|
//static hal_trx_end_isr_event_handler_t trx_end_callback;
|
||||||
/*============================ PROTOTYPES ====================================*/
|
|
||||||
/*============================ IMPLEMENTATION ================================*/
|
|
||||||
|
|
||||||
#if defined(__AVR__)
|
/*============================ IMPLEMENTATION ================================*/
|
||||||
|
#if defined(__AVR_ATmega128RFA1__)
|
||||||
|
//#include <avr/io.h>
|
||||||
|
#include <avr/interrupt.h>
|
||||||
|
/* AVR1281 with internal RF231 radio */
|
||||||
|
#define HAL_SPI_TRANSFER_OPEN()
|
||||||
|
//#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__)
|
||||||
/*
|
/*
|
||||||
* 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)
|
||||||
*/
|
*/
|
||||||
|
@ -198,7 +199,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__)
|
#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
|
||||||
|
hal_init(void)
|
||||||
|
{
|
||||||
|
/*Reset variables used in file.*/
|
||||||
|
hal_system_time = 0;
|
||||||
|
// 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(); /* Enable interrupts from the radio transceiver. */
|
||||||
|
}
|
||||||
|
|
||||||
|
#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_TIME_ISR() ISR(TIMER1_OVF_vect)
|
||||||
#define HAL_TICK_UPCNT() (TCNT1)
|
#define HAL_TICK_UPCNT() (TCNT1)
|
||||||
|
@ -406,6 +422,42 @@ hal_init(void)
|
||||||
// HAL_LEAVE_CRITICAL_REGION();
|
// HAL_LEAVE_CRITICAL_REGION();
|
||||||
//}
|
//}
|
||||||
|
|
||||||
|
#if defined(__AVR_ATmega128RFA1__)
|
||||||
|
/* Hack for internal radio registers. hal_register_read and hal_register_write are
|
||||||
|
handled through defines, but the preprocesser can't parse a macro containing
|
||||||
|
another #define with multiple arguments, e.g. using
|
||||||
|
#define hal_subregister_read( address, mask, position ) (address&mask)>>position
|
||||||
|
#define SR_TRX_STATUS TRX_STATUS, 0x1f, 0
|
||||||
|
the following only sees 1 argument to the macro
|
||||||
|
return hal_subregister_read(SR_TRX_STATUS);
|
||||||
|
|
||||||
|
Possible fix is through two defines:
|
||||||
|
#define x_hal_subregister_read(x) hal_subregister_read(x);
|
||||||
|
#define hal_subregister_read( address, mask, position ) (address&mask)>>position
|
||||||
|
but the subregister defines in atmega128rfa1_registermap.h are currently set up without
|
||||||
|
the _SFR_MEM8 attribute, for use by hal_subregister_write.
|
||||||
|
|
||||||
|
*/
|
||||||
|
uint8_t
|
||||||
|
hal_subregister_read(uint16_t address, uint8_t mask, uint8_t position)
|
||||||
|
{
|
||||||
|
return (_SFR_MEM8(address)&mask)>>position;
|
||||||
|
}
|
||||||
|
void
|
||||||
|
hal_subregister_write(uint16_t address, uint8_t mask, uint8_t position,
|
||||||
|
uint8_t value)
|
||||||
|
{
|
||||||
|
cli();
|
||||||
|
uint8_t register_value = _SFR_MEM8(address);
|
||||||
|
register_value &= ~mask;
|
||||||
|
value <<= position;
|
||||||
|
value &= mask;
|
||||||
|
value |= register_value;
|
||||||
|
_SFR_MEM8(address) = value;
|
||||||
|
sei();
|
||||||
|
}
|
||||||
|
|
||||||
|
#else /* defined(__AVR_ATmega128RFA1__) */
|
||||||
/*----------------------------------------------------------------------------*/
|
/*----------------------------------------------------------------------------*/
|
||||||
/** \brief This function reads data from one of the radio transceiver's registers.
|
/** \brief This function reads data from one of the radio transceiver's registers.
|
||||||
*
|
*
|
||||||
|
@ -419,18 +471,17 @@ hal_init(void)
|
||||||
uint8_t
|
uint8_t
|
||||||
hal_register_read(uint8_t address)
|
hal_register_read(uint8_t address)
|
||||||
{
|
{
|
||||||
|
uint8_t register_value;
|
||||||
/* Add the register read command to the register address. */
|
/* Add the register read command to the register address. */
|
||||||
address &= HAL_TRX_CMD_RADDRM;
|
/* Address should be < 0x2f so no need to mask */
|
||||||
address |= HAL_TRX_CMD_RR;
|
// address &= 0x3f;
|
||||||
|
address |= 0x80;
|
||||||
uint8_t register_value = 0;
|
|
||||||
|
|
||||||
HAL_SPI_TRANSFER_OPEN();
|
HAL_SPI_TRANSFER_OPEN();
|
||||||
|
|
||||||
/*Send Register address and read register content.*/
|
/*Send Register address and read register content.*/
|
||||||
register_value = HAL_SPI_TRANSFER(address); // dummy read
|
HAL_SPI_TRANSFER(address);
|
||||||
|
register_value = HAL_SPI_TRANSFER(0);
|
||||||
register_value = HAL_SPI_TRANSFER(register_value); // dummy write
|
|
||||||
|
|
||||||
HAL_SPI_TRANSFER_CLOSE();
|
HAL_SPI_TRANSFER_CLOSE();
|
||||||
|
|
||||||
|
@ -449,19 +500,17 @@ hal_register_read(uint8_t address)
|
||||||
void
|
void
|
||||||
hal_register_write(uint8_t address, uint8_t value)
|
hal_register_write(uint8_t address, uint8_t value)
|
||||||
{
|
{
|
||||||
/* Add the Register Write command to the address. */
|
/* Add the Register Write (short mode) command to the address. */
|
||||||
address = HAL_TRX_CMD_RW | (HAL_TRX_CMD_RADDRM & address);
|
address = 0xc0 | address;
|
||||||
|
|
||||||
HAL_SPI_TRANSFER_OPEN();
|
HAL_SPI_TRANSFER_OPEN();
|
||||||
|
|
||||||
/*Send Register address and write register content.*/
|
/*Send Register address and write register content.*/
|
||||||
uint8_t dummy_read = HAL_SPI_TRANSFER(address);
|
HAL_SPI_TRANSFER(address);
|
||||||
|
HAL_SPI_TRANSFER(value);
|
||||||
dummy_read = HAL_SPI_TRANSFER(value);
|
|
||||||
|
|
||||||
HAL_SPI_TRANSFER_CLOSE();
|
HAL_SPI_TRANSFER_CLOSE();
|
||||||
}
|
}
|
||||||
|
|
||||||
/*----------------------------------------------------------------------------*/
|
/*----------------------------------------------------------------------------*/
|
||||||
/** \brief This function reads the value of a specific subregister.
|
/** \brief This function reads the value of a specific subregister.
|
||||||
*
|
*
|
||||||
|
@ -483,7 +532,6 @@ hal_subregister_read(uint8_t address, uint8_t mask, uint8_t position)
|
||||||
|
|
||||||
return register_value;
|
return register_value;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*----------------------------------------------------------------------------*/
|
/*----------------------------------------------------------------------------*/
|
||||||
/** \brief This function writes a new value to one of the radio transceiver's
|
/** \brief This function writes a new value to one of the radio transceiver's
|
||||||
* subregisters.
|
* subregisters.
|
||||||
|
@ -501,7 +549,7 @@ hal_subregister_write(uint8_t address, uint8_t mask, uint8_t position,
|
||||||
uint8_t value)
|
uint8_t value)
|
||||||
{
|
{
|
||||||
/* Read current register value and mask area outside the subregister. */
|
/* Read current register value and mask area outside the subregister. */
|
||||||
uint8_t register_value = hal_register_read(address);
|
volatile uint8_t register_value = hal_register_read(address);
|
||||||
register_value &= ~mask;
|
register_value &= ~mask;
|
||||||
|
|
||||||
/* Start preparing the new subregister value. shift in place and mask. */
|
/* Start preparing the new subregister value. shift in place and mask. */
|
||||||
|
@ -513,7 +561,7 @@ hal_subregister_write(uint8_t address, uint8_t mask, uint8_t position,
|
||||||
/* Write the modified register value. */
|
/* Write the modified register value. */
|
||||||
hal_register_write(address, value);
|
hal_register_write(address, value);
|
||||||
}
|
}
|
||||||
|
#endif /* defined(__AVR_ATmega128RFA1__) */
|
||||||
/*----------------------------------------------------------------------------*/
|
/*----------------------------------------------------------------------------*/
|
||||||
/** \brief This function will upload a frame from the radio transceiver's frame
|
/** \brief This function will upload a frame from the radio transceiver's frame
|
||||||
* buffer.
|
* buffer.
|
||||||
|
@ -522,7 +570,8 @@ hal_subregister_write(uint8_t address, uint8_t mask, uint8_t position,
|
||||||
* is out of the defined bounds. Then the frame length, lqi value and crc
|
* is out of the defined bounds. Then the frame length, lqi value and crc
|
||||||
* be set to zero. This is done to indicate an error.
|
* be set to zero. This is done to indicate an error.
|
||||||
* This version is optimized for use with contiki RF230BB driver.
|
* This version is optimized for use with contiki RF230BB driver.
|
||||||
* The callback routine and CRC are left out for speed in reading the rx buffrer .
|
* The callback routine and CRC are left out for speed in reading the rx buffer.
|
||||||
|
* Any delays here can lead to overwrites by the next packet!
|
||||||
*
|
*
|
||||||
* \param rx_frame Pointer to the data structure where the frame is stored.
|
* \param rx_frame Pointer to the data structure where the frame is stored.
|
||||||
* \param rx_callback Pointer to callback function for receiving one byte at a time.
|
* \param rx_callback Pointer to callback function for receiving one byte at a time.
|
||||||
|
@ -531,6 +580,26 @@ void
|
||||||
//hal_frame_read(hal_rx_frame_t *rx_frame, rx_callback_t rx_callback)
|
//hal_frame_read(hal_rx_frame_t *rx_frame, rx_callback_t rx_callback)
|
||||||
hal_frame_read(hal_rx_frame_t *rx_frame)
|
hal_frame_read(hal_rx_frame_t *rx_frame)
|
||||||
{
|
{
|
||||||
|
#if defined(__AVR_ATmega128RFA1__)
|
||||||
|
|
||||||
|
uint8_t frame_length,*rx_data,*rx_buffer;
|
||||||
|
|
||||||
|
rx_data = (rx_frame->data);
|
||||||
|
frame_length = TST_RX_LENGTH; //frame length, not including lqi?
|
||||||
|
rx_frame->length = frame_length;
|
||||||
|
rx_buffer=(uint8_t *)0x180; //start of fifo in i/o space
|
||||||
|
|
||||||
|
do{
|
||||||
|
*rx_data++ = _SFR_MEM8(rx_buffer++);
|
||||||
|
|
||||||
|
} while (--frame_length > 0);
|
||||||
|
|
||||||
|
/*Read LQI value for this frame.*/
|
||||||
|
rx_frame->lqi = *rx_buffer;
|
||||||
|
if (1) {
|
||||||
|
|
||||||
|
#else /* defined(__AVR_ATmega128RFA1__) */
|
||||||
|
|
||||||
uint8_t *rx_data;
|
uint8_t *rx_data;
|
||||||
|
|
||||||
/* check that we have either valid frame pointer or callback pointer */
|
/* check that we have either valid frame pointer or callback pointer */
|
||||||
|
@ -539,14 +608,15 @@ hal_frame_read(hal_rx_frame_t *rx_frame)
|
||||||
|
|
||||||
HAL_SPI_TRANSFER_OPEN();
|
HAL_SPI_TRANSFER_OPEN();
|
||||||
|
|
||||||
/*Send frame read command.*/
|
/*Send frame read (long mode) command.*/
|
||||||
(void)HAL_SPI_TRANSFER(HAL_TRX_CMD_FR);
|
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);
|
uint8_t frame_length = HAL_SPI_TRANSFER(0);
|
||||||
|
|
||||||
/*Check for correct frame length.*/
|
/*Check for correct frame length.*/
|
||||||
if ((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)){
|
||||||
|
if (1) {
|
||||||
// uint16_t crc = 0;
|
// uint16_t crc = 0;
|
||||||
// if (rx_frame){
|
// if (rx_frame){
|
||||||
rx_data = (rx_frame->data);
|
rx_data = (rx_frame->data);
|
||||||
|
@ -584,12 +654,13 @@ hal_frame_read(hal_rx_frame_t *rx_frame)
|
||||||
// rx_callback(HAL_SPI_TRANSFER_READ());
|
// rx_callback(HAL_SPI_TRANSFER_READ());
|
||||||
// }
|
// }
|
||||||
|
|
||||||
|
#endif /* defined(__AVR_ATmega128RFA1__) */
|
||||||
|
|
||||||
/*Check calculated crc, and set crc field in hal_rx_frame_t accordingly.*/
|
/*Check calculated crc, and set crc field in hal_rx_frame_t accordingly.*/
|
||||||
// if (rx_frame){
|
// if (rx_frame){
|
||||||
rx_frame->crc = 1;
|
rx_frame->crc = 1;
|
||||||
// } else {
|
// } else {
|
||||||
// rx_callback(crc != HAL_CALCULATED_CRC_OK);
|
// rx_callback(crc != 0);
|
||||||
// }
|
// }
|
||||||
} else {
|
} else {
|
||||||
// if (rx_frame){
|
// if (rx_frame){
|
||||||
|
@ -612,24 +683,47 @@ hal_frame_read(hal_rx_frame_t *rx_frame)
|
||||||
void
|
void
|
||||||
hal_frame_write(uint8_t *write_buffer, uint8_t length)
|
hal_frame_write(uint8_t *write_buffer, uint8_t length)
|
||||||
{
|
{
|
||||||
length &= HAL_TRX_CMD_RADDRM; /* Truncate length to maximum frame length. */
|
#if defined(__AVR_ATmega128RFA1__)
|
||||||
|
uint8_t *tx_buffer;
|
||||||
|
tx_buffer=(uint8_t *)0x180; //start of fifo in i/o space
|
||||||
|
/* Write frame length, including the two byte checksum */
|
||||||
|
/* The top bit of the length field shall be set to 0 for IEEE 802.15.4 compliant frames */
|
||||||
|
/* It should already be clear, so bypassing the masking is sanity check of the uip stack */
|
||||||
|
// length &= 0x7f;
|
||||||
|
_SFR_MEM8(tx_buffer++) = length;
|
||||||
|
|
||||||
|
/* Download to the Frame Buffer.
|
||||||
|
* When the FCS is autogenerated there is no need to transfer the last two bytes
|
||||||
|
* since they will be overwritten.
|
||||||
|
*/
|
||||||
|
#if !RF230_CONF_CHECKSUM
|
||||||
|
length -= 2;
|
||||||
|
#endif
|
||||||
|
do _SFR_MEM8(tx_buffer++)= *write_buffer++; while (--length);
|
||||||
|
|
||||||
|
#else /* defined(__AVR_ATmega128RFA1__) */
|
||||||
|
/* Optionally truncate length to maximum frame length.
|
||||||
|
* Not doing this is a fast way to know when the application needs fixing!
|
||||||
|
*/
|
||||||
|
// length &= 0x7f;
|
||||||
|
|
||||||
HAL_SPI_TRANSFER_OPEN();
|
HAL_SPI_TRANSFER_OPEN();
|
||||||
|
|
||||||
/*SEND FRAME WRITE COMMAND AND FRAME LENGTH.*/
|
/* Send Frame Transmit (long mode) command and frame length */
|
||||||
|
HAL_SPI_TRANSFER(0x60);
|
||||||
uint8_t dummy_read = HAL_SPI_TRANSFER(HAL_TRX_CMD_FW);
|
HAL_SPI_TRANSFER(length);
|
||||||
|
|
||||||
dummy_read = HAL_SPI_TRANSFER(length);
|
/* Download to the Frame Buffer.
|
||||||
|
* When the FCS is autogenerated there is no need to transfer the last two bytes
|
||||||
/* Download to the Frame Buffer. */
|
* since they will be overwritten.
|
||||||
/* Note an autogenerated FCS is inserted into the last two bytes, so there is no
|
*/
|
||||||
* need to transfer them to the buffer */
|
#if !RF230_CONF_CHECKSUM
|
||||||
do{
|
length -= 2;
|
||||||
dummy_read = HAL_SPI_TRANSFER(*write_buffer++);
|
#endif
|
||||||
} while (--length > 2);
|
do HAL_SPI_TRANSFER(*write_buffer++); while (--length);
|
||||||
|
|
||||||
HAL_SPI_TRANSFER_CLOSE();
|
HAL_SPI_TRANSFER_CLOSE();
|
||||||
|
#endif /* defined(__AVR_ATmega128RFA1__) */
|
||||||
}
|
}
|
||||||
|
|
||||||
/*----------------------------------------------------------------------------*/
|
/*----------------------------------------------------------------------------*/
|
||||||
|
@ -647,14 +741,14 @@ hal_frame_write(uint8_t *write_buffer, uint8_t length)
|
||||||
// HAL_SPI_TRANSFER_OPEN();
|
// HAL_SPI_TRANSFER_OPEN();
|
||||||
|
|
||||||
/*Send SRAM read command.*/
|
/*Send SRAM read command.*/
|
||||||
// uint8_t dummy_read = HAL_SPI_TRANSFER(HAL_TRX_CMD_SR);
|
// HAL_SPI_TRANSFER(0x00);
|
||||||
|
|
||||||
/*Send address where to start reading.*/
|
/*Send address where to start reading.*/
|
||||||
// dummy_read = HAL_SPI_TRANSFER(address);
|
// HAL_SPI_TRANSFER(address);
|
||||||
|
|
||||||
/*Upload the chosen memory area.*/
|
/*Upload the chosen memory area.*/
|
||||||
// do{
|
// do{
|
||||||
// *data++ = HAL_SPI_TRANSFER(HAL_DUMMY_READ);
|
// *data++ = HAL_SPI_TRANSFER(0);
|
||||||
// } while (--length > 0);
|
// } while (--length > 0);
|
||||||
|
|
||||||
// HAL_SPI_TRANSFER_CLOSE();
|
// HAL_SPI_TRANSFER_CLOSE();
|
||||||
|
@ -664,7 +758,8 @@ hal_frame_write(uint8_t *write_buffer, uint8_t length)
|
||||||
/*----------------------------------------------------------------------------*/
|
/*----------------------------------------------------------------------------*/
|
||||||
/** \brief Write SRAM
|
/** \brief Write SRAM
|
||||||
*
|
*
|
||||||
* This function writes into the SRAM of the radio transceiver.
|
* This function writes into the SRAM of the radio transceiver. It can reduce
|
||||||
|
* SPI transfers if only part of a frame is to be changed before retransmission.
|
||||||
*
|
*
|
||||||
* \param address Address in the TRX's SRAM where the write burst should start
|
* \param address Address in the TRX's SRAM where the write burst should start
|
||||||
* \param length Length of the write burst
|
* \param length Length of the write burst
|
||||||
|
@ -676,14 +771,14 @@ hal_frame_write(uint8_t *write_buffer, uint8_t length)
|
||||||
// HAL_SPI_TRANSFER_OPEN();
|
// HAL_SPI_TRANSFER_OPEN();
|
||||||
|
|
||||||
/*Send SRAM write command.*/
|
/*Send SRAM write command.*/
|
||||||
// uint8_t dummy_read = HAL_SPI_TRANSFER(HAL_TRX_CMD_SW);
|
// HAL_SPI_TRANSFER(0x40);
|
||||||
|
|
||||||
/*Send address where to start writing to.*/
|
/*Send address where to start writing to.*/
|
||||||
// dummy_read = HAL_SPI_TRANSFER(address);
|
// HAL_SPI_TRANSFER(address);
|
||||||
|
|
||||||
/*Upload the chosen memory area.*/
|
/*Upload the chosen memory area.*/
|
||||||
// do{
|
// do{
|
||||||
// dummy_read = HAL_SPI_TRANSFER(*data++);
|
// HAL_SPI_TRANSFER(*data++);
|
||||||
// } while (--length > 0);
|
// } while (--length > 0);
|
||||||
|
|
||||||
// HAL_SPI_TRANSFER_CLOSE();
|
// HAL_SPI_TRANSFER_CLOSE();
|
||||||
|
@ -702,7 +797,10 @@ void RADIO_VECT(void);
|
||||||
#else /* !DOXYGEN */
|
#else /* !DOXYGEN */
|
||||||
/* These link to the RF230BB driver in rf230.c */
|
/* These link to the RF230BB driver in rf230.c */
|
||||||
void rf230_interrupt(void);
|
void rf230_interrupt(void);
|
||||||
extern hal_rx_frame_t rxframe;
|
|
||||||
|
extern hal_rx_frame_t rxframe[RF230_CONF_RX_BUFFERS];
|
||||||
|
extern uint8_t rxframe_head,rxframe_tail;
|
||||||
|
|
||||||
/* rf230interruptflag can be printed in the main idle loop for debugging */
|
/* rf230interruptflag can be printed in the main idle loop for debugging */
|
||||||
#define DEBUG 0
|
#define DEBUG 0
|
||||||
#if DEBUG
|
#if DEBUG
|
||||||
|
@ -712,6 +810,121 @@ volatile char rf230interruptflag;
|
||||||
#define INTERRUPTDEBUG(arg)
|
#define INTERRUPTDEBUG(arg)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(__AVR_ATmega128RFA1__)
|
||||||
|
/* The atmega128rfa1 has individual interrupts for the integrated radio */
|
||||||
|
/* Whichever are enabled by the RF230 driver must be present even if not used! */
|
||||||
|
ISR(TRX24_RX_END_vect)
|
||||||
|
{
|
||||||
|
INTERRUPTDEBUG(11);
|
||||||
|
/* Received packet interrupt */
|
||||||
|
/* 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);
|
||||||
|
|
||||||
|
#ifdef RF230_MIN_RX_POWER
|
||||||
|
/* Discard packets weaker than the minimum if defined. This is for testing miniature meshes.*/
|
||||||
|
/* Save the rssi for printing in the main loop */
|
||||||
|
#if RF230_CONF_AUTOACK
|
||||||
|
// rf230_last_rssi=hal_subregister_read(SR_ED_LEVEL);
|
||||||
|
rf230_last_rssi=hal_register_read(RG_PHY_ED_LEVEL);
|
||||||
|
#endif
|
||||||
|
// if (rf230_last_rssi >= RF230_MIN_RX_POWER) {
|
||||||
|
if (1) {
|
||||||
|
#endif
|
||||||
|
hal_frame_read(&rxframe[rxframe_tail]);
|
||||||
|
rxframe_tail++;if (rxframe_tail >= RF230_CONF_RX_BUFFERS) rxframe_tail=0;
|
||||||
|
rf230_interrupt();
|
||||||
|
#ifdef RF230_MIN_RX_POWER
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
ISR(TRX24_RX_START_vect)
|
||||||
|
{
|
||||||
|
INTERRUPTDEBUG(10);
|
||||||
|
/* Save RSSI for this packet if not in extended mode, scaling to 1dB resolution */
|
||||||
|
#if !RF230_CONF_AUTOACK
|
||||||
|
rf230_last_rssi = 3 * hal_subregister_read(SR_RSSI);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
}
|
||||||
|
ISR(TRX24_PLL_LOCK_vect)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
ISR(TRX24_PLL_UNLOCK_vect)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
#if 0
|
||||||
|
HAL_RF230_ISR() //for reference, for now
|
||||||
|
{
|
||||||
|
/*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?
|
||||||
|
// isr_timestamp /= HAL_US_PER_SYMBOL; /* Divide so that we get time in 16us resolution. */
|
||||||
|
// isr_timestamp &= HAL_SYMBOL_MASK;
|
||||||
|
|
||||||
|
uint8_t interrupt_source;
|
||||||
|
|
||||||
|
INTERRUPTDEBUG(1);
|
||||||
|
|
||||||
|
/*Read Interrupt source.*/
|
||||||
|
interrupt_source = IRQ_STATUS;
|
||||||
|
|
||||||
|
/*Handle the incomming interrupt. Prioritized.*/
|
||||||
|
if (interrupt_source & (1>>RX_START)){
|
||||||
|
INTERRUPTDEBUG(10);
|
||||||
|
/* Save RSSI for this packet if not in extended mode, scaling to 1dB resolution */
|
||||||
|
#if !RF230_CONF_AUTOACK
|
||||||
|
rf230_last_rssi = 3 * hal_subregister_read(SR_RSSI);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
} else if (interrupt_source & (1<<RX_END)){
|
||||||
|
INTERRUPTDEBUG(11);
|
||||||
|
/* Received packet interrupt */
|
||||||
|
/* 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);
|
||||||
|
|
||||||
|
#ifdef RF230_MIN_RX_POWER
|
||||||
|
/* Discard packets weaker than the minimum if defined. This is for testing miniature meshes.*/
|
||||||
|
/* Save the rssi for printing in the main loop */
|
||||||
|
#if RF230_CONF_AUTOACK
|
||||||
|
// rf230_last_rssi=hal_subregister_read(SR_ED_LEVEL);
|
||||||
|
rf230_last_rssi=hal_register_read(RG_PHY_ED_LEVEL);
|
||||||
|
#endif
|
||||||
|
// if (rf230_last_rssi >= RF230_MIN_RX_POWER) {
|
||||||
|
if (1) {
|
||||||
|
#endif
|
||||||
|
hal_frame_read(&rxframe[rxframe_tail]);
|
||||||
|
rxframe_tail++;if (rxframe_tail >= RF230_CONF_RX_BUFFERS) rxframe_tail=0;
|
||||||
|
rf230_interrupt();
|
||||||
|
// trx_end_callback(isr_timestamp);
|
||||||
|
#ifdef RF230_MIN_RX_POWER
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
} else if (interrupt_source & (1<<TX_END)){
|
||||||
|
INTERRUPTDEBUG(13);
|
||||||
|
;
|
||||||
|
} else if (interrupt_source & (1<<PLL_UNLOCK)){
|
||||||
|
INTERRUPTDEBUG(14);
|
||||||
|
;
|
||||||
|
} else if (interrupt_source & (1<<PLL_LOCK)){
|
||||||
|
INTERRUPTDEBUG(15);
|
||||||
|
// hal_pll_lock_flag++;
|
||||||
|
;
|
||||||
|
} else {
|
||||||
|
INTERRUPTDEBUG(99);
|
||||||
|
;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#else /* defined(__AVR_ATmega128RFA1__) */
|
||||||
|
/* 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
|
/*The following code reads the current system time. This is done by first
|
||||||
|
@ -727,14 +940,14 @@ HAL_RF230_ISR()
|
||||||
|
|
||||||
INTERRUPTDEBUG(1);
|
INTERRUPTDEBUG(1);
|
||||||
|
|
||||||
|
|
||||||
/* Using SPI bus from ISR is generally a bad idea... */
|
/* Using SPI bus from ISR is generally a bad idea... */
|
||||||
/* Note: all IRQ are not always automatically disabled when running in ISR */
|
/* Note: all IRQ are not always automatically disabled when running in ISR */
|
||||||
HAL_SPI_TRANSFER_OPEN();
|
HAL_SPI_TRANSFER_OPEN();
|
||||||
|
|
||||||
/*Read Interrupt source.*/
|
/*Read Interrupt source.*/
|
||||||
|
|
||||||
/*Send Register address and read register content.*/
|
/*Send Register address and read register content.*/
|
||||||
HAL_SPI_TRANSFER_WRITE(RG_IRQ_STATUS | HAL_TRX_CMD_RR);
|
HAL_SPI_TRANSFER_WRITE(0x80 | RG_IRQ_STATUS);
|
||||||
|
|
||||||
/* This is the second part of the convertion of system time to a 16 us time
|
/* 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
|
base. The division is moved here so we can spend less time waiting for SPI
|
||||||
|
@ -745,10 +958,13 @@ HAL_RF230_ISR()
|
||||||
|
|
||||||
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_READ(); /* The interrupt variable is used as a dummy read. */
|
||||||
|
|
||||||
interrupt_source = HAL_SPI_TRANSFER(interrupt_source);
|
interrupt_source = HAL_SPI_TRANSFER(interrupt_source);
|
||||||
|
#else
|
||||||
|
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.*/
|
||||||
|
@ -757,6 +973,7 @@ HAL_RF230_ISR()
|
||||||
/* Save RSSI for this packet if not in extended mode, scaling to 1dB resolution */
|
/* Save RSSI for this packet if not in extended mode, scaling to 1dB resolution */
|
||||||
#if !RF230_CONF_AUTOACK
|
#if !RF230_CONF_AUTOACK
|
||||||
#if 0 // 3-clock shift and add is faster on machines with no hardware multiply
|
#if 0 // 3-clock shift and add is faster on machines with no hardware multiply
|
||||||
|
// While the compiler should use similar code for multiply by 3 there may be a bug with -Os in avr-gcc that calls the general subroutine
|
||||||
rf230_last_rssi = hal_subregister_read(SR_RSSI);
|
rf230_last_rssi = hal_subregister_read(SR_RSSI);
|
||||||
rf230_last_rssi = (rf230_last_rssi <<1) + rf230_last_rssi;
|
rf230_last_rssi = (rf230_last_rssi <<1) + rf230_last_rssi;
|
||||||
#else // Faster with 1-clock multiply. Raven and Jackdaw have 2-clock multiply so same speed while saving 2 bytes of program memory
|
#else // Faster with 1-clock multiply. Raven and Jackdaw have 2-clock multiply so same speed while saving 2 bytes of program memory
|
||||||
|
@ -766,9 +983,7 @@ HAL_RF230_ISR()
|
||||||
// if(rx_start_callback != NULL){
|
// if(rx_start_callback != NULL){
|
||||||
// /* Read Frame length and call rx_start callback. */
|
// /* Read Frame length and call rx_start callback. */
|
||||||
// HAL_SPI_TRANSFER_OPEN();
|
// HAL_SPI_TRANSFER_OPEN();
|
||||||
|
// uint8_t frame_length = HAL_SPI_TRANSFER(0x20);
|
||||||
// uint8_t frame_length = HAL_SPI_TRANSFER(HAL_TRX_CMD_FR);
|
|
||||||
|
|
||||||
// frame_length = HAL_SPI_TRANSFER(frame_length);
|
// frame_length = HAL_SPI_TRANSFER(frame_length);
|
||||||
|
|
||||||
// HAL_SPI_TRANSFER_CLOSE();
|
// HAL_SPI_TRANSFER_CLOSE();
|
||||||
|
@ -786,31 +1001,25 @@ HAL_RF230_ISR()
|
||||||
/* 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.length) break; //toss packet if last one not processed yet
|
||||||
if (rxframe.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);
|
||||||
#endif
|
#endif
|
||||||
if (rf230_last_rssi >= RF230_MIN_RX_POWER) {
|
if (rf230_last_rssi >= RF230_MIN_RX_POWER) {
|
||||||
#endif
|
#endif
|
||||||
hal_frame_read(&rxframe);
|
hal_frame_read(&rxframe[rxframe_tail]);
|
||||||
|
rxframe_tail++;if (rxframe_tail >= RF230_CONF_RX_BUFFERS) rxframe_tail=0;
|
||||||
rf230_interrupt();
|
rf230_interrupt();
|
||||||
// trx_end_callback(isr_timestamp);
|
// trx_end_callback(isr_timestamp);
|
||||||
#ifdef RF230_MIN_RX_POWER
|
#ifdef RF230_MIN_RX_POWER
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if 0
|
|
||||||
/* Enable reception of next packet */
|
|
||||||
#if RF230_CONF_AUTOACK
|
|
||||||
hal_subregister_write(SR_TRX_CMD, RX_AACK_ON);
|
|
||||||
#else
|
|
||||||
hal_subregister_write(SR_TRX_CMD, RX_ON);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
} else if (interrupt_source & HAL_TRX_UR_MASK){
|
} else if (interrupt_source & HAL_TRX_UR_MASK){
|
||||||
|
@ -838,6 +1047,7 @@ HAL_RF230_ISR()
|
||||||
;
|
;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif /* defined(__AVR_ATmega128RFA1__) */
|
||||||
# endif /* defined(DOXYGEN) */
|
# endif /* defined(DOXYGEN) */
|
||||||
|
|
||||||
/*----------------------------------------------------------------------------*/
|
/*----------------------------------------------------------------------------*/
|
||||||
|
|
|
@ -42,8 +42,14 @@
|
||||||
|
|
||||||
#if defined(__AVR__)
|
#if defined(__AVR__)
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
#include <util/delay.h>
|
|
||||||
#define delay_us( us ) ( _delay_us( ( us ) ) )
|
//_delay_us has the potential to use floating point which brings the 256 byte clz table into RAM
|
||||||
|
//#include <util/delay.h>
|
||||||
|
//#define delay_us( us ) ( _delay_us( ( us ) ) )
|
||||||
|
//_delay_loop_2(uint16_t count) is 4 CPU cycles per iteration, up to 32 milliseconds at 8MHz
|
||||||
|
#include <util/delay_basic.h>
|
||||||
|
#define delay_us( us ) ( _delay_loop_2(1+(us*F_CPU)/4000000UL) )
|
||||||
|
|
||||||
#include <avr/pgmspace.h>
|
#include <avr/pgmspace.h>
|
||||||
#elif defined(__MSP430__)
|
#elif defined(__MSP430__)
|
||||||
#include <io.h>
|
#include <io.h>
|
||||||
|
@ -116,6 +122,7 @@ struct timestamp {
|
||||||
#define RADIOSLEEPSWHENOFF 1
|
#define RADIOSLEEPSWHENOFF 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//RS232 delays will cause 6lowpan fragment overruns!
|
||||||
#define DEBUG 0
|
#define DEBUG 0
|
||||||
#if DEBUG
|
#if DEBUG
|
||||||
#define PRINTF(FORMAT,args...) printf_P(PSTR(FORMAT),##args)
|
#define PRINTF(FORMAT,args...) printf_P(PSTR(FORMAT),##args)
|
||||||
|
@ -141,6 +148,9 @@ struct timestamp {
|
||||||
#if RADIOSTATS
|
#if RADIOSTATS
|
||||||
uint16_t RF230_sendpackets,RF230_receivepackets,RF230_sendfail,RF230_receivefail;
|
uint16_t RF230_sendpackets,RF230_receivepackets,RF230_sendfail,RF230_receivefail;
|
||||||
#endif
|
#endif
|
||||||
|
/* Set in clock.c every 256 seconds */
|
||||||
|
uint8_t rf230_calibrate;
|
||||||
|
uint8_t rf230_calibrated; //debugging
|
||||||
|
|
||||||
/* Track flow through driver, see contiki-raven-main.c for example of use */
|
/* Track flow through driver, see contiki-raven-main.c for example of use */
|
||||||
//#define DEBUGFLOWSIZE 64
|
//#define DEBUGFLOWSIZE 64
|
||||||
|
@ -217,7 +227,8 @@ uint8_t RF230_receive_on,RF230_sleeping;
|
||||||
static uint8_t channel;
|
static uint8_t channel;
|
||||||
|
|
||||||
/* Received frames are buffered to rxframe in the interrupt routine in hal.c */
|
/* Received frames are buffered to rxframe in the interrupt routine in hal.c */
|
||||||
hal_rx_frame_t rxframe;
|
uint8_t rxframe_head,rxframe_tail;
|
||||||
|
hal_rx_frame_t rxframe[RF230_CONF_RX_BUFFERS];
|
||||||
|
|
||||||
/*----------------------------------------------------------------------------*/
|
/*----------------------------------------------------------------------------*/
|
||||||
/** \brief This function return the Radio Transceivers current state.
|
/** \brief This function return the Radio Transceivers current state.
|
||||||
|
@ -450,7 +461,7 @@ rf230_is_ready_to_send() {
|
||||||
static void
|
static void
|
||||||
flushrx(void)
|
flushrx(void)
|
||||||
{
|
{
|
||||||
rxframe.length=0;
|
rxframe[rxframe_head].length=0;
|
||||||
}
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
static uint8_t locked, lock_on, lock_off;
|
static uint8_t locked, lock_on, lock_off;
|
||||||
|
@ -538,32 +549,148 @@ set_txpower(uint8_t power)
|
||||||
hal_subregister_write(SR_TX_PWR, power);
|
hal_subregister_write(SR_TX_PWR, power);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
/*----------------------------------------------------------------------------*/
|
||||||
|
/**
|
||||||
|
\brief Calibrate the internal RC oscillator
|
||||||
|
|
||||||
|
This function calibrates the internal RC oscillator, based
|
||||||
|
on an external 32KHz crystal connected to TIMER2. In order to
|
||||||
|
verify the calibration result you can program the CKOUT fuse
|
||||||
|
and monitor the CPU clock on an I/O pin.
|
||||||
|
*/
|
||||||
|
#define AVR_ENTER_CRITICAL_REGION( ) {uint8_t volatile saved_sreg = SREG; cli( )
|
||||||
|
#define AVR_LEAVE_CRITICAL_REGION( ) SREG = saved_sreg;}
|
||||||
|
uint8_t osccal_original,osccal_calibrated;
|
||||||
|
void
|
||||||
|
calibrate_rc_osc_32k(void)
|
||||||
|
{
|
||||||
|
#if 1
|
||||||
|
|
||||||
|
/* Calibrate RC Oscillator: The calibration routine is done by clocking TIMER2
|
||||||
|
* from the external 32kHz crystal while running an internal timer simultaneously.
|
||||||
|
* The internal timer will be clocked at the same speed as the internal RC
|
||||||
|
* oscillator, while TIMER2 is running at 32768 Hz. This way it is not necessary
|
||||||
|
* to use a timed loop, and keep track cycles in timed loop vs. optimization
|
||||||
|
* and compiler.
|
||||||
|
*/
|
||||||
|
uint8_t osccal_original = OSCCAL;
|
||||||
|
volatile uint16_t temp;
|
||||||
|
|
||||||
|
/* Start with current value, which for some MCUs could be in upper or lower range */
|
||||||
|
|
||||||
|
// PRR0 &= ~((1 << PRTIM2)|(1 << PRTIM1)); /* Enable Timer 1 and 2 */
|
||||||
|
|
||||||
|
TIMSK2 = 0x00; /* Disable Timer/Counter 2 interrupts. */
|
||||||
|
TIMSK1 = 0x00; /* Disable Timer/Counter 1 interrupts. */
|
||||||
|
|
||||||
|
/* Enable TIMER/COUNTER 2 to be clocked from the external 32kHz clock crystal.
|
||||||
|
* Then wait for the timer to become stable before doing any calibration.
|
||||||
|
*/
|
||||||
|
ASSR |= (1 << AS2);
|
||||||
|
// while (ASSR & ((1 << TCN2UB)|(1 << OCR2AUB)|(1 << TCR2AUB)|(1 << TCR2BUB))) { ; }
|
||||||
|
TCCR2B = 1 << CS20; /* run timer 2 at divide by 1 (32KHz) */
|
||||||
|
|
||||||
|
delay_us(50000UL); //crystal takes significant time to stabilize
|
||||||
|
AVR_ENTER_CRITICAL_REGION();
|
||||||
|
|
||||||
|
uint8_t counter = 128;
|
||||||
|
bool cal_ok = false;
|
||||||
|
do{
|
||||||
|
/* wait for timer to be ready for updated config */
|
||||||
|
TCCR1B = 1 << CS10;
|
||||||
|
|
||||||
|
while (ASSR & ((1 << TCN2UB)|(1 << OCR2AUB)|(1 << TCR2AUB)|(1 << TCR2BUB))) { ; }
|
||||||
|
|
||||||
|
TCNT2 = 0x80;
|
||||||
|
TCNT1 = 0;
|
||||||
|
|
||||||
|
TIFR2 = 0xFF; /* Clear TIFR2 flags (Yes, really) */
|
||||||
|
|
||||||
|
/* Wait for TIMER/COUNTER 2 to overflow. Stop TIMER/COUNTER 1 and 2, and
|
||||||
|
* read the counter value of TIMER/COUNTER 1. It will now contain the
|
||||||
|
* number of cpu cycles elapsed within the 3906.25 microsecond period.
|
||||||
|
*/
|
||||||
|
while (!(TIFR2 & (1 << TOV2))){
|
||||||
|
;
|
||||||
|
}
|
||||||
|
temp = TCNT1;
|
||||||
|
|
||||||
|
TCCR1B = 0;
|
||||||
|
/* Defining these as floating point introduces a lot of code and the 256 byte .clz table to RAM */
|
||||||
|
/* At 8 MHz we would expect 8*3906.25 = 31250 CPU clocks */
|
||||||
|
#define cal_upper 32812 //(31250*1.05) // 32812 = 0x802c
|
||||||
|
#define cal_lower 29687 //(31250*0.95) // 29687 = 0x73f7
|
||||||
|
/* Iteratively reduce the error to be within limits */
|
||||||
|
if (temp < cal_lower) {
|
||||||
|
/* Too slow. Put the hammer down. */
|
||||||
|
if (OSCCAL==0x7e) break; //stay in lowest range
|
||||||
|
if (OSCCAL==0xff) break;
|
||||||
|
OSCCAL++;
|
||||||
|
} else if (temp > cal_upper) {
|
||||||
|
/* Too fast, retard. */
|
||||||
|
if (OSCCAL==0x81) break; //stay in highest range
|
||||||
|
if (OSCCAL==0x00) break;
|
||||||
|
OSCCAL--;
|
||||||
|
} else {
|
||||||
|
/* The CPU clock frequency is now within +/- 0.5% of the target value. */
|
||||||
|
cal_ok = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
counter--;
|
||||||
|
} while ((counter != 0) && (false == cal_ok));
|
||||||
|
|
||||||
|
osccal_calibrated=OSCCAL;
|
||||||
|
if (true != cal_ok) {
|
||||||
|
/* We failed, therefore restore previous OSCCAL value. */
|
||||||
|
OSCCAL = osccal_original;
|
||||||
|
}
|
||||||
|
|
||||||
|
OSCCAL = osccal_original;
|
||||||
|
TCCR2B = 0;
|
||||||
|
|
||||||
|
ASSR &= ~(1 << AS2);
|
||||||
|
|
||||||
|
/* Disable both timers again to save power. */
|
||||||
|
// PRR0 |= (1 << PRTIM2);/* |(1 << PRTIM1); */
|
||||||
|
|
||||||
|
AVR_LEAVE_CRITICAL_REGION();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
int
|
int
|
||||||
rf230_init(void)
|
rf230_init(void)
|
||||||
{
|
{
|
||||||
|
uint8_t i;
|
||||||
DEBUGFLOW('I');
|
DEBUGFLOW('I');
|
||||||
|
|
||||||
/* Wait in case VCC just applied */
|
/* Wait in case VCC just applied */
|
||||||
delay_us(TIME_TO_ENTER_P_ON);
|
delay_us(TIME_TO_ENTER_P_ON);
|
||||||
|
|
||||||
/* Calibrate oscillator */
|
/* Calibrate oscillator */
|
||||||
// calibrate_rc_osc_32k();
|
// printf_P(PSTR("\nBefore calibration OSCCAL=%x\n"),OSCCAL);
|
||||||
|
// calibrate_rc_osc_32k();
|
||||||
|
// printf_P(PSTR("After calibration OSCCAL=%x\n"),OSCCAL);
|
||||||
|
|
||||||
/* Initialize Hardware Abstraction Layer. */
|
/* Initialize Hardware Abstraction Layer */
|
||||||
hal_init();
|
hal_init();
|
||||||
|
|
||||||
|
/* Set receive buffers empty and point to the first */
|
||||||
|
for (i=0;i<RF230_CONF_RX_BUFFERS;i++) rxframe[i].length=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();
|
||||||
delay_us(TIME_RESET);
|
delay_us(TIME_RESET);
|
||||||
hal_set_rst_high();
|
hal_set_rst_high();
|
||||||
|
|
||||||
/* Force transition to TRX_OFF. */
|
/* Force transition to TRX_OFF */
|
||||||
hal_subregister_write(SR_TRX_CMD, CMD_FORCE_TRX_OFF);
|
hal_subregister_write(SR_TRX_CMD, CMD_FORCE_TRX_OFF);
|
||||||
delay_us(TIME_P_ON_TO_TRX_OFF);
|
delay_us(TIME_P_ON_TO_TRX_OFF);
|
||||||
|
|
||||||
/* Verify that it is a supported version */
|
/* Verify that it is a supported version */
|
||||||
|
/* Note gcc optimizes this away if DEBUG is not set! */
|
||||||
|
//ATMEGA128RFA1 - version 4, ID 31
|
||||||
uint8_t tvers = hal_register_read(RG_VERSION_NUM);
|
uint8_t tvers = hal_register_read(RG_VERSION_NUM);
|
||||||
uint8_t tmanu = hal_register_read(RG_MAN_ID_0);
|
uint8_t tmanu = hal_register_read(RG_MAN_ID_0);
|
||||||
|
|
||||||
|
@ -577,6 +704,12 @@ rf230_init(void)
|
||||||
|
|
||||||
/* 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 (0 implies PLL_ON sends instead of the extended TX_ARET mode */
|
||||||
hal_subregister_write(SR_MAX_FRAME_RETRIES, RF230_CONF_AUTORETRIES );
|
hal_subregister_write(SR_MAX_FRAME_RETRIES, RF230_CONF_AUTORETRIES );
|
||||||
|
|
||||||
|
/* Set up carrier sense/clear channel assesment parameters for extended operating mode */
|
||||||
|
hal_subregister_write(SR_MAX_CSMA_RETRIES, 5 );//highest allowed retries
|
||||||
|
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(CSMA_SEED_1,42 );
|
||||||
|
|
||||||
/* Use automatic CRC unless manual is specified */
|
/* Use automatic CRC unless manual is specified */
|
||||||
#if RF230_CONF_CHECKSUM
|
#if RF230_CONF_CHECKSUM
|
||||||
|
@ -619,10 +752,20 @@ rf230_transmit(unsigned short payload_len)
|
||||||
radiowason=RF230_receive_on;
|
radiowason=RF230_receive_on;
|
||||||
|
|
||||||
/* If radio is sleeping we have to turn it on first */
|
/* If radio is sleeping we have to turn it on first */
|
||||||
|
/* This automatically does the PLL calibrations */
|
||||||
if (RF230_sleeping) {
|
if (RF230_sleeping) {
|
||||||
hal_set_slptr_low();
|
hal_set_slptr_low();
|
||||||
// delay_us(TIME_SLEEP_TO_TRX_OFF);
|
// delay_us(TIME_SLEEP_TO_TRX_OFF);
|
||||||
RF230_sleeping=0;
|
RF230_sleeping=0;
|
||||||
|
} else {
|
||||||
|
/* If on, do periodic calibration. See clock.c */
|
||||||
|
if (rf230_calibrate) {
|
||||||
|
hal_subregister_write(SR_PLL_CF_START,1); //takes 80us max
|
||||||
|
hal_subregister_write(SR_PLL_DCU_START,1); //takes 6us, concurrently
|
||||||
|
rf230_calibrate=0;
|
||||||
|
rf230_calibrated=1;
|
||||||
|
delay_us(80); //?
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Wait for any previous operation or state transition to finish */
|
/* Wait for any previous operation or state transition to finish */
|
||||||
|
@ -649,12 +792,19 @@ rf230_transmit(unsigned short payload_len)
|
||||||
#if RF230_CONF_TIMESTAMPS
|
#if RF230_CONF_TIMESTAMPS
|
||||||
rtimer_clock_t txtime = timesynch_time();
|
rtimer_clock_t txtime = timesynch_time();
|
||||||
#endif /* RF230_CONF_TIMESTAMPS */
|
#endif /* RF230_CONF_TIMESTAMPS */
|
||||||
|
#if defined(__AVR_ATmega128RFA1__)
|
||||||
|
/* No interrupts across frame download! */
|
||||||
|
cli();
|
||||||
|
/* slow down the transmit? */
|
||||||
|
// delay_us(500);
|
||||||
|
#endif
|
||||||
/* Toggle the SLP_TR pin to initiate the frame transmission */
|
/* 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();
|
||||||
|
#endif
|
||||||
PRINTF("rf230_transmit:\n");
|
PRINTF("rf230_transmit:\n");
|
||||||
#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
|
||||||
|
@ -984,14 +1134,14 @@ if (RF230_receive_on) {
|
||||||
|
|
||||||
pending = 1;
|
pending = 1;
|
||||||
|
|
||||||
#if RADIOSTATS
|
#if RADIOSTATS //TODO:This will double count buffered packets
|
||||||
RF230_receivepackets++;
|
RF230_receivepackets++;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if RADIOALWAYSON
|
#if RADIOALWAYSON
|
||||||
} else {
|
} else {
|
||||||
DEBUGFLOW('-');
|
DEBUGFLOW('-');
|
||||||
rxframe.length=0;
|
rxframe[rxframe_head].length=0;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
return 1;
|
return 1;
|
||||||
|
@ -1048,7 +1198,7 @@ PROCESS_THREAD(rf230_process, ev, data)
|
||||||
}
|
}
|
||||||
/* Get packet from Radio if any, else return zero.
|
/* Get packet from Radio if any, else return zero.
|
||||||
* The two-byte checksum is appended but the returned length does not include it.
|
* The two-byte checksum is appended but the returned length does not include it.
|
||||||
* At present the last frame is buffered in the interrupt routine so this routine
|
* Frames are buffered in the interrupt routine so this routine
|
||||||
* does not access the hardware or change its status
|
* does not access the hardware or change its status
|
||||||
*/
|
*/
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
|
@ -1066,7 +1216,7 @@ rf230_read(void *buf, unsigned short bufsize)
|
||||||
struct timestamp t;
|
struct timestamp t;
|
||||||
#endif /* RF230_CONF_TIMESTAMPS */
|
#endif /* RF230_CONF_TIMESTAMPS */
|
||||||
/* The length includes the twp-byte checksum but not the LQI byte */
|
/* The length includes the twp-byte checksum but not the LQI byte */
|
||||||
len=rxframe.length;
|
len=rxframe[rxframe_head].length;
|
||||||
if (len==0) {
|
if (len==0) {
|
||||||
#if RADIOALWAYSON && DEBUGFLOWSIZE
|
#if RADIOALWAYSON && DEBUGFLOWSIZE
|
||||||
if (RF230_receive_on==0) {if (debugflow[debugflowsize-1]!='z') DEBUGFLOW('z');} //cxmac calls with radio off?
|
if (RF230_receive_on==0) {if (debugflow[debugflowsize-1]!='z') DEBUGFLOW('z');} //cxmac calls with radio off?
|
||||||
|
@ -1088,13 +1238,13 @@ if (RF230_receive_on) {
|
||||||
rf230_time_of_departure = 0;
|
rf230_time_of_departure = 0;
|
||||||
#endif /* RF230_CONF_TIMESTAMPS */
|
#endif /* RF230_CONF_TIMESTAMPS */
|
||||||
|
|
||||||
// PRINTSHORT("r%d",rxframe.length);
|
// PRINTSHORT("r%d",rxframe[rxframe_head].length);
|
||||||
PRINTF("rf230_read: %u bytes lqi %u crc %u\n",rxframe.length,rxframe.lqi,rxframe.crc);
|
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
|
#if DEBUG>1
|
||||||
{
|
{
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
PRINTF("0000");
|
PRINTF("0000");
|
||||||
for (i=0;i<rxframe.length;i++) PRINTF(" %02x",rxframe.data[i]);
|
for (i=0;i<rxframe[rxframe_head].length;i++) PRINTF(" %02x",rxframe[rxframe_head].data[i]);
|
||||||
PRINTF("\n");
|
PRINTF("\n");
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -1129,11 +1279,16 @@ if (RF230_receive_on) {
|
||||||
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.data[0]);
|
framep=&(rxframe[rxframe_head].data[0]);
|
||||||
memcpy(buf,framep,len-AUX_LEN+CHECKSUM_LEN);
|
memcpy(buf,framep,len-AUX_LEN+CHECKSUM_LEN);
|
||||||
|
rf230_last_correlation = rxframe[rxframe_head].lqi;
|
||||||
|
|
||||||
/* Clear the length field to allow buffering of the next packet */
|
/* Clear the length field to allow buffering of the next packet */
|
||||||
rxframe.length=0;
|
rxframe[rxframe_head].length=0;
|
||||||
|
rxframe_head++;if (rxframe_head >= RF230_CONF_RX_BUFFERS) rxframe_head=0;
|
||||||
|
/* If another packet has been buffered, schedule another receive poll */
|
||||||
|
if (rxframe[rxframe_head].length) rf230_interrupt();
|
||||||
|
|
||||||
/* Point to the checksum */
|
/* Point to the checksum */
|
||||||
framep+=len-AUX_LEN;
|
framep+=len-AUX_LEN;
|
||||||
#if RF230_CONF_CHECKSUM
|
#if RF230_CONF_CHECKSUM
|
||||||
|
@ -1164,14 +1319,15 @@ if (RF230_receive_on) {
|
||||||
rf230_last_rssi = rf230_get_raw_rssi();
|
rf230_last_rssi = rf230_get_raw_rssi();
|
||||||
#else //faster
|
#else //faster
|
||||||
#if RF230_CONF_AUTOACK
|
#if RF230_CONF_AUTOACK
|
||||||
rf230_last_rssi = hal_subregister_read(SR_ED_LEVEL); //0-84 resolution 1 dB
|
// rf230_last_rssi = hal_subregister_read(SR_ED_LEVEL); //0-84 resolution 1 dB
|
||||||
|
rf230_last_rssi = hal_register_read(RG_PHY_ED_LEVEL); //0-84, resolution 1 dB
|
||||||
#else
|
#else
|
||||||
/* last_rssi will have been set at RX_START interrupt */
|
/* last_rssi will have been set at RX_START interrupt */
|
||||||
// rf230_last_rssi = 3*hal_subregister_read(SR_RSSI); //0-28 resolution 3 dB
|
// rf230_last_rssi = 3*hal_subregister_read(SR_RSSI); //0-28 resolution 3 dB
|
||||||
#endif
|
#endif
|
||||||
#endif /* speed vs. generality */
|
#endif /* speed vs. generality */
|
||||||
|
|
||||||
rf230_last_correlation = rxframe.lqi;
|
// rf230_last_correlation = rxframe[rxframe_head].lqi;
|
||||||
packetbuf_set_attr(PACKETBUF_ATTR_RSSI, rf230_last_rssi);
|
packetbuf_set_attr(PACKETBUF_ATTR_RSSI, rf230_last_rssi);
|
||||||
packetbuf_set_attr(PACKETBUF_ATTR_LINK_QUALITY, rf230_last_correlation);
|
packetbuf_set_attr(PACKETBUF_ATTR_LINK_QUALITY, rf230_last_correlation);
|
||||||
|
|
||||||
|
@ -1251,7 +1407,8 @@ rf230_get_raw_rssi(void)
|
||||||
/* The rssi register is multiplied by 3 to a consistent value from either register */
|
/* The rssi register is multiplied by 3 to a consistent value from either register */
|
||||||
state=radio_get_trx_state();
|
state=radio_get_trx_state();
|
||||||
if ((state==RX_AACK_ON) || (state==BUSY_RX_AACK)) {
|
if ((state==RX_AACK_ON) || (state==BUSY_RX_AACK)) {
|
||||||
rssi = hal_subregister_read(SR_ED_LEVEL); //0-84, resolution 1 dB
|
// rssi = hal_subregister_read(SR_ED_LEVEL); //0-84, resolution 1 dB
|
||||||
|
rssi = hal_register_read(RG_PHY_ED_LEVEL); //0-84, resolution 1 dB
|
||||||
} else {
|
} else {
|
||||||
#if 0 // 3-clock shift and add is faster on machines with no hardware multiply
|
#if 0 // 3-clock shift and add is faster on machines with no hardware multiply
|
||||||
/* avr-gcc may have an -Os bug that uses the general subroutine for multiplying by 3 */
|
/* avr-gcc may have an -Os bug that uses the general subroutine for multiplying by 3 */
|
||||||
|
|
|
@ -53,8 +53,13 @@
|
||||||
/*============================ INCLUDE =======================================*/
|
/*============================ INCLUDE =======================================*/
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include "at86rf230_registermap.h"
|
|
||||||
#include "hal.h"
|
#include "hal.h"
|
||||||
|
#if defined(__AVR_ATmega128RFA1__)
|
||||||
|
#include "atmega128rfa1_registermap.h"
|
||||||
|
#else
|
||||||
|
#include "at86rf230_registermap.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
/*============================ MACROS ========================================*/
|
/*============================ MACROS ========================================*/
|
||||||
#define SUPPORTED_PART_NUMBER ( 2 )
|
#define SUPPORTED_PART_NUMBER ( 2 )
|
||||||
|
@ -155,7 +160,8 @@ typedef enum{
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
typedef enum{
|
typedef enum{
|
||||||
CCA_ED = 0, /**< Use energy detection above threshold mode. */
|
// 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_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. */
|
||||||
}radio_cca_mode_t;
|
}radio_cca_mode_t;
|
||||||
|
|
|
@ -65,7 +65,7 @@
|
||||||
#define OCF3C OCF3B
|
#define OCF3C OCF3B
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(__AVR_AT90USB1287__)
|
#if defined(__AVR_AT90USB1287__) || defined(__AVR_ATmega128RFA1__)
|
||||||
#define ETIMSK TIMSK3
|
#define ETIMSK TIMSK3
|
||||||
#define ETIFR TIFR3
|
#define ETIFR TIFR3
|
||||||
#define TICIE3 ICIE3
|
#define TICIE3 ICIE3
|
||||||
|
|
Loading…
Reference in a new issue