Contiki 3.x
radio.c
Go to the documentation of this file.
1 /* Copyright (c) 2008, Swedish Institute of Computer Science
2  * All rights reserved.
3  *
4  * Additional fixes for AVR contributed by:
5  * Colin O'Flynn coflynn@newae.com
6  * Eric Gnoske egnoske@gmail.com
7  * Blake Leverett bleverett@gmail.com
8  * Mike Vidales mavida404@gmail.com
9  * Kevin Brown kbrown3@uccs.edu
10  * Nate Bohlmann nate@elfwerks.com
11  *
12  * All rights reserved.
13  *
14  * Redistribution and use in source and binary forms, with or without
15  * modification, are permitted provided that the following conditions are met:
16  *
17  * * Redistributions of source code must retain the above copyright
18  * notice, this list of conditions and the following disclaimer.
19  * * Redistributions in binary form must reproduce the above copyright
20  * notice, this list of conditions and the following disclaimer in
21  * the documentation and/or other materials provided with the
22  * distribution.
23  * * Neither the name of the copyright holders nor the names of
24  * contributors may be used to endorse or promote products derived
25  * from this software without specific prior written permission.
26  *
27  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
28  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
29  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
30  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
31  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
32  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
33  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
34  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
35  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
36  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
37  * POSSIBILITY OF SUCH DAMAGE.
38  *
39 */
40 
41 /**
42  * \brief This module contains the radio driver code for the Atmel
43  * AT86RF230, '231, and '212 chips.
44  *
45  * \author Blake Leverett <bleverett@gmail.com>
46  * Mike Vidales <mavida404@gmail.com>
47  * Eric Gnoske <egnoske@gmail.com>
48  *
49 */
50 
51 /** \addtogroup wireless
52  * @{
53  */
54 
55 /**
56  * \defgroup radiorf230 RF230 interface
57  * @{
58  */
59 /**
60  * \file
61  * This file contains radio driver code.
62  *
63  */
64 
65 
66 
67 /*============================ INCLUDE =======================================*/
68 #include <stdlib.h>
69 #include <util/delay.h>
70 #include "radio.h"
71 #include "hal.h"
72 #include "process.h"
73 #include "sicslowmac.h"
74 #include "frame.h"
75 
76 /*============================ MACROS ========================================*/
77 #define RADIO_CCA_DONE_MASK (1 << 7) /**< Mask used to check the CCA_DONE bit. */
78 #define RADIO_CCA_IDLE_MASK (1 << 6) /**< Mask used to check the CCA_STATUS bit. */
79 
80 #define RADIO_START_CCA (1) /**< Value in the CCA_REQUEST subregister that initiate a cca. */
81 
82 #define RADIO_TRANSMISSION_SUCCESS (0)
83 #define RADIO_BUSY_CHANNEL (3)
84 #define RADIO_MIN_IEEE_FRAME_LENGTH (5)
85 /*============================ TYPEDEFS ======================================*/
86 
87 /** \brief This enumeration defines the necessary timing information for the
88  * AT86RF230 radio transceiver. All times are in microseconds.
89  *
90  * These constants are extracted from the datasheet.
91  */
92 typedef enum{
93  TIME_TO_ENTER_P_ON = 510, /**< Transition time from VCC is applied to P_ON. */
94  TIME_P_ON_TO_TRX_OFF = 510, /**< Transition time from P_ON to TRX_OFF. */
95  TIME_SLEEP_TO_TRX_OFF = 880, /**< Transition time from SLEEP to TRX_OFF. */
96  TIME_RESET = 6, /**< Time to hold the RST pin low during reset */
97  TIME_ED_MEASUREMENT = 140, /**< Time it takes to do a ED measurement. */
98  TIME_CCA = 140, /**< Time it takes to do a CCA. */
99  TIME_PLL_LOCK = 150, /**< Maximum time it should take for the PLL to lock. */
100  TIME_FTN_TUNING = 25, /**< Maximum time it should take to do the filter tuning. */
101  TIME_NOCLK_TO_WAKE = 6, /**< Transition time from *_NOCLK to being awake. */
102  TIME_CMD_FORCE_TRX_OFF = 1, /**< Time it takes to execute the FORCE_TRX_OFF command. */
103  TIME_TRX_OFF_TO_PLL_ACTIVE = 180, /**< Transition time from TRX_OFF to: RX_ON, PLL_ON, TX_ARET_ON and RX_AACK_ON. */
104  TIME_STATE_TRANSITION_PLL_ACTIVE = 1, /**< Transition time from PLL active state to another. */
106 
107 /*============================ VARIABLES =====================================*/
108 static hal_rx_start_isr_event_handler_t user_rx_event;
109 static hal_trx_end_isr_event_handler_t user_trx_end_event;
110 static radio_rx_callback rx_frame_callback;
111 static uint8_t rssi_val;
112 static uint8_t rx_mode;
113 uint8_t rxMode = RX_AACK_ON;
114 
115 /* See clock.c and httpd-cgi.c for RADIOSTATS code */
116 #define RADIOSTATS 0
117 #if RADIOSTATS
118 uint8_t RF230_radio_on, RF230_rsigsi;
119 uint16_t RF230_sendpackets,RF230_receivepackets,RF230_sendfail,RF230_receivefail;
120 #endif
121 
122 static hal_rx_frame_t rx_frame;
123 static parsed_frame_t parsed_frame;
124 
125 /*============================ PROTOTYPES ====================================*/
126 bool radio_is_sleeping(void);
127 static void radio_rx_start_event(uint32_t const isr_timestamp, uint8_t const frame_length);
128 static void radio_trx_end_event(uint32_t const isr_timestamp);
129 
130 /** \brief Initialize the Transceiver Access Toolbox and lower layers.
131  *
132  * If the initialization is successful the radio transceiver will be in
133  * TRX_OFF state.
134  *
135  * \note This function must be called prior to any of the other functions in
136  * this file! Can be called from any transceiver state.
137  *
138  * \param cal_rc_osc If true, the radio's accurate clock is used to calibrate the
139  * CPU's internal RC oscillator.
140  *
141  * \param rx_event Optional pointer to a user-defined function to be called on an
142  * RX_START interrupt. Use NULL for no handler.
143  *
144  * \param trx_end_event Optional pointer to a user-defined function to be called on an
145  * TRX_END interrupt. Use NULL for no handler.
146  *
147  * \param rx_callback Optional pointer to a user-defined function that receives
148  * a frame from the radio one byte at a time. If the index parameter to
149  * this callback is 0xff, then the function should reset its state and prepare
150  * for a frame from the radio, with one call per byte.
151  *
152  * \retval RADIO_SUCCESS The radio transceiver was successfully initialized
153  * and put into the TRX_OFF state.
154  * \retval RADIO_UNSUPPORTED_DEVICE The connected device is not an Atmel
155  * AT86RF230 radio transceiver.
156  * \retval RADIO_TIMED_OUT The radio transceiver was not able to initialize and
157  * enter TRX_OFF state within the specified time.
158  */
160 radio_init(bool cal_rc_osc,
162  hal_trx_end_isr_event_handler_t trx_end_event,
163  radio_rx_callback rx_callback)
164 {
165  radio_status_t init_status = RADIO_SUCCESS;
166 
167  delay_us(TIME_TO_ENTER_P_ON);
168 
169  /* calibrate oscillator */
170  if (cal_rc_osc){
172  }
173 
174  /* Initialize Hardware Abstraction Layer. */
175  hal_init();
176 
177  radio_reset_trx(); /* Do HW reset of radio transeiver. */
178 
179  /* Force transition to TRX_OFF. */
181  delay_us(TIME_P_ON_TO_TRX_OFF); /* Wait for the transition to be complete. */
182 
183  if (radio_get_trx_state() != TRX_OFF){
184  init_status = RADIO_TIMED_OUT;
185  } else {
186  /* Read Version Number */
187  uint8_t version_number = hal_register_read(RG_VERSION_NUM);
188 
189  if ((version_number != RF230_REVA) && (version_number != RF230_REVB))
190  init_status = RADIO_UNSUPPORTED_DEVICE;
191  else {
192  if (hal_register_read(RG_MAN_ID_0) != SUPPORTED_MANUFACTURER_ID)
193  init_status = RADIO_UNSUPPORTED_DEVICE;
194  else
195  hal_register_write(RG_IRQ_MASK, RF230_SUPPORTED_INTERRUPT_MASK);
196  }
197 #if RADIOSTATS
198  RF230_radio_on = 1;
199 #endif
200  }
201 
202  /* set callbacks for events. Save user's rx_event, which we will */
203  /* call from radio_rx_start_event(). Same with trx_end */
204  user_rx_event = rx_event;
205  user_trx_end_event = trx_end_event;
206  hal_set_rx_start_event_handler(radio_rx_start_event);
207  hal_set_trx_end_event_handler(radio_trx_end_event);
208 
209  rx_frame_callback = rx_callback;
210 
211  return init_status;
212 }
213 
214 /*---------------------------------------------------------------------------*/
215 uint8_t *
216 radio_frame_data(void)
217 {
218  return rx_frame.data;
219 }
220 
221 uint8_t
222 radio_frame_length(void)
223 {
224  return rx_frame.length;
225 }
226 
227 /*---------------------------------------------------------------------------*/
228 static void
229 radio_rx_start_event(uint32_t const isr_timestamp, uint8_t const frame_length)
230 {
231  /* save away RSSI */
232  rssi_val = hal_subregister_read( SR_RSSI );
233 
234  /* call user's rx_start event handler */
235  if (user_rx_event)
236  user_rx_event(isr_timestamp, frame_length);
237 }
238 
239 /*---------------------------------------------------------------------------*/
240 uint8_t
241 radio_get_saved_rssi_value(void)
242 {
243  return rssi_val;
244 }
245 
246 /*---------------------------------------------------------------------------*/
247 static void
248 radio_trx_end_event(uint32_t const isr_timestamp)
249 {
250  volatile uint8_t status;
251 
252  /* call user's trx_end event handler */
253  if (user_trx_end_event){
254  user_trx_end_event(isr_timestamp);
255  return;
256  }
257  if (rx_mode){
258  /* radio has received frame, store it away */
259 #if RADIOSTATS
260  RF230_rsigsi=rssi_val;
261  RF230_receivepackets++;
262 #endif
263  parsed_frame.time = isr_timestamp;
264  parsed_frame.rssi = rssi_val;
265 
266  hal_frame_read(&rx_frame, NULL);
267  rx_frame_parse(&rx_frame, &parsed_frame);
268  }
269 
270  if (!rx_mode){
271  /* Put radio back into receive mode. */
273  radio_set_trx_state(rxMode);
274 
275  /* transmit mode, put end-of-transmit event in queue */
276  event_object_t event;
277  event.event = 0;
278  event.data = 0;
280  switch(status){
281  case TRAC_SUCCESS:
282  case TRAC_SUCCESS_DATA_PENDING:
283  event.event = MAC_EVENT_ACK;
284  break;
285  case TRAC_NO_ACK:
286  case TRAC_CHANNEL_ACCESS_FAILURE:
287  event.event = MAC_EVENT_NACK;
288 #if RADIOSTATS
289  RF230_sendfail++;
290 #endif
291  break;
292  case TRAC_SUCCESS_WAIT_FOR_ACK:
293  /* should only happen in RX mode */
294  case TRAC_INVALID:
295  /* should never happen here */
296  default:
297 #if RADIOSTATS
298  RF230_sendfail++;
299 #endif
300  break;
301  }
302  if (event.event)
303  mac_put_event(&event);
304  process_post(&mac_process, event.event, event.data);
305  }
306 }
307 /*----------------------------------------------------------------------------*/
308 /** \brief This function will return the channel used by the radio transceiver.
309  *
310  * \return Current channel, 11 to 26.
311  */
312 uint8_t
314 {
316 }
317 /*----------------------------------------------------------------------------*/
318 /** \brief This function will change the operating channel.
319  *
320  * \param channel New channel to operate on. Must be between 11 and 26.
321  *
322  * \retval RADIO_SUCCESS New channel set.
323  * \retval RADIO_WRONG_STATE Transceiver is in a state where the channel cannot
324  * be changed (SLEEP).
325  * \retval RADIO_INVALID_ARGUMENT Channel argument is out of bounds.
326  * \retval RADIO_TIMED_OUT The PLL did not lock within the specified time.
327  */
330 {
331  /*Do function parameter and state check.*/
332  if ((channel < RF230_MIN_CHANNEL) ||
333  (channel > RF230_MAX_CHANNEL)){
334  return RADIO_INVALID_ARGUMENT;
335  }
336 
337  if (radio_is_sleeping() == true){
338  return RADIO_WRONG_STATE;
339  }
340 
341  if (radio_get_operating_channel() == channel){
342  return RADIO_SUCCESS;
343  }
344 
345  /*Set new operating channel.*/
347 
348  /* Read current state and wait for the PLL_LOCK interrupt if the */
349  /* radio transceiver is in either RX_ON or PLL_ON. */
350  uint8_t trx_state = radio_get_trx_state();
351 
352  if ((trx_state == RX_ON) ||
353  (trx_state == PLL_ON)){
354  delay_us(TIME_PLL_LOCK);
355  }
356 
357  radio_status_t channel_set_status = RADIO_TIMED_OUT;
358 
359  /* Check that the channel was set properly. */
360  if (radio_get_operating_channel() == channel){
361  channel_set_status = RADIO_SUCCESS;
362  }
363 
364  return channel_set_status;
365 }
366 
367 /*----------------------------------------------------------------------------*/
368 /** \brief This function will read and return the output power level.
369  *
370  * \returns 0 to 15 Current output power in "TX power settings" as defined in
371  * the radio transceiver's datasheet
372  */
373 uint8_t
375 {
377 }
378 
379 /*----------------------------------------------------------------------------*/
380 /** \brief This function will change the output power level.
381  *
382  * \param power_level New output power level in the "TX power settings"
383  * as defined in the radio transceiver's datasheet.
384  *
385  * \retval RADIO_SUCCESS New output power set successfully.
386  * \retval RADIO_INVALID_ARGUMENT The supplied function argument is out of bounds.
387  * \retval RADIO_WRONG_STATE It is not possible to change the TX power when the
388  * device is sleeping.
389  */
391 radio_set_tx_power_level(uint8_t power_level)
392 {
393 
394  /*Check function parameter and state.*/
395  if (power_level > TX_PWR_17_2DBM){
396  return RADIO_INVALID_ARGUMENT;
397  }
398 
399  if (radio_is_sleeping() == true){
400  return RADIO_WRONG_STATE;
401  }
402 
403  /*Set new power level*/
404  hal_subregister_write(SR_TX_PWR, power_level);
405 
406  return RADIO_SUCCESS;
407 }
408 
409 /*----------------------------------------------------------------------------*/
410 /** \brief This function returns the current CCA mode used.
411  *
412  * \return CCA mode currently used, 0 to 3.
413  */
414 uint8_t
416 {
418 }
419 
420 /*----------------------------------------------------------------------------*/
421 /** \brief This function returns the current ED threshold used by the CCA algorithm.
422  *
423  * \return Current ED threshold, 0 to 15.
424  */
425 uint8_t
427 {
429 }
430 
431 /*----------------------------------------------------------------------------*/
432 /** \brief This function will configure the Clear Channel Assessment algorithm.
433  *
434  * \param mode Three modes are available: Energy above threshold, carrier
435  * sense only and carrier sense with energy above threshold.
436  * \param ed_threshold Above this energy threshold the channel is assumed to be
437  * busy. The threshold is given in positive dBm values.
438  * Ex. -91 dBm gives a csThreshold of 91. Value range for
439  * the variable is [61 to 91]. Only valid for the CCA_ED
440  * and CCA_CARRIER_SENSE_ED modes.
441  *
442  * \retval RADIO_SUCCESS Mode and its parameters successfully changed.
443  * \retval RADIO_WRONG_STATE This function cannot be called in the SLEEP state.
444  * \retval RADIO_INVALID_ARGUMENT If one of the three function arguments are out
445  * of bounds.
446  */
448 radio_set_cca_mode(uint8_t mode, uint8_t ed_threshold)
449 {
450  /*Check function parameters and state.*/
451  if ((mode != CCA_ED) &&
452  (mode != CCA_CARRIER_SENSE) &&
453  (mode != CCA_CARRIER_SENSE_WITH_ED)){
454  return RADIO_INVALID_ARGUMENT;
455  }
456 
457  /* Ensure that the ED threshold is within bounds. */
458  if (ed_threshold > RF230_MAX_ED_THRESHOLD){
459  return RADIO_INVALID_ARGUMENT;
460  }
461 
462  /* Ensure that the radio transceiver is not sleeping. */
463  if (radio_is_sleeping() == true){
464  return RADIO_WRONG_STATE;
465  }
466 
467  /*Change cca mode and ed threshold.*/
469  hal_subregister_write(SR_CCA_ED_THRES, ed_threshold);
470 
471  return RADIO_SUCCESS;
472 }
473 
474 /*----------------------------------------------------------------------------*/
475 /** \brief This function returns the Received Signal Strength Indication.
476  *
477  * \note This function should only be called from the: RX_ON and BUSY_RX. This
478  * can be ensured by reading the current state of the radio transceiver
479  * before executing this function!
480  * \param rssi Pointer to memory location where RSSI value should be written.
481  * \retval RADIO_SUCCESS The RSSI measurement was successful.
482  * \retval RADIO_WRONG_STATE The radio transceiver is not in RX_ON or BUSY_RX.
483  */
485 radio_get_rssi_value(uint8_t *rssi)
486 {
487 
488  uint8_t current_state = radio_get_trx_state();
490 
491  /*The RSSI measurement should only be done in RX_ON or BUSY_RX.*/
492  if ((current_state == RX_ON) ||
493  (current_state == BUSY_RX)){
494  *rssi = hal_subregister_read(SR_RSSI);
495  retval = RADIO_SUCCESS;
496  }
497 
498  return retval;
499 }
500 
501 /*----------------------------------------------------------------------------*/
502 /** \brief This function returns the current threshold volatge used by the
503  * battery monitor (BATMON_VTH).
504  *
505  * \note This function can not be called from P_ON or SLEEP. This is ensured
506  * by reading the device state before calling this function.
507  *
508  * \return Current threshold voltage, 0 to 15.
509  */
510 uint8_t
512 {
514 }
515 
516 /*----------------------------------------------------------------------------*/
517 /** \brief This function returns if high or low voltage range is used.
518  *
519  * \note This function can not be called from P_ON or SLEEP. This is ensured
520  * by reading the device state before calling this function.
521  *
522  * \retval 0 Low voltage range selected.
523  * \retval 1 High voltage range selected.
524  */
525 uint8_t
527 {
529 }
530 
531 /*----------------------------------------------------------------------------*/
532 /** \brief This function is used to configure the battery monitor module
533  *
534  * \param range True means high voltage range and false low voltage range.
535  * \param voltage_threshold The datasheet defines 16 voltage levels for both
536  * low and high range.
537  * \retval RADIO_SUCCESS Battery monitor configured
538  * \retval RADIO_WRONG_STATE The device is sleeping.
539  * \retval RADIO_INVALID_ARGUMENT The voltage_threshold parameter is out of
540  * bounds (Not within [0 - 15]).
541  */
543 radio_batmon_configure(bool range, uint8_t voltage_threshold)
544 {
545 
546  /*Check function parameters and state.*/
547  if (voltage_threshold > BATTERY_MONITOR_HIGHEST_VOLTAGE){
548  return RADIO_INVALID_ARGUMENT;
549  }
550 
551  if (radio_is_sleeping() == true){
552  return RADIO_WRONG_STATE;
553  }
554 
555  /*Write new voltage range and voltage level.*/
556  if (range == true){
557  hal_subregister_write(SR_BATMON_HR, BATTERY_MONITOR_HIGH_VOLTAGE);
558  } else {
559  hal_subregister_write(SR_BATMON_HR, BATTERY_MONITOR_LOW_VOLTAGE);
560  }
561 
562  hal_subregister_write(SR_BATMON_VTH, voltage_threshold);
563 
564  return RADIO_SUCCESS;
565 }
566 
567 /*----------------------------------------------------------------------------*/
568 /** \brief This function returns the status of the Battery Monitor module.
569  *
570  * \note This function can not be called from P_ON or SLEEP. This is ensured
571  * by reading the device state before calling this function.
572  *
573  * \retval RADIO_BAT_LOW Battery voltage is below the programmed threshold.
574  * \retval RADIO_BAT_OK Battery voltage is above the programmed threshold.
575  */
578 {
579 
580  radio_status_t batmon_status = RADIO_BAT_LOW;
581 
583  BATTERY_MONITOR_VOLTAGE_UNDER_THRESHOLD){
584  batmon_status = RADIO_BAT_OK;
585  }
586 
587  return batmon_status;
588 }
589 
590 /*----------------------------------------------------------------------------*/
591 /** \brief This function returns the current clock setting for the CLKM pin.
592  *
593  * \retval CLKM_DISABLED CLKM pin is disabled.
594  * \retval CLKM_1MHZ CLKM pin is prescaled to 1 MHz.
595  * \retval CLKM_2MHZ CLKM pin is prescaled to 2 MHz.
596  * \retval CLKM_4MHZ CLKM pin is prescaled to 4 MHz.
597  * \retval CLKM_8MHZ CLKM pin is prescaled to 8 MHz.
598  * \retval CLKM_16MHZ CLKM pin is not prescaled. Output is 16 MHz.
599  */
600 uint8_t
602 {
604 }
605 
606 /*----------------------------------------------------------------------------*/
607 /** \brief This function changes the prescaler on the CLKM pin.
608  *
609  * \param direct This boolean variable is used to determine if the frequency
610  * of the CLKM pin shall be changed directly or not. If direct
611  * equals true, the frequency will be changed directly. This is
612  * fine if the CLKM signal is used to drive a timer etc. on the
613  * connected microcontroller. However, the CLKM signal can also
614  * be used to clock the microcontroller itself. In this situation
615  * it is possible to change the CLKM frequency indirectly
616  * (direct == false). When the direct argument equlas false, the
617  * CLKM frequency will be changed first after the radio transceiver
618  * has been taken to SLEEP and awaken again.
619  * \param clock_speed This parameter can be one of the following constants:
620  * CLKM_DISABLED, CLKM_1MHZ, CLKM_2MHZ, CLKM_4MHZ, CLKM_8MHZ
621  * or CLKM_16MHZ.
622  *
623  * \retval RADIO_SUCCESS Clock speed updated. New state is TRX_OFF.
624  * \retval RADIO_INVALID_ARGUMENT Requested clock speed is out of bounds.
625  */
627 radio_set_clock_speed(bool direct, uint8_t clock_speed)
628 {
629  /*Check function parameter and current clock speed.*/
630  if (clock_speed > CLKM_16MHZ){
631  return RADIO_INVALID_ARGUMENT;
632  }
633 
634  if (radio_get_clock_speed() == clock_speed){
635  return RADIO_SUCCESS;
636  }
637 
638  /*Select to change the CLKM frequency directly or after returning from SLEEP.*/
639  if (direct == false){
641  } else {
643  }
644 
645  hal_subregister_write(SR_CLKM_CTRL, clock_speed);
646 
647  return RADIO_SUCCESS;
648 }
649 
650 /*----------------------------------------------------------------------------*/
651 /** \brief This function calibrates the Single Side Band Filter.
652  *
653  * \retval RADIO_SUCCESS Filter is calibrated.
654  * \retval RADIO_TIMED_OUT The calibration could not be completed within time.
655  * \retval RADIO_WRONG_STATE This function can only be called from TRX_OFF or
656  * PLL_ON.
657  */
660 {
661  /*Check current state. Only possible to do filter calibration from TRX_OFF or PLL_ON.*/
662  uint8_t trx_state = radio_get_trx_state();
663 
664  if ((trx_state != TRX_OFF) &&
665  (trx_state != PLL_ON)){
666  return RADIO_WRONG_STATE;
667  }
668 
669  /* Start the tuning algorithm by writing one to the FTN_START subregister. */
671  delay_us(TIME_FTN_TUNING); /* Wait for the calibration to finish. */
672 
673  radio_status_t filter_calibration_status = RADIO_TIMED_OUT;
674 
675  /* Verify the calibration result. */
676  if (hal_subregister_read(SR_FTN_START) == FTN_CALIBRATION_DONE){
677  filter_calibration_status = RADIO_SUCCESS;
678  }
679 
680  return filter_calibration_status;
681 }
682 
683 /*----------------------------------------------------------------------------*/
684 /** \brief This function calibrates the PLL.
685  *
686  * \retval RADIO_SUCCESS PLL Center Frequency and Delay Cell is calibrated.
687  * \retval RADIO_TIMED_OUT The calibration could not be completed within time.
688  * \retval RADIO_WRONG_STATE This function can only be called from PLL_ON.
689  */
692 {
693 
694  /*Check current state. Only possible to calibrate PLL from PLL_ON state*/
695  if (radio_get_trx_state() != PLL_ON){
696  return RADIO_WRONG_STATE;
697  }
698 
699  /* Initiate the DCU and CF calibration loops. */
702 
703  /* Wait maximum 150 us for the PLL to lock. */
705  delay_us(TIME_PLL_LOCK);
706 
707  radio_status_t pll_calibration_status = RADIO_TIMED_OUT;
708 
709  if (hal_get_pll_lock_flag() > 0){
710  if (hal_subregister_read(SR_PLL_DCU_START) == PLL_DCU_CALIBRATION_DONE){
711  if (hal_subregister_read(SR_PLL_CF_START) == PLL_CF_CALIBRATION_DONE){
712  pll_calibration_status = RADIO_SUCCESS;
713  }
714  }
715  }
716 
717  return pll_calibration_status;
718 }
719 
720 /*----------------------------------------------------------------------------*/
721 /** \brief This function return the Radio Transceivers current state.
722  *
723  * \retval P_ON When the external supply voltage (VDD) is
724  * first supplied to the transceiver IC, the
725  * system is in the P_ON (Poweron) mode.
726  * \retval BUSY_RX The radio transceiver is busy receiving a
727  * frame.
728  * \retval BUSY_TX The radio transceiver is busy transmitting a
729  * frame.
730  * \retval RX_ON The RX_ON mode enables the analog and digital
731  * receiver blocks and the PLL frequency
732  * synthesizer.
733  * \retval TRX_OFF In this mode, the SPI module and crystal
734  * oscillator are active.
735  * \retval PLL_ON Entering the PLL_ON mode from TRX_OFF will
736  * first enable the analog voltage regulator. The
737  * transceiver is ready to transmit a frame.
738  * \retval BUSY_RX_AACK The radio was in RX_AACK_ON mode and received
739  * the Start of Frame Delimiter (SFD). State
740  * transition to BUSY_RX_AACK is done if the SFD
741  * is valid.
742  * \retval BUSY_TX_ARET The radio transceiver is busy handling the
743  * auto retry mechanism.
744  * \retval RX_AACK_ON The auto acknowledge mode of the radio is
745  * enabled and it is waiting for an incomming
746  * frame.
747  * \retval TX_ARET_ON The auto retry mechanism is enabled and the
748  * radio transceiver is waiting for the user to
749  * send the TX_START command.
750  * \retval RX_ON_NOCLK The radio transceiver is listening for
751  * incomming frames, but the CLKM is disabled so
752  * that the controller could be sleeping.
753  * However, this is only true if the controller
754  * is run from the clock output of the radio.
755  * \retval RX_AACK_ON_NOCLK Same as the RX_ON_NOCLK state, but with the
756  * auto acknowledge module turned on.
757  * \retval BUSY_RX_AACK_NOCLK Same as BUSY_RX_AACK, but the controller
758  * could be sleeping since the CLKM pin is
759  * disabled.
760  * \retval STATE_TRANSITION The radio transceiver's state machine is in
761  * transition between two states.
762  */
763 uint8_t
765 {
767 }
768 
769 /*----------------------------------------------------------------------------*/
770 /** \brief This function checks if the radio transceiver is sleeping.
771  *
772  * \retval true The radio transceiver is in SLEEP or one of the *_NOCLK
773  * states.
774  * \retval false The radio transceiver is not sleeping.
775  */
777 {
778  bool sleeping = false;
779 
780  /* The radio transceiver will be at SLEEP or one of the *_NOCLK states only if */
781  /* the SLP_TR pin is high. */
782  if (hal_get_slptr() != 0){
783  sleeping = true;
784  }
785 
786  return sleeping;
787 }
788 
789 /*----------------------------------------------------------------------------*/
790 /** \brief This function will change the current state of the radio
791  * transceiver's internal state machine.
792  *
793  * \param new_state Here is a list of possible states:
794  * - RX_ON Requested transition to RX_ON state.
795  * - TRX_OFF Requested transition to TRX_OFF state.
796  * - PLL_ON Requested transition to PLL_ON state.
797  * - RX_AACK_ON Requested transition to RX_AACK_ON state.
798  * - TX_ARET_ON Requested transition to TX_ARET_ON state.
799  *
800  * \retval RADIO_SUCCESS Requested state transition completed
801  * successfully.
802  * \retval RADIO_INVALID_ARGUMENT Supplied function parameter out of bounds.
803  * \retval RADIO_WRONG_STATE Illegal state to do transition from.
804  * \retval RADIO_BUSY_STATE The radio transceiver is busy.
805  * \retval RADIO_TIMED_OUT The state transition could not be completed
806  * within resonable time.
807  */
809 radio_set_trx_state(uint8_t new_state)
810 {
811  uint8_t original_state;
812 
813  /*Check function paramter and current state of the radio transceiver.*/
814  if (!((new_state == TRX_OFF) ||
815  (new_state == RX_ON) ||
816  (new_state == PLL_ON) ||
817  (new_state == RX_AACK_ON) ||
818  (new_state == TX_ARET_ON))){
819  return RADIO_INVALID_ARGUMENT;
820  }
821 
822  if (radio_is_sleeping() == true){
823  return RADIO_WRONG_STATE;
824  }
825 
826  // Wait for radio to finish previous operation
827  for(;;)
828  {
829  original_state = radio_get_trx_state();
830  if (original_state != BUSY_TX_ARET &&
831  original_state != BUSY_RX_AACK &&
832  original_state != BUSY_RX &&
833  original_state != BUSY_TX)
834  break;
835  }
836 
837  if (new_state == original_state){
838  return RADIO_SUCCESS;
839  }
840 
841 
842  /* At this point it is clear that the requested new_state is: */
843  /* TRX_OFF, RX_ON, PLL_ON, RX_AACK_ON or TX_ARET_ON. */
844 
845  /* The radio transceiver can be in one of the following states: */
846  /* TRX_OFF, RX_ON, PLL_ON, RX_AACK_ON, TX_ARET_ON. */
847  if(new_state == TRX_OFF){
848  radio_reset_state_machine(); /* Go to TRX_OFF from any state. */
849  } else {
850  /* It is not allowed to go from RX_AACK_ON or TX_AACK_ON and directly to */
851  /* TX_AACK_ON or RX_AACK_ON respectively. Need to go via RX_ON or PLL_ON. */
852  if ((new_state == TX_ARET_ON) &&
853  (original_state == RX_AACK_ON)){
854  /* First do intermediate state transition to PLL_ON, then to TX_ARET_ON. */
855  /* The final state transition to TX_ARET_ON is handled after the if-else if. */
858  } else if ((new_state == RX_AACK_ON) &&
859  (original_state == TX_ARET_ON)){
860  /* First do intermediate state transition to RX_ON, then to RX_AACK_ON. */
861  /* The final state transition to RX_AACK_ON is handled after the if-else if. */
864  }
865 
866  /* Any other state transition can be done directly. */
867  hal_subregister_write(SR_TRX_CMD, new_state);
868 
869  /* When the PLL is active most states can be reached in 1us. However, from */
870  /* TRX_OFF the PLL needs time to activate. */
871  if (original_state == TRX_OFF){
872  delay_us(TIME_TRX_OFF_TO_PLL_ACTIVE);
873  } else {
875  }
876  } /* end: if(new_state == TRX_OFF) ... */
877 
878  /*Verify state transition.*/
879  radio_status_t set_state_status = RADIO_TIMED_OUT;
880 
881  if (radio_get_trx_state() == new_state){
882  set_state_status = RADIO_SUCCESS;
883  /* set rx_mode flag based on mode we're changing to */
884  if (new_state == RX_ON ||
885  new_state == RX_AACK_ON){
886  rx_mode = true;
887  } else {
888  rx_mode = false;
889  }
890  }
891 
892  return set_state_status;
893 }
894 
895 /*----------------------------------------------------------------------------*/
896 /** \brief This function will put the radio transceiver to sleep.
897  *
898  * \retval RADIO_SUCCESS Sleep mode entered successfully.
899  * \retval RADIO_TIMED_OUT The transition to TRX_OFF took too long.
900  */
903 {
904  if (radio_is_sleeping() == true){
905  return RADIO_SUCCESS;
906  }
907 
908  radio_reset_state_machine(); /* Force the device into TRX_OFF. */
909 
910  radio_status_t enter_sleep_status = RADIO_TIMED_OUT;
911 
912  if (radio_get_trx_state() == TRX_OFF){
913  /* Enter Sleep. */
915  enter_sleep_status = RADIO_SUCCESS;
916 #if RADIOSTATS
917  RF230_radio_on = 0;
918 #endif
919  }
920 
921  return enter_sleep_status;
922 }
923 
924 /*----------------------------------------------------------------------------*/
925 /** \brief This function will take the radio transceiver from sleep mode and
926  * put it into the TRX_OFF state.
927  *
928  * \retval RADIO_SUCCESS Left sleep mode and entered TRX_OFF state.
929  * \retval RADIO_TIMED_OUT Transition to TRX_OFF state timed out.
930  */
933 {
934  /* Check if the radio transceiver is actually sleeping. */
935  if (radio_is_sleeping() == false){
936  return RADIO_SUCCESS;
937  }
938 
940  delay_us(TIME_SLEEP_TO_TRX_OFF);
941 
942  radio_status_t leave_sleep_status = RADIO_TIMED_OUT;
943 
944  /* Ensure that the radio transceiver is in the TRX_OFF state. */
945  if (radio_get_trx_state() == TRX_OFF){
946  leave_sleep_status = RADIO_SUCCESS;
947 #if RADIOSTATS
948  RF230_radio_on = 1;
949 #endif
950  }
951 
952  return leave_sleep_status;
953 }
954 
955 /*----------------------------------------------------------------------------*/
956 /** \brief This function will reset the state machine (to TRX_OFF) from any of
957  * its states, except for the SLEEP state.
958  */
959 void
961 {
963  delay_us(TIME_NOCLK_TO_WAKE);
965  delay_us(TIME_CMD_FORCE_TRX_OFF);
966 }
967 
968 /*----------------------------------------------------------------------------*/
969 /** \brief This function will reset all the registers and the state machine of
970  * the radio transceiver.
971  */
972 void
974 {
975  hal_set_rst_low();
977  delay_us(TIME_RESET);
979 }
980 
981 /*----------------------------------------------------------------------------*/
982 /** \brief This function will enable or disable automatic CRC during frame
983  * transmission.
984  *
985  * \param auto_crc_on If this parameter equals true auto CRC will be used for
986  * all frames to be transmitted. The framelength must be
987  * increased by two bytes (16 bit CRC). If the parameter equals
988  * false, the automatic CRC will be disabled.
989  */
990 void
991 radio_use_auto_tx_crc(bool auto_crc_on)
992 {
993  if (auto_crc_on == true){
995  } else {
997  }
998 }
999 
1000 /*----------------------------------------------------------------------------*/
1001 /** \brief This function will download a frame to the radio transceiver's
1002  * transmit buffer and send it.
1003  *
1004  * \param data_length Length of the frame to be transmitted. 1 to 128 bytes are the valid lengths.
1005  * \param *data Pointer to the data to transmit
1006  *
1007  * \retval RADIO_SUCCESS Frame downloaded and sent successfully.
1008  * \retval RADIO_INVALID_ARGUMENT If the dataLength is 0 byte or more than 127
1009  * bytes the frame will not be sent.
1010  * \retval RADIO_WRONG_STATE It is only possible to use this function in the
1011  * PLL_ON and TX_ARET_ON state. If any other state is
1012  * detected this error message will be returned.
1013  */
1015 radio_send_data(uint8_t data_length, uint8_t *data)
1016 {
1017  /*Check function parameters and current state.*/
1018  if (data_length > RF230_MAX_TX_FRAME_LENGTH){
1019 #if RADIOSTATS
1020  RF230_sendfail++;
1021 #endif
1022  return RADIO_INVALID_ARGUMENT;
1023  }
1024 
1025  /* If we are busy, return */
1027  {
1028 #if RADIOSTATS
1029  RF230_sendfail++;
1030 #endif
1031  return RADIO_WRONG_STATE;
1032  }
1033 
1036 
1037  /*Do frame transmission.*/
1038  /* Toggle the SLP_TR pin to initiate the frame transmission. */
1041 
1042  hal_frame_write(data, data_length); /* Then write data to the frame buffer. */
1043 #if RADIOSTATS
1044  RF230_sendpackets++;
1045 #endif
1046  return RADIO_SUCCESS;
1047 }
1048 
1049 /*----------------------------------------------------------------------------*/
1050 /** \brief This function will read the I_AM_COORD sub register.
1051  *
1052  * \retval 0 Not coordinator.
1053  * \retval 1 Coordinator role enabled.
1054  */
1055 uint8_t
1057 {
1059 }
1060 
1061 /*----------------------------------------------------------------------------*/
1062 /** \brief This function will set the I_AM_COORD sub register.
1063  *
1064  * \param[in] i_am_coordinator If this parameter is true, the associated
1065  * coordinator role will be enabled in the radio
1066  * transceiver's address filter.
1067  * False disables the same feature.
1068  */
1069 void
1070 radio_set_device_role(bool i_am_coordinator)
1071 {
1072  hal_subregister_write(SR_I_AM_COORD, i_am_coordinator);
1073 }
1074 
1075 /*----------------------------------------------------------------------------*/
1076 /** \brief This function will return the PANID used by the address filter.
1077  *
1078  * \retval Any value from 0 to 0xFFFF.
1079  */
1080 uint16_t
1082 {
1083 
1084  uint8_t pan_id_15_8 = hal_register_read(RG_PAN_ID_1); /* Read pan_id_15_8. */
1085  uint8_t pan_id_7_0 = hal_register_read(RG_PAN_ID_0); /* Read pan_id_7_0. */
1086 
1087  uint16_t pan_id = ((uint16_t)(pan_id_15_8 << 8)) | pan_id_7_0;
1088 
1089  return pan_id;
1090 }
1091 
1092 /*----------------------------------------------------------------------------*/
1093 /** \brief This function will set the PANID used by the address filter.
1094  *
1095  * \param new_pan_id Desired PANID. Can be any value from 0x0000 to 0xFFFF
1096  */
1097 void
1098 radio_set_pan_id(uint16_t new_pan_id)
1099 {
1100 
1101  uint8_t pan_byte = new_pan_id & 0xFF; /* Extract new_pan_id_7_0. */
1102  hal_register_write(RG_PAN_ID_0, pan_byte);
1103 
1104  pan_byte = (new_pan_id >> 8*1) & 0xFF; /* Extract new_pan_id_15_8. */
1105  hal_register_write(RG_PAN_ID_1, pan_byte);
1106 }
1107 
1108 /*----------------------------------------------------------------------------*/
1109 /** \brief This function will return the current short address used by the
1110  * address filter.
1111  *
1112  * \retval Any value from 0x0000 to 0xFFFF
1113  */
1114 uint16_t
1116 {
1117 
1118  uint8_t short_address_15_8 = hal_register_read(RG_SHORT_ADDR_1); /* Read short_address_15_8. */
1119  uint8_t short_address_7_0 = hal_register_read(RG_SHORT_ADDR_1); /* Read short_address_7_0. */
1120 
1121  uint16_t short_address = ((uint16_t)(short_address_15_8 << 8)) | short_address_7_0;
1122 
1123  return short_address;
1124 }
1125 
1126 /*----------------------------------------------------------------------------*/
1127 /** \brief This function will set the short address used by the address filter.
1128  *
1129  * \param new_short_address Short address to be used by the address filter.
1130  */
1131 void
1132 radio_set_short_address(uint16_t new_short_address)
1133 {
1134 
1135  uint8_t short_address_byte = new_short_address & 0xFF; /* Extract short_address_7_0. */
1136  hal_register_write(RG_SHORT_ADDR_0, short_address_byte);
1137 
1138  short_address_byte = (new_short_address >> 8*1) & 0xFF; /* Extract short_address_15_8. */
1139  hal_register_write(RG_SHORT_ADDR_1, short_address_byte);
1140 }
1141 
1142 /*----------------------------------------------------------------------------*/
1143 /** \brief This function will read the extended address used by the address
1144  * filter.
1145  *
1146  * \note In this function a pointer is used to convey the 64-bit result, since
1147  * it is very inefficient to use the stack for this.
1148  *
1149  * \return Extended Address, any 64-bit value.
1150  */
1151 void
1152 radio_get_extended_address(uint8_t *extended_address)
1153 {
1154  *extended_address++ = hal_register_read(RG_IEEE_ADDR_0);
1155  *extended_address++ = hal_register_read(RG_IEEE_ADDR_1);
1156  *extended_address++ = hal_register_read(RG_IEEE_ADDR_2);
1157  *extended_address++ = hal_register_read(RG_IEEE_ADDR_3);
1158  *extended_address++ = hal_register_read(RG_IEEE_ADDR_4);
1159  *extended_address++ = hal_register_read(RG_IEEE_ADDR_5);
1160  *extended_address++ = hal_register_read(RG_IEEE_ADDR_6);
1161  *extended_address = hal_register_read(RG_IEEE_ADDR_7);
1162 }
1163 
1164 /*----------------------------------------------------------------------------*/
1165 /** \brief This function will set a new extended address to be used by the
1166  * address filter.
1167  *
1168  * \param extended_address Extended address to be used by the address filter.
1169  */
1170 void
1171 radio_set_extended_address(uint8_t *extended_address)
1172 {
1173  hal_register_write(RG_IEEE_ADDR_0, *extended_address++);
1174  hal_register_write(RG_IEEE_ADDR_1, *extended_address++);
1175  hal_register_write(RG_IEEE_ADDR_2, *extended_address++);
1176  hal_register_write(RG_IEEE_ADDR_3, *extended_address++);
1177  hal_register_write(RG_IEEE_ADDR_4, *extended_address++);
1178  hal_register_write(RG_IEEE_ADDR_5, *extended_address++);
1179  hal_register_write(RG_IEEE_ADDR_6, *extended_address++);
1180  hal_register_write(RG_IEEE_ADDR_7, *extended_address++);
1181 }
1182 
1183 /*----------------------------------------------------------------------------*/
1184 /** \brief This function will configure the CSMA algorithm used by the radio
1185  * transceiver when transmitting data from TX_ARET_ON state.
1186  *
1187  * \param seed0 Lower 8 bits of the seed used for the random number generator
1188  * in the CSMA algorithm. Value range: 0 to 255.
1189  * \param be_csma_seed1 Is a combined argument of the MIN_BE, MAX_CSMA_RETRIES
1190  * and SEED1 variables:
1191  * -# MIN_BE: Bit[7:6] Minimum back-off exponent in the
1192  * CSMA/CA algorithm.
1193  * -# MAX_CSMA_RETRIES: Bit[5:3] Number of retries in
1194  * TX_ARET_ON mode to repeat the CSMA/CA procedures
1195  * before the ARET procedure gives up.
1196  * -# SEED1: Bits[2:0] Higher 3 bits of CSMA_SEED, bits[10:8]
1197  * Seed for the random number generator in the
1198  * CSMA/CA algorithm.
1199  * \retval RADIO_SUCCESS The CSMA algorithm was configured successfully.
1200  * \retval RADIO_WRONG_STATE This function should not be called in the
1201  * SLEEP state.
1202  */
1204 radio_configure_csma(uint8_t seed0, uint8_t be_csma_seed1)
1205 {
1206 
1207  /*Check state.*/
1208  if (radio_is_sleeping() == true){
1209  return RADIO_WRONG_STATE;
1210  }
1211 
1212  /*Extract parameters, and configure the CSMA-CA algorithm.*/
1213  uint8_t back_off_exponent = (be_csma_seed1 & 0xC0) >> 6;
1214  uint8_t csma_retries = (be_csma_seed1 & 0x38) >> 3;
1215  uint8_t seed1 = (be_csma_seed1 & 0x07);
1216 
1217  hal_subregister_write(SR_MAX_FRAME_RETRIES, 0); /* AT86RF230 rev A errata. */
1219  hal_subregister_write(SR_MIN_BE, back_off_exponent);
1222 
1223  return RADIO_SUCCESS;
1224 }
1225 
1226 /*----------------------------------------------------------------------------*/
1227 /**
1228  \brief Calibrate the internal RC oscillator
1229 
1230  This function calibrates the internal RC oscillator, based
1231  on the 1 MHz clock supplied by the AT86RF2xx. In order to
1232  verify the calibration result you can program the CKOUT fuse
1233  and monitor the CPU clock on an I/O pin.
1234 
1235  \return TRUE if calibrate passed; FALSE if calibrate failed.
1236 */
1237 bool
1239 {
1240  bool success = false;
1241 
1242  /* Use the 1 MHz CLK_M from the AT86RF230. */
1243  uint16_t temp, counter;
1244  uint8_t osccal_saved;
1245  uint8_t tccr2b, tccr1b, tccr1a;
1246 
1247  /* in the following line, 1000000ULL represents the 1MHz input signal */
1248  /* from the radio. 265 is the number of counts to overflow 8-bit */
1249  /* timer 2. 32 is the divide by 32 prescaler for timer 1. F_CPU is */
1250  /* the main clock frequency. */
1251 #define TARGETVAL ((1000000ULL * 256 * 32) / F_CPU)
1252 
1253 
1254  osccal_saved = OSCCAL;
1255  cli();
1256 
1258 
1259  /* Save current values of timer status. */
1260  tccr2b = TCCR2B;
1261  tccr1b = TCCR1B;
1262  tccr1a = TCCR1A;
1263 
1264  /* Stop timers 1 and 2. */
1265  /* Set timer 1 to normal mode (no CTC, no PWM, just count). */
1266  TCCR2B = 0;
1267  TCCR1B = 0;
1268  TCCR1A = 0;
1269 
1270  for (counter = 0; counter < 1000; counter++){
1271  /* Delete pending timer 1 and 2 interrupts, and clear the */
1272  /* counters. */
1273  TIFR1 = 0xFF;
1274  TIFR2 = 0xFF;
1275  TCNT2 = 0;
1276  TCNT1 = 0;
1277  /* Timer 2 driven from clock divided by 32 */
1278  TCCR2B = (1 << CS21) | (1 << CS20);
1279  /* Timer 1 driven with external clock */
1280  TCCR1B = (1 << CS12) | (1 << CS11);
1281 
1282  /* Wait for timer 2 to overflow. */
1283  while (!(TIFR2 & (1 << TOV2))){
1284  ;
1285  }
1286 
1287  /* Stop timer 1. Now, TCNT1 contains the number of CPU cycles */
1288  /* counted while timer 2 was counting */
1289  TCCR1B = 0;
1290  TCCR2B = 0;
1291 
1292  temp = TCNT1;
1293 
1294  if (temp < (uint16_t)(0.995 * TARGETVAL)){
1295  /* Too fast, slow down */
1296  OSCCAL--;
1297  } else if (temp > (uint16_t)(1.005 * TARGETVAL)){
1298  /* Too slow, speed up */
1299  OSCCAL++;
1300  } else {
1301  /* We are within +/- 0.5 % of our target frequency, so we're */
1302  /* done. */
1303  success = true;
1304  break;
1305  }
1306  }
1307 
1308  radio_set_clock_speed(true, CLKM_DISABLED);
1309 
1310  /* restore timer status regs */
1311  TCCR2B = tccr2b;
1312  TCCR1B = tccr1b;
1313  TCCR1A = tccr1a;
1314  if (!success){
1315  /* We failed, therefore restore previous OSCCAL value. */
1316  OSCCAL = osccal_saved;
1317  }
1318 
1319  return success;
1320 }
1321 
1322 /*----------------------------------------------------------------------------*/
1323 /**
1324  \brief Calibrate the internal RC oscillator
1325 
1326  This function calibrates the internal RC oscillator, based
1327  on an external 32KHz crystal connected to TIMER2. In order to
1328  verify the calibration result you can program the CKOUT fuse
1329  and monitor the CPU clock on an I/O pin.
1330 */
1331 void
1333 {
1334  /* Calibrate RC Oscillator: The calibration routine is done by clocking TIMER2
1335  * from the external 32kHz crystal while running an internal timer simultaneously.
1336  * The internal timer will be clocked at the same speed as the internal RC
1337  * oscillator, while TIMER2 is running at 32768 Hz. This way it is not necessary
1338  * to use a timed loop, and keep track cycles in timed loop vs. optimization
1339  * and compiler.
1340  */
1341  uint8_t osccal_original = OSCCAL;
1342  volatile uint16_t temp;
1343 
1344  /* This is bad practice, but seems to work. */
1345  OSCCAL = 0x80;
1346 
1347 
1348  // PRR0 &= ~((1 << PRTIM2)|(1 << PRTIM1)); /* Enable Timer 1 and 2 */
1349 
1350  TIMSK2 = 0x00; /* Disable Timer/Counter 2 interrupts. */
1351  TIMSK1 = 0x00; /* Disable Timer/Counter 1 interrupts. */
1352 
1353  /* Enable TIMER/COUNTER 2 to be clocked from the external 32kHz clock crystal.
1354  * Then wait for the timer to become stable before doing any calibration.
1355  */
1356  ASSR |= (1 << AS2);
1357  while (ASSR & ((1 << TCN2UB)|(1 << OCR2AUB)|(1 << TCR2AUB)|(1 << TCR2BUB))) { ; }
1358  TCCR2B = 1 << CS20; /* run timer 2 at divide by 1 (32KHz) */
1359 
1361 
1362  uint8_t counter = 128;
1363  bool cal_ok = false;
1364  do{
1365  /* wait for timer to be ready for updated config */
1366  TCCR1B = 1 << CS10;
1367 
1368  while (ASSR & ((1 << TCN2UB)|(1 << OCR2AUB)|(1 << TCR2AUB)|(1 << TCR2BUB))) { ; }
1369 
1370  TCNT2 = 0x80;
1371  TCNT1 = 0;
1372 
1373  TIFR2 = 0xFF;
1374 
1375  /* Wait for TIMER/COUNTER 2 to overflow. Stop TIMER/COUNTER 1 and 2, and
1376  * read the counter value of TIMER/COUNTER 1. It will now contain the
1377  * number of cpu cycles elapsed within the period.
1378  */
1379  while (!(TIFR2 & (1 << TOV2))){
1380  ;
1381  }
1382  temp = TCNT1;
1383 
1384  TCCR1B = 0;
1385 
1386 #define cal_upper (31250*1.05) // 32812 = 0x802c
1387 #define cal_lower (31250*0.95) // 29687 = 0x73f7
1388  /* Iteratively reduce the error to be within limits */
1389  if (temp < cal_lower) {
1390  /* Too slow. Put the hammer down. */
1391  OSCCAL++;
1392  } else if (temp > cal_upper) {
1393  /* Too fast, retard. */
1394  OSCCAL--;
1395  } else {
1396  /* The CPU clock frequency is now within +/- 0.5% of the target value. */
1397  cal_ok = true;
1398  }
1399 
1400  counter--;
1401  } while ((counter != 0) && (false == cal_ok));
1402 
1403  if (true != cal_ok) {
1404  /* We failed, therefore restore previous OSCCAL value. */
1405  OSCCAL = osccal_original;
1406  }
1407 
1408  TCCR2B = 0;
1409 
1410  ASSR &= ~(1 << AS2);
1411 
1412  /* Disable both timers again to save power. */
1413  // PRR0 |= (1 << PRTIM2);/* |(1 << PRTIM1); */
1414 
1416 }
1417 
1418 /** @} */
1419 /** @} */
1420 /*EOF*/
#define SR_MIN_BE
Access parameters for sub-register MIN_BE in register RG_CSMA_SEED_1.
#define SR_FTN_START
Access parameters for sub-register FTN_START in register RG_FTN_CTRL.
#define hal_set_slptr_low()
This macro pulls the SLP_TR pin low.
Definition: hal.h:249
The requested service timed out.
Definition: radio.h:109
#define SR_CSMA_SEED_1
Access parameters for sub-register CSMA_SEED_1 in register RG_CSMA_SEED_1.
#define RX_ON
Constant RX_ON for sub-register SR_TRX_STATUS.
radio_status_t radio_batmon_configure(bool range, uint8_t voltage_threshold)
This function is used to configure the battery monitor module.
Definition: radio.c:543
#define SR_TRX_STATUS
Access parameters for sub-register TRX_STATUS in register RG_TRX_STATUS.
Time it takes to execute the FORCE_TRX_OFF command.
Definition: radio.c:102
#define SR_PLL_DCU_START
Access parameters for sub-register PLL_DCU_START in register RG_PLL_DCU.
radio_status_t radio_set_clock_speed(bool direct, uint8_t clock_speed)
This function changes the prescaler on the CLKM pin.
Definition: radio.c:627
#define hal_get_slptr()
Read current state of the SLP_TR pin (High/Low).
Definition: hal.h:250
Transition time from P_ON to TRX_OFF.
Definition: radio.c:94
#define RG_IEEE_ADDR_3
Offset for register IEEE_ADDR_3.
#define RG_IRQ_MASK
Offset for register IRQ_MASK.
#define SR_CLKM_SHA_SEL
Access parameters for sub-register CLKM_SHA_SEL in register RG_TRX_CTRL_0.
radio_status_t radio_configure_csma(uint8_t seed0, uint8_t be_csma_seed1)
This function will configure the CSMA algorithm used by the radio transceiver when transmitting data ...
Definition: radio.c:1204
uint8_t hal_register_read(uint8_t address)
This function reads data from one of the radio transceiver&#39;s registers.
Definition: hal.c:304
Measured battery voltage is lower than voltage threshold.
Definition: radio.h:116
uint8_t radio_batmon_get_voltage_threshold(void)
This function returns the current threshold volatge used by the battery monitor (BATMON_VTH).
Definition: radio.c:511
radio_status_t radio_get_rssi_value(uint8_t *rssi)
This function returns the Received Signal Strength Indication.
Definition: radio.c:485
#define RG_CSMA_SEED_0
Offset for register CSMA_SEED_0.
void hal_clear_pll_lock_flag(void)
This function clears the PLL_LOCK flag.
Definition: hal.c:286
radio_status_t radio_send_data(uint8_t data_length, uint8_t *data)
This function will download a frame to the radio transceiver&#39;s transmit buffer and send it...
Definition: radio.c:1015
bool radio_is_sleeping(void)
This function checks if the radio transceiver is sleeping.
Definition: radio.c:776
radio_status_t radio_set_tx_power_level(uint8_t power_level)
This function will change the output power level.
Definition: radio.c:391
#define RX_AACK_ON
Constant RX_AACK_ON for sub-register SR_TRX_STATUS.
uint8_t radio_get_device_role(void)
This function will read the I_AM_COORD sub register.
Definition: radio.c:1056
#define RG_IEEE_ADDR_5
Offset for register IEEE_ADDR_5.
#define RG_IEEE_ADDR_4
Offset for register IEEE_ADDR_4.
#define SR_TRAC_STATUS
Access parameters for sub-register TRAC_STATUS in register RG_TRX_STATE.
Use carrier sense mode.
Definition: radio.h:145
#define AVR_ENTER_CRITICAL_REGION()
This macro will protect the following code from interrupts.
Definition: hal.h:313
Transition time from *_NOCLK to being awake.
Definition: radio.c:101
#define RG_SHORT_ADDR_1
Offset for register SHORT_ADDR_1.
radio_status_t radio_calibrate_filter(void)
This function calibrates the Single Side Band Filter.
Definition: radio.c:659
void rx_frame_parse(hal_rx_frame_t *rx_frame, parsed_frame_t *pf)
Parses an input frame.
Definition: frame.c:255
void calibrate_rc_osc_32k(void)
Calibrate the internal RC oscillator.
Definition: radio.c:1332
uint8_t radio_get_tx_power_level(void)
This function will read and return the output power level.
Definition: radio.c:374
#define AVR_LEAVE_CRITICAL_REGION()
This macro must always be used in conjunction with AVR_ENTER_CRITICAL_REGION so that interrupts are e...
Definition: hal.h:317
The connected device is not an Atmel AT86RF230.
Definition: radio.h:107
uint8_t radio_get_ed_threshold(void)
This function returns the current ED threshold used by the CCA algorithm.
Definition: radio.c:426
Transition time from SLEEP to TRX_OFF.
Definition: radio.c:95
#define RG_PAN_ID_0
Offset for register PAN_ID_0.
Transition time from PLL active state to another.
Definition: radio.c:104
#define TRX_OFF
Constant TRX_OFF for sub-register SR_TRX_STATUS.
uint8_t length
Length of frame.
Definition: hal.h:352
uint8_t hal_get_pll_lock_flag(void)
This function returns the current value of the PLL_LOCK flag.
Definition: hal.c:277
void radio_use_auto_tx_crc(bool auto_crc_on)
This function will enable or disable automatic CRC during frame transmission.
Definition: radio.c:991
uint8_t hal_subregister_read(uint8_t address, uint8_t mask, uint8_t position)
This function reads the value of a specific subregister.
Definition: hal.c:377
#define NULL
The null pointer.
#define hal_set_rst_low()
This macro pulls the RST pin low.
Definition: hal.h:256
This file contains low-level radio driver code.
#define SR_CHANNEL
Access parameters for sub-register CHANNEL in register RG_PHY_CC_CCA.
#define SR_CCA_MODE
Access parameters for sub-register CCA_MODE in register RG_PHY_CC_CCA.
uint8_t radio_get_operating_channel(void)
This function will return the channel used by the radio transceiver.
Definition: radio.c:313
void hal_init(void)
This function initializes the Hardware Abstraction Layer.
Definition: hal.c:133
This struct defines the rx data container.
Definition: hal.h:351
void hal_subregister_write(uint8_t address, uint8_t mask, uint8_t position, uint8_t value)
This function writes a new value to one of the radio transceiver&#39;s subregisters.
Definition: hal.c:400
#define hal_set_rst_high()
This macro pulls the RST pin high.
Definition: hal.h:255
uint8_t data[HAL_MAX_FRAME_LENGTH]
Actual frame data.
Definition: hal.h:353
#define SR_BATMON_HR
Access parameters for sub-register BATMON_HR in register RG_BATMON.
bool calibrate_rc_osc_clkm(void)
Calibrate the internal RC oscillator.
Definition: radio.c:1238
#define BUSY_RX
Constant BUSY_RX for sub-register SR_TRX_STATUS.
uint8_t radio_get_clock_speed(void)
This function returns the current clock setting for the CLKM pin.
Definition: radio.c:601
#define SR_TRX_CMD
Access parameters for sub-register TRX_CMD in register RG_TRX_STATE.
radio_status_t radio_leave_sleep_mode(void)
This function will take the radio transceiver from sleep mode and put it into the TRX_OFF state...
Definition: radio.c:932
void radio_get_extended_address(uint8_t *extended_address)
This function will read the extended address used by the address filter.
Definition: radio.c:1152
void hal_frame_read(hal_rx_frame_t *rx_frame, rx_callback_t rx_callback)
This function will upload a frame from the radio transceiver&#39;s frame buffer.
Definition: hal.c:429
#define RG_MAN_ID_0
Offset for register MAN_ID_0.
uint8_t radio_get_trx_state(void)
This function return the Radio Transceivers current state.
Definition: radio.c:764
void(* hal_trx_end_isr_event_handler_t)(uint32_t const isr_timestamp)
RRX_END event handler callback type.
Definition: hal.h:362
int process_post(struct process *p, process_event_t ev, process_data_t data)
Post an asynchronous event.
Definition: process.c:322
Transition time from TRX_OFF to: RX_ON, PLL_ON, TX_ARET_ON and RX_AACK_ON.
Definition: radio.c:103
#define SR_I_AM_COORD
Access parameters for sub-register I_AM_COORD in register RG_CSMA_SEED_1.
Maximum time it should take for the PLL to lock.
Definition: radio.c:99
#define RG_SHORT_ADDR_0
Offset for register SHORT_ADDR_0.
uint16_t radio_get_pan_id(void)
This function will return the PANID used by the address filter.
Definition: radio.c:1081
Transition time from VCC is applied to P_ON.
Definition: radio.c:93
radio_status_t radio_set_cca_mode(uint8_t mode, uint8_t ed_threshold)
This function will configure the Clear Channel Assessment algorithm.
Definition: radio.c:448
#define SR_RSSI
Access parameters for sub-register RSSI in register RG_PHY_RSSI.
void hal_frame_write(uint8_t *write_buffer, uint8_t length)
This function will download a frame to the radio transceiver&#39;s frame buffer.
Definition: hal.c:516
The end-user tried to do an invalid state transition.
Definition: radio.h:110
uint16_t radio_get_short_address(void)
This function will return the current short address used by the address filter.
Definition: radio.c:1115
#define SR_CLKM_CTRL
Access parameters for sub-register CLKM_CTRL in register RG_TRX_CTRL_0.
Use a combination of both energy detection and carrier sense.
Definition: radio.h:146
#define CLKM_1MHz
Constant CLKM_1MHz for sub-register SR_CLKM_CTRL.
radio_status_t radio_init(bool cal_rc_osc, hal_rx_start_isr_event_handler_t rx_event, hal_trx_end_isr_event_handler_t trx_end_event, radio_rx_callback rx_callback)
Initialize the Transceiver Access Toolbox and lower layers.
Definition: radio.c:160
uint8_t radio_get_cca_mode(void)
This function returns the current CCA mode used.
Definition: radio.c:415
#define hal_set_slptr_high()
This macro pulls the SLP_TR pin high.
Definition: hal.h:248
#define SR_MAX_FRAME_RETRIES
Access parameters for sub-register MAX_FRAME_RETRIES in register RG_XAH_CTRL_0.
radio_trx_timing_t
This enumeration defines the necessary timing information for the AT86RF230 radio transceiver...
Definition: radio.c:92
#define RG_IEEE_ADDR_0
Offset for register IEEE_ADDR_0.
radio_status_t radio_calibrate_pll(void)
This function calibrates the PLL.
Definition: radio.c:691
#define SR_BATMON_OK
Access parameters for sub-register BATMON_OK in register RG_BATMON.
radio_status_t
This enumeration defines the possible return values for the TAT API functions.
Definition: radio.h:105
#define SR_PLL_CF_START
Access parameters for sub-register PLL_CF_START in register RG_PLL_CF.
#define BUSY_RX_AACK
Constant BUSY_RX_AACK for sub-register SR_TRX_STATUS.
#define CMD_FORCE_TRX_OFF
Constant CMD_FORCE_TRX_OFF for sub-register SR_TRX_CMD.
radio_status_t radio_set_operating_channel(uint8_t channel)
This function will change the operating channel.
Definition: radio.c:329
#define RG_IEEE_ADDR_1
Offset for register IEEE_ADDR_1.
Time it takes to do a ED measurement.
Definition: radio.c:97
#define RF230_MAX_TX_FRAME_LENGTH
127 Byte PSDU.
Definition: radio.h:69
The requested service was performed successfully.
Definition: radio.h:106
void hal_set_rx_start_event_handler(hal_rx_start_isr_event_handler_t rx_start_callback_handle)
This function is used to set new RX_START event handler, overriding old handler reference.
Definition: hal.c:251
#define RG_IEEE_ADDR_7
Offset for register IEEE_ADDR_7.
#define RG_IEEE_ADDR_6
Offset for register IEEE_ADDR_6.
Time it takes to do a CCA.
Definition: radio.c:98
Time to hold the RST pin low during reset.
Definition: radio.c:96
void radio_set_pan_id(uint16_t new_pan_id)
This function will set the PANID used by the address filter.
Definition: radio.c:1098
#define SR_TX_PWR
Access parameters for sub-register TX_PWR in register RG_PHY_TX_PWR.
#define BUSY_TX_ARET
Constant BUSY_TX_ARET for sub-register SR_TRX_STATUS.
void radio_set_device_role(bool i_am_coordinator)
This function will set the I_AM_COORD sub register.
Definition: radio.c:1070
#define TX_ARET_ON
Constant TX_ARET_ON for sub-register SR_TRX_STATUS.
#define RG_VERSION_NUM
Offset for register VERSION_NUM.
#define RG_IEEE_ADDR_2
Offset for register IEEE_ADDR_2.
void mac_put_event(event_object_t *object)
Puts an event into the queue of events.
Definition: sicslowmac.c:133
void radio_set_extended_address(uint8_t *extended_address)
This function will set a new extended address to be used by the address filter.
Definition: radio.c:1171
#define PLL_ON
Constant PLL_ON for sub-register SR_TRX_STATUS.
void hal_register_write(uint8_t address, uint8_t value)
This function writes a new value to one of the radio transceiver&#39;s registers.
Definition: hal.c:342
radio_status_t radio_enter_sleep_mode(void)
This function will put the radio transceiver to sleep.
Definition: radio.c:902
#define SR_BATMON_VTH
Access parameters for sub-register BATMON_VTH in register RG_BATMON.
void radio_set_short_address(uint16_t new_short_address)
This function will set the short address used by the address filter.
Definition: radio.c:1132
#define SR_TX_AUTO_CRC_ON
Access parameters for sub-register TX_AUTO_CRC_ON in register RG_PHY_TX_PWR.
Maximum time it should take to do the filter tuning.
Definition: radio.c:100
#define SR_MAX_CSMA_RETRIES
Access parameters for sub-register MAX_CSMA_RETRIES in register RG_XAH_CTRL_0.
#define RG_PAN_ID_1
Offset for register PAN_ID_1.
802.15.4 frame creation and parsing functions
One or more of the supplied function arguments are invalid.
Definition: radio.h:108
Header file for the Contiki process interface.
#define SR_CCA_ED_THRES
Access parameters for sub-register CCA_ED_THRES in register RG_CCA_THRES.
uint8_t radio_batmon_get_voltage_range(void)
This function returns if high or low voltage range is used.
Definition: radio.c:526
radio_status_t radio_set_trx_state(uint8_t new_state)
This function will change the current state of the radio transceiver&#39;s internal state machine...
Definition: radio.c:809
#define BUSY_TX
Constant BUSY_TX for sub-register SR_TRX_STATUS.
This file contains radio driver code.
Use energy detection above threshold mode.
Definition: radio.h:144
void hal_set_trx_end_event_handler(hal_trx_end_isr_event_handler_t trx_end_callback_handle)
This function is used to set new TRX_END event handler, overriding old handler reference.
Definition: hal.c:217
void radio_reset_state_machine(void)
This function will reset the state machine (to TRX_OFF) from any of its states, except for the SLEEP ...
Definition: radio.c:960
void(* hal_rx_start_isr_event_handler_t)(uint32_t const isr_timestamp, uint8_t const frame_length)
RX_START event handler callback type.
Definition: hal.h:359
void radio_reset_trx(void)
This function will reset all the registers and the state machine of the radio transceiver.
Definition: radio.c:973
Measured battery voltage is above the voltage threshold.
Definition: radio.h:117
radio_status_t radio_batmon_get_status(void)
This function returns the status of the Battery Monitor module.
Definition: radio.c:577