Contiki 2.6

rf230bb.c

00001 /*
00002  * Copyright (c) 2007, Swedish Institute of Computer Science
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions
00007  * are met:
00008  * 1. Redistributions of source code must retain the above copyright
00009  *    notice, this list of conditions and the following disclaimer.
00010  * 2. Redistributions in binary form must reproduce the above copyright
00011  *    notice, this list of conditions and the following disclaimer in the
00012  *    documentation and/or other materials provided with the distribution.
00013  * 3. Neither the name of the Institute nor the names of its contributors
00014  *    may be used to endorse or promote products derived from this software
00015  *    without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND
00018  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED.  IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE
00021  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00022  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
00023  * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
00024  * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00025  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
00026  * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
00027  * SUCH DAMAGE.
00028  *
00029  * This file is part of the Contiki operating system.
00030  *
00031  */
00032 /*
00033  * This code is almost device independent and should be easy to port.
00034  * Ported to Atmel RF230 21Feb2010 by dak
00035  */
00036 
00037 #include <stdio.h>
00038 #include <string.h>
00039 
00040 #include "contiki.h"
00041 
00042 #if defined(__AVR__)
00043 #include <avr/io.h>
00044 
00045 //_delay_us has the potential to use floating point which brings the 256 byte clz table into RAM
00046 //#include <util/delay.h>
00047 //#define delay_us( us )   ( _delay_us( ( us ) ) )
00048 //_delay_loop_2(uint16_t count) is 4 CPU cycles per iteration, up to 32 milliseconds at 8MHz
00049 #include <util/delay_basic.h>
00050 #define delay_us( us )   ( _delay_loop_2(1+((unsigned long long)us*F_CPU)/4000000UL) ) 
00051 
00052 #include <avr/pgmspace.h>
00053 #elif defined(__MSP430__)
00054 #include <io.h>
00055 #endif
00056 
00057 #include "dev/leds.h"
00058 #include "dev/spi.h"
00059 #include "rf230bb.h"
00060 
00061 #include "net/packetbuf.h"
00062 #include "net/rime/rimestats.h"
00063 #include "net/netstack.h"
00064 
00065 #include "sys/timetable.h"
00066 
00067 #define WITH_SEND_CCA 0
00068 
00069 /* Timestamps have not been tested */
00070 #if RF230_CONF_TIMESTAMPS
00071 #include "net/rime/timesynch.h"
00072 #define TIMESTAMP_LEN 3
00073 #else /* RF230_CONF_TIMESTAMPS */
00074 #define TIMESTAMP_LEN 0
00075 #endif /* RF230_CONF_TIMESTAMPS */
00076 /* Nonzero FOOTER_LEN has not been tested */
00077 #define FOOTER_LEN 0
00078 
00079 /* RF230_CONF_CHECKSUM=0 for automatic hardware checksum */
00080 #ifndef RF230_CONF_CHECKSUM
00081 #define RF230_CONF_CHECKSUM 0
00082 #endif
00083 
00084 /* Autoack setting ignored in non-extended mode */
00085 #ifndef RF230_CONF_AUTOACK
00086 #define RF230_CONF_AUTOACK 1
00087 #endif
00088 
00089 /* We need to turn off autoack in promiscuous mode */
00090 #if RF230_CONF_AUTOACK
00091 static bool is_promiscuous;
00092 #endif
00093 
00094 /* RF230_CONF_AUTORETRIES is 1 plus the number written to the hardware. */
00095 /* Valid range 1-16, zero disables extended mode. */
00096 #ifndef RF230_CONF_AUTORETRIES
00097 #define RF230_CONF_AUTORETRIES 3
00098 #endif
00099 
00100 /* In extended mode (AUTORETRIES>0) the tx routine waits for hardware
00101  * processing of an expected ACK and returns RADIO_TX_OK/NOACK result.
00102  * In non-extended mode the ACK is treated as a normal rx packet.
00103  * If the caller needs the ACK to be returned as an rx packet,
00104  * RF230_INSERTACK will generate one based on the hardware result.
00105  * This is triggered when the read routine is called with a buffer
00106  * length of three (the ack length).
00107  * In extended nmode it can be enabled by default to support either
00108  * method. In nonextended mode it would pass an extra ACK to RDCs
00109  * that use the TX_OK result to signal a successful ACK.
00110  * Adds 100 bytes of program flash and two bytes of RAM. 
00111  */
00112 #if RF320_CONF_INSERTACK && RF230_CONF_AUTORETRIES
00113 #define RF230_INSERTACK 1
00114 uint8_t ack_pending,ack_seqnum;
00115 #endif
00116 
00117 /* RF230_CONF_CSMARETRIES is number of random-backoff/CCA retries. */
00118 /* The hardware will accept 0-7, but 802.15.4-2003 only allows 5 maximum */
00119 #ifndef RF230_CONF_CSMARETRIES
00120 #define RF230_CONF_CSMARETRIES 5
00121 #endif
00122 
00123 //Automatic and manual CRC both append 2 bytes to packets 
00124 #if RF230_CONF_CHECKSUM || defined(RF230BB_HOOK_TX_PACKET)
00125 #include "lib/crc16.h"
00126 #endif
00127 #define CHECKSUM_LEN 2
00128 
00129 /* Note the AUX_LEN is equal to the CHECKSUM_LEN in any tested configurations to date! */
00130 #define AUX_LEN (CHECKSUM_LEN + TIMESTAMP_LEN + FOOTER_LEN)
00131 #if AUX_LEN != CHECKSUM_LEN
00132 #warning RF230 Untested Configuration!
00133 #endif
00134 
00135 struct timestamp {
00136   uint16_t time;
00137   uint8_t authority_level;
00138 };
00139 
00140 #define FOOTER1_CRC_OK      0x80
00141 #define FOOTER1_CORRELATION 0x7f
00142 
00143 /* Leave radio on when USB powered or for testing low power protocols */
00144 /* This allows DEBUGFLOW indication of packets received when the radio is "off" */
00145 #if JACKDAW
00146 #define RADIOALWAYSON 1
00147 #else
00148 #define RADIOALWAYSON 0
00149 #define RADIOSLEEPSWHENOFF 1
00150 #endif
00151 
00152 /* RS232 delays will cause 6lowpan fragment overruns! Use DEBUGFLOW instead. */
00153 #define DEBUG 0
00154 #if DEBUG
00155 #define PRINTF(FORMAT,args...) printf_P(PSTR(FORMAT),##args)
00156 #define PRINTSHORT(FORMAT,args...) printf_P(PSTR(FORMAT),##args)
00157 #else
00158 #define PRINTF(...)
00159 #define PRINTSHORT(...)
00160 #endif
00161 #if DEBUG>1
00162 /* Output format is suitable for text2pcap to convert to wireshark pcap file.
00163  * Use $text2pcap -e 0x809a (these_outputs) capture.pcap
00164  * Since the hardware calculates and appends the two byte checksum to Tx packets,
00165  * we just add two zero bytes to the packet dump. Don't forget to enable wireshark
00166  * 802.15.4 dissection even when the checksum is wrong!
00167  */
00168 #endif
00169 
00170 /* See clock.c and httpd-cgi.c for RADIOSTATS code */
00171 #if AVR_WEBSERVER
00172 #define RADIOSTATS 1
00173 #endif
00174 #if RADIOSTATS
00175 uint16_t RF230_sendpackets,RF230_receivepackets,RF230_sendfail,RF230_receivefail;
00176 #endif
00177 
00178 #if RADIO_CONF_CALIBRATE_INTERVAL
00179 /* Set in clock.c every 256 seconds */
00180 /* The calibration is automatic when the radio turns on, so not needed when duty cycling */
00181 uint8_t rf230_calibrate;
00182 uint8_t rf230_calibrated; //for debugging, prints from main loop when calibration occurs
00183 #endif
00184 
00185 /* Track flow through mac, rdc and radio drivers, see contiki-raven-main.c for example of use */
00186 #if DEBUGFLOWSIZE
00187 extern uint8_t debugflowsize,debugflow[DEBUGFLOWSIZE];
00188 #define DEBUGFLOW(c) if (debugflowsize<(DEBUGFLOWSIZE-1)) debugflow[debugflowsize++]=c
00189 #else
00190 #define DEBUGFLOW(c)
00191 #endif
00192 
00193 /* XXX hack: these will be made as Chameleon packet attributes */
00194 rtimer_clock_t rf230_time_of_arrival, rf230_time_of_departure;
00195 
00196 int rf230_authority_level_of_sender;
00197 
00198 #if RF230_CONF_TIMESTAMPS
00199 static rtimer_clock_t setup_time_for_transmission;
00200 static unsigned long total_time_for_transmission, total_transmission_len;
00201 static int num_transmissions;
00202 #endif
00203 
00204 #if defined(__AVR_ATmega128RFA1__)
00205 volatile uint8_t rf230_interruptwait,rf230_ccawait;
00206 #endif
00207 
00208 uint8_t volatile rf230_pending;
00209 
00210 /* RF230 hardware delay times, from datasheet */
00211 typedef enum{
00212     TIME_TO_ENTER_P_ON               = 510, /**<  Transition time from VCC is applied to P_ON - most favorable case! */
00213     TIME_P_ON_TO_TRX_OFF             = 510, /**<  Transition time from P_ON to TRX_OFF. */
00214     TIME_SLEEP_TO_TRX_OFF            = 880, /**<  Transition time from SLEEP to TRX_OFF. */
00215     TIME_RESET                       = 6,   /**<  Time to hold the RST pin low during reset */
00216     TIME_ED_MEASUREMENT              = 140, /**<  Time it takes to do a ED measurement. */
00217     TIME_CCA                         = 140, /**<  Time it takes to do a CCA. */
00218     TIME_PLL_LOCK                    = 150, /**<  Maximum time it should take for the PLL to lock. */
00219     TIME_FTN_TUNING                  = 25,  /**<  Maximum time it should take to do the filter tuning. */
00220     TIME_NOCLK_TO_WAKE               = 6,   /**<  Transition time from *_NOCLK to being awake. */
00221     TIME_CMD_FORCE_TRX_OFF           = 1,   /**<  Time it takes to execute the FORCE_TRX_OFF command. */
00222     TIME_TRX_OFF_TO_PLL_ACTIVE       = 180, /**<  Transition time from TRX_OFF to: RX_ON, PLL_ON, TX_ARET_ON and RX_AACK_ON. */
00223     TIME_STATE_TRANSITION_PLL_ACTIVE = 1,   /**<  Transition time from PLL active state to another. */
00224 }radio_trx_timing_t;
00225 /*---------------------------------------------------------------------------*/
00226 PROCESS(rf230_process, "RF230 driver");
00227 /*---------------------------------------------------------------------------*/
00228 
00229 int rf230_on(void);
00230 int rf230_off(void);
00231 
00232 static int rf230_read(void *buf, unsigned short bufsize);
00233 
00234 static int rf230_prepare(const void *data, unsigned short len);
00235 static int rf230_transmit(unsigned short len);
00236 static int rf230_send(const void *data, unsigned short len);
00237 
00238 static int rf230_receiving_packet(void);
00239 static int rf230_pending_packet(void);
00240 static int rf230_cca(void);
00241 
00242 uint8_t rf230_last_correlation,rf230_last_rssi,rf230_smallest_rssi;
00243 
00244 const struct radio_driver rf230_driver =
00245   {
00246     rf230_init,
00247     rf230_prepare,
00248     rf230_transmit,
00249     rf230_send,
00250     rf230_read,
00251     rf230_cca,
00252     rf230_receiving_packet,
00253     rf230_pending_packet,
00254     rf230_on,
00255     rf230_off
00256   };
00257 
00258 uint8_t RF230_receive_on;
00259 static uint8_t channel;
00260 
00261 /* Received frames are buffered to rxframe in the interrupt routine in hal.c */
00262 uint8_t rxframe_head,rxframe_tail;
00263 hal_rx_frame_t rxframe[RF230_CONF_RX_BUFFERS];
00264 
00265 /*----------------------------------------------------------------------------*/
00266 /** \brief  This function return the Radio Transceivers current state.
00267  *
00268  *  \retval     P_ON               When the external supply voltage (VDD) is
00269  *                                 first supplied to the transceiver IC, the
00270  *                                 system is in the P_ON (Poweron) mode.
00271  *  \retval     BUSY_RX            The radio transceiver is busy receiving a
00272  *                                 frame.
00273  *  \retval     BUSY_TX            The radio transceiver is busy transmitting a
00274  *                                 frame.
00275  *  \retval     RX_ON              The RX_ON mode enables the analog and digital
00276  *                                 receiver blocks and the PLL frequency
00277  *                                 synthesizer.
00278  *  \retval     TRX_OFF            In this mode, the SPI module and crystal
00279  *                                 oscillator are active.
00280  *  \retval     PLL_ON             Entering the PLL_ON mode from TRX_OFF will
00281  *                                 first enable the analog voltage regulator. The
00282  *                                 transceiver is ready to transmit a frame.
00283  *  \retval     BUSY_RX_AACK       The radio was in RX_AACK_ON mode and received
00284  *                                 the Start of Frame Delimiter (SFD). State
00285  *                                 transition to BUSY_RX_AACK is done if the SFD
00286  *                                 is valid.
00287  *  \retval     BUSY_TX_ARET       The radio transceiver is busy handling the
00288  *                                 auto retry mechanism.
00289  *  \retval     RX_AACK_ON         The auto acknowledge mode of the radio is
00290  *                                 enabled and it is waiting for an incomming
00291  *                                 frame.
00292  *  \retval     TX_ARET_ON         The auto retry mechanism is enabled and the
00293  *                                 radio transceiver is waiting for the user to
00294  *                                 send the TX_START command.
00295  *  \retval     RX_ON_NOCLK        The radio transceiver is listening for
00296  *                                 incomming frames, but the CLKM is disabled so
00297  *                                 that the controller could be sleeping.
00298  *                                 However, this is only true if the controller
00299  *                                 is run from the clock output of the radio.
00300  *  \retval     RX_AACK_ON_NOCLK   Same as the RX_ON_NOCLK state, but with the
00301  *                                 auto acknowledge module turned on.
00302  *  \retval     BUSY_RX_AACK_NOCLK Same as BUSY_RX_AACK, but the controller
00303  *                                 could be sleeping since the CLKM pin is
00304  *                                 disabled.
00305  *  \retval     STATE_TRANSITION   The radio transceiver's state machine is in
00306  *                                 transition between two states.
00307  */
00308 //static uint8_t
00309 uint8_t
00310 radio_get_trx_state(void)
00311 {
00312     return hal_subregister_read(SR_TRX_STATUS);
00313 }
00314 
00315 /*----------------------------------------------------------------------------*/
00316 /** \brief  This function checks if the radio transceiver is sleeping.
00317  *
00318  *  \retval     true    The radio transceiver is in SLEEP or one of the *_NOCLK
00319  *                      states.
00320  *  \retval     false   The radio transceiver is not sleeping.
00321  */
00322 #if 0
00323 static bool radio_is_sleeping(void)
00324 {
00325     bool sleeping = false;
00326 
00327     /* The radio transceiver will be at SLEEP or one of the *_NOCLK states only if */
00328     /* the SLP_TR pin is high. */
00329     if (hal_get_slptr() != 0){
00330         sleeping = true;
00331     }
00332 
00333     return sleeping;
00334 }
00335 #endif
00336 /*----------------------------------------------------------------------------*/
00337 /** \brief  This function will reset the state machine (to TRX_OFF) from any of
00338  *          its states, except for the SLEEP state.
00339  */
00340 static void
00341 radio_reset_state_machine(void)
00342 {
00343     if (hal_get_slptr()) DEBUGFLOW('"');
00344     hal_set_slptr_low();
00345     delay_us(TIME_NOCLK_TO_WAKE);
00346     hal_subregister_write(SR_TRX_CMD, CMD_FORCE_TRX_OFF);
00347     delay_us(TIME_CMD_FORCE_TRX_OFF);
00348 }
00349 /*---------------------------------------------------------------------------*/
00350 static char
00351 rf230_isidle(void)
00352 {
00353   uint8_t radio_state;
00354   if (hal_get_slptr()) {
00355     DEBUGFLOW(']');
00356         return 1;
00357   } else {
00358   radio_state = hal_subregister_read(SR_TRX_STATUS);
00359   if (radio_state != BUSY_TX_ARET &&
00360       radio_state != BUSY_RX_AACK &&
00361       radio_state != STATE_TRANSITION &&
00362       radio_state != BUSY_RX && 
00363       radio_state != BUSY_TX) {
00364     return(1);
00365   } else {
00366 //    printf(".%u",radio_state);
00367     return(0);
00368   }
00369   }
00370 }
00371   
00372 static void
00373 rf230_waitidle(void)
00374 {
00375 int i;
00376   for (i=0;i<10000;i++) {  //to avoid potential hangs
00377  // while (1) {
00378     if (rf230_isidle()) break;
00379   }
00380   if (i>=10000) {DEBUGFLOW('H');DEBUGFLOW('R');}
00381 }
00382 
00383 /*----------------------------------------------------------------------------*/
00384 /** \brief  This function will change the current state of the radio
00385  *          transceiver's internal state machine.
00386  *
00387  *  \param     new_state        Here is a list of possible states:
00388  *             - RX_ON        Requested transition to RX_ON state.
00389  *             - TRX_OFF      Requested transition to TRX_OFF state.
00390  *             - PLL_ON       Requested transition to PLL_ON state.
00391  *             - RX_AACK_ON   Requested transition to RX_AACK_ON state.
00392  *             - TX_ARET_ON   Requested transition to TX_ARET_ON state.
00393  *
00394  *  \retval    RADIO_SUCCESS          Requested state transition completed
00395  *                                  successfully.
00396  *  \retval    RADIO_INVALID_ARGUMENT Supplied function parameter out of bounds.
00397  *  \retval    RADIO_WRONG_STATE      Illegal state to do transition from.
00398  *  \retval    RADIO_BUSY_STATE       The radio transceiver is busy.
00399  *  \retval    RADIO_TIMED_OUT        The state transition could not be completed
00400  *                                  within resonable time.
00401  */
00402 static radio_status_t
00403 radio_set_trx_state(uint8_t new_state)
00404 {
00405     uint8_t original_state;
00406 
00407     /*Check function paramter and current state of the radio transceiver.*/
00408     if (!((new_state == TRX_OFF)    ||
00409           (new_state == RX_ON)      ||
00410           (new_state == PLL_ON)     ||
00411           (new_state == RX_AACK_ON) ||
00412           (new_state == TX_ARET_ON))){
00413         return RADIO_INVALID_ARGUMENT;
00414     }
00415 
00416         if (hal_get_slptr()) {
00417         return RADIO_WRONG_STATE;
00418     }
00419 
00420     /* Wait for radio to finish previous operation */
00421     rf230_waitidle();
00422  //   for(;;)
00423  //   {
00424         original_state = radio_get_trx_state();
00425   //      if (original_state != BUSY_TX_ARET &&
00426   //          original_state != BUSY_RX_AACK &&
00427   //          original_state != BUSY_RX && 
00428   //          original_state != BUSY_TX)
00429   //          break;
00430   //  }
00431 
00432     if (new_state == original_state){
00433         return RADIO_SUCCESS;
00434     }
00435 
00436 
00437     /* At this point it is clear that the requested new_state is: */
00438     /* TRX_OFF, RX_ON, PLL_ON, RX_AACK_ON or TX_ARET_ON. */
00439 
00440     /* The radio transceiver can be in one of the following states: */
00441     /* TRX_OFF, RX_ON, PLL_ON, RX_AACK_ON, TX_ARET_ON. */
00442     if(new_state == TRX_OFF){
00443         radio_reset_state_machine(); /* Go to TRX_OFF from any state. */
00444     } else {
00445         /* It is not allowed to go from RX_AACK_ON or TX_AACK_ON and directly to */
00446         /* TX_AACK_ON or RX_AACK_ON respectively. Need to go via RX_ON or PLL_ON. */
00447         if ((new_state == TX_ARET_ON) &&
00448             (original_state == RX_AACK_ON)){
00449             /* First do intermediate state transition to PLL_ON, then to TX_ARET_ON. */
00450             /* The final state transition to TX_ARET_ON is handled after the if-else if. */
00451             hal_subregister_write(SR_TRX_CMD, PLL_ON);
00452             delay_us(TIME_STATE_TRANSITION_PLL_ACTIVE);
00453         } else if ((new_state == RX_AACK_ON) &&
00454                  (original_state == TX_ARET_ON)){
00455             /* First do intermediate state transition to RX_ON, then to RX_AACK_ON. */
00456             /* The final state transition to RX_AACK_ON is handled after the if-else if. */
00457             hal_subregister_write(SR_TRX_CMD, RX_ON);
00458             delay_us(TIME_STATE_TRANSITION_PLL_ACTIVE);
00459         }
00460 
00461         /* Any other state transition can be done directly. */
00462         hal_subregister_write(SR_TRX_CMD, new_state);
00463 
00464         /* When the PLL is active most states can be reached in 1us. However, from */
00465         /* TRX_OFF the PLL needs time to activate. */
00466         if (original_state == TRX_OFF){
00467             delay_us(TIME_TRX_OFF_TO_PLL_ACTIVE);
00468         } else {
00469             delay_us(TIME_STATE_TRANSITION_PLL_ACTIVE);
00470         }
00471     } /*  end: if(new_state == TRX_OFF) ... */
00472 
00473     /*Verify state transition.*/
00474     radio_status_t set_state_status = RADIO_TIMED_OUT;
00475 
00476     if (radio_get_trx_state() == new_state){
00477         set_state_status = RADIO_SUCCESS;
00478     }
00479 
00480     return set_state_status;
00481 }
00482 
00483 void
00484 rf230_set_promiscuous_mode(bool isPromiscuous) {
00485 #if RF230_CONF_AUTOACK
00486     is_promiscuous = isPromiscuous;
00487 /* TODO: Figure out when to pass promisc state to 802.15.4 */
00488 //    radio_set_trx_state(is_promiscuous?RX_ON:RX_AACK_ON);
00489 #endif
00490 }
00491 
00492 bool
00493 rf230_is_ready_to_send() {
00494         switch(radio_get_trx_state()) {
00495                 case BUSY_TX:
00496                 case BUSY_TX_ARET:
00497                         return false;
00498         }
00499         
00500         return true;
00501 }
00502 
00503 
00504 static void
00505 flushrx(void)
00506 {
00507   rxframe[rxframe_head].length=0;
00508 }
00509 /*---------------------------------------------------------------------------*/
00510 static void
00511 on(void)
00512 {
00513 //   ENERGEST_OFF(ENERGEST_TYPE_LISTEN);//testing
00514   ENERGEST_ON(ENERGEST_TYPE_LISTEN);
00515   RF230_receive_on = 1;
00516 #ifdef RF230BB_HOOK_RADIO_ON
00517   RF230BB_HOOK_RADIO_ON();
00518 #endif
00519 
00520 /* If radio is off (slptr high), turn it on */
00521   if (hal_get_slptr()) {
00522     ENERGEST_ON(ENERGEST_TYPE_LED_RED);
00523 #if RF230BB_CONF_LEDONPORTE1
00524     PORTE|=(1<<PE1); //ledon
00525 #endif
00526 #if defined(__AVR_ATmega128RFA1__)
00527 /* Use the poweron interrupt for delay */
00528     rf230_interruptwait=1;
00529     sei();
00530     hal_set_slptr_low();
00531     while (rf230_interruptwait) {}
00532 #else
00533 /* SPI based radios. The wake time depends on board capacitance.
00534  * Make sure the delay is long enough, as using SPI too soon will reset the MCU!
00535  * Use 2x the nominal value for safety. 1.5x is not long enough for Raven!
00536  */
00537 //  uint8_t sreg = SREG;cli();
00538     hal_set_slptr_low();
00539     delay_us(2*TIME_SLEEP_TO_TRX_OFF);
00540 //  delay_us(TIME_SLEEP_TO_TRX_OFF+TIME_SLEEP_TO_TRX_OFF/2);
00541 //  SREG=sreg;
00542 #endif
00543   }
00544 
00545 #if RF230_CONF_AUTOACK
00546  // radio_set_trx_state(is_promiscuous?RX_ON:RX_AACK_ON);
00547   radio_set_trx_state(RX_AACK_ON);
00548 #else
00549   radio_set_trx_state(RX_ON);
00550 #endif
00551   rf230_waitidle();
00552 }
00553 static void
00554 off(void)
00555 {
00556 #if RF230BB_CONF_LEDONPORTE1
00557   PORTE&=~(1<<PE1); //ledoff
00558 #endif
00559 #ifdef RF230BB_HOOK_RADIO_OFF
00560   RF230BB_HOOK_RADIO_OFF();
00561 #endif
00562 
00563   /* Wait for any transmission to end */
00564   rf230_waitidle(); 
00565 
00566 #if RADIOALWAYSON
00567 /* Do not transmit autoacks when stack thinks radio is off */
00568   radio_set_trx_state(RX_ON);
00569 #else 
00570   /* Force the device into TRX_OFF. */   
00571   radio_reset_state_machine();
00572 #if RADIOSLEEPSWHENOFF
00573   /* Sleep Radio */
00574   hal_set_slptr_high();
00575   ENERGEST_OFF(ENERGEST_TYPE_LED_RED);
00576 #endif
00577 #endif /* RADIOALWAYSON */
00578 
00579    RF230_receive_on = 0;
00580    ENERGEST_OFF(ENERGEST_TYPE_LISTEN);
00581 }
00582 /*---------------------------------------------------------------------------*/
00583 static void
00584 set_txpower(uint8_t power)
00585 {
00586   if (power > TX_PWR_17_2DBM){
00587     power=TX_PWR_17_2DBM;
00588   }
00589   if (hal_get_slptr()) {
00590     DEBUGFLOW('f');
00591     PRINTF("rf230_set_txpower:Sleeping");  //happens with cxmac
00592   } else {
00593     DEBUGFLOW('g');
00594     hal_subregister_write(SR_TX_PWR, power);
00595   }
00596 }
00597 void rf230_setpendingbit(uint8_t value)
00598 {
00599   hal_subregister_write(SR_AACK_SET_PD, value);
00600 }
00601 #if 0
00602 /*----------------------------------------------------------------------------*/
00603 /**
00604     \brief Calibrate the internal RC oscillator
00605 
00606     This function calibrates the internal RC oscillator, based
00607     on an external 32KHz crystal connected to TIMER2. In order to
00608     verify the calibration result you can program the CKOUT fuse
00609     and monitor the CPU clock on an I/O pin.
00610 */
00611 #define AVR_ENTER_CRITICAL_REGION( ) {uint8_t volatile saved_sreg = SREG; cli( )
00612 #define AVR_LEAVE_CRITICAL_REGION( ) SREG = saved_sreg;}
00613     uint8_t osccal_original,osccal_calibrated;
00614 void
00615 calibrate_rc_osc_32k(void)
00616 {
00617 
00618     /* Calibrate RC Oscillator: The calibration routine is done by clocking TIMER2
00619      * from the external 32kHz crystal while running an internal timer simultaneously.
00620      * The internal timer will be clocked at the same speed as the internal RC
00621      * oscillator, while TIMER2 is running at 32768 Hz. This way it is not necessary
00622      * to use a timed loop, and keep track cycles in timed loop vs. optimization
00623      * and compiler.
00624      */
00625     uint8_t osccal_original = OSCCAL;
00626     volatile uint16_t temp;
00627      
00628     /* Start with current value, which for some MCUs could be in upper or lower range */
00629 
00630 //  PRR0 &= ~((1 << PRTIM2)|(1 << PRTIM1)); /*  Enable Timer 1 and 2 */
00631 
00632     TIMSK2 = 0x00; /*  Disable Timer/Counter 2 interrupts. */
00633     TIMSK1 = 0x00; /*  Disable Timer/Counter 1 interrupts. */
00634 
00635     /* Enable TIMER/COUNTER 2 to be clocked from the external 32kHz clock crystal.
00636      * Then wait for the timer to become stable before doing any calibration.
00637      */
00638     ASSR |= (1 << AS2);
00639  // while (ASSR & ((1 << TCN2UB)|(1 << OCR2AUB)|(1 << TCR2AUB)|(1 << TCR2BUB))) { ; }
00640     TCCR2B = 1 << CS20;   /* run timer 2 at divide by 1 (32KHz) */
00641 
00642     delay_us(50000UL);  //crystal takes significant time to stabilize
00643     AVR_ENTER_CRITICAL_REGION();
00644 
00645     uint8_t counter = 128;
00646     bool cal_ok = false;
00647     do{
00648         /* wait for timer to be ready for updated config */
00649         TCCR1B = 1 << CS10;
00650 
00651         while (ASSR & ((1 << TCN2UB)|(1 << OCR2AUB)|(1 << TCR2AUB)|(1 << TCR2BUB))) { ; }
00652 
00653         TCNT2 = 0x80;
00654         TCNT1 = 0;
00655 
00656         TIFR2 = 0xFF; /* Clear TIFR2 flags (Yes, really) */
00657 
00658         /* Wait for TIMER/COUNTER 2 to overflow. Stop TIMER/COUNTER 1 and 2, and
00659          * read the counter value of TIMER/COUNTER 1. It will now contain the
00660          * number of cpu cycles elapsed within the 3906.25 microsecond period.
00661          */
00662         while (!(TIFR2 & (1 << TOV2))){
00663             ;
00664             }
00665         temp = TCNT1;
00666 
00667         TCCR1B = 0;
00668 /* Defining these as floating point introduces a lot of code and the 256 byte .clz table to RAM */
00669 /* At 8 MHz we would expect 8*3906.25 = 31250 CPU clocks */
00670 #define cal_upper 32812 //(31250*1.05) // 32812 = 0x802c
00671 #define cal_lower 29687 //(31250*0.95) // 29687 = 0x73f7
00672         /* Iteratively reduce the error to be within limits */
00673         if (temp < cal_lower) {
00674             /* Too slow. Put the hammer down. */
00675             if (OSCCAL==0x7e) break; //stay in lowest range
00676             if (OSCCAL==0xff) break;
00677             OSCCAL++;
00678         } else if (temp > cal_upper) {
00679             /* Too fast, retard. */
00680             if (OSCCAL==0x81) break; //stay in highest range
00681             if (OSCCAL==0x00) break;
00682             OSCCAL--;
00683         } else {
00684             /* The CPU clock frequency is now within +/- 0.5% of the target value. */
00685             cal_ok = true;
00686         }
00687 
00688         counter--;
00689     } while ((counter != 0) && (false == cal_ok));
00690 
00691      osccal_calibrated=OSCCAL;   
00692     if (true != cal_ok) {
00693         /* We failed, therefore restore previous OSCCAL value. */
00694         OSCCAL = osccal_original;
00695     }
00696 
00697     OSCCAL = osccal_original;
00698     TCCR2B = 0;
00699 
00700     ASSR &= ~(1 << AS2);
00701 
00702     /* Disable both timers again to save power. */
00703     //    PRR0 |= (1 << PRTIM2);/* |(1 << PRTIM1); */
00704 
00705     AVR_LEAVE_CRITICAL_REGION();
00706 }
00707 #endif
00708 /*---------------------------------------------------------------------------*/
00709 int
00710 rf230_init(void)
00711 {
00712   uint8_t i;
00713   DEBUGFLOW('i');
00714   /* Wait in case VCC just applied */
00715   delay_us(TIME_TO_ENTER_P_ON);
00716   /* Initialize Hardware Abstraction Layer */
00717   hal_init();
00718  
00719   /* Calibrate oscillator */
00720  // printf_P(PSTR("\nBefore calibration OSCCAL=%x\n"),OSCCAL);
00721  // calibrate_rc_osc_32k();
00722  // printf_P(PSTR("After calibration OSCCAL=%x\n"),OSCCAL); 
00723 
00724   /* Set receive buffers empty and point to the first */
00725   for (i=0;i<RF230_CONF_RX_BUFFERS;i++) rxframe[i].length=0;
00726   rxframe_head=0;rxframe_tail=0;
00727   
00728   /* Do full rf230 Reset */
00729   hal_set_rst_low();
00730   hal_set_slptr_low();
00731 #if 1
00732   /* On powerup a TIME_RESET delay is needed here, however on some other MCU reset
00733    * (JTAG, WDT, Brownout) the radio may be sleeping. It can enter an uncertain
00734    * state (sending wrong hardware FCS for example) unless the full wakeup delay
00735    * is done.
00736    * Wake time depends on board capacitance; use 2x the nominal delay for safety.
00737    * See www.avrfreaks.net/index.php?name=PNphpBB2&file=viewtopic&t=78725
00738    */
00739   delay_us(2*TIME_SLEEP_TO_TRX_OFF);
00740 #else
00741   delay_us(TIME_RESET);
00742 #endif
00743   hal_set_rst_high();
00744 
00745   /* Force transition to TRX_OFF */
00746   hal_subregister_write(SR_TRX_CMD, CMD_FORCE_TRX_OFF);
00747   delay_us(TIME_P_ON_TO_TRX_OFF);
00748   
00749   /* Verify that it is a supported version */
00750   /* Note gcc optimizes this away if DEBUG is not set! */
00751   //ATMEGA128RFA1 - version 4, ID 31
00752   uint8_t tvers = hal_register_read(RG_VERSION_NUM);
00753   uint8_t tmanu = hal_register_read(RG_MAN_ID_0);
00754 
00755   if ((tvers != RF230_REVA) && (tvers != RF230_REVB))
00756     PRINTF("rf230: Unsupported version %u\n",tvers);
00757   if (tmanu != SUPPORTED_MANUFACTURER_ID) 
00758     PRINTF("rf230: Unsupported manufacturer ID %u\n",tmanu);
00759 
00760   PRINTF("rf230: Version %u, ID %u\n",tvers,tmanu);
00761   
00762   rf230_warm_reset();
00763  
00764  /* Start the packet receive process */
00765   process_start(&rf230_process, NULL);
00766  
00767  /* Leave radio in on state (?)*/
00768   on();
00769 
00770   return 1;
00771 }
00772 /*---------------------------------------------------------------------------*/
00773 /* Used to reinitialize radio parameters without losing pan and mac address, channel, power, etc. */
00774 void rf230_warm_reset(void) {
00775 #if RF230_CONF_SNEEZER && JACKDAW
00776   /* Take jackdaw radio out of test mode */
00777 #warning Manipulating PORTB pins for RF230 Sneezer mode!
00778   PORTB &= ~(1<<7);
00779   DDRB  &= ~(1<<7);
00780 #endif
00781   
00782   hal_register_write(RG_IRQ_MASK, RF230_SUPPORTED_INTERRUPT_MASK);
00783 
00784   /* Set up number of automatic retries 0-15 (0 implies PLL_ON sends instead of the extended TX_ARET mode */
00785   hal_subregister_write(SR_MAX_FRAME_RETRIES, RF230_CONF_AUTORETRIES );
00786  
00787  /* Set up carrier sense/clear channel assesment parameters for extended operating mode */
00788   hal_subregister_write(SR_MAX_CSMA_RETRIES, 5 );//highest allowed retries
00789   hal_register_write(RG_CSMA_BE, 0x80);       //min backoff exponent 0, max 8 (highest allowed)
00790   hal_register_write(RG_CSMA_SEED_0,hal_register_read(RG_PHY_RSSI) );//upper two RSSI reg bits RND_VALUE are random in rf231
00791  // hal_register_write(CSMA_SEED_1,42 );
00792 
00793   /* CCA Mode Mode 1=Energy above threshold  2=Carrier sense only  3=Both 0=Either (RF231 only) */
00794 //hal_subregister_write(SR_CCA_MODE,1);  //1 is the power-on default
00795 
00796   /* Carrier sense threshold (not implemented in RF230 or RF231) */
00797 // hal_subregister_write(SR_CCA_CS_THRES,1);
00798 
00799   /* Receiver sensitivity. If nonzero rf231/128rfa1 saves 0.5ma in rx mode */
00800   /* Not implemented on rf230 but does not hurt to write to it */
00801 #ifdef RF230_MIN_RX_POWER
00802 #if RF230_MIN_RX_POWER > 84
00803 #warning rf231 power threshold clipped to -48dBm by hardware register
00804  hal_register_write(RG_RX_SYN, 0xf);
00805 #elif RF230_MIN_RX_POWER < 0
00806 #error RF230_MIN_RX_POWER can not be negative!
00807 #endif
00808   hal_register_write(RG_RX_SYN, RF230_MIN_RX_POWER/6 + 1); //1-15 -> -90 to -48dBm
00809 #endif
00810 
00811   /* CCA energy threshold = -91dB + 2*SR_CCA_ED_THRESH. Reset defaults to -77dB */
00812   /* Use RF230 base of -91;  RF231 base is -90 according to datasheet */
00813 #ifdef RF230_CONF_CCA_THRES
00814 #if RF230_CONF_CCA_THRES < -91
00815 #warning
00816 #warning RF230_CONF_CCA_THRES below hardware limit, setting to -91dBm
00817 #warning
00818   hal_subregister_write(SR_CCA_ED_THRES,0);  
00819 #elif RF230_CONF_CCA_THRES > -61
00820 #warning
00821 #warning RF230_CONF_CCA_THRES above hardware limit, setting to -61dBm
00822 #warning
00823   hal_subregister_write(SR_CCA_ED_THRES,15);  
00824 #else
00825   hal_subregister_write(SR_CCA_ED_THRES,(RF230_CONF_CCA_THRES+91)/2);  
00826 #endif
00827 #endif
00828 
00829   /* Use automatic CRC unless manual is specified */
00830 #if RF230_CONF_CHECKSUM
00831   hal_subregister_write(SR_TX_AUTO_CRC_ON, 0);
00832 #else
00833   hal_subregister_write(SR_TX_AUTO_CRC_ON, 1);
00834 #endif
00835 
00836 /* Limit tx power for testing miniature Raven mesh */
00837 #ifdef RF230_MAX_TX_POWER
00838   set_txpower(RF230_MAX_TX_POWER);  //0=3dbm 15=-17.2dbm
00839 #endif
00840 }
00841 /*---------------------------------------------------------------------------*/
00842 static uint8_t buffer[RF230_MAX_TX_FRAME_LENGTH+AUX_LEN];
00843 
00844 static int
00845 rf230_transmit(unsigned short payload_len)
00846 {
00847   int txpower;
00848   uint8_t total_len;
00849   uint8_t tx_result;
00850 #if RF230_CONF_TIMESTAMPS
00851   struct timestamp timestamp;
00852 #endif /* RF230_CONF_TIMESTAMPS */
00853 
00854   /* If radio is sleeping we have to turn it on first */
00855   /* This automatically does the PLL calibrations */
00856   if (hal_get_slptr()) {
00857 #if defined(__AVR_ATmega128RFA1__)
00858         ENERGEST_ON(ENERGEST_TYPE_LED_RED);
00859 #if RF230BB_CONF_LEDONPORTE1
00860     PORTE|=(1<<PE1); //ledon
00861 #endif
00862         rf230_interruptwait=1;
00863         hal_set_slptr_low();
00864 //      while (rf230_interruptwait) {}  
00865     {
00866       int i;
00867       for (i=0;i<10000;i++) {
00868         if (!rf230_interruptwait) break;
00869       }
00870     }
00871 #else
00872     hal_set_slptr_low();
00873     DEBUGFLOW('j');
00874     delay_us(2*TIME_SLEEP_TO_TRX_OFF); //extra delay depends on board capacitance
00875 //      delay_us(TIME_SLEEP_TO_TRX_OFF+TIME_SLEEP_TO_TRX_OFF/2);
00876 #endif
00877 
00878   } else {
00879 #if RADIO_CONF_CALIBRATE_INTERVAL
00880   /* If nonzero, do periodic calibration. See clock.c */
00881     if (rf230_calibrate) {
00882       DEBUGFLOW('k');
00883       hal_subregister_write(SR_PLL_CF_START,1);   //takes 80us max
00884       hal_subregister_write(SR_PLL_DCU_START,1); //takes 6us, concurrently
00885       rf230_calibrate=0;
00886       rf230_calibrated=1;
00887       delay_us(80); //?
00888     }
00889 #endif
00890   }
00891  
00892   /* Wait for any previous operation or state transition to finish */
00893   rf230_waitidle();
00894   if(RF230_receive_on) {
00895     ENERGEST_OFF(ENERGEST_TYPE_LISTEN);
00896   }
00897   /* Prepare to transmit */
00898 #if RF230_CONF_AUTORETRIES
00899   radio_set_trx_state(TX_ARET_ON);
00900   DEBUGFLOW('t');
00901 #else
00902   radio_set_trx_state(PLL_ON);
00903   DEBUGFLOW('T');
00904 #endif
00905 
00906   txpower = 0;
00907   
00908   if(packetbuf_attr(PACKETBUF_ATTR_RADIO_TXPOWER) > 0) {
00909     /* Remember the current transmission power */
00910     txpower = rf230_get_txpower();
00911     /* Set the specified transmission power */
00912     set_txpower(packetbuf_attr(PACKETBUF_ATTR_RADIO_TXPOWER) - 1);
00913   }
00914 
00915   total_len = payload_len + AUX_LEN;
00916 
00917 #if RF230_CONF_TIMESTAMPS
00918   rtimer_clock_t txtime = timesynch_time();
00919 #endif /* RF230_CONF_TIMESTAMPS */
00920 
00921   ENERGEST_ON(ENERGEST_TYPE_TRANSMIT);
00922   
00923 #if defined(__AVR_ATmega128RFA1__)
00924 /* No interrupts across frame download! */
00925   cli();
00926 /* slow down the transmit? */
00927  //   delay_us(500);
00928 #endif
00929  /* Toggle the SLP_TR pin to initiate the frame transmission */
00930   hal_set_slptr_high();
00931   hal_set_slptr_low();
00932   hal_frame_write(buffer, total_len);
00933 #if defined(__AVR_ATmega128RFA1__)
00934  sei();
00935 #endif
00936   PRINTF("rf230_transmit: %d\n", (int)total_len);
00937 #if DEBUG>1
00938 /* Note the dumped packet will have a zero checksum unless compiled with RF230_CONF_CHECKSUM
00939  * since we don't know what it will be if calculated by the hardware.
00940  */
00941   {
00942     uint8_t i;
00943     PRINTF("0000");       //Start a new wireshark packet
00944     for (i=0;i<total_len;i++) PRINTF(" %02x",buffer[i]);
00945     PRINTF("\n");
00946   }
00947 #endif
00948 
00949 #if RADIOSTATS
00950   RF230_sendpackets++;
00951 #endif
00952  
00953  /* We wait until transmission has ended so that we get an
00954      accurate measurement of the transmission time.*/
00955   rf230_waitidle();
00956 
00957  /* Get the transmission result */  
00958 #if RF230_CONF_AUTORETRIES
00959   tx_result = hal_subregister_read(SR_TRAC_STATUS);
00960 #else
00961   tx_result=RADIO_TX_OK;
00962 #endif
00963 
00964 #ifdef ENERGEST_CONF_LEVELDEVICE_LEVELS
00965   ENERGEST_OFF_LEVEL(ENERGEST_TYPE_TRANSMIT,rf230_get_txpower());
00966 #endif
00967 
00968  /* Restore the transmission power */
00969  if(packetbuf_attr(PACKETBUF_ATTR_RADIO_TXPOWER) > 0) {
00970     set_txpower(txpower & 0xff);
00971   }
00972  
00973 #if RF230_CONF_TIMESTAMPS
00974   setup_time_for_transmission = txtime - timestamp.time;
00975 
00976   if(num_transmissions < 10000) {
00977     total_time_for_transmission += timesynch_time() - txtime;
00978     total_transmission_len += total_len;
00979     num_transmissions++;
00980   }
00981 
00982 #endif /* RF230_CONF_TIMESTAMPS */
00983 
00984   ENERGEST_OFF(ENERGEST_TYPE_TRANSMIT);
00985   if(RF230_receive_on) {
00986     DEBUGFLOW('l');
00987     ENERGEST_ON(ENERGEST_TYPE_LISTEN);
00988     on();
00989   } else {
00990 #if RADIOALWAYSON
00991     /* Enable reception */
00992     on();
00993 #else
00994     off();
00995     PRINTF("rf230_transmit: turning radio off\n");
00996 #endif
00997   }
00998 
00999 #if RF230_INSERTACK
01000    ack_pending = 0;
01001 #endif
01002 
01003   if (tx_result==1) {        //success, data pending from addressee
01004     tx_result=RADIO_TX_OK;           //handle as ordinary success
01005   }
01006 
01007   if (tx_result==RADIO_TX_OK) {
01008     RIMESTATS_ADD(lltx);
01009     if(packetbuf_attr(PACKETBUF_ATTR_RELIABLE))
01010       RIMESTATS_ADD(ackrx);             //ack was requested and received
01011 #if RF230_INSERTACK
01012   /* Not PAN broadcast to FFFF, and ACK was requested and received */
01013   if (!((buffer[5]==0xff) && (buffer[6]==0xff)) && (buffer[0]&(1<<6)))
01014     ack_pending=1;
01015 #endif
01016 
01017   } else if (tx_result==3) {        //CSMA channel access failure
01018     DEBUGFLOW('m');
01019     RIMESTATS_ADD(contentiondrop);
01020     PRINTF("rf230_transmit: Transmission never started\n");
01021     tx_result = RADIO_TX_COLLISION;
01022   } else if (tx_result==5) {        //Expected ACK, none received
01023     DEBUGFLOW('n');
01024     tx_result = RADIO_TX_NOACK;
01025     PRINTF("rf230_transmit: ACK not received\n");
01026     RIMESTATS_ADD(badackrx);            //ack was requested but not received
01027   } else if (tx_result==7) {        //Invalid (Can't happen since waited for idle above?)
01028     DEBUGFLOW('o');
01029     tx_result = RADIO_TX_ERR;
01030   }
01031 
01032   return tx_result;
01033 }
01034 /*---------------------------------------------------------------------------*/
01035 static int
01036 rf230_prepare(const void *payload, unsigned short payload_len)
01037 {
01038   int ret = 0;
01039   uint8_t total_len,*pbuf;
01040 #if RF230_CONF_TIMESTAMPS
01041   struct timestamp timestamp;
01042 #endif
01043 #if RF230_CONF_CHECKSUM
01044   uint16_t checksum;
01045 #endif
01046 #if RF230_INSERTACK
01047 /* The sequence number is needed to construct the ack packet */
01048   ack_seqnum=*(((uint8_t *)payload)+2);
01049 #endif
01050 
01051   DEBUGFLOW('p');
01052 
01053 //  PRINTF("rf230: sending %d bytes\n", payload_len);
01054 //  PRINTSHORT("s%d ",payload_len);
01055 
01056   RIMESTATS_ADD(tx);
01057 
01058 #if RF230_CONF_CHECKSUM
01059   checksum = crc16_data(payload, payload_len, 0);
01060 #endif
01061  
01062   /* Copy payload to RAM buffer */
01063   total_len = payload_len + AUX_LEN;
01064   if (total_len > RF230_MAX_TX_FRAME_LENGTH){
01065 #if RADIOSTATS
01066     RF230_sendfail++;
01067 #endif
01068     PRINTF("rf230_prepare: packet too large (%d, max: %d)\n",total_len,RF230_MAX_TX_FRAME_LENGTH);
01069     ret = -1;
01070     goto bail;
01071   }
01072   pbuf=&buffer[0];
01073   memcpy(pbuf,payload,payload_len);
01074   pbuf+=payload_len;
01075 
01076 #if RF230_CONF_CHECKSUM
01077   memcpy(pbuf,&checksum,CHECKSUM_LEN);
01078   pbuf+=CHECKSUM_LEN;
01079 #endif
01080 
01081 #if RF230_CONF_TIMESTAMPS
01082   timestamp.authority_level = timesynch_authority_level();
01083   timestamp.time = timesynch_time();
01084   memcpy(pbuf,&timestamp,TIMESTAMP_LEN);
01085   pbuf+=TIMESTAMP_LEN;
01086 #endif
01087 /*------------------------------------------------------------*/  
01088 
01089 #ifdef RF230BB_HOOK_TX_PACKET
01090 #if !RF230_CONF_CHECKSUM
01091   { // Add a checksum before we log the packet out
01092     uint16_t checksum;
01093     checksum = crc16_data(payload, payload_len, 0);
01094     memcpy(buffer+total_len-CHECKSUM_LEN,&checksum,CHECKSUM_LEN);
01095   }
01096 #endif /* RF230_CONF_CHECKSUM */
01097   RF230BB_HOOK_TX_PACKET(buffer,total_len);
01098 #endif
01099   
01100 
01101 bail:
01102   return ret;
01103 }
01104 /*---------------------------------------------------------------------------*/
01105 static int
01106 rf230_send(const void *payload, unsigned short payload_len)
01107 {
01108         int ret = 0;
01109 
01110 #ifdef RF230BB_HOOK_IS_SEND_ENABLED
01111         if(!RF230BB_HOOK_IS_SEND_ENABLED()) {
01112                 goto bail;
01113         }
01114 #endif
01115         
01116         if((ret=rf230_prepare(payload, payload_len))) {
01117             PRINTF("rf230_send: Unable to send, prep failed (%d)\n",ret);
01118                 goto bail;
01119         }
01120 
01121         ret = rf230_transmit(payload_len);
01122         
01123 bail:
01124 #if RADIOSTATS
01125     if (ret) RF230_sendfail++;
01126 #endif
01127         return ret;
01128 }
01129 /*---------------------------------------------------------------------------*/
01130 int
01131 rf230_off(void)
01132 {
01133   /* Don't do anything if we are already turned off. */
01134   if(RF230_receive_on == 0) {
01135     return 0;
01136   }
01137 
01138   /* If we are currently receiving a packet, we still call off(),
01139      as that routine waits until Rx is complete (packet uploaded in ISR
01140      so no worries about losing it). If using RX_AACK_MODE, chances are
01141      the packet is not for us and will be discarded. */
01142   if (!rf230_isidle()) {
01143     PRINTF("rf230_off: busy receiving\r\n");
01144     //return 1;
01145   }
01146 
01147   off();
01148   return 0;
01149 }
01150 /*---------------------------------------------------------------------------*/
01151 int
01152 rf230_on(void)
01153 {
01154   if(RF230_receive_on) {
01155     DEBUGFLOW('q');
01156     return 1;
01157   }
01158 
01159   on();
01160   return 1;
01161 }
01162 /*---------------------------------------------------------------------------*/
01163 uint8_t
01164 rf230_get_channel(void)
01165 {
01166 //jackdaw reads zero channel, raven reads correct channel?
01167 //return hal_subregister_read(SR_CHANNEL);
01168   return channel;
01169 }
01170 /*---------------------------------------------------------------------------*/
01171 void
01172 rf230_set_channel(uint8_t c)
01173 {
01174  /* Wait for any transmission to end. */
01175   PRINTF("rf230: Set Channel %u\n",c);
01176   rf230_waitidle();
01177   channel=c;
01178   hal_subregister_write(SR_CHANNEL, c);
01179 }
01180 /*---------------------------------------------------------------------------*/
01181 void
01182 rf230_listen_channel(uint8_t c)
01183 {
01184  /* Same as set channel but forces RX_ON state for sniffer or energy scan */
01185 //  PRINTF("rf230: Listen Channel %u\n",c);
01186   rf230_set_channel(c);
01187   radio_set_trx_state(RX_ON);
01188 }
01189 /*---------------------------------------------------------------------------*/
01190 void
01191 rf230_set_pan_addr(unsigned pan,
01192                     unsigned addr,
01193                     const uint8_t ieee_addr[8])
01194 //rf230_set_pan_addr(uint16_t pan,uint16_t addr,uint8_t *ieee_addr)
01195 {
01196   PRINTF("rf230: PAN=%x Short Addr=%x\n",pan,addr);
01197   
01198   uint8_t abyte;
01199   abyte = pan & 0xFF;
01200   hal_register_write(RG_PAN_ID_0,abyte);
01201   abyte = (pan >> 8*1) & 0xFF;
01202   hal_register_write(RG_PAN_ID_1, abyte);
01203 
01204   abyte = addr & 0xFF;
01205   hal_register_write(RG_SHORT_ADDR_0, abyte);
01206   abyte = (addr >> 8*1) & 0xFF;
01207   hal_register_write(RG_SHORT_ADDR_1, abyte);  
01208 
01209   if (ieee_addr != NULL) {
01210     PRINTF("MAC=%x",*ieee_addr);
01211     hal_register_write(RG_IEEE_ADDR_7, *ieee_addr++);
01212     PRINTF(":%x",*ieee_addr);
01213     hal_register_write(RG_IEEE_ADDR_6, *ieee_addr++);
01214     PRINTF(":%x",*ieee_addr);
01215     hal_register_write(RG_IEEE_ADDR_5, *ieee_addr++);
01216     PRINTF(":%x",*ieee_addr);
01217     hal_register_write(RG_IEEE_ADDR_4, *ieee_addr++);
01218     PRINTF(":%x",*ieee_addr);
01219     hal_register_write(RG_IEEE_ADDR_3, *ieee_addr++);
01220     PRINTF(":%x",*ieee_addr);
01221     hal_register_write(RG_IEEE_ADDR_2, *ieee_addr++);
01222     PRINTF(":%x",*ieee_addr);
01223     hal_register_write(RG_IEEE_ADDR_1, *ieee_addr++);
01224     PRINTF(":%x",*ieee_addr);
01225     hal_register_write(RG_IEEE_ADDR_0, *ieee_addr);
01226     PRINTF("\n");
01227   }
01228 }
01229 /*---------------------------------------------------------------------------*/
01230 /*
01231  * Interrupt leaves frame intact in FIFO.
01232  */
01233 #if RF230_CONF_TIMESTAMPS
01234 static volatile rtimer_clock_t interrupt_time;
01235 static volatile int interrupt_time_set;
01236 #endif /* RF230_CONF_TIMESTAMPS */
01237 #if RF230_TIMETABLE_PROFILING
01238 #define rf230_timetable_size 16
01239 TIMETABLE(rf230_timetable);
01240 TIMETABLE_AGGREGATE(aggregate_time, 10);
01241 #endif /* RF230_TIMETABLE_PROFILING */
01242 int
01243 rf230_interrupt(void)
01244 {
01245   /* Poll the receive process, unless the stack thinks the radio is off */
01246 #if RADIOALWAYSON
01247 if (RF230_receive_on) {
01248   DEBUGFLOW('+');
01249 #endif
01250 #if RF230_CONF_TIMESTAMPS
01251   interrupt_time = timesynch_time();
01252   interrupt_time_set = 1;
01253 #endif /* RF230_CONF_TIMESTAMPS */
01254 
01255   process_poll(&rf230_process);
01256   
01257 #if RF230_TIMETABLE_PROFILING
01258   timetable_clear(&rf230_timetable);
01259   TIMETABLE_TIMESTAMP(rf230_timetable, "interrupt");
01260 #endif /* RF230_TIMETABLE_PROFILING */
01261 
01262   rf230_pending = 1;
01263   
01264 #if RADIOSTATS //TODO:This will double count buffered packets
01265   RF230_receivepackets++;
01266 #endif
01267   RIMESTATS_ADD(llrx);
01268 
01269 #if RADIOALWAYSON
01270 } else {
01271   DEBUGFLOW('-');
01272   rxframe[rxframe_head].length=0;
01273 }
01274 #endif
01275   return 1;
01276 }
01277 /*---------------------------------------------------------------------------*/
01278 /* Process to handle input packets
01279  * Receive interrupts cause this process to be polled
01280  * It calls the core MAC layer which calls rf230_read to get the packet
01281  * rf230processflag can be printed in the main idle loop for debugging
01282  */
01283 #if 0
01284 uint8_t rf230processflag;
01285 #define RF230PROCESSFLAG(arg) rf230processflag=arg
01286 #else
01287 #define RF230PROCESSFLAG(arg)
01288 #endif
01289 
01290 PROCESS_THREAD(rf230_process, ev, data)
01291 {
01292   int len;
01293   PROCESS_BEGIN();
01294   RF230PROCESSFLAG(99);
01295 
01296   while(1) {
01297     PROCESS_YIELD_UNTIL(ev == PROCESS_EVENT_POLL);
01298     RF230PROCESSFLAG(42);
01299 #if RF230_TIMETABLE_PROFILING
01300     TIMETABLE_TIMESTAMP(rf230_timetable, "poll");
01301 #endif /* RF230_TIMETABLE_PROFILING */
01302 
01303     rf230_pending = 0;
01304 
01305     packetbuf_clear();
01306 
01307     /* Turn off interrupts to avoid ISR writing to the same buffers we are reading. */
01308     HAL_ENTER_CRITICAL_REGION();
01309 
01310     len = rf230_read(packetbuf_dataptr(), PACKETBUF_SIZE);        
01311 
01312     /* Restore interrupts. */
01313     HAL_LEAVE_CRITICAL_REGION();
01314     PRINTF("rf230_read: %u bytes lqi %u\n",len,rf230_last_correlation);
01315 
01316     RF230PROCESSFLAG(1);
01317     if(len > 0) {
01318       packetbuf_set_datalen(len);
01319       RF230PROCESSFLAG(2);
01320       NETSTACK_RDC.input();
01321 #if RF230_TIMETABLE_PROFILING
01322       TIMETABLE_TIMESTAMP(rf230_timetable, "end");
01323       timetable_aggregate_compute_detailed(&aggregate_time,
01324                                            &rf230_timetable);
01325       timetable_clear(&rf230_timetable);
01326 #endif /* RF230_TIMETABLE_PROFILING */
01327     } else {
01328 #if RADIOSTATS
01329        RF230_receivefail++;
01330 #endif
01331     }
01332   }
01333 
01334   PROCESS_END();
01335 }
01336 /* Read packet that was uploaded from Radio in ISR, else return zero.
01337  * The two-byte checksum is appended but the returned length does not include it.
01338  * Frames are buffered in the interrupt routine so this routine
01339  * does not access the hardware or change its status.
01340  * However, this routine must be called with interrupts disabled to avoid ISR
01341  * writing to the same buffer we are reading.
01342  * As a result, PRINTF cannot be used in here.
01343  */
01344 /*---------------------------------------------------------------------------*/
01345 static int
01346 rf230_read(void *buf, unsigned short bufsize)
01347 {
01348   uint8_t len,*framep;
01349 #if FOOTER_LEN
01350   uint8_t footer[FOOTER_LEN];
01351 #endif
01352 #if RF230_CONF_CHECKSUM
01353   uint16_t checksum;
01354 #endif
01355 #if RF230_CONF_TIMESTAMPS
01356   struct timestamp t;
01357 #endif
01358 #if RF230_INSERTACK
01359 /* Return an ACK to the mac layer */
01360   if(ack_pending && bufsize == 3){      
01361     ack_pending=0;
01362     uint8_t *buff=(uint8_t *)buf;
01363     buff[0]=2;
01364     buff[1]=0;
01365     buff[2]=ack_seqnum;
01366     return bufsize;
01367  }
01368 #endif
01369 
01370   /* The length includes the twp-byte checksum but not the LQI byte */
01371   len=rxframe[rxframe_head].length;
01372   if (len==0) {
01373 #if RADIOALWAYSON && DEBUGFLOWSIZE
01374    if (RF230_receive_on==0) {if (debugflow[debugflowsize-1]!='z') DEBUGFLOW('z');} //cxmac calls with radio off?
01375 #endif
01376     return 0;
01377   }
01378 
01379 #if RADIOALWAYSON
01380 if (RF230_receive_on) {
01381 #else
01382 if (hal_get_slptr()) {
01383   DEBUGFLOW('!');
01384   return 0;
01385 }
01386 if (!RF230_receive_on) {
01387   DEBUGFLOW('[');
01388   return 0;
01389 }
01390 #endif
01391 
01392 #if RF230_CONF_TIMESTAMPS
01393   if(interrupt_time_set) {
01394     rf230_time_of_arrival = interrupt_time;
01395     interrupt_time_set = 0;
01396   } else {
01397     rf230_time_of_arrival = 0;
01398   }
01399   rf230_time_of_departure = 0;
01400 #endif /* RF230_CONF_TIMESTAMPS */
01401 
01402   // can't use PRINTF as interrupts are disabled
01403 // PRINTSHORT("r%d",rxframe[rxframe_head].length);  
01404   //PRINTF("rf230_read: %u bytes lqi %u crc %u\n",rxframe[rxframe_head].length,rxframe[rxframe_head].lqi,rxframe[rxframe_head].crc);
01405 #if DEBUG>1
01406  {
01407     //uint8_t i;
01408     //PRINTF("0000");
01409     //for (i=0;i<rxframe[rxframe_head].length;i++) PRINTF(" %02x",rxframe[rxframe_head].data[i]);
01410     //PRINTF("\n");
01411   }
01412 #endif
01413 
01414 //if(len > RF230_MAX_PACKET_LEN) {
01415   if(len > RF230_MAX_TX_FRAME_LENGTH) {
01416     /* Oops, we must be out of sync. */
01417     DEBUGFLOW('u');
01418     flushrx();
01419     RIMESTATS_ADD(badsynch);
01420     return 0;
01421   }
01422 
01423   if(len <= AUX_LEN) {
01424     DEBUGFLOW('s');
01425     //PRINTF("len <= AUX_LEN\n");
01426     flushrx();
01427     RIMESTATS_ADD(tooshort);
01428     return 0;
01429   }
01430 
01431   if(len - AUX_LEN > bufsize) {
01432     DEBUGFLOW('v');
01433     //PRINTF("len - AUX_LEN > bufsize\n");
01434     flushrx();
01435     RIMESTATS_ADD(toolong);
01436     return 0;
01437   }
01438  /* Transfer the frame, stripping the footer, but copying the checksum */
01439   framep=&(rxframe[rxframe_head].data[0]);
01440   memcpy(buf,framep,len-AUX_LEN+CHECKSUM_LEN);
01441   rf230_last_correlation = rxframe[rxframe_head].lqi;
01442 
01443   /* Clear the length field to allow buffering of the next packet */
01444   rxframe[rxframe_head].length=0;
01445   rxframe_head++;if (rxframe_head >= RF230_CONF_RX_BUFFERS) rxframe_head=0;
01446   /* If another packet has been buffered, schedule another receive poll */
01447   if (rxframe[rxframe_head].length) rf230_interrupt();
01448   
01449  /* Point to the checksum */
01450   framep+=len-AUX_LEN; 
01451 #if RF230_CONF_CHECKSUM
01452   memcpy(&checksum,framep,CHECKSUM_LEN);
01453 #endif /* RF230_CONF_CHECKSUM */
01454   framep+=CHECKSUM_LEN;
01455 #if RF230_CONF_TIMESTAMPS
01456   memcpy(&t,framep,TIMESTAMP_LEN);
01457 #endif /* RF230_CONF_TIMESTAMPS */
01458   framep+=TIMESTAMP_LEN;
01459 #if FOOTER_LEN
01460   memcpy(footer,framep,FOOTER_LEN);
01461 #endif
01462 #if RF230_CONF_CHECKSUM
01463   if(checksum != crc16_data(buf, len - AUX_LEN, 0)) {
01464     DEBUGFLOW('w');
01465     //PRINTF("checksum failed 0x%04x != 0x%04x\n",
01466     //  checksum, crc16_data(buf, len - AUX_LEN, 0));
01467   }
01468 #if FOOTER_LEN
01469   if(footer[1] & FOOTER1_CRC_OK &&
01470      checksum == crc16_data(buf, len - AUX_LEN, 0)) {
01471 #endif
01472 #endif /* RF230_CONF_CHECKSUM */
01473 
01474 /* Get the received signal strength for the packet, 0-84 dB above rx threshold */
01475 #if 0   //more general
01476     rf230_last_rssi = rf230_get_raw_rssi();
01477 #else   //faster
01478 #if RF230_CONF_AUTOACK
01479  //   rf230_last_rssi = hal_subregister_read(SR_ED_LEVEL);  //0-84 resolution 1 dB
01480     rf230_last_rssi = hal_register_read(RG_PHY_ED_LEVEL);  //0-84, resolution 1 dB
01481 #else
01482 /* last_rssi will have been set at RX_START interrupt */
01483 //  rf230_last_rssi = 3*hal_subregister_read(SR_RSSI);    //0-28 resolution 3 dB
01484 #endif
01485 #endif /* speed vs. generality */
01486 
01487   /* Save the smallest rssi. The display routine can reset by setting it to zero */
01488   if ((rf230_smallest_rssi==0) || (rf230_last_rssi<rf230_smallest_rssi))
01489      rf230_smallest_rssi=rf230_last_rssi;
01490 
01491  //   rf230_last_correlation = rxframe[rxframe_head].lqi;
01492     packetbuf_set_attr(PACKETBUF_ATTR_RSSI, rf230_last_rssi);
01493     packetbuf_set_attr(PACKETBUF_ATTR_LINK_QUALITY, rf230_last_correlation);
01494 
01495     RIMESTATS_ADD(rx);
01496 
01497 #if RF230_CONF_TIMESTAMPS
01498     rf230_time_of_departure =
01499       t.time +
01500       setup_time_for_transmission +
01501       (total_time_for_transmission * (len - 2)) / total_transmission_len;
01502 
01503     rf230_authority_level_of_sender = t.authority_level;
01504 
01505     packetbuf_set_attr(PACKETBUF_ATTR_TIMESTAMP, t.time);
01506 #endif /* RF230_CONF_TIMESTAMPS */
01507 
01508 #if RF230_CONF_CHECKSUM
01509 #if FOOTER_LEN
01510   } else {
01511     DEBUGFLOW('x');
01512     //PRINTF("bad crc");
01513     RIMESTATS_ADD(badcrc);
01514     len = AUX_LEN;
01515   }
01516 #endif
01517 #endif
01518 
01519 #ifdef RF230BB_HOOK_RX_PACKET
01520   RF230BB_HOOK_RX_PACKET(buf,len);
01521 #endif
01522 
01523   /* Here return just the data length. The checksum is however still in the buffer for packet sniffing */
01524   return len - AUX_LEN;
01525 
01526 #if RADIOALWAYSON
01527 } else {
01528    DEBUGFLOW('y');  //Stack thought radio was off
01529    return 0;
01530 }
01531 #endif
01532 }
01533 /*---------------------------------------------------------------------------*/
01534 void
01535 rf230_set_txpower(uint8_t power)
01536 {
01537   set_txpower(power);
01538 }
01539 /*---------------------------------------------------------------------------*/
01540 uint8_t
01541 rf230_get_txpower(void)
01542 {
01543         uint8_t power = TX_PWR_UNDEFINED;
01544         if (hal_get_slptr()) {
01545                 PRINTF("rf230_get_txpower:Sleeping");
01546         } else {
01547                 power = hal_subregister_read(SR_TX_PWR);
01548         }
01549         return power;
01550 }
01551 
01552 /*---------------------------------------------------------------------------*/
01553 uint8_t
01554 rf230_get_raw_rssi(void)
01555 {
01556   uint8_t rssi,state;
01557   bool radio_was_off = 0;
01558 
01559   /*The RSSI measurement should only be done in RX_ON or BUSY_RX.*/
01560   if(!RF230_receive_on) {
01561     radio_was_off = 1;
01562     rf230_on();
01563   }
01564 
01565 /* The energy detect register is used in extended mode (since RSSI will read 0) */
01566 /* The rssi register is multiplied by 3 to a consistent value from either register */
01567   state=radio_get_trx_state();
01568   if ((state==RX_AACK_ON) || (state==BUSY_RX_AACK)) {
01569  //  rssi = hal_subregister_read(SR_ED_LEVEL);  //0-84, resolution 1 dB
01570      rssi = hal_register_read(RG_PHY_ED_LEVEL);  //0-84, resolution 1 dB
01571   } else {
01572 #if 0   // 3-clock shift and add is faster on machines with no hardware multiply
01573 /* avr-gcc may have an -Os bug that uses the general subroutine for multiplying by 3 */
01574      rssi = hal_subregister_read(SR_RSSI);      //0-28, resolution 3 dB
01575      rssi = (rssi << 1)  + rssi;                //*3
01576 #else  // 1 or 2 clock multiply, or compiler with correct optimization
01577      rssi = 3 * hal_subregister_read(SR_RSSI);
01578 #endif
01579 
01580   }
01581 
01582   if(radio_was_off) {
01583     rf230_off();
01584   }
01585   return rssi;
01586 }
01587 
01588 /*---------------------------------------------------------------------------*/
01589 static int
01590 rf230_cca(void)
01591 {
01592   uint8_t cca=0;
01593   uint8_t radio_was_off = 0;
01594 
01595   /* Turn radio on if necessary. If radio is currently busy return busy channel */
01596   /* This may happen when testing radio duty cycling with RADIOALWAYSON */
01597   if(RF230_receive_on) {
01598     if (hal_get_slptr()) {  //should not be sleeping!
01599           DEBUGFLOW('<');
01600           goto busyexit;
01601         } else {
01602       if (!rf230_isidle()) {DEBUGFLOW('2');goto busyexit;}
01603         }
01604   } else {
01605     radio_was_off = 1;
01606     rf230_on();
01607   }
01608 
01609   ENERGEST_ON(ENERGEST_TYPE_LED_YELLOW);
01610   /* CCA Mode Mode 1=Energy above threshold  2=Carrier sense only  3=Both 0=Either (RF231 only) */
01611   /* Use the current mode. Note triggering a manual CCA is not recommended in extended mode */
01612 //hal_subregister_write(SR_CCA_MODE,1);
01613 
01614   /* Start the CCA, wait till done, return result */
01615   /* Note reading the TRX_STATUS register clears both CCA_STATUS and CCA_DONE bits */
01616 #if defined(__AVR_ATmega128RFA1__)
01617 #if 1  //interrupt method
01618     sei();
01619 //rf230_waitidle();
01620 //TODO:disable reception for version bug
01621   radio_set_trx_state(RX_ON);
01622 //  rf230_waitidle();
01623     rf230_ccawait=1;
01624 //CCA_REQUEST is supposed to trigger the interrupt but it doesn't
01625 //  hal_subregister_write(SR_CCA_REQUEST,1);
01626     hal_register_write(PHY_ED_LEVEL,0);
01627 //  delay_us(TIME_CCA);
01628 //  if (hal_register_read(RG_PHY_ED_LEVEL)<(91-77)) cca=0xff;
01629     while (rf230_ccawait) {}
01630 #ifdef RF230_CONF_CCA_THRES
01631     if (hal_register_read(RG_PHY_ED_LEVEL)<(91+RF230_CONF_CCA_THRES) cca=0xff;
01632 #else
01633     if (hal_register_read(RG_PHY_ED_LEVEL)<(91-77)) cca=0xff;
01634 #endif
01635 //TODO:see if the status register works!
01636 //   cca=hal_register_read(RG_TRX_STATUS);
01637 #if RF230_CONF_AUTOACK
01638   radio_set_trx_state(RX_AACK_ON);
01639 #endif
01640 #else
01641   /* If already in receive mode can read the current ED register without delay */
01642   /* CCA energy threshold = -91dB + 2*SR_CCA_ED_THRESH. Reset defaults to -77dB */
01643 #ifdef RF230_CONF_CCA_THRES
01644     if (hal_register_read(RG_PHY_ED_LEVEL)<(91+RF230_CONF_CCA_THRES) cca=0xff;
01645 #else
01646         if (hal_register_read(RG_PHY_ED_LEVEL)<(91-77)) cca=0xff;
01647 #endif
01648 #endif
01649 
01650 
01651 #else /* RF230, RF231 */
01652   /* Don't allow interrupts! */
01653   /* Start the CCA, wait till done, return result */
01654   /* Note reading the TRX_STATUS register clears both CCA_STATUS and CCA_DONE bits */
01655 { uint8_t volatile saved_sreg = SREG;
01656   cli();
01657   rf230_waitidle();
01658   hal_subregister_write(SR_CCA_REQUEST,1);
01659   delay_us(TIME_CCA);
01660   while ((cca & 0x80) == 0 ) {
01661     cca=hal_register_read(RG_TRX_STATUS);
01662   }
01663   SREG=saved_sreg;
01664 }
01665 #endif
01666   ENERGEST_OFF(ENERGEST_TYPE_LED_YELLOW); 
01667   if(radio_was_off) {
01668     rf230_off();
01669   }
01670 // if (cca & 0x40) {/*DEBUGFLOW('3')*/;} else {rf230_pending=1;DEBUGFLOW('4');}  
01671    if (cca & 0x40) {
01672 //   DEBUGFLOW('5');
01673          return 1;
01674    } else {
01675 //  DEBUGFLOW('6');
01676  busyexit:
01677          return 0;
01678    }
01679 }
01680 /*---------------------------------------------------------------------------*/
01681 int
01682 rf230_receiving_packet(void)
01683 {
01684   uint8_t radio_state;
01685   if (hal_get_slptr()) {
01686     DEBUGFLOW('=');
01687   } else {  
01688     radio_state = hal_subregister_read(SR_TRX_STATUS);
01689     if ((radio_state==BUSY_RX) || (radio_state==BUSY_RX_AACK)) {
01690 //      DEBUGFLOW('8');
01691 //        rf230_pending=1;
01692       return 1;
01693     }
01694   }
01695   return 0;
01696 }
01697 /*---------------------------------------------------------------------------*/
01698 static int
01699 rf230_pending_packet(void)
01700 {
01701 #if RF230_INSERTACK
01702     if(ack_pending == 1) return 1;
01703 #endif
01704   return rf230_pending;
01705 }
01706 /*---------------------------------------------------------------------------*/
01707 #if RF230_CONF_SNEEZER && JACKDAW
01708 /* See A.2 in the datasheet for the sequence needed.
01709  * This version for RF230 only, hence Jackdaw.
01710  * A full reset seems not necessary and allows keeping the pan address, etc.
01711  * for an easy reset back to network mode.
01712  */
01713 void rf230_start_sneeze(void) {
01714 //write buffer with random data for uniform spectral noise
01715 
01716 //uint8_t txpower = hal_register_read(0x05);  //save auto_crc bit and power
01717 //  hal_set_rst_low();
01718 //  hal_set_slptr_low();
01719 //  delay_us(TIME_RESET);
01720 //  hal_set_rst_high();
01721     hal_register_write(0x0E, 0x01);
01722     hal_register_write(0x02, 0x03);
01723     hal_register_write(0x03, 0x10);
01724  // hal_register_write(0x08, 0x20+26);    //channel 26
01725     hal_subregister_write(SR_CCA_MODE,1); //leave channel unchanged
01726 
01727  // hal_register_write(0x05, 0x00);       //output power maximum
01728     hal_subregister_write(SR_TX_AUTO_CRC_ON, 0);  //clear AUTO_CRC, leave output power unchanged
01729  
01730     hal_register_read(0x01);             //should be trx-off state=0x08  
01731     hal_frame_write(buffer, 127);        //maximum length, random for spectral noise 
01732 
01733     hal_register_write(0x36,0x0F);       //configure continuous TX
01734     hal_register_write(0x3D,0x00);       //Modulated frame, other options are:
01735 //  hal_register_write(RG_TX_2,0x10);    //CW -2MHz
01736 //  hal_register_write(RG_TX_2,0x80);    //CW -500KHz
01737 //  hal_register_write(RG_TX_2,0xC0);    //CW +500KHz
01738 
01739     DDRB  |= 1<<7;                       //Raven USB stick has PB7 connected to the RF230 TST pin.   
01740     PORTB |= 1<<7;                       //Raise it to enable continuous TX Test Mode.
01741 
01742     hal_register_write(0x02,0x09);       //Set TRX_STATE to PLL_ON
01743     delay_us(TIME_TRX_OFF_TO_PLL_ACTIVE);
01744     delay_us(TIME_PLL_LOCK);
01745     delay_us(TIME_PLL_LOCK);
01746  // while (hal_register_read(0x0f)!=1) {continue;}  //wait for pll lock-hangs
01747     hal_register_write(0x02,0x02);       //Set TRX_STATE to TX_START
01748 }
01749 #endif