Contiki 2.6

radio.c

Go to the documentation of this file.
00001 /*   Copyright (c) 2008, Swedish Institute of Computer Science
00002  *  All rights reserved.
00003  *
00004  *  Additional fixes for AVR contributed by:
00005  *      Colin O'Flynn coflynn@newae.com
00006  *      Eric Gnoske egnoske@gmail.com
00007  *      Blake Leverett bleverett@gmail.com
00008  *      Mike Vidales mavida404@gmail.com
00009  *      Kevin Brown kbrown3@uccs.edu
00010  *      Nate Bohlmann nate@elfwerks.com
00011  *
00012  *   All rights reserved.
00013  *
00014  *   Redistribution and use in source and binary forms, with or without
00015  *   modification, are permitted provided that the following conditions are met:
00016  *
00017  *   * Redistributions of source code must retain the above copyright
00018  *     notice, this list of conditions and the following disclaimer.
00019  *   * Redistributions in binary form must reproduce the above copyright
00020  *     notice, this list of conditions and the following disclaimer in
00021  *     the documentation and/or other materials provided with the
00022  *     distribution.
00023  *   * Neither the name of the copyright holders nor the names of
00024  *     contributors may be used to endorse or promote products derived
00025  *     from this software without specific prior written permission.
00026  *
00027  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00028  *  AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00029  *  IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00030  *  ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00031  *  LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00032  *  CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00033  *  SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00034  *  INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00035  *  CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00036  *  ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00037  *  POSSIBILITY OF SUCH DAMAGE.
00038  *
00039  * $Id: radio.c,v 1.5 2010/02/12 18:00:30 dak664 Exp $
00040 */
00041 
00042 /**
00043  *  \brief This module contains the radio driver code for the Atmel
00044  *  AT86RF230, '231, and '212 chips.
00045  *
00046  *  \author Blake Leverett <bleverett@gmail.com>
00047  *          Mike Vidales <mavida404@gmail.com>
00048  *          Eric Gnoske <egnoske@gmail.com>
00049  *
00050 */
00051 
00052 /**  \addtogroup wireless
00053  * @{
00054  */
00055 
00056 /**
00057  *  \defgroup radiorf230 RF230 interface
00058  * @{
00059  */
00060 /**
00061  *  \file
00062  *  This file contains radio driver code.
00063  *
00064  */
00065 
00066 
00067 
00068 /*============================ INCLUDE =======================================*/
00069 #include <stdlib.h>
00070 #include <util/delay.h>
00071 #include "radio.h"
00072 #include "hal.h"
00073 #include "process.h"
00074 #include "sicslowmac.h"
00075 #include "frame.h"
00076 
00077 /*============================ MACROS ========================================*/
00078 #define RADIO_CCA_DONE_MASK     (1 << 7) /**<  Mask used to check the CCA_DONE bit. */
00079 #define RADIO_CCA_IDLE_MASK     (1 << 6) /**<  Mask used to check the CCA_STATUS bit. */
00080 
00081 #define RADIO_START_CCA (1) /**<  Value in the CCA_REQUEST subregister that initiate a cca. */
00082 
00083 #define RADIO_TRANSMISSION_SUCCESS  (0)
00084 #define RADIO_BUSY_CHANNEL          (3)
00085 #define RADIO_MIN_IEEE_FRAME_LENGTH (5)
00086 /*============================ TYPEDEFS ======================================*/
00087 
00088 /** \brief  This enumeration defines the necessary timing information for the
00089  *          AT86RF230 radio transceiver. All times are in microseconds.
00090  *
00091  *          These constants are extracted from the datasheet.
00092  */
00093 typedef enum{
00094     TIME_TO_ENTER_P_ON               = 510, /**<  Transition time from VCC is applied to P_ON. */
00095     TIME_P_ON_TO_TRX_OFF             = 510, /**<  Transition time from P_ON to TRX_OFF. */
00096     TIME_SLEEP_TO_TRX_OFF            = 880, /**<  Transition time from SLEEP to TRX_OFF. */
00097     TIME_RESET                       = 6,   /**<  Time to hold the RST pin low during reset */
00098     TIME_ED_MEASUREMENT              = 140, /**<  Time it takes to do a ED measurement. */
00099     TIME_CCA                         = 140, /**<  Time it takes to do a CCA. */
00100     TIME_PLL_LOCK                    = 150, /**<  Maximum time it should take for the PLL to lock. */
00101     TIME_FTN_TUNING                  = 25,  /**<  Maximum time it should take to do the filter tuning. */
00102     TIME_NOCLK_TO_WAKE               = 6,   /**<  Transition time from *_NOCLK to being awake. */
00103     TIME_CMD_FORCE_TRX_OFF           = 1,    /**<  Time it takes to execute the FORCE_TRX_OFF command. */
00104     TIME_TRX_OFF_TO_PLL_ACTIVE       = 180, /**<  Transition time from TRX_OFF to: RX_ON, PLL_ON, TX_ARET_ON and RX_AACK_ON. */
00105     TIME_STATE_TRANSITION_PLL_ACTIVE = 1, /**<  Transition time from PLL active state to another. */
00106 }radio_trx_timing_t;
00107 
00108 /*============================ VARIABLES =====================================*/
00109 static hal_rx_start_isr_event_handler_t user_rx_event;
00110 static hal_trx_end_isr_event_handler_t user_trx_end_event;
00111 static radio_rx_callback rx_frame_callback;
00112 static uint8_t rssi_val;
00113 static uint8_t rx_mode;
00114 uint8_t rxMode = RX_AACK_ON;
00115 
00116 /* See clock.c and httpd-cgi.c for RADIOSTATS code */
00117 #define RADIOSTATS 0
00118 #if RADIOSTATS
00119 uint8_t RF230_radio_on, RF230_rsigsi;
00120 uint16_t RF230_sendpackets,RF230_receivepackets,RF230_sendfail,RF230_receivefail;
00121 #endif
00122 
00123 static hal_rx_frame_t rx_frame;
00124 static parsed_frame_t parsed_frame;
00125 
00126 /*============================ PROTOTYPES ====================================*/
00127 bool radio_is_sleeping(void);
00128 static void radio_rx_start_event(uint32_t const isr_timestamp, uint8_t const frame_length);
00129 static void radio_trx_end_event(uint32_t const isr_timestamp);
00130 
00131 /** \brief  Initialize the Transceiver Access Toolbox and lower layers.
00132  *
00133  *          If the initialization is successful the radio transceiver will be in
00134  *          TRX_OFF state.
00135  *
00136  *  \note  This function must be called prior to any of the other functions in
00137  *         this file! Can be called from any transceiver state.
00138  *
00139  *  \param cal_rc_osc If true, the radio's accurate clock is used to calibrate the
00140  *                    CPU's internal RC oscillator.
00141  *
00142  *  \param rx_event Optional pointer to a user-defined function to be called on an
00143  *                  RX_START interrupt.  Use NULL for no handler.
00144  *
00145  *  \param trx_end_event Optional pointer to a user-defined function to be called on an
00146  *                  TRX_END interrupt.  Use NULL for no handler.
00147  *
00148  *  \param rx_callback Optional pointer to a user-defined function that receives
00149  *         a frame from the radio one byte at a time.  If the index parameter to
00150  *         this callback is 0xff, then the function should reset its state and prepare
00151  *         for a frame from the radio, with one call per byte.
00152  *
00153  *  \retval RADIO_SUCCESS     The radio transceiver was successfully initialized
00154  *                          and put into the TRX_OFF state.
00155  *  \retval RADIO_UNSUPPORTED_DEVICE  The connected device is not an Atmel
00156  *                                  AT86RF230 radio transceiver.
00157  *  \retval RADIO_TIMED_OUT   The radio transceiver was not able to initialize and
00158  *                          enter TRX_OFF state within the specified time.
00159  */
00160 radio_status_t
00161 radio_init(bool cal_rc_osc,
00162            hal_rx_start_isr_event_handler_t rx_event,
00163            hal_trx_end_isr_event_handler_t trx_end_event,
00164            radio_rx_callback rx_callback)
00165 {
00166     radio_status_t init_status = RADIO_SUCCESS;
00167 
00168     delay_us(TIME_TO_ENTER_P_ON);
00169 
00170     /*  calibrate oscillator */
00171     if (cal_rc_osc){
00172         calibrate_rc_osc_32k();
00173     }
00174 
00175     /* Initialize Hardware Abstraction Layer. */
00176     hal_init();
00177 
00178     radio_reset_trx(); /* Do HW reset of radio transeiver. */
00179 
00180     /* Force transition to TRX_OFF. */
00181     hal_subregister_write(SR_TRX_CMD, CMD_FORCE_TRX_OFF);
00182     delay_us(TIME_P_ON_TO_TRX_OFF); /* Wait for the transition to be complete. */
00183 
00184     if (radio_get_trx_state() != TRX_OFF){
00185         init_status = RADIO_TIMED_OUT;
00186     } else {
00187         /* Read Version Number */
00188         uint8_t version_number = hal_register_read(RG_VERSION_NUM);
00189 
00190         if ((version_number != RF230_REVA) && (version_number != RF230_REVB))
00191             init_status = RADIO_UNSUPPORTED_DEVICE;
00192         else {
00193             if (hal_register_read(RG_MAN_ID_0) != SUPPORTED_MANUFACTURER_ID)
00194                 init_status = RADIO_UNSUPPORTED_DEVICE;
00195             else
00196                 hal_register_write(RG_IRQ_MASK, RF230_SUPPORTED_INTERRUPT_MASK);
00197         }
00198 #if RADIOSTATS
00199         RF230_radio_on = 1;
00200 #endif
00201     }
00202 
00203     /*  set callbacks for events.  Save user's rx_event, which we will */
00204     /*  call from radio_rx_start_event().  Same with trx_end */
00205     user_rx_event = rx_event;
00206     user_trx_end_event = trx_end_event;
00207     hal_set_rx_start_event_handler(radio_rx_start_event);
00208     hal_set_trx_end_event_handler(radio_trx_end_event);
00209 
00210     rx_frame_callback = rx_callback;
00211 
00212     return init_status;
00213 }
00214 
00215 /*---------------------------------------------------------------------------*/
00216 uint8_t *
00217 radio_frame_data(void)
00218 {
00219         return rx_frame.data;
00220 }
00221 
00222 uint8_t
00223 radio_frame_length(void)
00224 {
00225         return rx_frame.length;
00226 }
00227 
00228 /*---------------------------------------------------------------------------*/
00229 static void
00230 radio_rx_start_event(uint32_t const isr_timestamp, uint8_t const frame_length)
00231 {
00232     /*  save away RSSI */
00233     rssi_val =  hal_subregister_read( SR_RSSI );
00234 
00235     /*  call user's rx_start event handler */
00236     if (user_rx_event)
00237         user_rx_event(isr_timestamp, frame_length);
00238 }
00239 
00240 /*---------------------------------------------------------------------------*/
00241 uint8_t
00242 radio_get_saved_rssi_value(void)
00243 {
00244     return rssi_val;
00245 }
00246 
00247 /*---------------------------------------------------------------------------*/
00248 static void
00249 radio_trx_end_event(uint32_t const isr_timestamp)
00250 {
00251     volatile uint8_t status;
00252 
00253     /*  call user's trx_end event handler */
00254     if (user_trx_end_event){
00255         user_trx_end_event(isr_timestamp);
00256         return;
00257     }
00258     if (rx_mode){
00259         /* radio has received frame, store it away */
00260 #if RADIOSTATS
00261         RF230_rsigsi=rssi_val;
00262         RF230_receivepackets++;
00263 #endif
00264         parsed_frame.time = isr_timestamp;
00265         parsed_frame.rssi = rssi_val;
00266         
00267         hal_frame_read(&rx_frame, NULL);
00268         rx_frame_parse(&rx_frame, &parsed_frame);
00269         }
00270 
00271     if (!rx_mode){
00272         /*  Put radio back into receive mode. */
00273         radio_set_trx_state(TRX_OFF);
00274         radio_set_trx_state(rxMode);
00275 
00276         /*  transmit mode, put end-of-transmit event in queue */
00277         event_object_t event;
00278         event.event = 0;
00279         event.data = 0;
00280         status = hal_subregister_read(SR_TRAC_STATUS);
00281         switch(status){
00282         case TRAC_SUCCESS:
00283         case TRAC_SUCCESS_DATA_PENDING:
00284             event.event = MAC_EVENT_ACK;
00285             break;
00286         case TRAC_NO_ACK:
00287         case TRAC_CHANNEL_ACCESS_FAILURE:
00288             event.event = MAC_EVENT_NACK;
00289 #if RADIOSTATS
00290         RF230_sendfail++;
00291 #endif
00292             break;
00293         case TRAC_SUCCESS_WAIT_FOR_ACK:
00294             /*  should only happen in RX mode */
00295         case TRAC_INVALID:
00296             /*  should never happen here */
00297         default:
00298 #if RADIOSTATS
00299             RF230_sendfail++;
00300 #endif
00301             break;
00302         }
00303         if (event.event)
00304             mac_put_event(&event);
00305         process_post(&mac_process, event.event, event.data);
00306     }
00307 }
00308 /*----------------------------------------------------------------------------*/
00309 /** \brief  This function will return the channel used by the radio transceiver.
00310  *
00311  *  \return Current channel, 11 to 26.
00312  */
00313 uint8_t
00314 radio_get_operating_channel(void)
00315 {
00316     return hal_subregister_read(SR_CHANNEL);
00317 }
00318 /*----------------------------------------------------------------------------*/
00319 /** \brief This function will change the operating channel.
00320  *
00321  *  \param  channel New channel to operate on. Must be between 11 and 26.
00322  *
00323  *  \retval RADIO_SUCCESS New channel set.
00324  *  \retval RADIO_WRONG_STATE Transceiver is in a state where the channel cannot
00325  *                          be changed (SLEEP).
00326  *  \retval RADIO_INVALID_ARGUMENT Channel argument is out of bounds.
00327  *  \retval RADIO_TIMED_OUT The PLL did not lock within the specified time.
00328  */
00329 radio_status_t
00330 radio_set_operating_channel(uint8_t channel)
00331 {
00332     /*Do function parameter and state check.*/
00333     if ((channel < RF230_MIN_CHANNEL) ||
00334         (channel > RF230_MAX_CHANNEL)){
00335         return RADIO_INVALID_ARGUMENT;
00336     }
00337 
00338     if (radio_is_sleeping() == true){
00339         return RADIO_WRONG_STATE;
00340     }
00341 
00342     if (radio_get_operating_channel() == channel){
00343         return RADIO_SUCCESS;
00344     }
00345 
00346     /*Set new operating channel.*/
00347     hal_subregister_write(SR_CHANNEL, channel);
00348 
00349     /* Read current state and wait for the PLL_LOCK interrupt if the */
00350     /* radio transceiver is in either RX_ON or PLL_ON. */
00351     uint8_t trx_state = radio_get_trx_state();
00352 
00353     if ((trx_state == RX_ON) ||
00354         (trx_state == PLL_ON)){
00355         delay_us(TIME_PLL_LOCK);
00356     }
00357 
00358     radio_status_t channel_set_status = RADIO_TIMED_OUT;
00359 
00360     /* Check that the channel was set properly. */
00361     if (radio_get_operating_channel() == channel){
00362         channel_set_status = RADIO_SUCCESS;
00363     }
00364 
00365     return channel_set_status;
00366 }
00367 
00368 /*----------------------------------------------------------------------------*/
00369 /** \brief This function will read and return the output power level.
00370  *
00371  *  \returns 0 to 15 Current output power in "TX power settings" as defined in
00372  *          the radio transceiver's datasheet
00373  */
00374 uint8_t
00375 radio_get_tx_power_level(void)
00376 {
00377     return hal_subregister_read(SR_TX_PWR);
00378 }
00379 
00380 /*----------------------------------------------------------------------------*/
00381 /** \brief This function will change the output power level.
00382  *
00383  *  \param  power_level New output power level in the "TX power settings"
00384  *                      as defined in the radio transceiver's datasheet.
00385  *
00386  *  \retval RADIO_SUCCESS New output power set successfully.
00387  *  \retval RADIO_INVALID_ARGUMENT The supplied function argument is out of bounds.
00388  *  \retval RADIO_WRONG_STATE It is not possible to change the TX power when the
00389  *                          device is sleeping.
00390  */
00391 radio_status_t
00392 radio_set_tx_power_level(uint8_t power_level)
00393 {
00394 
00395     /*Check function parameter and state.*/
00396     if (power_level > TX_PWR_17_2DBM){
00397         return RADIO_INVALID_ARGUMENT;
00398     }
00399 
00400     if (radio_is_sleeping() == true){
00401         return RADIO_WRONG_STATE;
00402     }
00403 
00404     /*Set new power level*/
00405     hal_subregister_write(SR_TX_PWR, power_level);
00406 
00407     return RADIO_SUCCESS;
00408 }
00409 
00410 /*----------------------------------------------------------------------------*/
00411 /** \brief This function returns the current CCA mode used.
00412  *
00413  *  \return CCA mode currently used, 0 to 3.
00414  */
00415 uint8_t
00416 radio_get_cca_mode(void)
00417 {
00418     return hal_subregister_read(SR_CCA_MODE);
00419 }
00420 
00421 /*----------------------------------------------------------------------------*/
00422 /** \brief This function returns the current ED threshold used by the CCA algorithm.
00423  *
00424  *  \return Current ED threshold, 0 to 15.
00425  */
00426 uint8_t
00427 radio_get_ed_threshold(void)
00428 {
00429     return hal_subregister_read(SR_CCA_ED_THRES);
00430 }
00431 
00432 /*----------------------------------------------------------------------------*/
00433 /** \brief This function will configure the Clear Channel Assessment algorithm.
00434  *
00435  *  \param  mode Three modes are available: Energy above threshold, carrier
00436  *               sense only and carrier sense with energy above threshold.
00437  *  \param  ed_threshold Above this energy threshold the channel is assumed to be
00438  *                      busy. The threshold is given in positive dBm values.
00439  *                      Ex. -91 dBm gives a csThreshold of 91. Value range for
00440  *                      the variable is [61 to 91]. Only valid for the CCA_ED
00441  *                      and CCA_CARRIER_SENSE_ED modes.
00442  *
00443  *  \retval RADIO_SUCCESS Mode and its parameters successfully changed.
00444  *  \retval RADIO_WRONG_STATE This function cannot be called in the SLEEP state.
00445  *  \retval RADIO_INVALID_ARGUMENT If one of the three function arguments are out
00446  *                               of bounds.
00447  */
00448 radio_status_t
00449 radio_set_cca_mode(uint8_t mode, uint8_t ed_threshold)
00450 {
00451     /*Check function parameters and state.*/
00452     if ((mode != CCA_ED) &&
00453         (mode != CCA_CARRIER_SENSE) &&
00454         (mode != CCA_CARRIER_SENSE_WITH_ED)){
00455         return RADIO_INVALID_ARGUMENT;
00456     }
00457 
00458     /* Ensure that the ED threshold is within bounds. */
00459     if (ed_threshold > RF230_MAX_ED_THRESHOLD){
00460         return RADIO_INVALID_ARGUMENT;
00461     }
00462 
00463     /* Ensure that the radio transceiver is not sleeping. */
00464     if (radio_is_sleeping() == true){
00465         return RADIO_WRONG_STATE;
00466     }
00467 
00468     /*Change cca mode and ed threshold.*/
00469     hal_subregister_write(SR_CCA_MODE, mode);
00470     hal_subregister_write(SR_CCA_ED_THRES, ed_threshold);
00471 
00472     return RADIO_SUCCESS;
00473 }
00474 
00475 /*----------------------------------------------------------------------------*/
00476 /** \brief This function returns the Received Signal Strength Indication.
00477  *
00478  *  \note This function should only be called from the: RX_ON and BUSY_RX. This
00479  *        can be ensured by reading the current state of the radio transceiver
00480  *        before executing this function!
00481  *  \param rssi Pointer to memory location where RSSI value should be written.
00482  *  \retval RADIO_SUCCESS The RSSI measurement was successful.
00483  *  \retval RADIO_WRONG_STATE The radio transceiver is not in RX_ON or BUSY_RX.
00484  */
00485 radio_status_t
00486 radio_get_rssi_value(uint8_t *rssi)
00487 {
00488 
00489     uint8_t current_state = radio_get_trx_state();
00490     radio_status_t retval = RADIO_WRONG_STATE;
00491 
00492     /*The RSSI measurement should only be done in RX_ON or BUSY_RX.*/
00493     if ((current_state == RX_ON) ||
00494         (current_state == BUSY_RX)){
00495         *rssi = hal_subregister_read(SR_RSSI);
00496         retval = RADIO_SUCCESS;
00497     }
00498 
00499     return retval;
00500 }
00501 
00502 /*----------------------------------------------------------------------------*/
00503 /** \brief This function returns the current threshold volatge used by the
00504  *         battery monitor (BATMON_VTH).
00505  *
00506  *  \note This function can not be called from P_ON or SLEEP. This is ensured
00507  *        by reading the device state before calling this function.
00508  *
00509  *  \return Current threshold voltage, 0 to 15.
00510  */
00511 uint8_t
00512 radio_batmon_get_voltage_threshold(void)
00513 {
00514     return hal_subregister_read(SR_BATMON_VTH);
00515 }
00516 
00517 /*----------------------------------------------------------------------------*/
00518 /** \brief This function returns if high or low voltage range is used.
00519  *
00520  *  \note This function can not be called from P_ON or SLEEP. This is ensured
00521  *        by reading the device state before calling this function.
00522  *
00523  *  \retval 0 Low voltage range selected.
00524  *  \retval 1 High voltage range selected.
00525  */
00526 uint8_t
00527 radio_batmon_get_voltage_range(void)
00528 {
00529     return hal_subregister_read(SR_BATMON_HR);
00530 }
00531 
00532 /*----------------------------------------------------------------------------*/
00533 /** \brief This function is used to configure the battery monitor module
00534  *
00535  *  \param range True means high voltage range and false low voltage range.
00536  *  \param voltage_threshold The datasheet defines 16 voltage levels for both
00537  *                          low and high range.
00538  *  \retval RADIO_SUCCESS Battery monitor configured
00539  *  \retval RADIO_WRONG_STATE The device is sleeping.
00540  *  \retval RADIO_INVALID_ARGUMENT The voltage_threshold parameter is out of
00541  *                               bounds (Not within [0 - 15]).
00542  */
00543 radio_status_t
00544 radio_batmon_configure(bool range, uint8_t voltage_threshold)
00545 {
00546 
00547     /*Check function parameters and state.*/
00548     if (voltage_threshold > BATTERY_MONITOR_HIGHEST_VOLTAGE){
00549         return RADIO_INVALID_ARGUMENT;
00550     }
00551 
00552     if (radio_is_sleeping() == true){
00553         return RADIO_WRONG_STATE;
00554     }
00555 
00556     /*Write new voltage range and voltage level.*/
00557     if (range == true){
00558         hal_subregister_write(SR_BATMON_HR, BATTERY_MONITOR_HIGH_VOLTAGE);
00559     } else {
00560         hal_subregister_write(SR_BATMON_HR, BATTERY_MONITOR_LOW_VOLTAGE);
00561     }
00562 
00563     hal_subregister_write(SR_BATMON_VTH, voltage_threshold);
00564 
00565     return RADIO_SUCCESS;
00566 }
00567 
00568 /*----------------------------------------------------------------------------*/
00569 /** \brief This function returns the status of the Battery Monitor module.
00570  *
00571  *  \note This function can not be called from P_ON or SLEEP. This is ensured
00572  *        by reading the device state before calling this function.
00573  *
00574  *  \retval RADIO_BAT_LOW Battery voltage is below the programmed threshold.
00575  *  \retval RADIO_BAT_OK Battery voltage is above the programmed threshold.
00576  */
00577 radio_status_t
00578 radio_batmon_get_status(void)
00579 {
00580 
00581     radio_status_t batmon_status = RADIO_BAT_LOW;
00582 
00583     if (hal_subregister_read(SR_BATMON_OK) !=
00584         BATTERY_MONITOR_VOLTAGE_UNDER_THRESHOLD){
00585         batmon_status = RADIO_BAT_OK;
00586     }
00587 
00588     return batmon_status;
00589 }
00590 
00591 /*----------------------------------------------------------------------------*/
00592 /** \brief This function returns the current clock setting for the CLKM pin.
00593  *
00594  *  \retval CLKM_DISABLED CLKM pin is disabled.
00595  *  \retval CLKM_1MHZ CLKM pin is prescaled to 1 MHz.
00596  *  \retval CLKM_2MHZ CLKM pin is prescaled to 2 MHz.
00597  *  \retval CLKM_4MHZ CLKM pin is prescaled to 4 MHz.
00598  *  \retval CLKM_8MHZ CLKM pin is prescaled to 8 MHz.
00599  *  \retval CLKM_16MHZ CLKM pin is not prescaled. Output is 16 MHz.
00600  */
00601 uint8_t
00602 radio_get_clock_speed(void)
00603 {
00604     return hal_subregister_read(SR_CLKM_CTRL);
00605 }
00606 
00607 /*----------------------------------------------------------------------------*/
00608 /** \brief This function changes the prescaler on the CLKM pin.
00609  *
00610  *  \param direct   This boolean variable is used to determine if the frequency
00611  *                  of the CLKM pin shall be changed directly or not. If direct
00612  *                  equals true, the frequency will be changed directly. This is
00613  *                  fine if the CLKM signal is used to drive a timer etc. on the
00614  *                  connected microcontroller. However, the CLKM signal can also
00615  *                  be used to clock the microcontroller itself. In this situation
00616  *                  it is possible to change the CLKM frequency indirectly
00617  *                  (direct == false). When the direct argument equlas false, the
00618  *                  CLKM frequency will be changed first after the radio transceiver
00619  *                  has been taken to SLEEP and awaken again.
00620  *  \param clock_speed This parameter can be one of the following constants:
00621  *                     CLKM_DISABLED, CLKM_1MHZ, CLKM_2MHZ, CLKM_4MHZ, CLKM_8MHZ
00622  *                     or CLKM_16MHZ.
00623  *
00624  *  \retval RADIO_SUCCESS Clock speed updated. New state is TRX_OFF.
00625  *  \retval RADIO_INVALID_ARGUMENT Requested clock speed is out of bounds.
00626  */
00627 radio_status_t
00628 radio_set_clock_speed(bool direct, uint8_t clock_speed)
00629 {
00630         /*Check function parameter and current clock speed.*/
00631     if (clock_speed > CLKM_16MHZ){
00632             return RADIO_INVALID_ARGUMENT;
00633     }
00634 
00635     if (radio_get_clock_speed() == clock_speed){
00636         return RADIO_SUCCESS;
00637     }
00638 
00639         /*Select to change the CLKM frequency directly or after returning from SLEEP.*/
00640     if (direct == false){
00641             hal_subregister_write(SR_CLKM_SHA_SEL, 1);
00642     } else {
00643             hal_subregister_write(SR_CLKM_SHA_SEL, 0);
00644     }
00645         
00646         hal_subregister_write(SR_CLKM_CTRL, clock_speed);
00647 
00648     return RADIO_SUCCESS;
00649 }
00650 
00651 /*----------------------------------------------------------------------------*/
00652 /** \brief  This function calibrates the Single Side Band Filter.
00653  *
00654  *  \retval     RADIO_SUCCESS    Filter is calibrated.
00655  *  \retval     RADIO_TIMED_OUT  The calibration could not be completed within time.
00656  *  \retval     RADIO_WRONG_STATE This function can only be called from TRX_OFF or
00657  *              PLL_ON.
00658  */
00659 radio_status_t
00660 radio_calibrate_filter(void)
00661 {
00662     /*Check current state. Only possible to do filter calibration from TRX_OFF or PLL_ON.*/
00663     uint8_t trx_state = radio_get_trx_state();
00664 
00665     if ((trx_state != TRX_OFF) &&
00666         (trx_state != PLL_ON)){
00667         return RADIO_WRONG_STATE;
00668     }
00669 
00670     /* Start the tuning algorithm by writing one to the FTN_START subregister. */
00671     hal_subregister_write(SR_FTN_START, 1);
00672     delay_us(TIME_FTN_TUNING); /* Wait for the calibration to finish. */
00673 
00674     radio_status_t filter_calibration_status = RADIO_TIMED_OUT;
00675 
00676     /* Verify the calibration result. */
00677     if (hal_subregister_read(SR_FTN_START) == FTN_CALIBRATION_DONE){
00678         filter_calibration_status = RADIO_SUCCESS;
00679     }
00680 
00681     return filter_calibration_status;
00682 }
00683 
00684 /*----------------------------------------------------------------------------*/
00685 /** \brief  This function calibrates the PLL.
00686  *
00687  *  \retval     RADIO_SUCCESS    PLL Center Frequency and Delay Cell is calibrated.
00688  *  \retval     RADIO_TIMED_OUT  The calibration could not be completed within time.
00689  *  \retval     RADIO_WRONG_STATE This function can only be called from PLL_ON.
00690  */
00691 radio_status_t
00692 radio_calibrate_pll(void)
00693 {
00694 
00695     /*Check current state. Only possible to calibrate PLL from PLL_ON state*/
00696     if (radio_get_trx_state() != PLL_ON){
00697         return RADIO_WRONG_STATE;
00698     }
00699 
00700     /* Initiate the DCU and CF calibration loops. */
00701     hal_subregister_write(SR_PLL_DCU_START, 1);
00702     hal_subregister_write(SR_PLL_CF_START, 1);
00703 
00704     /* Wait maximum 150 us for the PLL to lock. */
00705     hal_clear_pll_lock_flag();
00706     delay_us(TIME_PLL_LOCK);
00707 
00708     radio_status_t pll_calibration_status = RADIO_TIMED_OUT;
00709 
00710     if (hal_get_pll_lock_flag() > 0){
00711         if (hal_subregister_read(SR_PLL_DCU_START) == PLL_DCU_CALIBRATION_DONE){
00712             if (hal_subregister_read(SR_PLL_CF_START) == PLL_CF_CALIBRATION_DONE){
00713                 pll_calibration_status = RADIO_SUCCESS;
00714             }
00715         }
00716     }
00717 
00718     return pll_calibration_status;
00719 }
00720 
00721 /*----------------------------------------------------------------------------*/
00722 /** \brief  This function return the Radio Transceivers current state.
00723  *
00724  *  \retval     P_ON               When the external supply voltage (VDD) is
00725  *                                 first supplied to the transceiver IC, the
00726  *                                 system is in the P_ON (Poweron) mode.
00727  *  \retval     BUSY_RX            The radio transceiver is busy receiving a
00728  *                                 frame.
00729  *  \retval     BUSY_TX            The radio transceiver is busy transmitting a
00730  *                                 frame.
00731  *  \retval     RX_ON              The RX_ON mode enables the analog and digital
00732  *                                 receiver blocks and the PLL frequency
00733  *                                 synthesizer.
00734  *  \retval     TRX_OFF            In this mode, the SPI module and crystal
00735  *                                 oscillator are active.
00736  *  \retval     PLL_ON             Entering the PLL_ON mode from TRX_OFF will
00737  *                                 first enable the analog voltage regulator. The
00738  *                                 transceiver is ready to transmit a frame.
00739  *  \retval     BUSY_RX_AACK       The radio was in RX_AACK_ON mode and received
00740  *                                 the Start of Frame Delimiter (SFD). State
00741  *                                 transition to BUSY_RX_AACK is done if the SFD
00742  *                                 is valid.
00743  *  \retval     BUSY_TX_ARET       The radio transceiver is busy handling the
00744  *                                 auto retry mechanism.
00745  *  \retval     RX_AACK_ON         The auto acknowledge mode of the radio is
00746  *                                 enabled and it is waiting for an incomming
00747  *                                 frame.
00748  *  \retval     TX_ARET_ON         The auto retry mechanism is enabled and the
00749  *                                 radio transceiver is waiting for the user to
00750  *                                 send the TX_START command.
00751  *  \retval     RX_ON_NOCLK        The radio transceiver is listening for
00752  *                                 incomming frames, but the CLKM is disabled so
00753  *                                 that the controller could be sleeping.
00754  *                                 However, this is only true if the controller
00755  *                                 is run from the clock output of the radio.
00756  *  \retval     RX_AACK_ON_NOCLK   Same as the RX_ON_NOCLK state, but with the
00757  *                                 auto acknowledge module turned on.
00758  *  \retval     BUSY_RX_AACK_NOCLK Same as BUSY_RX_AACK, but the controller
00759  *                                 could be sleeping since the CLKM pin is
00760  *                                 disabled.
00761  *  \retval     STATE_TRANSITION   The radio transceiver's state machine is in
00762  *                                 transition between two states.
00763  */
00764 uint8_t
00765 radio_get_trx_state(void)
00766 {
00767     return hal_subregister_read(SR_TRX_STATUS);
00768 }
00769 
00770 /*----------------------------------------------------------------------------*/
00771 /** \brief  This function checks if the radio transceiver is sleeping.
00772  *
00773  *  \retval     true    The radio transceiver is in SLEEP or one of the *_NOCLK
00774  *                      states.
00775  *  \retval     false   The radio transceiver is not sleeping.
00776  */
00777 bool radio_is_sleeping(void)
00778 {
00779     bool sleeping = false;
00780 
00781     /* The radio transceiver will be at SLEEP or one of the *_NOCLK states only if */
00782     /* the SLP_TR pin is high. */
00783     if (hal_get_slptr() != 0){
00784         sleeping = true;
00785     }
00786 
00787     return sleeping;
00788 }
00789 
00790 /*----------------------------------------------------------------------------*/
00791 /** \brief  This function will change the current state of the radio
00792  *          transceiver's internal state machine.
00793  *
00794  *  \param     new_state        Here is a list of possible states:
00795  *             - RX_ON        Requested transition to RX_ON state.
00796  *             - TRX_OFF      Requested transition to TRX_OFF state.
00797  *             - PLL_ON       Requested transition to PLL_ON state.
00798  *             - RX_AACK_ON   Requested transition to RX_AACK_ON state.
00799  *             - TX_ARET_ON   Requested transition to TX_ARET_ON state.
00800  *
00801  *  \retval    RADIO_SUCCESS          Requested state transition completed
00802  *                                  successfully.
00803  *  \retval    RADIO_INVALID_ARGUMENT Supplied function parameter out of bounds.
00804  *  \retval    RADIO_WRONG_STATE      Illegal state to do transition from.
00805  *  \retval    RADIO_BUSY_STATE       The radio transceiver is busy.
00806  *  \retval    RADIO_TIMED_OUT        The state transition could not be completed
00807  *                                  within resonable time.
00808  */
00809 radio_status_t
00810 radio_set_trx_state(uint8_t new_state)
00811 {
00812     uint8_t original_state;
00813 
00814     /*Check function paramter and current state of the radio transceiver.*/
00815     if (!((new_state == TRX_OFF)    ||
00816           (new_state == RX_ON)      ||
00817           (new_state == PLL_ON)     ||
00818           (new_state == RX_AACK_ON) ||
00819           (new_state == TX_ARET_ON))){
00820         return RADIO_INVALID_ARGUMENT;
00821     }
00822 
00823     if (radio_is_sleeping() == true){
00824         return RADIO_WRONG_STATE;
00825     }
00826 
00827     // Wait for radio to finish previous operation
00828     for(;;)
00829     {
00830         original_state = radio_get_trx_state();
00831         if (original_state != BUSY_TX_ARET &&
00832             original_state != BUSY_RX_AACK &&
00833             original_state != BUSY_RX && 
00834             original_state != BUSY_TX)
00835             break;
00836     }
00837 
00838     if (new_state == original_state){
00839         return RADIO_SUCCESS;
00840     }
00841 
00842 
00843     /* At this point it is clear that the requested new_state is: */
00844     /* TRX_OFF, RX_ON, PLL_ON, RX_AACK_ON or TX_ARET_ON. */
00845 
00846     /* The radio transceiver can be in one of the following states: */
00847     /* TRX_OFF, RX_ON, PLL_ON, RX_AACK_ON, TX_ARET_ON. */
00848     if(new_state == TRX_OFF){
00849         radio_reset_state_machine(); /* Go to TRX_OFF from any state. */
00850     } else {
00851         /* It is not allowed to go from RX_AACK_ON or TX_AACK_ON and directly to */
00852         /* TX_AACK_ON or RX_AACK_ON respectively. Need to go via RX_ON or PLL_ON. */
00853         if ((new_state == TX_ARET_ON) &&
00854             (original_state == RX_AACK_ON)){
00855             /* First do intermediate state transition to PLL_ON, then to TX_ARET_ON. */
00856             /* The final state transition to TX_ARET_ON is handled after the if-else if. */
00857             hal_subregister_write(SR_TRX_CMD, PLL_ON);
00858             delay_us(TIME_STATE_TRANSITION_PLL_ACTIVE);
00859         } else if ((new_state == RX_AACK_ON) &&
00860                  (original_state == TX_ARET_ON)){
00861             /* First do intermediate state transition to RX_ON, then to RX_AACK_ON. */
00862             /* The final state transition to RX_AACK_ON is handled after the if-else if. */
00863             hal_subregister_write(SR_TRX_CMD, RX_ON);
00864             delay_us(TIME_STATE_TRANSITION_PLL_ACTIVE);
00865         }
00866 
00867         /* Any other state transition can be done directly. */
00868         hal_subregister_write(SR_TRX_CMD, new_state);
00869 
00870         /* When the PLL is active most states can be reached in 1us. However, from */
00871         /* TRX_OFF the PLL needs time to activate. */
00872         if (original_state == TRX_OFF){
00873             delay_us(TIME_TRX_OFF_TO_PLL_ACTIVE);
00874         } else {
00875             delay_us(TIME_STATE_TRANSITION_PLL_ACTIVE);
00876         }
00877     } /*  end: if(new_state == TRX_OFF) ... */
00878 
00879     /*Verify state transition.*/
00880     radio_status_t set_state_status = RADIO_TIMED_OUT;
00881 
00882     if (radio_get_trx_state() == new_state){
00883         set_state_status = RADIO_SUCCESS;
00884         /*  set rx_mode flag based on mode we're changing to */
00885         if (new_state == RX_ON ||
00886             new_state == RX_AACK_ON){
00887             rx_mode = true;
00888         } else {
00889             rx_mode = false;
00890     }
00891     }
00892 
00893     return set_state_status;
00894 }
00895 
00896 /*----------------------------------------------------------------------------*/
00897 /** \brief  This function will put the radio transceiver to sleep.
00898  *
00899  *  \retval    RADIO_SUCCESS          Sleep mode entered successfully.
00900  *  \retval    RADIO_TIMED_OUT        The transition to TRX_OFF took too long.
00901  */
00902 radio_status_t
00903 radio_enter_sleep_mode(void)
00904 {
00905     if (radio_is_sleeping() == true){
00906         return RADIO_SUCCESS;
00907     }
00908 
00909     radio_reset_state_machine(); /* Force the device into TRX_OFF. */
00910 
00911     radio_status_t enter_sleep_status = RADIO_TIMED_OUT;
00912 
00913     if (radio_get_trx_state() == TRX_OFF){
00914         /* Enter Sleep. */
00915         hal_set_slptr_high();
00916         enter_sleep_status = RADIO_SUCCESS;
00917 #if RADIOSTATS
00918         RF230_radio_on = 0;
00919 #endif
00920     }
00921 
00922     return enter_sleep_status;
00923 }
00924 
00925 /*----------------------------------------------------------------------------*/
00926 /** \brief  This function will take the radio transceiver from sleep mode and
00927  *          put it into the TRX_OFF state.
00928  *
00929  *  \retval    RADIO_SUCCESS          Left sleep mode and entered TRX_OFF state.
00930  *  \retval    RADIO_TIMED_OUT        Transition to TRX_OFF state timed out.
00931  */
00932 radio_status_t
00933 radio_leave_sleep_mode(void)
00934 {
00935     /* Check if the radio transceiver is actually sleeping. */
00936     if (radio_is_sleeping() == false){
00937         return RADIO_SUCCESS;
00938     }
00939 
00940     hal_set_slptr_low();
00941     delay_us(TIME_SLEEP_TO_TRX_OFF);
00942 
00943     radio_status_t leave_sleep_status = RADIO_TIMED_OUT;
00944 
00945     /* Ensure that the radio transceiver is in the TRX_OFF state. */
00946     if (radio_get_trx_state() == TRX_OFF){
00947         leave_sleep_status = RADIO_SUCCESS;
00948 #if RADIOSTATS
00949         RF230_radio_on = 1;
00950 #endif
00951     }
00952 
00953     return leave_sleep_status;
00954 }
00955 
00956 /*----------------------------------------------------------------------------*/
00957 /** \brief  This function will reset the state machine (to TRX_OFF) from any of
00958  *          its states, except for the SLEEP state.
00959  */
00960 void
00961 radio_reset_state_machine(void)
00962 {
00963     hal_set_slptr_low();
00964     delay_us(TIME_NOCLK_TO_WAKE);
00965     hal_subregister_write(SR_TRX_CMD, CMD_FORCE_TRX_OFF);
00966     delay_us(TIME_CMD_FORCE_TRX_OFF);
00967 }
00968 
00969 /*----------------------------------------------------------------------------*/
00970 /** \brief  This function will reset all the registers and the state machine of
00971  *          the radio transceiver.
00972  */
00973 void
00974 radio_reset_trx(void)
00975 {
00976     hal_set_rst_low();
00977     hal_set_slptr_low();
00978     delay_us(TIME_RESET);
00979     hal_set_rst_high();
00980 }
00981 
00982 /*----------------------------------------------------------------------------*/
00983 /** \brief  This function will enable or disable automatic CRC during frame
00984  *          transmission.
00985  *
00986  *  \param  auto_crc_on If this parameter equals true auto CRC will be used for
00987  *                      all frames to be transmitted. The framelength must be
00988  *                      increased by two bytes (16 bit CRC). If the parameter equals
00989  *                      false, the automatic CRC will be disabled.
00990  */
00991 void
00992 radio_use_auto_tx_crc(bool auto_crc_on)
00993 {
00994     if (auto_crc_on == true){
00995         hal_subregister_write(SR_TX_AUTO_CRC_ON, 1);
00996     } else {
00997         hal_subregister_write(SR_TX_AUTO_CRC_ON, 0);
00998     }
00999 }
01000 
01001 /*----------------------------------------------------------------------------*/
01002 /** \brief  This function will download a frame to the radio transceiver's
01003  *          transmit buffer and send it.
01004  *
01005  *  \param  data_length Length of the frame to be transmitted. 1 to 128 bytes are the valid lengths.
01006  *  \param  *data   Pointer to the data to transmit
01007  *
01008  *  \retval RADIO_SUCCESS Frame downloaded and sent successfully.
01009  *  \retval RADIO_INVALID_ARGUMENT If the dataLength is 0 byte or more than 127
01010  *                               bytes the frame will not be sent.
01011  *  \retval RADIO_WRONG_STATE It is only possible to use this function in the
01012  *                          PLL_ON and TX_ARET_ON state. If any other state is
01013  *                          detected this error message will be returned.
01014  */
01015 radio_status_t
01016 radio_send_data(uint8_t data_length, uint8_t *data)
01017 {
01018     /*Check function parameters and current state.*/
01019     if (data_length > RF230_MAX_TX_FRAME_LENGTH){
01020 #if RADIOSTATS
01021         RF230_sendfail++;
01022 #endif
01023         return RADIO_INVALID_ARGUMENT;
01024     }
01025 
01026      /* If we are busy, return */
01027         if ((radio_get_trx_state() == BUSY_TX) || (radio_get_trx_state() == BUSY_TX_ARET) )
01028         {
01029 #if RADIOSTATS
01030         RF230_sendfail++;
01031 #endif
01032         return RADIO_WRONG_STATE;
01033         }
01034 
01035     radio_set_trx_state(TRX_OFF);
01036     radio_set_trx_state(TX_ARET_ON);
01037 
01038     /*Do frame transmission.*/
01039     /* Toggle the SLP_TR pin to initiate the frame transmission. */
01040     hal_set_slptr_high();
01041     hal_set_slptr_low();
01042 
01043     hal_frame_write(data, data_length); /* Then write data to the frame buffer. */
01044 #if RADIOSTATS
01045     RF230_sendpackets++;
01046 #endif
01047     return RADIO_SUCCESS;
01048 }
01049 
01050 /*----------------------------------------------------------------------------*/
01051 /** \brief  This function will read the I_AM_COORD sub register.
01052  *
01053  *  \retval 0 Not coordinator.
01054  *  \retval 1 Coordinator role enabled.
01055  */
01056 uint8_t
01057 radio_get_device_role(void)
01058 {
01059     return hal_subregister_read(SR_I_AM_COORD);
01060 }
01061 
01062 /*----------------------------------------------------------------------------*/
01063 /** \brief  This function will set the I_AM_COORD sub register.
01064  *
01065  *  \param[in] i_am_coordinator If this parameter is true, the associated
01066  *                              coordinator role will be enabled in the radio
01067  *                              transceiver's address filter.
01068  *                              False disables the same feature.
01069  */
01070 void
01071 radio_set_device_role(bool i_am_coordinator)
01072 {
01073     hal_subregister_write(SR_I_AM_COORD, i_am_coordinator);
01074 }
01075 
01076 /*----------------------------------------------------------------------------*/
01077 /** \brief  This function will return the PANID used by the address filter.
01078  *
01079  *  \retval Any value from 0 to 0xFFFF.
01080  */
01081 uint16_t
01082 radio_get_pan_id(void)
01083 {
01084 
01085     uint8_t pan_id_15_8 = hal_register_read(RG_PAN_ID_1); /*  Read pan_id_15_8. */
01086     uint8_t pan_id_7_0 = hal_register_read(RG_PAN_ID_0); /*  Read pan_id_7_0. */
01087 
01088     uint16_t pan_id = ((uint16_t)(pan_id_15_8 << 8)) | pan_id_7_0;
01089 
01090     return pan_id;
01091 }
01092 
01093 /*----------------------------------------------------------------------------*/
01094 /** \brief  This function will set the PANID used by the address filter.
01095  *
01096  *  \param  new_pan_id Desired PANID. Can be any value from 0x0000 to 0xFFFF
01097  */
01098 void
01099 radio_set_pan_id(uint16_t new_pan_id)
01100 {
01101 
01102     uint8_t pan_byte = new_pan_id & 0xFF; /*  Extract new_pan_id_7_0. */
01103     hal_register_write(RG_PAN_ID_0, pan_byte);
01104 
01105     pan_byte = (new_pan_id >> 8*1) & 0xFF;  /*  Extract new_pan_id_15_8. */
01106     hal_register_write(RG_PAN_ID_1, pan_byte);
01107 }
01108 
01109 /*----------------------------------------------------------------------------*/
01110 /** \brief  This function will return the current short address used by the
01111  *          address filter.
01112  *
01113  *  \retval Any value from 0x0000 to 0xFFFF
01114  */
01115 uint16_t
01116 radio_get_short_address(void)
01117 {
01118 
01119     uint8_t short_address_15_8 = hal_register_read(RG_SHORT_ADDR_1); /*  Read short_address_15_8. */
01120     uint8_t short_address_7_0  = hal_register_read(RG_SHORT_ADDR_1); /*  Read short_address_7_0. */
01121 
01122     uint16_t short_address = ((uint16_t)(short_address_15_8 << 8)) | short_address_7_0;
01123 
01124     return short_address;
01125 }
01126 
01127 /*----------------------------------------------------------------------------*/
01128 /** \brief  This function will set the short address used by the address filter.
01129  *
01130  *  \param  new_short_address Short address to be used by the address filter.
01131  */
01132 void
01133 radio_set_short_address(uint16_t new_short_address)
01134 {
01135 
01136     uint8_t short_address_byte = new_short_address & 0xFF; /*  Extract short_address_7_0. */
01137     hal_register_write(RG_SHORT_ADDR_0, short_address_byte);
01138 
01139     short_address_byte = (new_short_address >> 8*1) & 0xFF; /*  Extract short_address_15_8. */
01140     hal_register_write(RG_SHORT_ADDR_1, short_address_byte);
01141 }
01142 
01143 /*----------------------------------------------------------------------------*/
01144 /** \brief  This function will read the extended address used by the address
01145  *          filter.
01146  *
01147  *  \note In this function a pointer is used to convey the 64-bit result, since
01148  *        it is very inefficient to use the stack for this.
01149  *
01150  *  \return Extended Address, any 64-bit value.
01151  */
01152 void
01153 radio_get_extended_address(uint8_t *extended_address)
01154 {
01155     *extended_address++ = hal_register_read(RG_IEEE_ADDR_0);
01156     *extended_address++ = hal_register_read(RG_IEEE_ADDR_1);
01157     *extended_address++ = hal_register_read(RG_IEEE_ADDR_2);
01158     *extended_address++ = hal_register_read(RG_IEEE_ADDR_3);
01159     *extended_address++ = hal_register_read(RG_IEEE_ADDR_4);
01160     *extended_address++ = hal_register_read(RG_IEEE_ADDR_5);
01161     *extended_address++ = hal_register_read(RG_IEEE_ADDR_6);
01162     *extended_address   = hal_register_read(RG_IEEE_ADDR_7);
01163 }
01164 
01165 /*----------------------------------------------------------------------------*/
01166 /** \brief  This function will set a new extended address to be used by the
01167  *          address filter.
01168  *
01169  *  \param  extended_address Extended address to be used by the address filter.
01170  */
01171 void
01172 radio_set_extended_address(uint8_t *extended_address)
01173 {
01174     hal_register_write(RG_IEEE_ADDR_0, *extended_address++);
01175     hal_register_write(RG_IEEE_ADDR_1, *extended_address++);
01176     hal_register_write(RG_IEEE_ADDR_2, *extended_address++);
01177     hal_register_write(RG_IEEE_ADDR_3, *extended_address++);
01178     hal_register_write(RG_IEEE_ADDR_4, *extended_address++);
01179     hal_register_write(RG_IEEE_ADDR_5, *extended_address++);
01180     hal_register_write(RG_IEEE_ADDR_6, *extended_address++);
01181     hal_register_write(RG_IEEE_ADDR_7, *extended_address++);
01182 }
01183 
01184 /*----------------------------------------------------------------------------*/
01185 /** \brief  This function will configure the CSMA algorithm used by the radio
01186  *          transceiver when transmitting data from TX_ARET_ON state.
01187  *
01188  *  \param  seed0 Lower 8 bits of the seed used for the random number generator
01189  *                in the CSMA algorithm. Value range: 0 to 255.
01190  *  \param  be_csma_seed1 Is a combined argument of the MIN_BE, MAX_CSMA_RETRIES
01191  *                        and SEED1 variables:
01192  *                        -# MIN_BE: Bit[7:6] Minimum back-off exponent in the
01193  *                           CSMA/CA algorithm.
01194  *                        -# MAX_CSMA_RETRIES: Bit[5:3] Number of retries in
01195  *                          TX_ARET_ON mode to repeat the CSMA/CA procedures
01196  *                          before the ARET procedure gives up.
01197  *                        -# SEED1: Bits[2:0] Higher 3 bits of CSMA_SEED, bits[10:8]
01198  *                           Seed for the random number generator in the
01199  *                           CSMA/CA algorithm.
01200  *  \retval RADIO_SUCCESS The CSMA algorithm was configured successfully.
01201  *  \retval RADIO_WRONG_STATE This function should not be called in the
01202  *                          SLEEP state.
01203  */
01204 radio_status_t
01205 radio_configure_csma(uint8_t seed0, uint8_t be_csma_seed1)
01206 {
01207 
01208     /*Check state.*/
01209     if (radio_is_sleeping() == true){
01210         return RADIO_WRONG_STATE;
01211     }
01212 
01213     /*Extract parameters, and configure the CSMA-CA algorithm.*/
01214     uint8_t back_off_exponent = (be_csma_seed1 & 0xC0) >> 6;
01215     uint8_t csma_retries      = (be_csma_seed1 & 0x38) >> 3;
01216     uint8_t seed1             = (be_csma_seed1 & 0x07);
01217 
01218     hal_subregister_write(SR_MAX_FRAME_RETRIES, 0); /* AT86RF230 rev A errata. */
01219     hal_subregister_write(SR_MAX_CSMA_RETRIES, csma_retries);
01220     hal_subregister_write(SR_MIN_BE, back_off_exponent);
01221     hal_register_write(RG_CSMA_SEED_0, seed0);
01222     hal_subregister_write(SR_CSMA_SEED_1, seed1);
01223 
01224     return RADIO_SUCCESS;
01225 }
01226 
01227 /*----------------------------------------------------------------------------*/
01228 /**
01229     \brief Calibrate the internal RC oscillator
01230 
01231     This function calibrates the internal RC oscillator, based
01232     on the 1 MHz clock supplied by the AT86RF2xx. In order to
01233     verify the calibration result you can program the CKOUT fuse
01234     and monitor the CPU clock on an I/O pin.
01235 
01236     \return TRUE if calibrate passed; FALSE if calibrate failed.
01237 */
01238 bool
01239 calibrate_rc_osc_clkm(void)
01240 {
01241         bool success = false;
01242 
01243     /*  Use the 1 MHz CLK_M from the AT86RF230. */
01244     uint16_t temp, counter;
01245     uint8_t osccal_saved;
01246     uint8_t tccr2b, tccr1b, tccr1a;
01247 
01248     /*  in the following line, 1000000ULL represents the 1MHz input signal */
01249     /*  from the radio.  265 is the number of counts to overflow 8-bit */
01250     /*  timer 2.  32 is the divide by 32 prescaler for timer 1.  F_CPU is */
01251     /*  the main clock frequency. */
01252 #define TARGETVAL ((1000000ULL * 256 * 32) / F_CPU)
01253 
01254 
01255         osccal_saved = OSCCAL;
01256         cli();
01257 
01258         radio_set_clock_speed(true, CLKM_1MHz);
01259 
01260     /*  Save current values of timer status. */
01261         tccr2b = TCCR2B;
01262         tccr1b = TCCR1B;
01263         tccr1a = TCCR1A;
01264 
01265     /*  Stop timers 1 and 2. */
01266     /*  Set timer 1 to normal mode (no CTC, no PWM, just count). */
01267         TCCR2B = 0;
01268         TCCR1B = 0;
01269         TCCR1A = 0;
01270 
01271     for (counter = 0; counter < 1000;  counter++){
01272         /*  Delete pending timer 1 and 2 interrupts, and clear the */
01273         /*  counters. */
01274             TIFR1 = 0xFF;
01275             TIFR2 = 0xFF;
01276             TCNT2 = 0;
01277             TCNT1 = 0;
01278         /*  Timer 2 driven from clock divided by 32 */
01279             TCCR2B = (1 << CS21) | (1 << CS20);
01280         /*  Timer 1 driven with external clock */
01281             TCCR1B = (1 << CS12) | (1 << CS11);
01282 
01283         /*  Wait for timer 2 to overflow. */
01284         while (!(TIFR2 & (1 << TOV2))){
01285                 ;
01286         }
01287 
01288         /*  Stop timer 1.  Now, TCNT1 contains the number of CPU cycles */
01289         /*  counted while timer 2 was counting */
01290             TCCR1B = 0;
01291             TCCR2B = 0;
01292 
01293             temp = TCNT1;
01294 
01295         if (temp < (uint16_t)(0.995 * TARGETVAL)){
01296             /*  Too fast, slow down */
01297                 OSCCAL--;
01298         } else if (temp > (uint16_t)(1.005 * TARGETVAL)){
01299             /*  Too slow, speed up */
01300                 OSCCAL++;
01301         } else {
01302             /*  We are within +/- 0.5 % of our target frequency, so we're */
01303             /*  done. */
01304                 success = true;
01305                 break;
01306             }
01307         }
01308 
01309         radio_set_clock_speed(true, CLKM_DISABLED);
01310 
01311     /*  restore timer status regs */
01312         TCCR2B = tccr2b;
01313         TCCR1B = tccr1b;
01314         TCCR1A = tccr1a;
01315     if (!success){
01316         /*  We failed, therefore restore previous OSCCAL value. */
01317             OSCCAL = osccal_saved;
01318         }
01319 
01320         return success;
01321 }
01322 
01323 /*----------------------------------------------------------------------------*/
01324 /**
01325     \brief Calibrate the internal RC oscillator
01326 
01327     This function calibrates the internal RC oscillator, based
01328     on an external 32KHz crystal connected to TIMER2. In order to
01329     verify the calibration result you can program the CKOUT fuse
01330     and monitor the CPU clock on an I/O pin.
01331 */
01332 void
01333 calibrate_rc_osc_32k(void)
01334 {
01335     /* Calibrate RC Oscillator: The calibration routine is done by clocking TIMER2
01336      * from the external 32kHz crystal while running an internal timer simultaneously.
01337      * The internal timer will be clocked at the same speed as the internal RC
01338      * oscillator, while TIMER2 is running at 32768 Hz. This way it is not necessary
01339      * to use a timed loop, and keep track cycles in timed loop vs. optimization
01340      * and compiler.
01341      */
01342     uint8_t osccal_original = OSCCAL;
01343     volatile uint16_t temp;
01344         
01345     /* This is bad practice, but seems to work. */
01346     OSCCAL = 0x80;
01347 
01348 
01349   //    PRR0 &= ~((1 << PRTIM2)|(1 << PRTIM1)); /*  Enable Timer 1 and 2 */
01350 
01351     TIMSK2 = 0x00; /*  Disable Timer/Counter 2 interrupts. */
01352     TIMSK1 = 0x00; /*  Disable Timer/Counter 1 interrupts. */
01353 
01354     /* Enable TIMER/COUNTER 2 to be clocked from the external 32kHz clock crystal.
01355      * Then wait for the timer to become stable before doing any calibration.
01356      */
01357     ASSR |= (1 << AS2);
01358     while (ASSR & ((1 << TCN2UB)|(1 << OCR2AUB)|(1 << TCR2AUB)|(1 << TCR2BUB))) { ; }
01359     TCCR2B = 1 << CS20;   /* run timer 2 at divide by 1 (32KHz) */
01360 
01361     AVR_ENTER_CRITICAL_REGION();
01362 
01363     uint8_t counter = 128;
01364     bool cal_ok = false;
01365     do{
01366         /* wait for timer to be ready for updated config */
01367         TCCR1B = 1 << CS10;
01368 
01369         while (ASSR & ((1 << TCN2UB)|(1 << OCR2AUB)|(1 << TCR2AUB)|(1 << TCR2BUB))) { ; }
01370 
01371         TCNT2 = 0x80;
01372         TCNT1 = 0;
01373 
01374         TIFR2 = 0xFF;
01375 
01376         /* Wait for TIMER/COUNTER 2 to overflow. Stop TIMER/COUNTER 1 and 2, and
01377          * read the counter value of TIMER/COUNTER 1. It will now contain the
01378          * number of cpu cycles elapsed within the period.
01379          */
01380         while (!(TIFR2 & (1 << TOV2))){
01381             ;
01382             }
01383         temp = TCNT1;
01384 
01385         TCCR1B = 0;
01386 
01387 #define cal_upper (31250*1.05) // 32812 = 0x802c
01388 #define cal_lower (31250*0.95) // 29687 = 0x73f7
01389         /* Iteratively reduce the error to be within limits */
01390         if (temp < cal_lower) {
01391             /* Too slow. Put the hammer down. */
01392             OSCCAL++;
01393         } else if (temp > cal_upper) {
01394             /* Too fast, retard. */
01395             OSCCAL--;
01396         } else {
01397             /* The CPU clock frequency is now within +/- 0.5% of the target value. */
01398             cal_ok = true;
01399         }
01400 
01401         counter--;
01402     } while ((counter != 0) && (false == cal_ok));
01403 
01404     if (true != cal_ok) {
01405         /* We failed, therefore restore previous OSCCAL value. */
01406         OSCCAL = osccal_original;
01407     }
01408 
01409     TCCR2B = 0;
01410 
01411     ASSR &= ~(1 << AS2);
01412 
01413     /* Disable both timers again to save power. */
01414     //    PRR0 |= (1 << PRTIM2);/* |(1 << PRTIM1); */
01415 
01416     AVR_LEAVE_CRITICAL_REGION();
01417 }
01418 
01419 /** @} */
01420 /** @} */
01421 /*EOF*/