halbb.c

Go to the documentation of this file.
00001 /*   Copyright (c) 2009, Swedish Institute of Computer Science
00002  *  All rights reserved. 
00003  *
00004  *  Additional fixes for AVR contributed by:
00005  *
00006  *      Colin O'Flynn coflynn@newae.com
00007  *      Eric Gnoske egnoske@gmail.com
00008  *      Blake Leverett bleverett@gmail.com
00009  *      Mike Vidales mavida404@gmail.com
00010  *      Kevin Brown kbrown3@uccs.edu
00011  *      Nate Bohlmann nate@elfwerks.com
00012  *      David Kopf dak664@embarqmail.com
00013  *
00014  *   All rights reserved.
00015  *
00016  *   Redistribution and use in source and binary forms, with or without
00017  *   modification, are permitted provided that the following conditions are met:
00018  *
00019  *   * Redistributions of source code must retain the above copyright
00020  *     notice, this list of conditions and the following disclaimer.
00021  *   * Redistributions in binary form must reproduce the above copyright
00022  *     notice, this list of conditions and the following disclaimer in
00023  *     the documentation and/or other materials provided with the
00024  *     distribution.
00025  *   * Neither the name of the copyright holders nor the names of
00026  *     contributors may be used to endorse or promote products derived
00027  *     from this software without specific prior written permission.
00028  *
00029  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00030  *  AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00031  *  IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00032  *  ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00033  *  LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00034  *  CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00035  *  SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00036  *  INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00037  *  CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00038  *  ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00039  *  POSSIBILITY OF SUCH DAMAGE.
00040  *
00041  * 
00042 */
00043 
00044 /**
00045  *   \addtogroup wireless
00046  *  @{
00047 */
00048 
00049 /**
00050  *   \defgroup hal RF230 hardware level drivers
00051  *   @{
00052  */
00053 
00054 /**
00055  *  \file
00056  *  This file contains low-level radio driver code.
00057  *  This version is optimized for use with the "barebones" RF230bb driver,
00058  *  which communicates directly with the contiki core MAC layer.
00059  *  It is optimized for speed at the expense of generality.
00060  */
00061 
00062 
00063 
00064 /*============================ INCLUDE =======================================*/
00065 #include <stdlib.h>
00066 
00067 #include "hal.h"
00068 
00069 #if defined(__AVR_ATmega128RFA1__)
00070 #include <avr/io.h>
00071 #include "atmega128rfa1_registermap.h"
00072 #else
00073 #include "at86rf230_registermap.h"
00074 #endif
00075 
00076 /*============================ VARIABLES =====================================*/
00077 /** \brief This is a file internal variable that contains the 16 MSB of the
00078  *         system time.
00079  *
00080  *         The system time (32-bit) is the current time in microseconds. For the
00081  *         AVR microcontroller implementation this is solved by using a 16-bit
00082  *         timer (Timer1) with a clock frequency of 1MHz. The hal_system_time is
00083  *         incremented when the 16-bit timer overflows, representing the 16 MSB.
00084  *         The timer value it self (TCNT1) is then the 16 LSB.
00085  *
00086  *  \see hal_get_system_time
00087  */
00088 static uint16_t hal_system_time = 0;
00089 volatile extern signed char rf230_last_rssi;
00090 
00091 //static uint8_t volatile hal_bat_low_flag;
00092 //static uint8_t volatile hal_pll_lock_flag;
00093 
00094 /*============================ CALLBACKS =====================================*/
00095 
00096 /** \brief This function is called when a rx_start interrupt is signaled.
00097  *
00098  *         If this function pointer is set to something else than NULL, it will
00099  *         be called when a RX_START event is signaled. The function takes two
00100  *         parameters: timestamp in IEEE 802.15.4 symbols (16 us resolution) and
00101  *         frame length. The event handler will be called in the interrupt domain,
00102  *         so the function must be kept short and not be blocking! Otherwise the
00103  *         system performance will be greatly degraded.
00104  *
00105  *  \see hal_set_rx_start_event_handler
00106  */
00107 //static hal_rx_start_isr_event_handler_t rx_start_callback;
00108 
00109 /** \brief This function is called when a trx_end interrupt is signaled.
00110  *
00111  *         If this function pointer is set to something else than NULL, it will
00112  *         be called when a TRX_END event is signaled. The function takes one
00113  *         parameter: timestamp in IEEE 802.15.4 symbols (16 us resolution).
00114  *         The event handler will be called in the interrupt domain,
00115  *         so the function must not block!
00116  *
00117  *  \see hal_set_trx_end_event_handler
00118  */
00119 //static hal_trx_end_isr_event_handler_t trx_end_callback;
00120 
00121 /*============================ IMPLEMENTATION ================================*/
00122 #if defined(__AVR_ATmega128RFA1__)
00123 //#include <avr/io.h>
00124 #include <avr/interrupt.h>
00125 /* AVR1281 with internal RF231 radio */
00126 #define HAL_SPI_TRANSFER_OPEN() 
00127 //#define HAL_SPI_TRANSFER_WRITE(to_write) (SPDR = (to_write))
00128 #define HAL_SPI_TRANSFER_WAIT()
00129 #define HAL_SPI_TRANSFER_READ() (SPDR)
00130 #define HAL_SPI_TRANSFER_CLOSE()
00131 #if 0
00132 #define HAL_SPI_TRANSFER(to_write) (      \
00133                                     HAL_SPI_TRANSFER_WRITE(to_write),   \
00134                                     HAL_SPI_TRANSFER_WAIT(),            \
00135                                     HAL_SPI_TRANSFER_READ() )
00136 #endif
00137 #elif defined(__AVR__)
00138 /*
00139  * AVR with hardware SPI tranfers (TODO: move to hw spi hal for avr cpu)
00140  */
00141 #include <avr/io.h>
00142 #include <avr/interrupt.h>
00143 
00144 #define HAL_SPI_TRANSFER_OPEN() { \
00145   HAL_ENTER_CRITICAL_REGION();    \
00146   HAL_SS_LOW(); /* Start the SPI transaction by pulling the Slave Select low. */
00147 #define HAL_SPI_TRANSFER_WRITE(to_write) (SPDR = (to_write))
00148 #define HAL_SPI_TRANSFER_WAIT() ({while ((SPSR & (1 << SPIF)) == 0) {;}}) /* gcc extension, alternative inline function */
00149 #define HAL_SPI_TRANSFER_READ() (SPDR)
00150 #define HAL_SPI_TRANSFER_CLOSE() \
00151     HAL_SS_HIGH(); /* End the transaction by pulling the Slave Select High. */ \
00152     HAL_LEAVE_CRITICAL_REGION(); \
00153     }
00154 #define HAL_SPI_TRANSFER(to_write) (      \
00155                                     HAL_SPI_TRANSFER_WRITE(to_write),   \
00156                                     HAL_SPI_TRANSFER_WAIT(),            \
00157                                     HAL_SPI_TRANSFER_READ() )
00158 
00159 #else /* __AVR__ */
00160 /*
00161  * Other SPI architecture (parts to core, parts to m16c6Xp 
00162  */
00163 #include "contiki-mulle.h" // MULLE_ENTER_CRITICAL_REGION
00164 
00165 // Software SPI transfers
00166 #define HAL_SPI_TRANSFER_OPEN() { uint8_t spiTemp; \
00167   HAL_ENTER_CRITICAL_REGION();    \
00168   HAL_SS_LOW(); /* Start the SPI transaction by pulling the Slave Select low. */
00169 #define HAL_SPI_TRANSFER_WRITE(to_write) (spiTemp = spiWrite(to_write))
00170 #define HAL_SPI_TRANSFER_WAIT()  ({0;})
00171 #define HAL_SPI_TRANSFER_READ() (spiTemp)
00172 #define HAL_SPI_TRANSFER_CLOSE() \
00173     HAL_SS_HIGH(); /* End the transaction by pulling the Slave Select High. */ \
00174     HAL_LEAVE_CRITICAL_REGION(); \
00175     }
00176 #define HAL_SPI_TRANSFER(to_write) (spiTemp = spiWrite(to_write))
00177 
00178 inline uint8_t spiWrite(uint8_t byte)
00179 {
00180     uint8_t data = 0;
00181     uint8_t mask = 0x80;
00182     do
00183     {
00184         if( (byte & mask) != 0 )
00185             HAL_PORT_MOSI |= (1 << HAL_MOSI_PIN); //call MOSI.set();
00186         else
00187             HAL_PORT_MOSI &= ~(1 << HAL_MOSI_PIN); //call MOSI.clr();
00188 
00189         if( (HAL_PORT_MISO & (1 << HAL_MISO_PIN)) > 0) //call MISO.get() )
00190             data |= mask;
00191 
00192         HAL_PORT_SCK &= ~(1 << HAL_SCK_PIN); //call SCLK.clr();
00193         HAL_PORT_SCK |= (1 << HAL_SCK_PIN); //call SCLK.set();
00194     } while( (mask >>= 1) != 0 );
00195     return data;
00196 }
00197 
00198 #endif  /* !__AVR__ */
00199  
00200 /** \brief  This function initializes the Hardware Abstraction Layer.
00201  */
00202 #if defined(__AVR_ATmega128RFA1__)
00203 //#define HAL_RF230_ISR() ISR(RADIO_VECT)
00204 #define HAL_TIME_ISR()  ISR(TIMER1_OVF_vect)
00205 #define HAL_TICK_UPCNT() (TCNT1)
00206 void
00207 hal_init(void)
00208 {
00209     /*Reset variables used in file.*/
00210     hal_system_time = 0;
00211  //   TCCR1B = HAL_TCCR1B_CONFIG;       /* Set clock prescaler */
00212  //   TIFR1 |= (1 << ICF1);             /* Clear Input Capture Flag. */
00213  //   HAL_ENABLE_OVERFLOW_INTERRUPT(); /* Enable Timer1 overflow interrupt. */
00214     hal_enable_trx_interrupt();    /* Enable interrupts from the radio transceiver. */
00215 }
00216 
00217 #elif defined(__AVR__)
00218 #define HAL_RF230_ISR() ISR(RADIO_VECT)
00219 #define HAL_TIME_ISR()  ISR(TIMER1_OVF_vect)
00220 #define HAL_TICK_UPCNT() (TCNT1)
00221 void
00222 hal_init(void)
00223 {
00224     /*Reset variables used in file.*/
00225     hal_system_time = 0;
00226 //  hal_reset_flags();
00227 
00228     /*IO Specific Initialization - sleep and reset pins. */
00229     DDR_SLP_TR |= (1 << SLP_TR); /* Enable SLP_TR as output. */
00230     DDR_RST    |= (1 << RST);    /* Enable RST as output. */
00231 
00232     /*SPI Specific Initialization.*/
00233     /* Set SS, CLK and MOSI as output. */
00234     HAL_DDR_SPI  |= (1 << HAL_DD_SS) | (1 << HAL_DD_SCK) | (1 << HAL_DD_MOSI);
00235     HAL_PORT_SPI |= (1 << HAL_DD_SS) | (1 << HAL_DD_SCK); /* Set SS and CLK high */
00236     /* Run SPI at max speed */
00237     SPCR         = (1 << SPE) | (1 << MSTR); /* Enable SPI module and master operation. */
00238     SPSR         = (1 << SPI2X); /* Enable doubled SPI speed in master mode. */
00239 
00240     /*TIMER1 Specific Initialization.*/
00241     TCCR1B = HAL_TCCR1B_CONFIG;       /* Set clock prescaler */
00242     TIFR1 |= (1 << ICF1);             /* Clear Input Capture Flag. */
00243     HAL_ENABLE_OVERFLOW_INTERRUPT(); /* Enable Timer1 overflow interrupt. */
00244     hal_enable_trx_interrupt();    /* Enable interrupts from the radio transceiver. */
00245 }
00246 
00247 #else /* __AVR__ */
00248 
00249 #define HAL_RF230_ISR() M16C_INTERRUPT(M16C_INT1)
00250 #define HAL_TIME_ISR()  M16C_INTERRUPT(M16C_TMRB4)
00251 #define HAL_TICK_UPCNT() (0xFFFF-TB4) // TB4 counts down so we need to convert it to upcounting
00252 
00253 void
00254 hal_init(void)
00255 {
00256     /*Reset variables used in file.*/
00257     hal_system_time = 0;
00258 //  hal_reset_flags();
00259 
00260     /*IO Specific Initialization - sleep and reset pins. */
00261     DDR_SLP_TR |= (1 << SLP_TR); /* Enable SLP_TR as output. */
00262     DDR_RST    |= (1 << RST);    /* Enable RST as output. */
00263 
00264     /*SPI Specific Initialization.*/
00265     /* Set SS, CLK and MOSI as output. */
00266     HAL_DDR_SS  |= (1 << HAL_SS_PIN);
00267     HAL_DDR_SCK  |= (1 << HAL_SCK_PIN);
00268     HAL_DDR_MOSI  |= (1 << HAL_MOSI_PIN);
00269     HAL_DDR_MISO  &= ~(1 << HAL_MISO_PIN);
00270 
00271     /* Set SS */
00272     HAL_PORT_SS |= (1 << HAL_SS_PIN); // HAL_SS_HIGH()
00273     HAL_PORT_SCK &= ~(1 << HAL_SCK_PIN); // SCLK.clr()
00274 
00275     /*TIMER Specific Initialization.*/
00276     // Init count source (Timer B3)
00277     TB3 = ((16*10) - 1); // 16 us ticks
00278     TB3MR.BYTE = 0b00000000; // Timer mode, F1
00279     TBSR.BIT.TB3S = 1; // Start Timer B3
00280 
00281     TB4 = 0xFFFF; //
00282     TB4MR.BYTE = 0b10000001; // Counter mode, count TB3
00283     TBSR.BIT.TB4S = 1; // Start Timer B4
00284     INT1IC.BIT.POL = 1; // Select rising edge
00285     HAL_ENABLE_OVERFLOW_INTERRUPT(); /* Enable Timer overflow interrupt. */
00286     hal_enable_trx_interrupt();    /* Enable interrupts from the radio transceiver. */
00287 }
00288 #endif  /* !__AVR__ */
00289 
00290 /*----------------------------------------------------------------------------*/
00291 /** \brief  This function reset the interrupt flags and interrupt event handlers
00292  *          (Callbacks) to their default value.
00293  */
00294 //void
00295 //hal_reset_flags(void)
00296 //{
00297 //    HAL_ENTER_CRITICAL_REGION();
00298 
00299     /* Reset Flags. */
00300 //    hal_bat_low_flag     = 0;
00301 //    hal_pll_lock_flag    = 0;
00302 
00303     /* Reset Associated Event Handlers. */
00304 //    rx_start_callback = NULL;
00305 //    trx_end_callback  = NULL;
00306 
00307 //    HAL_LEAVE_CRITICAL_REGION();
00308 //}
00309 
00310 /*----------------------------------------------------------------------------*/
00311 /** \brief  This function returns the current value of the BAT_LOW flag.
00312  *
00313  *  The BAT_LOW flag is incremented each time a BAT_LOW event is signaled from the
00314  *  radio transceiver. This way it is possible for the end user to poll the flag
00315  *  for new event occurances.
00316  */
00317 //uint8_t
00318 //hal_get_bat_low_flag(void)
00319 //{
00320 //    return hal_bat_low_flag;
00321 //}
00322 
00323 /*----------------------------------------------------------------------------*/
00324 /** \brief  This function clears the BAT_LOW flag.
00325  */
00326 //void
00327 //hal_clear_bat_low_flag(void)
00328 //{
00329 //    HAL_ENTER_CRITICAL_REGION();
00330 //    hal_bat_low_flag = 0;
00331 //    HAL_LEAVE_CRITICAL_REGION();
00332 //}
00333 
00334 /*----------------------------------------------------------------------------*/
00335 /** \brief  This function is used to set new TRX_END event handler, overriding
00336  *          old handler reference.
00337  */
00338 //hal_trx_end_isr_event_handler_t
00339 //hal_get_trx_end_event_handler(void)
00340 //{
00341 //    return trx_end_callback;
00342 //}
00343 
00344 /*----------------------------------------------------------------------------*/
00345 /** \brief  This function is used to set new TRX_END event handler, overriding
00346  *          old handler reference.
00347  */
00348 //void
00349 //hal_set_trx_end_event_handler(hal_trx_end_isr_event_handler_t trx_end_callback_handle)
00350 //{
00351 //    HAL_ENTER_CRITICAL_REGION();
00352 //    trx_end_callback = trx_end_callback_handle;
00353 //    HAL_LEAVE_CRITICAL_REGION();
00354 //}
00355 
00356 /*----------------------------------------------------------------------------*/
00357 /** \brief  Remove event handler reference.
00358  */
00359 //void
00360 //hal_clear_trx_end_event_handler(void)
00361 //{
00362 //    HAL_ENTER_CRITICAL_REGION();
00363 //    trx_end_callback = NULL;
00364 //    HAL_LEAVE_CRITICAL_REGION();
00365 //}
00366 
00367 /*----------------------------------------------------------------------------*/
00368 /** \brief  This function returns the active RX_START event handler
00369  *
00370  *  \return Current RX_START event handler registered.
00371  */
00372 //hal_rx_start_isr_event_handler_t
00373 //hal_get_rx_start_event_handler(void)
00374 //{
00375 //    return rx_start_callback;
00376 //}
00377 
00378 /*----------------------------------------------------------------------------*/
00379 /** \brief  This function is used to set new RX_START event handler, overriding
00380  *          old handler reference.
00381  */
00382 //void
00383 //hal_set_rx_start_event_handler(hal_rx_start_isr_event_handler_t rx_start_callback_handle)
00384 //{
00385 //    HAL_ENTER_CRITICAL_REGION();
00386 //    rx_start_callback = rx_start_callback_handle;
00387 //    HAL_LEAVE_CRITICAL_REGION();
00388 //}
00389 
00390 /*----------------------------------------------------------------------------*/
00391 /** \brief  Remove event handler reference.
00392  */
00393 //void
00394 //hal_clear_rx_start_event_handler(void)
00395 //{
00396 //    HAL_ENTER_CRITICAL_REGION();
00397 //    rx_start_callback = NULL;
00398 //    HAL_LEAVE_CRITICAL_REGION();
00399 //}
00400 
00401 /*----------------------------------------------------------------------------*/
00402 /** \brief  This function returns the current value of the PLL_LOCK flag.
00403  *
00404  *  The PLL_LOCK flag is incremented each time a PLL_LOCK event is signaled from the
00405  *  radio transceiver. This way it is possible for the end user to poll the flag
00406  *  for new event occurances.
00407  */
00408 //uint8_t
00409 //hal_get_pll_lock_flag(void)
00410 //{
00411 //    return hal_pll_lock_flag;
00412 //}
00413 
00414 /*----------------------------------------------------------------------------*/
00415 /** \brief  This function clears the PLL_LOCK flag.
00416  */
00417 //void
00418 //hal_clear_pll_lock_flag(void)
00419 //{
00420 //    HAL_ENTER_CRITICAL_REGION();
00421 //    hal_pll_lock_flag = 0;
00422 //    HAL_LEAVE_CRITICAL_REGION();
00423 //}
00424 
00425 #if defined(__AVR_ATmega128RFA1__)
00426 /* Hack for internal radio registers. hal_register_read and hal_register_write are
00427    handled through defines, but the preprocesser can't parse a macro containing
00428    another #define with multiple arguments, e.g. using
00429    #define hal_subregister_read( address, mask, position ) (address&mask)>>position
00430    #define SR_TRX_STATUS         TRX_STATUS, 0x1f, 0
00431    the following only sees 1 argument to the macro
00432    return hal_subregister_read(SR_TRX_STATUS);
00433    
00434    Possible fix is through two defines:
00435    #define x_hal_subregister_read(x) hal_subregister_read(x);
00436    #define hal_subregister_read( address, mask, position ) (address&mask)>>position
00437    but the subregister defines in atmega128rfa1_registermap.h are currently set up without
00438    the _SFR_MEM8 attribute, for use by hal_subregister_write.
00439    
00440  */
00441 uint8_t
00442 hal_subregister_read(uint16_t address, uint8_t mask, uint8_t position)
00443 {
00444     return (_SFR_MEM8(address)&mask)>>position;
00445 }
00446 void
00447 hal_subregister_write(uint16_t address, uint8_t mask, uint8_t position,
00448                             uint8_t value)
00449 {
00450  cli();
00451     uint8_t register_value = _SFR_MEM8(address);
00452     register_value &= ~mask;
00453     value <<= position;
00454     value &= mask;
00455     value |= register_value;
00456     _SFR_MEM8(address) = value;
00457  sei();
00458 }
00459 
00460 #else /* defined(__AVR_ATmega128RFA1__) */
00461 /*----------------------------------------------------------------------------*/
00462 /** \brief  This function reads data from one of the radio transceiver's registers.
00463  *
00464  *  \param  address Register address to read from. See datasheet for register
00465  *                  map.
00466  *
00467  *  \see Look at the at86rf230_registermap.h file for register address definitions.
00468  *
00469  *  \returns The actual value of the read register.
00470  */
00471 uint8_t
00472 hal_register_read(uint8_t address)
00473 {
00474     uint8_t register_value;
00475     /* Add the register read command to the register address. */
00476     /* Address should be < 0x2f so no need to mask */
00477 //  address &= 0x3f;
00478     address |= 0x80;
00479 
00480     HAL_SPI_TRANSFER_OPEN();
00481 
00482     /*Send Register address and read register content.*/
00483     HAL_SPI_TRANSFER(address);
00484     register_value = HAL_SPI_TRANSFER(0);
00485 
00486     HAL_SPI_TRANSFER_CLOSE();
00487 
00488     return register_value;
00489 }
00490 
00491 /*----------------------------------------------------------------------------*/
00492 /** \brief  This function writes a new value to one of the radio transceiver's
00493  *          registers.
00494  *
00495  *  \see Look at the at86rf230_registermap.h file for register address definitions.
00496  *
00497  *  \param  address Address of register to write.
00498  *  \param  value   Value to write.
00499  */
00500 void
00501 hal_register_write(uint8_t address, uint8_t value)
00502 {
00503     /* Add the Register Write (short mode) command to the address. */
00504     address = 0xc0 | address;
00505 
00506     HAL_SPI_TRANSFER_OPEN();
00507 
00508     /*Send Register address and write register content.*/
00509     HAL_SPI_TRANSFER(address);
00510     HAL_SPI_TRANSFER(value);
00511 
00512     HAL_SPI_TRANSFER_CLOSE();
00513 }
00514 /*----------------------------------------------------------------------------*/
00515 /** \brief  This function reads the value of a specific subregister.
00516  *
00517  *  \see Look at the at86rf230_registermap.h file for register and subregister
00518  *       definitions.
00519  *
00520  *  \param  address  Main register's address.
00521  *  \param  mask  Bit mask of the subregister.
00522  *  \param  position   Bit position of the subregister
00523  *  \retval Value of the read subregister.
00524  */
00525 uint8_t
00526 hal_subregister_read(uint8_t address, uint8_t mask, uint8_t position)
00527 {
00528     /* Read current register value and mask out subregister. */
00529     uint8_t register_value = hal_register_read(address);
00530     register_value &= mask;
00531     register_value >>= position; /* Align subregister value. */
00532 
00533     return register_value;
00534 }
00535 /*----------------------------------------------------------------------------*/
00536 /** \brief  This function writes a new value to one of the radio transceiver's
00537  *          subregisters.
00538  *
00539  *  \see Look at the at86rf230_registermap.h file for register and subregister
00540  *       definitions.
00541  *
00542  *  \param  address  Main register's address.
00543  *  \param  mask  Bit mask of the subregister.
00544  *  \param  position  Bit position of the subregister
00545  *  \param  value  Value to write into the subregister.
00546  */
00547 void
00548 hal_subregister_write(uint8_t address, uint8_t mask, uint8_t position,
00549                             uint8_t value)
00550 {
00551     /* Read current register value and mask area outside the subregister. */
00552     volatile uint8_t register_value = hal_register_read(address);
00553     register_value &= ~mask;
00554 
00555     /* Start preparing the new subregister value. shift in place and mask. */
00556     value <<= position;
00557     value &= mask;
00558 
00559     value |= register_value; /* Set the new subregister value. */
00560 
00561     /* Write the modified register value. */
00562     hal_register_write(address, value);
00563 }
00564 #endif /* defined(__AVR_ATmega128RFA1__) */
00565 /*----------------------------------------------------------------------------*/
00566 /** \brief  This function will upload a frame from the radio transceiver's frame
00567  *          buffer.
00568  *
00569  *          If the frame currently available in the radio transceiver's frame buffer
00570  *          is out of the defined bounds. Then the frame length, lqi value and crc
00571  *          be set to zero. This is done to indicate an error.
00572  *          This version is optimized for use with contiki RF230BB driver.
00573  *          The callback routine and CRC are left out for speed in reading the rx buffer.
00574  *          Any delays here can lead to overwrites by the next packet!
00575  *
00576  *  \param  rx_frame    Pointer to the data structure where the frame is stored.
00577  *  \param  rx_callback Pointer to callback function for receiving one byte at a time.
00578  */
00579 void
00580 //hal_frame_read(hal_rx_frame_t *rx_frame, rx_callback_t rx_callback)
00581 hal_frame_read(hal_rx_frame_t *rx_frame)
00582 {
00583 #if defined(__AVR_ATmega128RFA1__)
00584 
00585     uint8_t frame_length,*rx_data,*rx_buffer;
00586   
00587     rx_data = (rx_frame->data);
00588     frame_length =  TST_RX_LENGTH;  //frame length, not including lqi?
00589     rx_frame->length = frame_length;
00590     rx_buffer=(uint8_t *)0x180;  //start of fifo in i/o space
00591 
00592     do{
00593         *rx_data++ = _SFR_MEM8(rx_buffer++);
00594 
00595     } while (--frame_length > 0);
00596 
00597     /*Read LQI value for this frame.*/
00598     rx_frame->lqi = *rx_buffer;
00599     if (1) {  
00600     
00601 #else /* defined(__AVR_ATmega128RFA1__) */
00602 
00603     uint8_t *rx_data;
00604 
00605     /*  check that we have either valid frame pointer or callback pointer */
00606 //  if (!rx_frame && !rx_callback)
00607 //      return;
00608 
00609     HAL_SPI_TRANSFER_OPEN();
00610 
00611     /*Send frame read (long mode) command.*/
00612     HAL_SPI_TRANSFER(0x20);
00613 
00614     /*Read frame length. This includes the checksum. */
00615     uint8_t frame_length = HAL_SPI_TRANSFER(0);
00616 
00617     /*Check for correct frame length.*/
00618 //   if ((frame_length >= HAL_MIN_FRAME_LENGTH) && (frame_length <= HAL_MAX_FRAME_LENGTH)){
00619      if (1) {
00620 //      uint16_t crc = 0;
00621 //      if (rx_frame){
00622             rx_data = (rx_frame->data);
00623             rx_frame->length = frame_length;
00624 //      } else {
00625 //          rx_callback(frame_length);
00626 //      }
00627         /*Upload frame buffer to data pointer */
00628 
00629             HAL_SPI_TRANSFER_WRITE(0);
00630             HAL_SPI_TRANSFER_WAIT();
00631 
00632         do{
00633             *rx_data++ = HAL_SPI_TRANSFER_READ();
00634             HAL_SPI_TRANSFER_WRITE(0);
00635 
00636 //           if (rx_frame){
00637 //             *rx_data++ = tempData;
00638 //          } else {
00639 //              rx_callback(tempData);
00640 //          }
00641 /* RF230 does crc in hardware, doing the checksum here ensures the rx buffer has not been overwritten by the next packet */
00642 /* Since doing the checksum makes such overwrites more probable, we skip it and hope for the best. */
00643 /* A full buffer should be read in 320us at 2x spi clocking, so with a low interrupt latency overwrites should not occur */
00644 //         crc = _crc_ccitt_update(crc, tempData);
00645 
00646             HAL_SPI_TRANSFER_WAIT();
00647 
00648         } while (--frame_length > 0);
00649 
00650         /*Read LQI value for this frame.*/
00651 //      if (rx_frame){
00652             rx_frame->lqi = HAL_SPI_TRANSFER_READ();
00653 //      } else {
00654 //          rx_callback(HAL_SPI_TRANSFER_READ());
00655 //      }
00656         
00657 #endif /* defined(__AVR_ATmega128RFA1__) */
00658 
00659         /*Check calculated crc, and set crc field in hal_rx_frame_t accordingly.*/
00660 //      if (rx_frame){
00661             rx_frame->crc = 1;
00662 //      } else {
00663 //          rx_callback(crc != 0);
00664 //      }
00665     } else {
00666 //      if (rx_frame){
00667             rx_frame->length = 0;
00668             rx_frame->lqi    = 0;
00669             rx_frame->crc    = false;
00670 //      }
00671     }
00672 
00673     HAL_SPI_TRANSFER_CLOSE();
00674 }
00675 
00676 /*----------------------------------------------------------------------------*/
00677 /** \brief  This function will download a frame to the radio transceiver's frame
00678  *          buffer.
00679  *
00680  *  \param  write_buffer    Pointer to data that is to be written to frame buffer.
00681  *  \param  length          Length of data. The maximum length is 127 bytes.
00682  */
00683 void
00684 hal_frame_write(uint8_t *write_buffer, uint8_t length)
00685 {
00686 #if defined(__AVR_ATmega128RFA1__)
00687     uint8_t *tx_buffer;
00688     tx_buffer=(uint8_t *)0x180;  //start of fifo in i/o space
00689     /* Write frame length, including the two byte checksum */
00690     /* The top bit of the length field shall be set to 0 for IEEE 802.15.4 compliant frames */
00691     /* It should already be clear, so bypassing the masking is sanity check of the uip stack */
00692 //  length &= 0x7f;
00693     _SFR_MEM8(tx_buffer++) = length;
00694     
00695     /* Download to the Frame Buffer.
00696      * When the FCS is autogenerated there is no need to transfer the last two bytes
00697      * since they will be overwritten.
00698      */
00699 #if !RF230_CONF_CHECKSUM
00700     length -= 2;
00701 #endif
00702     do  _SFR_MEM8(tx_buffer++)= *write_buffer++; while (--length);
00703 
00704 #else /* defined(__AVR_ATmega128RFA1__) */
00705     /* Optionally truncate length to maximum frame length.
00706      * Not doing this is a fast way to know when the application needs fixing!
00707      */
00708 //  length &= 0x7f; 
00709 
00710     HAL_SPI_TRANSFER_OPEN();
00711 
00712     /* Send Frame Transmit (long mode) command and frame length */
00713     HAL_SPI_TRANSFER(0x60);
00714     HAL_SPI_TRANSFER(length);
00715 
00716     /* Download to the Frame Buffer.
00717      * When the FCS is autogenerated there is no need to transfer the last two bytes
00718      * since they will be overwritten.
00719      */
00720 #if !RF230_CONF_CHECKSUM
00721     length -= 2;
00722 #endif
00723     do HAL_SPI_TRANSFER(*write_buffer++); while (--length);
00724 
00725     HAL_SPI_TRANSFER_CLOSE();
00726 #endif /* defined(__AVR_ATmega128RFA1__) */
00727 }
00728 
00729 /*----------------------------------------------------------------------------*/
00730 /** \brief Read SRAM
00731  *
00732  * This function reads from the SRAM of the radio transceiver.
00733  *
00734  * \param address Address in the TRX's SRAM where the read burst should start
00735  * \param length Length of the read burst
00736  * \param data Pointer to buffer where data is stored.
00737  */
00738 //void
00739 //hal_sram_read(uint8_t address, uint8_t length, uint8_t *data)
00740 //{
00741 //    HAL_SPI_TRANSFER_OPEN();
00742 
00743     /*Send SRAM read command.*/
00744 //    HAL_SPI_TRANSFER(0x00);
00745 
00746     /*Send address where to start reading.*/
00747 //    HAL_SPI_TRANSFER(address);
00748 
00749     /*Upload the chosen memory area.*/
00750 //    do{
00751 //        *data++ = HAL_SPI_TRANSFER(0);
00752 //    } while (--length > 0);
00753 
00754 //    HAL_SPI_TRANSFER_CLOSE();
00755 
00756 //}
00757 
00758 /*----------------------------------------------------------------------------*/
00759 /** \brief Write SRAM
00760  *
00761  * This function writes into the SRAM of the radio transceiver. It can reduce
00762  * SPI transfers if only part of a frame is to be changed before retransmission.
00763  *
00764  * \param address Address in the TRX's SRAM where the write burst should start
00765  * \param length  Length of the write burst
00766  * \param data    Pointer to an array of bytes that should be written
00767  */
00768 //void
00769 //hal_sram_write(uint8_t address, uint8_t length, uint8_t *data)
00770 //{
00771 //    HAL_SPI_TRANSFER_OPEN();
00772 
00773     /*Send SRAM write command.*/
00774 //    HAL_SPI_TRANSFER(0x40);
00775 
00776     /*Send address where to start writing to.*/
00777 //    HAL_SPI_TRANSFER(address);
00778 
00779     /*Upload the chosen memory area.*/
00780 //    do{
00781 //        HAL_SPI_TRANSFER(*data++);
00782 //    } while (--length > 0);
00783 
00784 //    HAL_SPI_TRANSFER_CLOSE();
00785 
00786 //}
00787 
00788 /*----------------------------------------------------------------------------*/
00789 /* This #if compile switch is used to provide a "standard" function body for the */
00790 /* doxygen documentation. */
00791 #if defined(DOXYGEN)
00792 /** \brief ISR for the radio IRQ line, triggered by the input capture.
00793  *  This is the interrupt service routine for timer1.ICIE1 input capture.
00794  *  It is triggered of a rising edge on the radio transceivers IRQ line.
00795  */
00796 void RADIO_VECT(void);
00797 #else  /* !DOXYGEN */
00798 /* These link to the RF230BB driver in rf230.c */
00799 void rf230_interrupt(void);
00800 
00801 extern hal_rx_frame_t rxframe[RF230_CONF_RX_BUFFERS];
00802 extern uint8_t rxframe_head,rxframe_tail;
00803 
00804 /* rf230interruptflag can be printed in the main idle loop for debugging */
00805 #define DEBUG 0
00806 #if DEBUG
00807 volatile char rf230interruptflag;
00808 #define INTERRUPTDEBUG(arg) rf230interruptflag=arg
00809 #else
00810 #define INTERRUPTDEBUG(arg)
00811 #endif
00812 
00813 #if defined(__AVR_ATmega128RFA1__)
00814 /* The atmega128rfa1 has individual interrupts for the integrated radio */
00815 /* Whichever are enabled by the RF230 driver must be present even if not used! */
00816 ISR(TRX24_RX_END_vect)
00817 {
00818            INTERRUPTDEBUG(11);              
00819        /* Received packet interrupt */ 
00820        /* Buffer the frame and call rf230_interrupt to schedule poll for rf230 receive process */
00821 //         if (rxframe.length) break;                   //toss packet if last one not processed yet
00822          if (rxframe[rxframe_tail].length) INTERRUPTDEBUG(42); else INTERRUPTDEBUG(12);
00823 
00824 #ifdef RF230_MIN_RX_POWER                
00825        /* Discard packets weaker than the minimum if defined. This is for testing miniature meshes.*/
00826        /* Save the rssi for printing in the main loop */
00827 #if RF230_CONF_AUTOACK
00828  //       rf230_last_rssi=hal_subregister_read(SR_ED_LEVEL);
00829         rf230_last_rssi=hal_register_read(RG_PHY_ED_LEVEL);
00830 #endif
00831 //      if (rf230_last_rssi >= RF230_MIN_RX_POWER) {
00832         if (1) {        
00833 #endif
00834          hal_frame_read(&rxframe[rxframe_tail]);
00835          rxframe_tail++;if (rxframe_tail >= RF230_CONF_RX_BUFFERS) rxframe_tail=0;
00836          rf230_interrupt();
00837 #ifdef RF230_MIN_RX_POWER
00838         }
00839 #endif
00840 }
00841 ISR(TRX24_RX_START_vect)
00842 {
00843     INTERRUPTDEBUG(10);
00844     /* Save RSSI for this packet if not in extended mode, scaling to 1dB resolution */
00845 #if !RF230_CONF_AUTOACK
00846     rf230_last_rssi = 3 * hal_subregister_read(SR_RSSI);
00847 #endif
00848 
00849 }
00850 ISR(TRX24_PLL_LOCK_vect)
00851 {
00852 }
00853 ISR(TRX24_PLL_UNLOCK_vect)
00854 {
00855 }
00856 
00857 #if 0
00858 HAL_RF230_ISR() //for reference, for now
00859 {
00860     /*The following code reads the current system time. This is done by first
00861       reading the hal_system_time and then adding the 16 LSB directly from the
00862       hardware counter.
00863      */
00864 //    uint32_t isr_timestamp = hal_system_time;
00865 //    isr_timestamp <<= 16;
00866 //    isr_timestamp |= HAL_TICK_UPCNT(); // TODO: what if this wraps after reading hal_system_time?
00867 //   isr_timestamp /= HAL_US_PER_SYMBOL; /* Divide so that we get time in 16us resolution. */
00868 //   isr_timestamp &= HAL_SYMBOL_MASK;
00869 
00870     uint8_t interrupt_source;
00871 
00872     INTERRUPTDEBUG(1);
00873 
00874     /*Read Interrupt source.*/
00875     interrupt_source = IRQ_STATUS;
00876 
00877     /*Handle the incomming interrupt. Prioritized.*/
00878     if (interrupt_source & (1>>RX_START)){
00879            INTERRUPTDEBUG(10);
00880     /* Save RSSI for this packet if not in extended mode, scaling to 1dB resolution */
00881 #if !RF230_CONF_AUTOACK
00882        rf230_last_rssi = 3 * hal_subregister_read(SR_RSSI);
00883 #endif
00884 
00885     } else if (interrupt_source & (1<<RX_END)){
00886            INTERRUPTDEBUG(11);              
00887        /* Received packet interrupt */ 
00888        /* Buffer the frame and call rf230_interrupt to schedule poll for rf230 receive process */
00889 //         if (rxframe.length) break;                   //toss packet if last one not processed yet
00890          if (rxframe[rxframe_tail].length) INTERRUPTDEBUG(42); else INTERRUPTDEBUG(12);
00891 
00892 #ifdef RF230_MIN_RX_POWER                
00893        /* Discard packets weaker than the minimum if defined. This is for testing miniature meshes.*/
00894        /* Save the rssi for printing in the main loop */
00895 #if RF230_CONF_AUTOACK
00896 //        rf230_last_rssi=hal_subregister_read(SR_ED_LEVEL);
00897         rf230_last_rssi=hal_register_read(RG_PHY_ED_LEVEL);
00898 #endif
00899 //      if (rf230_last_rssi >= RF230_MIN_RX_POWER) {
00900         if (1) {        
00901 #endif
00902          hal_frame_read(&rxframe[rxframe_tail]);
00903          rxframe_tail++;if (rxframe_tail >= RF230_CONF_RX_BUFFERS) rxframe_tail=0;
00904          rf230_interrupt();
00905 //       trx_end_callback(isr_timestamp);
00906 #ifdef RF230_MIN_RX_POWER
00907         }
00908 #endif
00909               
00910     } else if (interrupt_source & (1<<TX_END)){
00911         INTERRUPTDEBUG(13);
00912         ;
00913     } else if (interrupt_source & (1<<PLL_UNLOCK)){
00914         INTERRUPTDEBUG(14);
00915             ;
00916     } else if (interrupt_source & (1<<PLL_LOCK)){
00917         INTERRUPTDEBUG(15);
00918 //      hal_pll_lock_flag++;
00919         ;
00920      } else {
00921         INTERRUPTDEBUG(99);
00922             ;
00923     }
00924 }
00925 #endif
00926 #else /* defined(__AVR_ATmega128RFA1__) */
00927 /* Separate RF230 has a single radio interrupt and the source must be read from the IRQ_STATUS register */
00928 HAL_RF230_ISR()
00929 {
00930     /*The following code reads the current system time. This is done by first
00931       reading the hal_system_time and then adding the 16 LSB directly from the
00932       hardware counter.
00933      */
00934 //    uint32_t isr_timestamp = hal_system_time;
00935 //    isr_timestamp <<= 16;
00936 //    isr_timestamp |= HAL_TICK_UPCNT(); // TODO: what if this wraps after reading hal_system_time?
00937 
00938     volatile uint8_t state;
00939     uint8_t interrupt_source; /* used after HAL_SPI_TRANSFER_OPEN/CLOSE block */
00940 
00941     INTERRUPTDEBUG(1);
00942 
00943     
00944     /* Using SPI bus from ISR is generally a bad idea... */
00945     /* Note: all IRQ are not always automatically disabled when running in ISR */
00946     HAL_SPI_TRANSFER_OPEN();
00947 
00948     /*Read Interrupt source.*/
00949     /*Send Register address and read register content.*/
00950     HAL_SPI_TRANSFER_WRITE(0x80 | RG_IRQ_STATUS);
00951 
00952     /* This is the second part of the convertion of system time to a 16 us time
00953        base. The division is moved here so we can spend less time waiting for SPI
00954        data.
00955      */
00956 //   isr_timestamp /= HAL_US_PER_SYMBOL; /* Divide so that we get time in 16us resolution. */
00957 //   isr_timestamp &= HAL_SYMBOL_MASK;
00958 
00959     HAL_SPI_TRANSFER_WAIT(); /* AFTER possible interleaved processing */
00960 
00961 #if 0 //dak
00962     interrupt_source = HAL_SPI_TRANSFER_READ(); /* The interrupt variable is used as a dummy read. */
00963 
00964     interrupt_source = HAL_SPI_TRANSFER(interrupt_source);
00965 #else
00966     interrupt_source = HAL_SPI_TRANSFER(0);
00967 #endif
00968     HAL_SPI_TRANSFER_CLOSE();
00969 
00970     /*Handle the incomming interrupt. Prioritized.*/
00971     if ((interrupt_source & HAL_RX_START_MASK)){
00972            INTERRUPTDEBUG(10);
00973     /* Save RSSI for this packet if not in extended mode, scaling to 1dB resolution */
00974 #if !RF230_CONF_AUTOACK
00975 #if 0  // 3-clock shift and add is faster on machines with no hardware multiply
00976        // 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
00977         rf230_last_rssi = hal_subregister_read(SR_RSSI);
00978         rf230_last_rssi = (rf230_last_rssi <<1)  + rf230_last_rssi;
00979 #else  // Faster with 1-clock multiply. Raven and Jackdaw have 2-clock multiply so same speed while saving 2 bytes of program memory
00980         rf230_last_rssi = 3 * hal_subregister_read(SR_RSSI);
00981 #endif
00982 #endif
00983 //       if(rx_start_callback != NULL){
00984 //            /* Read Frame length and call rx_start callback. */
00985 //            HAL_SPI_TRANSFER_OPEN();
00986 //            uint8_t frame_length = HAL_SPI_TRANSFER(0x20);
00987 //            frame_length = HAL_SPI_TRANSFER(frame_length);
00988 
00989 //            HAL_SPI_TRANSFER_CLOSE();
00990 
00991 //            rx_start_callback(isr_timestamp, frame_length);
00992 //       }
00993     } else if (interrupt_source & HAL_TRX_END_MASK){
00994            INTERRUPTDEBUG(11);              
00995 //         if(trx_end_callback != NULL){
00996 //       trx_end_callback(isr_timestamp);
00997 //     }
00998         
00999        state = hal_subregister_read(SR_TRX_STATUS);
01000        if((state == BUSY_RX_AACK) || (state == RX_ON) || (state == BUSY_RX) || (state == RX_AACK_ON)){
01001        /* Received packet interrupt */ 
01002        /* Buffer the frame and call rf230_interrupt to schedule poll for rf230 receive process */
01003 //         if (rxframe.length) break;                   //toss packet if last one not processed yet
01004          if (rxframe[rxframe_tail].length) INTERRUPTDEBUG(42); else INTERRUPTDEBUG(12);
01005  
01006 #ifdef RF230_MIN_RX_POWER                
01007        /* Discard packets weaker than the minimum if defined. This is for testing miniature meshes.*/
01008        /* Save the rssi for printing in the main loop */
01009 #if RF230_CONF_AUTOACK
01010  //       rf230_last_rssi=hal_subregister_read(SR_ED_LEVEL);
01011         rf230_last_rssi=hal_register_read(RG_PHY_ED_LEVEL);
01012 #endif
01013         if (rf230_last_rssi >= RF230_MIN_RX_POWER) {       
01014 #endif
01015          hal_frame_read(&rxframe[rxframe_tail]);
01016          rxframe_tail++;if (rxframe_tail >= RF230_CONF_RX_BUFFERS) rxframe_tail=0;
01017          rf230_interrupt();
01018 //       trx_end_callback(isr_timestamp);
01019 #ifdef RF230_MIN_RX_POWER
01020         }
01021 #endif
01022 
01023        }
01024               
01025     } else if (interrupt_source & HAL_TRX_UR_MASK){
01026         INTERRUPTDEBUG(13);
01027         ;
01028     } else if (interrupt_source & HAL_PLL_UNLOCK_MASK){
01029         INTERRUPTDEBUG(14);
01030             ;
01031     } else if (interrupt_source & HAL_PLL_LOCK_MASK){
01032         INTERRUPTDEBUG(15);
01033 //      hal_pll_lock_flag++;
01034         ;
01035     } else if (interrupt_source & HAL_BAT_LOW_MASK){
01036         /*  Disable BAT_LOW interrupt to prevent endless interrupts. The interrupt */
01037         /*  will continously be asserted while the supply voltage is less than the */
01038         /*  user-defined voltage threshold. */
01039         uint8_t trx_isr_mask = hal_register_read(RG_IRQ_MASK);
01040         trx_isr_mask &= ~HAL_BAT_LOW_MASK;
01041         hal_register_write(RG_IRQ_MASK, trx_isr_mask);
01042 //      hal_bat_low_flag++; /* Increment BAT_LOW flag. */
01043         INTERRUPTDEBUG(16);
01044         ;
01045      } else {
01046         INTERRUPTDEBUG(99);
01047             ;
01048     }
01049 }
01050 #endif /* defined(__AVR_ATmega128RFA1__) */ 
01051 #   endif /* defined(DOXYGEN) */
01052 
01053 /*----------------------------------------------------------------------------*/
01054 /* This #if compile switch is used to provide a "standard" function body for the */
01055 /* doxygen documentation. */
01056 #if defined(DOXYGEN)
01057 /** \brief Timer Overflow ISR
01058  * This is the interrupt service routine for timer1 overflow.
01059  */
01060 void TIMER1_OVF_vect(void);
01061 #else  /* !DOXYGEN */
01062 HAL_TIME_ISR()
01063 {
01064     hal_system_time++;
01065 }
01066 #endif
01067 
01068 /** @} */
01069 /** @} */
01070 
01071 /*EOF*/

Generated on Mon Apr 11 14:23:37 2011 for Contiki 2.5 by  doxygen 1.6.1