69 #include <util/delay.h>
73 #include "sicslowmac.h"
77 #define RADIO_CCA_DONE_MASK (1 << 7)
78 #define RADIO_CCA_IDLE_MASK (1 << 6)
80 #define RADIO_START_CCA (1)
82 #define RADIO_TRANSMISSION_SUCCESS (0)
83 #define RADIO_BUSY_CHANNEL (3)
84 #define RADIO_MIN_IEEE_FRAME_LENGTH (5)
110 static radio_rx_callback rx_frame_callback;
111 static uint8_t rssi_val;
112 static uint8_t rx_mode;
118 uint8_t RF230_radio_on, RF230_rsigsi;
119 uint16_t RF230_sendpackets,RF230_receivepackets,RF230_sendfail,RF230_receivefail;
123 static parsed_frame_t parsed_frame;
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);
163 radio_rx_callback rx_callback)
189 if ((version_number != RF230_REVA) && (version_number != RF230_REVB))
204 user_rx_event = rx_event;
205 user_trx_end_event = trx_end_event;
209 rx_frame_callback = rx_callback;
216 radio_frame_data(
void)
218 return rx_frame.
data;
222 radio_frame_length(
void)
229 radio_rx_start_event(uint32_t
const isr_timestamp, uint8_t
const frame_length)
236 user_rx_event(isr_timestamp, frame_length);
241 radio_get_saved_rssi_value(
void)
248 radio_trx_end_event(uint32_t
const isr_timestamp)
250 volatile uint8_t status;
253 if (user_trx_end_event){
254 user_trx_end_event(isr_timestamp);
260 RF230_rsigsi=rssi_val;
261 RF230_receivepackets++;
263 parsed_frame.time = isr_timestamp;
264 parsed_frame.rssi = rssi_val;
276 event_object_t event;
282 case TRAC_SUCCESS_DATA_PENDING:
283 event.event = MAC_EVENT_ACK;
286 case TRAC_CHANNEL_ACCESS_FAILURE:
287 event.event = MAC_EVENT_NACK;
292 case TRAC_SUCCESS_WAIT_FOR_ACK:
332 if ((channel < RF230_MIN_CHANNEL) ||
333 (channel > RF230_MAX_CHANNEL)){
352 if ((trx_state ==
RX_ON) ||
364 return channel_set_status;
395 if (power_level > TX_PWR_17_2DBM){
458 if (ed_threshold > RF230_MAX_ED_THRESHOLD){
492 if ((current_state ==
RX_ON) ||
547 if (voltage_threshold > BATTERY_MONITOR_HIGHEST_VOLTAGE){
583 BATTERY_MONITOR_VOLTAGE_UNDER_THRESHOLD){
587 return batmon_status;
630 if (clock_speed > CLKM_16MHZ){
639 if (direct ==
false){
680 return filter_calibration_status;
717 return pll_calibration_status;
778 bool sleeping =
false;
811 uint8_t original_state;
814 if (!((new_state ==
TRX_OFF) ||
815 (new_state ==
RX_ON) ||
837 if (new_state == original_state){
871 if (original_state ==
TRX_OFF){
884 if (new_state ==
RX_ON ||
892 return set_state_status;
921 return enter_sleep_status;
952 return leave_sleep_status;
993 if (auto_crc_on ==
true){
1044 RF230_sendpackets++;
1087 uint16_t pan_id = ((uint16_t)(pan_id_15_8 << 8)) | pan_id_7_0;
1101 uint8_t pan_byte = new_pan_id & 0xFF;
1104 pan_byte = (new_pan_id >> 8*1) & 0xFF;
1121 uint16_t short_address = ((uint16_t)(short_address_15_8 << 8)) | short_address_7_0;
1123 return short_address;
1135 uint8_t short_address_byte = new_short_address & 0xFF;
1138 short_address_byte = (new_short_address >> 8*1) & 0xFF;
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);
1240 bool success =
false;
1243 uint16_t temp, counter;
1244 uint8_t osccal_saved;
1245 uint8_t tccr2b, tccr1b, tccr1a;
1251 #define TARGETVAL ((1000000ULL * 256 * 32) / F_CPU)
1254 osccal_saved = OSCCAL;
1270 for (counter = 0; counter < 1000; counter++){
1278 TCCR2B = (1 << CS21) | (1 << CS20);
1280 TCCR1B = (1 << CS12) | (1 << CS11);
1283 while (!(TIFR2 & (1 << TOV2))){
1294 if (temp < (uint16_t)(0.995 * TARGETVAL)){
1297 }
else if (temp > (uint16_t)(1.005 * TARGETVAL)){
1316 OSCCAL = osccal_saved;
1341 uint8_t osccal_original = OSCCAL;
1342 volatile uint16_t temp;
1357 while (ASSR & ((1 << TCN2UB)|(1 << OCR2AUB)|(1 << TCR2AUB)|(1 << TCR2BUB))) { ; }
1362 uint8_t counter = 128;
1363 bool cal_ok =
false;
1368 while (ASSR & ((1 << TCN2UB)|(1 << OCR2AUB)|(1 << TCR2AUB)|(1 << TCR2BUB))) { ; }
1379 while (!(TIFR2 & (1 << TOV2))){
1386 #define cal_upper (31250*1.05) // 32812 = 0x802c
1387 #define cal_lower (31250*0.95) // 29687 = 0x73f7
1389 if (temp < cal_lower) {
1392 }
else if (temp > cal_upper) {
1401 }
while ((counter != 0) && (
false == cal_ok));
1403 if (
true != cal_ok) {
1405 OSCCAL = osccal_original;
1410 ASSR &= ~(1 << AS2);
#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.
The requested service timed out.
#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.
#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.
#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.
#define hal_get_slptr()
Read current state of the SLP_TR pin (High/Low).
Transition time from P_ON to TRX_OFF.
#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 ...
uint8_t hal_register_read(uint8_t address)
This function reads data from one of the radio transceiver's registers.
Measured battery voltage is lower than voltage threshold.
uint8_t radio_batmon_get_voltage_threshold(void)
This function returns the current threshold volatge used by the battery monitor (BATMON_VTH).
radio_status_t radio_get_rssi_value(uint8_t *rssi)
This function returns the Received Signal Strength Indication.
#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.
radio_status_t radio_send_data(uint8_t data_length, uint8_t *data)
This function will download a frame to the radio transceiver's transmit buffer and send it...
bool radio_is_sleeping(void)
This function checks if the radio transceiver is sleeping.
radio_status_t radio_set_tx_power_level(uint8_t power_level)
This function will change the output power level.
#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.
#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.
#define AVR_ENTER_CRITICAL_REGION()
This macro will protect the following code from interrupts.
Transition time from *_NOCLK to being awake.
#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.
void rx_frame_parse(hal_rx_frame_t *rx_frame, parsed_frame_t *pf)
Parses an input frame.
void calibrate_rc_osc_32k(void)
Calibrate the internal RC oscillator.
uint8_t radio_get_tx_power_level(void)
This function will read and return the output power level.
#define AVR_LEAVE_CRITICAL_REGION()
This macro must always be used in conjunction with AVR_ENTER_CRITICAL_REGION so that interrupts are e...
The connected device is not an Atmel AT86RF230.
uint8_t radio_get_ed_threshold(void)
This function returns the current ED threshold used by the CCA algorithm.
Transition time from SLEEP to TRX_OFF.
#define RG_PAN_ID_0
Offset for register PAN_ID_0.
Transition time from PLL active state to another.
#define TRX_OFF
Constant TRX_OFF for sub-register SR_TRX_STATUS.
uint8_t length
Length of frame.
uint8_t hal_get_pll_lock_flag(void)
This function returns the current value of the PLL_LOCK flag.
void radio_use_auto_tx_crc(bool auto_crc_on)
This function will enable or disable automatic CRC during frame transmission.
uint8_t hal_subregister_read(uint8_t address, uint8_t mask, uint8_t position)
This function reads the value of a specific subregister.
#define NULL
The null pointer.
#define hal_set_rst_low()
This macro pulls the RST pin low.
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.
void hal_init(void)
This function initializes the Hardware Abstraction Layer.
This struct defines the rx data container.
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's subregisters.
#define hal_set_rst_high()
This macro pulls the RST pin high.
uint8_t data[HAL_MAX_FRAME_LENGTH]
Actual frame data.
#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.
#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.
#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...
void radio_get_extended_address(uint8_t *extended_address)
This function will read the extended address used by the address filter.
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's frame buffer.
#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.
void(* hal_trx_end_isr_event_handler_t)(uint32_t const isr_timestamp)
RRX_END event handler callback type.
int process_post(struct process *p, process_event_t ev, process_data_t data)
Post an asynchronous event.
Transition time from TRX_OFF to: RX_ON, PLL_ON, TX_ARET_ON and RX_AACK_ON.
#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.
#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.
Transition time from VCC is applied to P_ON.
radio_status_t radio_set_cca_mode(uint8_t mode, uint8_t ed_threshold)
This function will configure the Clear Channel Assessment algorithm.
#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's frame buffer.
The end-user tried to do an invalid state transition.
uint16_t radio_get_short_address(void)
This function will return the current short address used by the address filter.
#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.
#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.
uint8_t radio_get_cca_mode(void)
This function returns the current CCA mode used.
#define hal_set_slptr_high()
This macro pulls the SLP_TR pin high.
#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...
#define RG_IEEE_ADDR_0
Offset for register IEEE_ADDR_0.
radio_status_t radio_calibrate_pll(void)
This function calibrates the PLL.
#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.
#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.
#define RG_IEEE_ADDR_1
Offset for register IEEE_ADDR_1.
Time it takes to do a ED measurement.
#define RF230_MAX_TX_FRAME_LENGTH
127 Byte PSDU.
The requested service was performed successfully.
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.
#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.
Time to hold the RST pin low during reset.
void radio_set_pan_id(uint16_t new_pan_id)
This function will set the PANID used by the address filter.
#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.
#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.
void radio_set_extended_address(uint8_t *extended_address)
This function will set a new extended address to be used by the address filter.
#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's registers.
radio_status_t radio_enter_sleep_mode(void)
This function will put the radio transceiver to sleep.
#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.
#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.
#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.
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.
radio_status_t radio_set_trx_state(uint8_t new_state)
This function will change the current state of the radio transceiver's internal state machine...
#define BUSY_TX
Constant BUSY_TX for sub-register SR_TRX_STATUS.
This file contains radio driver code.
Use energy detection above threshold mode.
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.
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 ...
void(* hal_rx_start_isr_event_handler_t)(uint32_t const isr_timestamp, uint8_t const frame_length)
RX_START event handler callback type.
void radio_reset_trx(void)
This function will reset all the registers and the state machine of the radio transceiver.
Measured battery voltage is above the voltage threshold.
radio_status_t radio_batmon_get_status(void)
This function returns the status of the Battery Monitor module.