Kenji Arai / mbed-os_TYBLE16

Dependents:   TYBLE16_simple_data_logger TYBLE16_MP3_Air

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers NanostackRfPhys2lp.cpp Source File

NanostackRfPhys2lp.cpp

00001 /*
00002  * Copyright (c) 2018 ARM Limited. All rights reserved.
00003  * SPDX-License-Identifier: Apache-2.0
00004  * Licensed under the Apache License, Version 2.0 (the License); you may
00005  * not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  * http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an AS IS BASIS, WITHOUT
00012  * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 #include <string.h>
00017 #if defined(MBED_CONF_NANOSTACK_CONFIGURATION) && DEVICE_SPI && DEVICE_INTERRUPTIN && defined(MBED_CONF_RTOS_PRESENT)
00018 #include "platform/arm_hal_interrupt.h"
00019 #include "nanostack/platform/arm_hal_phy.h"
00020 #include "ns_types.h"
00021 #include "NanostackRfPhys2lp.h"
00022 #include "s2lpReg.h"
00023 #include "rf_configuration.h"
00024 #include "randLIB.h"
00025 #include "mbed_trace.h"
00026 #include "mbed_toolchain.h"
00027 #include "common_functions.h"
00028 #include <Timer.h>
00029 #include "Timeout.h"
00030 #include "Thread.h"
00031 #include "mbed_wait_api.h"
00032 #include "platform/mbed_error.h"
00033 
00034 using namespace mbed;
00035 using namespace rtos;
00036 
00037 #define TRACE_GROUP "s2lp"
00038 
00039 #define INTERRUPT_GPIO  S2LP_GPIO3
00040 
00041 #if INTERRUPT_GPIO == S2LP_GPIO0
00042 #define INT_IN_GPIO     rf->RF_S2LP_GPIO0
00043 #elif INTERRUPT_GPIO == S2LP_GPIO1
00044 #define INT_IN_GPIO     rf->RF_S2LP_GPIO1
00045 #elif INTERRUPT_GPIO == S2LP_GPIO2
00046 #define INT_IN_GPIO     rf->RF_S2LP_GPIO2
00047 #else
00048 #define INT_IN_GPIO     rf->RF_S2LP_GPIO3
00049 #endif
00050 
00051 #ifdef TEST_GPIOS_ENABLED
00052 #define TEST_TX_STARTED     rf->TEST1 = 1;
00053 #define TEST_TX_DONE        rf->TEST1 = 0;
00054 #define TEST_RX_STARTED     rf->TEST2 = 1;
00055 #define TEST_RX_DONE        rf->TEST2 = 0;
00056 #define TEST_ACK_TX_STARTED rf->TEST3 = 1;
00057 #define TEST_ACK_TX_DONE    rf->TEST3 = 0;
00058 #define TEST1_ON            rf->TEST4 = 1;
00059 #define TEST1_OFF           rf->TEST4 = 0;
00060 #define TEST2_ON            rf->TEST5 = 1;
00061 #define TEST2_OFF           rf->TEST5 = 0;
00062 extern void (*fhss_uc_switch)(void);
00063 extern void (*fhss_bc_switch)(void);
00064 #else //TEST_GPIOS_ENABLED
00065 #define TEST_TX_STARTED
00066 #define TEST_TX_DONE
00067 #define TEST_RX_STARTED
00068 #define TEST_RX_DONE
00069 #define TEST_ACK_TX_STARTED
00070 #define TEST_ACK_TX_DONE
00071 #define TEST1_ON
00072 #define TEST1_OFF
00073 #define TEST2_ON
00074 #define TEST2_OFF
00075 #endif //TEST_GPIOS_ENABLED
00076 
00077 #define MAC_FRAME_TYPE_MASK     0x07
00078 #define MAC_FRAME_BEACON        (0)
00079 #define MAC_TYPE_DATA           (1)
00080 #define MAC_TYPE_ACK            (2)
00081 #define MAC_TYPE_COMMAND        (3)
00082 #define MAC_DATA_PENDING        0x10
00083 #define FC_DST_MODE             0x0C
00084 #define FC_SRC_MODE             0xC0
00085 #define FC_DST_ADDR_NONE        0x00
00086 #define FC_DST_16_BITS          0x08
00087 #define FC_DST_64_BITS          0x0C
00088 #define FC_SRC_64_BITS          0xC0
00089 #define FC_SEQUENCE_COMPRESSION 0x01
00090 #define FC_AR                   0x20
00091 #define FC_PAN_ID_COMPRESSION   0x40
00092 #define VERSION_FIELD_MASK      0x30
00093 #define SHIFT_SEQ_COMP_FIELD    (0)
00094 #define SHIFT_VERSION_FIELD     (4)
00095 #define SHIFT_PANID_COMP_FIELD  (6)
00096 #define OFFSET_DST_PAN_ID       (3)
00097 #define OFFSET_DST_ADDR         (5)
00098 
00099 #define CS_SELECT()  {rf->CS = 0;}
00100 #define CS_RELEASE() {rf->CS = 1;}
00101 
00102 typedef enum {
00103     RF_MODE_NORMAL = 0,
00104     RF_MODE_SNIFFER = 1
00105 } rf_mode_e;
00106 
00107 class UnlockedSPI : public SPI {
00108 public:
00109     UnlockedSPI(PinName sdi, PinName sdo, PinName sclk) :
00110         SPI(sdi, sdo, sclk) { }
00111     virtual void lock() { }
00112     virtual void unlock() { }
00113 };
00114 
00115 class RFPins {
00116 public:
00117     RFPins(PinName spi_sdi, PinName spi_sdo,
00118            PinName spi_sclk, PinName spi_cs, PinName spi_sdn,
00119 #ifdef TEST_GPIOS_ENABLED
00120            PinName spi_test1, PinName spi_test2, PinName spi_test3, PinName spi_test4, PinName spi_test5,
00121 #endif //TEST_GPIOS_ENABLED
00122            PinName spi_gpio0, PinName spi_gpio1, PinName spi_gpio2,
00123            PinName spi_gpio3);
00124     UnlockedSPI spi;
00125     DigitalOut CS;
00126     DigitalOut SDN;
00127 #ifdef TEST_GPIOS_ENABLED
00128     DigitalOut TEST1;
00129     DigitalOut TEST2;
00130     DigitalOut TEST3;
00131     DigitalOut TEST4;
00132     DigitalOut TEST5;
00133 #endif //TEST_GPIOS_ENABLED
00134     InterruptIn RF_S2LP_GPIO0;
00135     InterruptIn RF_S2LP_GPIO1;
00136     InterruptIn RF_S2LP_GPIO2;
00137     InterruptIn RF_S2LP_GPIO3;
00138     Timeout cca_timer;
00139     Timeout backup_timer;
00140     Timer tx_timer;
00141     Thread irq_thread;
00142     Mutex mutex;
00143     void rf_irq_task();
00144 };
00145 
00146 RFPins::RFPins(PinName spi_sdi, PinName spi_sdo,
00147                PinName spi_sclk, PinName spi_cs, PinName spi_sdn,
00148 #ifdef TEST_GPIOS_ENABLED
00149                PinName spi_test1, PinName spi_test2, PinName spi_test3, PinName spi_test4, PinName spi_test5,
00150 #endif //TEST_GPIOS_ENABLED
00151                PinName spi_gpio0, PinName spi_gpio1, PinName spi_gpio2,
00152                PinName spi_gpio3)
00153     :   spi(spi_sdi, spi_sdo, spi_sclk),
00154         CS(spi_cs),
00155         SDN(spi_sdn),
00156 #ifdef TEST_GPIOS_ENABLED
00157         TEST1(spi_test1),
00158         TEST2(spi_test2),
00159         TEST3(spi_test3),
00160         TEST4(spi_test4),
00161         TEST5(spi_test5),
00162 #endif //TEST_GPIOS_ENABLED
00163         RF_S2LP_GPIO0(spi_gpio0),
00164         RF_S2LP_GPIO1(spi_gpio1),
00165         RF_S2LP_GPIO2(spi_gpio2),
00166         RF_S2LP_GPIO3(spi_gpio3),
00167         irq_thread(osPriorityRealtime, 1024)
00168 {
00169     irq_thread.start(mbed::callback(this, &RFPins::rf_irq_task));
00170 }
00171 
00172 static uint8_t rf_read_register(uint8_t addr);
00173 static s2lp_states_e rf_read_state(void);
00174 static void rf_write_register(uint8_t addr, uint8_t data);
00175 static void rf_interrupt_handler(void);
00176 static void rf_receive(uint8_t rx_channel);
00177 static void rf_cca_timer_stop(void);
00178 static void rf_backup_timer_start(uint32_t slots);
00179 static void rf_backup_timer_stop(void);
00180 static void rf_rx_ready_handler(void);
00181 static uint32_t read_irq_status(void);
00182 static bool rf_rx_filter(uint8_t *mac_header, uint8_t *mac_64bit_addr, uint8_t *mac_16bit_addr, uint8_t *pan_id);
00183 static void rf_cca_timer_start(uint32_t slots);
00184 
00185 static RFPins *rf;
00186 static phy_device_driver_s device_driver;
00187 static int8_t rf_radio_driver_id = -1;
00188 static uint8_t *tx_data_ptr;
00189 static uint16_t tx_data_length;
00190 static uint16_t rx_data_length;
00191 static uint32_t enabled_interrupts;
00192 static uint8_t mac_tx_handle;
00193 static uint8_t rf_rx_channel;
00194 static uint8_t rf_new_channel;
00195 static uint8_t rx_buffer[RF_MTU];
00196 static rf_states_e rf_state = RF_IDLE;
00197 // This will be used when given channel spacing cannot be supported by transceiver
00198 static uint8_t rf_channel_multiplier = 1;
00199 static uint16_t tx_sequence = 0xffff;
00200 static uint32_t tx_time = 0;
00201 static uint32_t rx_time = 0;
00202 static uint32_t tx_finnish_time = 0;
00203 static uint32_t rf_symbol_rate;
00204 static bool cca_enabled = true;
00205 static uint8_t s2lp_PAN_ID[2] = {0xff, 0xff};
00206 static uint8_t s2lp_short_address[2];
00207 static uint8_t s2lp_MAC[8];
00208 static rf_mode_e rf_mode = RF_MODE_NORMAL;
00209 static bool rf_update_config = false;
00210 static uint16_t cur_packet_len = 0xffff;
00211 static uint32_t receiver_ready_timestamp;
00212 
00213 static int16_t rssi_threshold = RSSI_THRESHOLD;
00214 
00215 /* Channel configurations for sub-GHz */
00216 static phy_rf_channel_configuration_s phy_subghz = {
00217     .channel_0_center_frequency = 868300000U,
00218     .channel_spacing = 500000U,
00219     .datarate = 250000U,
00220     .number_of_channels = 11U,
00221     .modulation = M_2FSK,
00222     .modulation_index = MODULATION_INDEX_UNDEFINED
00223 };
00224 
00225 
00226 static const phy_device_channel_page_s phy_channel_pages[] = {
00227     { CHANNEL_PAGE_2, &phy_subghz},
00228     { CHANNEL_PAGE_0, NULL}
00229 };
00230 
00231 
00232 #include "rtos.h"
00233 
00234 static void rf_irq_task_process_irq();
00235 
00236 #define SIG_ALL             (SIG_RADIO|SIG_TIMER_CCA|SIG_TIMER_BACKUP)
00237 #define SIG_RADIO           1
00238 #define SIG_TIMER_CCA       2
00239 #define SIG_TIMER_BACKUP    4
00240 
00241 
00242 #define ACK_FRAME_LENGTH    3
00243 // Give some additional time for processing, PHY headers, CRC etc.
00244 #define PACKET_SENDING_EXTRA_TIME   5000
00245 #define MAX_PACKET_SENDING_TIME (uint32_t)(8000000/phy_subghz.datarate)*FIFO_SIZE + PACKET_SENDING_EXTRA_TIME
00246 #define ACK_SENDING_TIME (uint32_t)(8000000/phy_subghz.datarate)*ACK_FRAME_LENGTH + PACKET_SENDING_EXTRA_TIME
00247 
00248 #ifdef TEST_GPIOS_ENABLED
00249 void test1_toggle(void)
00250 {
00251     if (rf->TEST4) {
00252         rf->TEST4 = 0;
00253     } else {
00254         rf->TEST4 = 1;
00255     }
00256 }
00257 void test2_toggle(void)
00258 {
00259     if (rf->TEST5) {
00260         rf->TEST5 = 0;
00261     } else {
00262         rf->TEST5 = 1;
00263     }
00264 }
00265 #endif //TEST_GPIOS_ENABLED
00266 
00267 static void rf_calculate_symbol_rate(uint32_t baudrate, phy_modulation_e modulation)
00268 {
00269     (void) modulation;
00270     uint8_t bits_in_symbols = 1;
00271     rf_symbol_rate = baudrate / bits_in_symbols;
00272 }
00273 
00274 static uint32_t rf_get_timestamp(void)
00275 {
00276     return (uint32_t)rf->tx_timer.read_us();
00277 }
00278 
00279 static void rf_lock(void)
00280 {
00281     platform_enter_critical();
00282 }
00283 
00284 static void rf_unlock(void)
00285 {
00286     platform_exit_critical();
00287 }
00288 
00289 static void rf_cca_timer_signal(void)
00290 {
00291     rf->irq_thread.flags_set(SIG_TIMER_CCA);
00292 }
00293 
00294 static void rf_backup_timer_signal(void)
00295 {
00296     rf->irq_thread.flags_set(SIG_TIMER_BACKUP);
00297 }
00298 
00299 /*
00300  * \brief Function writes/read data in SPI interface
00301  */
00302 static void rf_spi_exchange(const void *tx, size_t tx_len, void *rx, size_t rx_len)
00303 {
00304     rf->spi.write(static_cast<const char *>(tx), tx_len, static_cast<char *>(rx), rx_len);
00305 }
00306 
00307 static uint8_t rf_read_register(uint8_t addr)
00308 {
00309     const uint8_t tx[2] = {SPI_RD_REG, addr};
00310     uint8_t rx[3];
00311     rf_lock();
00312     CS_SELECT();
00313     rf_spi_exchange(tx, sizeof(tx), rx, sizeof(rx));
00314     CS_RELEASE();
00315     rf_unlock();
00316     return rx[2];
00317 }
00318 
00319 static void rf_write_register(uint8_t addr, uint8_t data)
00320 {
00321     const uint8_t tx[3] = {SPI_WR_REG, addr, data};
00322     rf_lock();
00323     CS_SELECT();
00324     rf_spi_exchange(tx, sizeof(tx), NULL, 0);
00325     CS_RELEASE();
00326     rf_unlock();
00327 }
00328 
00329 static void rf_write_register_field(uint8_t addr, uint8_t field, uint8_t value)
00330 {
00331     uint8_t reg_tmp = rf_read_register(addr);
00332     reg_tmp &= ~field;
00333     reg_tmp |= value;
00334     rf_write_register(addr, reg_tmp);
00335 }
00336 
00337 static s2lp_states_e rf_read_state(void)
00338 {
00339     return (s2lp_states_e)(rf_read_register(MC_STATE0) >> 1);
00340 }
00341 
00342 static void rf_poll_state_change(s2lp_states_e state)
00343 {
00344     uint16_t break_counter = 0;
00345     while (state != rf_read_state()) {
00346         if (break_counter++ == 0xffff) {
00347             tr_err("Failed to change state from %x to: %x", rf_read_state(), state);
00348             break;
00349         }
00350     }
00351 }
00352 
00353 static void rf_enable_gpio_signal(uint8_t gpio_pin, uint8_t interrupt_signal, uint8_t gpio_mode)
00354 {
00355     rf_write_register(GPIO0_CONF + gpio_pin, (interrupt_signal << 3) | gpio_mode);
00356 }
00357 
00358 static void rf_enable_interrupt(uint8_t event)
00359 {
00360     if (enabled_interrupts & (1 << event)) {
00361         return;
00362     }
00363     rf_write_register_field(IRQ_MASK0 - (event / 8), 1 << (event % 8), 1 << (event % 8));
00364     enabled_interrupts |= (1 << event);
00365 }
00366 
00367 static void rf_disable_interrupt(uint8_t event)
00368 {
00369     if (!(enabled_interrupts & (1 << event))) {
00370         return;
00371     }
00372     rf_write_register_field(IRQ_MASK0 - (event / 8), 1 << (event % 8), 0 << (event % 8));
00373     enabled_interrupts &= ~(1 << event);
00374 }
00375 
00376 static void rf_disable_all_interrupts(void)
00377 {
00378     if ((uint8_t)enabled_interrupts & 0xff) {
00379         rf_write_register(IRQ_MASK0, 0);
00380     }
00381     if ((uint8_t)(enabled_interrupts >> 8) & 0xff) {
00382         rf_write_register(IRQ_MASK1, 0);
00383     }
00384     if ((uint8_t)(enabled_interrupts >> 16) & 0xff) {
00385         rf_write_register(IRQ_MASK2, 0);
00386     }
00387     if ((uint8_t)(enabled_interrupts >> 24) & 0xff) {
00388         rf_write_register(IRQ_MASK3, 0);
00389     }
00390     enabled_interrupts = 0;
00391     read_irq_status();
00392 }
00393 
00394 static void rf_enable_gpio_interrupt(void)
00395 {
00396     rf_enable_gpio_signal(INTERRUPT_GPIO, NIRQ, DIG_OUT_HIGH);
00397     INT_IN_GPIO.mode(PullUp);
00398     INT_IN_GPIO.fall(&rf_interrupt_handler);
00399     INT_IN_GPIO.enable_irq();
00400 }
00401 
00402 static void rf_send_command(s2lp_commands_e command)
00403 {
00404     const uint8_t tx[2] = {SPI_CMD, command};
00405     rf_lock();
00406     CS_SELECT();
00407     rf_spi_exchange(tx, sizeof(tx), NULL, 0);
00408     CS_RELEASE();
00409     rf_unlock();
00410 }
00411 
00412 static void rf_state_change(s2lp_states_e state, bool lock_mode_tx)
00413 {
00414     s2lp_commands_e command;
00415 
00416     if (S2LP_STATE_READY == state) {
00417         s2lp_states_e cur_state = rf_read_state();
00418         if (S2LP_STATE_TX == cur_state || S2LP_STATE_RX == cur_state) {
00419             command = S2LP_CMD_SABORT;
00420         } else {
00421             command = S2LP_CMD_READY;
00422         }
00423     } else if (S2LP_STATE_LOCK == state && lock_mode_tx) {
00424         command = S2LP_CMD_LOCKTX;
00425     } else if (S2LP_STATE_LOCK == state && !lock_mode_tx) {
00426         command = S2LP_CMD_LOCKRX;
00427     } else if (S2LP_STATE_RX == state) {
00428         command = S2LP_CMD_RX;
00429     } else if (S2LP_STATE_TX == state) {
00430         command = S2LP_CMD_TX;
00431     } else {
00432         tr_err("Invalid state %x", state);
00433         return;
00434     }
00435     rf_send_command(command);
00436     rf_poll_state_change(state);
00437 }
00438 
00439 static uint8_t rf_write_tx_fifo(uint8_t *ptr, uint16_t length)
00440 {
00441     uint8_t free_bytes_in_fifo = FIFO_SIZE - rf_read_register(TX_FIFO_STATUS);
00442     const uint8_t spi_header[SPI_HEADER_LENGTH] = {SPI_WR_REG, TX_FIFO};
00443     uint8_t written_length = length;
00444     if (length > free_bytes_in_fifo) {
00445         written_length = free_bytes_in_fifo;
00446     }
00447     CS_SELECT();
00448     rf_spi_exchange(spi_header, SPI_HEADER_LENGTH, NULL, 0);
00449     rf_spi_exchange(ptr, written_length, NULL, 0);
00450     CS_RELEASE();
00451     return written_length;
00452 }
00453 
00454 static int rf_read_rx_fifo(uint16_t rx_index, uint16_t length)
00455 {
00456     if ((rx_index + length) > RF_MTU) {
00457         return -1;
00458     }
00459     uint8_t *ptr = &rx_buffer[rx_index];
00460     const uint8_t spi_header[SPI_HEADER_LENGTH] = {SPI_RD_REG, RX_FIFO};
00461     CS_SELECT();
00462     rf_spi_exchange(spi_header, SPI_HEADER_LENGTH, NULL, 0);
00463     rf_spi_exchange(NULL, 0, ptr, length);
00464     CS_RELEASE();
00465     return length;
00466 }
00467 
00468 static void rf_flush_tx_fifo(void)
00469 {
00470     if (rf_read_register(TX_FIFO_STATUS)) {
00471         rf_send_command(S2LP_CMD_FLUSHTXFIFO);
00472     }
00473 }
00474 
00475 static void rf_flush_rx_fifo(void)
00476 {
00477     if (rf_read_register(RX_FIFO_STATUS)) {
00478         rf_send_command(S2LP_CMD_FLUSHRXFIFO);
00479     }
00480 }
00481 
00482 static void rf_write_packet_length(uint16_t packet_length)
00483 {
00484     if ((uint8_t)(cur_packet_len >> 8) != (packet_length / 256)) {
00485         rf_write_register(PCKTLEN1, packet_length / 256);
00486     }
00487     if ((uint8_t)cur_packet_len != (packet_length % 256)) {
00488         rf_write_register(PCKTLEN0, packet_length % 256);
00489     }
00490     cur_packet_len = packet_length;
00491 }
00492 
00493 static uint32_t read_irq_status(void)
00494 {
00495     const uint8_t tx[2] = {SPI_RD_REG, IRQ_STATUS3};
00496     uint8_t rx[6];
00497     CS_SELECT();
00498     rf_spi_exchange(tx, sizeof(tx), rx, sizeof(rx));
00499     CS_RELEASE();
00500     return (((uint32_t)rx[2] << 24) | ((uint32_t)rx[3] << 16) | ((uint32_t)rx[4] << 8) | rx[5]);
00501 }
00502 
00503 static void rf_set_channel_configuration_registers(void)
00504 {
00505     // Set RSSI threshold
00506     uint8_t rssi_th;
00507     rf_conf_calculate_rssi_threshold_registers(rssi_threshold, &rssi_th);
00508     rf_write_register(RSSI_TH, rssi_th);
00509     // Set deviation
00510     uint32_t deviation = rf_conf_calculate_deviation(phy_subghz.modulation_index, phy_subghz.datarate);
00511     if (!deviation) {
00512         deviation = DEFAULT_DEVIATION;
00513     }
00514     uint8_t fdev_m, fdev_e;
00515     rf_conf_calculate_deviation_registers(deviation, &fdev_m, &fdev_e);
00516     rf_write_register(MOD0, fdev_m);
00517     rf_write_register_field(MOD1, FDEV_E_FIELD, fdev_e);
00518 
00519     // Set datarate
00520     uint16_t datarate_m;
00521     uint8_t datarate_e;
00522     rf_conf_calculate_datarate_registers(phy_subghz.datarate, &datarate_m, &datarate_e);
00523     rf_write_register_field(MOD2, DATARATE_E_FIELD, datarate_e);
00524     rf_write_register(MOD3, (uint8_t)datarate_m);
00525     rf_write_register(MOD4, datarate_m >> 8);
00526     // Set RX filter bandwidth, using channel spacing as RX filter bandwidth
00527     uint8_t chflt_m, chflt_e;
00528     rf_conf_calculate_rx_filter_bandwidth_registers(phy_subghz.channel_spacing, &chflt_m, &chflt_e);
00529     rf_write_register_field(CHFLT, CHFLT_M_FIELD, chflt_m << 4);
00530     rf_write_register_field(CHFLT, CHFLT_E_FIELD, chflt_e);
00531     // Set base frequency (Channel 0 center frequency)
00532     uint8_t synt3, synt2, synt1, synt0;
00533     rf_conf_calculate_base_frequency_registers(phy_subghz.channel_0_center_frequency, &synt3, &synt2, &synt1, &synt0);
00534     rf_write_register_field(SYNT3, SYNT_FIELD, synt3);
00535     rf_write_register(SYNT2, synt2);
00536     rf_write_register(SYNT1, synt1);
00537     rf_write_register(SYNT0, synt0);
00538     // Set channel spacing
00539     uint8_t ch_space;
00540     uint8_t ch_space_divider = 1;
00541     while (rf_conf_calculate_channel_spacing_registers(phy_subghz.channel_spacing / ch_space_divider, &ch_space)) {
00542         ch_space_divider++;
00543         rf_channel_multiplier++;
00544     }
00545     rf_write_register(CHSPACE, ch_space);
00546     /* Preamble is set for S2-LP as repetitions of 01 or 10 pair
00547      *
00548      * For datarate < 150kbps, using phyFskPreambleLength = 8 repetitions of 01010101
00549      * For datarate >= 150kbps and datarate < 300kbps, using phyFskPreambleLength = 12 repetitions of 01010101
00550      * For datarate >= 300kbps, using phyFskPreambleLength = 24 repetitions of 01010101
00551      */
00552     uint8_t preamble_len = 24 * 4;
00553     if (phy_subghz.datarate < 150000) {
00554         preamble_len = 8 * 4;
00555     } else if (phy_subghz.datarate < 300000) {
00556         preamble_len = 12 * 4;
00557     }
00558     rf_write_register(PCKTCTRL5, preamble_len);
00559 }
00560 
00561 static void rf_init_registers(void)
00562 {
00563     rf_write_register_field(PCKTCTRL3, PCKT_FORMAT_FIELD, PCKT_FORMAT_802_15_4);
00564     rf_write_register_field(MOD2, MOD_TYPE_FIELD, MOD_2FSK);
00565     rf_write_register(PCKT_FLT_OPTIONS, 0);
00566     rf_write_register_field(PCKTCTRL1, PCKT_CRCMODE_FIELD, PCKT_CRCMODE_0x04C11DB7);
00567     rf_write_register_field(PCKTCTRL1, PCKT_TXSOURCE_FIELD, PCKT_TXSOURCE_NORMAL);
00568     rf_write_register_field(PCKTCTRL1, PCKT_WHITENING_FIELD, PCKT_WHITENING_ENABLED);
00569     rf_write_register_field(PCKTCTRL2, PCKT_FIXVARLEN_FIELD, PCKT_VARIABLE_LEN);
00570     rf_write_register_field(PCKTCTRL2, PCKT_FCS_TYPE_FIELD, PCKT_FCS_TYPE_4_OCTET);
00571     rf_write_register_field(PCKTCTRL3, PCKT_RXMODE_FIELD, PCKT_RXMODE_NORMAL);
00572     rf_write_register_field(PCKTCTRL3, PCKT_BYTE_SWAP_FIELD, PCKT_BYTE_SWAP_LSB);
00573     rf_write_register_field(PCKTCTRL6, PCKT_SYNCLEN_FIELD, PCKT_SYNCLEN);
00574     rf_write_register_field(QI, PQI_TH_FIELD, PQI_TH);
00575     rf_write_register_field(QI, SQI_EN_FIELD, SQI_EN);
00576     rf_write_register(SYNC0, SFD0);
00577     rf_write_register(SYNC1, SFD1);
00578     rf_set_channel_configuration_registers();
00579 }
00580 
00581 static int8_t rf_address_write(phy_address_type_e address_type, uint8_t *address_ptr)
00582 {
00583     int8_t ret_val = 0;
00584     switch (address_type) {
00585         /*Set 48-bit address*/
00586         case PHY_MAC_48BIT:
00587             break;
00588         /*Set 64-bit address*/
00589         case PHY_MAC_64BIT:
00590             memcpy(s2lp_MAC, address_ptr, 8);
00591             break;
00592         /*Set 16-bit address*/
00593         case PHY_MAC_16BIT:
00594             memcpy(s2lp_short_address, address_ptr, 2);
00595             break;
00596         /*Set PAN Id*/
00597         case PHY_MAC_PANID:
00598             memcpy(s2lp_PAN_ID, address_ptr, 2);
00599             break;
00600     }
00601     return ret_val;
00602 }
00603 
00604 static int8_t rf_extension(phy_extension_type_e extension_type, uint8_t *data_ptr)
00605 {
00606     int8_t retval = 0;
00607     phy_csma_params_t *csma_params;
00608     phy_rf_channel_configuration_s *channel_params;
00609     uint32_t *timer_value;
00610     switch (extension_type) {
00611         case PHY_EXTENSION_SET_CHANNEL:
00612             if (rf_state == RF_IDLE || rf_state == RF_CSMA_STARTED) {
00613                 rf_receive(*data_ptr);
00614             } else {
00615                 // Store the new channel if couldn't change it yet.
00616                 rf_new_channel = *data_ptr;
00617                 retval = -1;
00618             }
00619             break;
00620         case PHY_EXTENSION_CTRL_PENDING_BIT:
00621             break;
00622         /*Return frame pending status*/
00623         case PHY_EXTENSION_READ_LAST_ACK_PENDING_STATUS:
00624             break;
00625         case PHY_EXTENSION_ACCEPT_ANY_BEACON:
00626             break;
00627         case PHY_EXTENSION_SET_TX_TIME:
00628             tx_time = common_read_32_bit(data_ptr);
00629             break;
00630         case PHY_EXTENSION_READ_RX_TIME:
00631             common_write_32_bit(rx_time, data_ptr);
00632             break;
00633         case PHY_EXTENSION_DYNAMIC_RF_SUPPORTED:
00634             *data_ptr = true;
00635             break;
00636         case PHY_EXTENSION_GET_TIMESTAMP:
00637             timer_value = (uint32_t *)data_ptr;
00638             *timer_value = rf_get_timestamp();
00639             break;
00640         case PHY_EXTENSION_SET_CSMA_PARAMETERS:
00641             csma_params = (phy_csma_params_t *)data_ptr;
00642             if (csma_params->backoff_time == 0) {
00643                 rf_cca_timer_stop();
00644                 if (rf_read_register(TX_FIFO_STATUS)) {
00645                     rf_send_command(S2LP_CMD_SABORT);
00646                     rf_poll_state_change(S2LP_STATE_READY);
00647                     rf_send_command(S2LP_CMD_FLUSHTXFIFO);
00648                     rf_poll_state_change(S2LP_STATE_READY);
00649                 }
00650                 if (rf_state == RF_TX_STARTED) {
00651                     rf_state = RF_IDLE;
00652                     rf_receive(rf_rx_channel);
00653                 }
00654                 tx_time = 0;
00655             } else {
00656                 tx_time = csma_params->backoff_time;
00657                 cca_enabled = csma_params->cca_enabled;
00658             }
00659             break;
00660         case PHY_EXTENSION_READ_TX_FINNISH_TIME:
00661             timer_value = (uint32_t *)data_ptr;
00662             *timer_value = tx_finnish_time;
00663             break;
00664 
00665         case PHY_EXTENSION_GET_SYMBOLS_PER_SECOND:
00666             timer_value = (uint32_t *)data_ptr;
00667             *timer_value = rf_symbol_rate;
00668             break;
00669         case PHY_EXTENSION_SET_RF_CONFIGURATION:
00670             channel_params = (phy_rf_channel_configuration_s *)data_ptr;
00671             phy_subghz.datarate = channel_params->datarate;
00672             phy_subghz.channel_spacing = channel_params->channel_spacing;
00673             phy_subghz.channel_0_center_frequency = channel_params->channel_0_center_frequency;
00674             phy_subghz.number_of_channels = channel_params->number_of_channels;
00675             phy_subghz.modulation = channel_params->modulation;
00676             phy_subghz.modulation_index = channel_params->modulation_index;
00677             rf_calculate_symbol_rate(phy_subghz.datarate, phy_subghz.modulation);
00678             rf_update_config = true;
00679             if (rf_state == RF_IDLE) {
00680                 rf_receive(rf_rx_channel);
00681             }
00682             break;
00683         case PHY_EXTENSION_SET_TX_POWER:
00684             // TODO: Set TX output power
00685             break;
00686         case PHY_EXTENSION_SET_CCA_THRESHOLD:
00687             rssi_threshold = rf_conf_cca_threshold_percent_to_rssi(*data_ptr);
00688             rf_update_config = true;
00689             if (rf_state == RF_IDLE) {
00690                 rf_receive(rf_rx_channel);
00691             }
00692             break;
00693         default:
00694             break;
00695     }
00696 
00697     return retval;
00698 }
00699 
00700 
00701 static int8_t rf_interface_state_control(phy_interface_state_e new_state, uint8_t rf_channel)
00702 {
00703     int8_t ret_val = 0;
00704     switch (new_state) {
00705         /*Reset PHY driver and set to idle*/
00706         case PHY_INTERFACE_RESET:
00707             break;
00708         /*Disable PHY Interface driver*/
00709         case PHY_INTERFACE_DOWN:
00710             rf_lock();
00711             rf_send_command(S2LP_CMD_SABORT);
00712             rf_disable_all_interrupts();
00713             rf_poll_state_change(S2LP_STATE_READY);
00714             rf_flush_rx_fifo();
00715             rf_flush_tx_fifo();
00716             rf_state = RF_IDLE;
00717             rf_unlock();
00718             break;
00719         /*Enable PHY Interface driver*/
00720         case PHY_INTERFACE_UP:
00721             rf_mode = RF_MODE_NORMAL;
00722             rf_receive(rf_channel);
00723             break;
00724         /*Enable wireless interface ED scan mode*/
00725         case PHY_INTERFACE_RX_ENERGY_STATE:
00726             break;
00727         /*Enable Sniffer state*/
00728         case PHY_INTERFACE_SNIFFER_STATE:
00729             rf_mode = RF_MODE_SNIFFER;
00730             rf_receive(rf_channel);
00731             break;
00732     }
00733     return ret_val;
00734 }
00735 
00736 static void rf_tx_sent_handler(void)
00737 {
00738     rf_backup_timer_stop();
00739     rf_disable_interrupt(TX_DATA_SENT);
00740     if (rf_state != RF_TX_ACK) {
00741         tx_finnish_time = rf_get_timestamp();
00742         TEST_TX_DONE
00743         rf_state = RF_IDLE;
00744         rf_receive(rf_rx_channel);
00745         if (device_driver.phy_tx_done_cb) {
00746             device_driver.phy_tx_done_cb(rf_radio_driver_id, mac_tx_handle, PHY_LINK_TX_SUCCESS, 0, 0);
00747         }
00748     } else {
00749         TEST_ACK_TX_DONE
00750         rf_receive(rf_rx_channel);
00751     }
00752 }
00753 
00754 static void rf_tx_threshold_handler(void)
00755 {
00756     rf_backup_timer_stop();
00757     rf_disable_interrupt(TX_FIFO_ALMOST_EMPTY);
00758     // TODO check the FIFO threshold. By default, threshold is half of the FIFO size
00759     uint8_t written_length = rf_write_tx_fifo(tx_data_ptr, tx_data_length);
00760     if (written_length < tx_data_length) {
00761         tx_data_ptr += written_length;
00762         tx_data_length -= written_length;
00763         rf_enable_interrupt(TX_FIFO_ALMOST_EMPTY);
00764     }
00765     rf_backup_timer_start(MAX_PACKET_SENDING_TIME);
00766 }
00767 
00768 static void rf_start_tx(void)
00769 {
00770     rf_send_command(S2LP_CMD_SABORT);
00771     rf_disable_all_interrupts();
00772     rf_poll_state_change(S2LP_STATE_READY);
00773     rf_state_change(S2LP_STATE_TX, false);
00774     // More TX data to be written in FIFO when TX threshold interrupt occurs
00775     if (tx_data_ptr) {
00776         rf_enable_interrupt(TX_FIFO_ALMOST_EMPTY);
00777     }
00778     rf_enable_interrupt(TX_DATA_SENT);
00779     rf_enable_interrupt(TX_FIFO_UNF_OVF);
00780     rf_backup_timer_start(MAX_PACKET_SENDING_TIME);
00781 }
00782 
00783 static int rf_cca_check(void)
00784 {
00785     uint32_t time_from_receiver_ready = rf_get_timestamp() - receiver_ready_timestamp;
00786     if (time_from_receiver_ready < RSSI_SETTLING_TIME) {
00787         wait_us(RSSI_SETTLING_TIME - time_from_receiver_ready);
00788     }
00789     return (rf_read_register(LINK_QUALIF1) & CARRIER_SENSE);
00790 }
00791 
00792 static void rf_cca_timer_interrupt(void)
00793 {
00794     int8_t status = device_driver.phy_tx_done_cb(rf_radio_driver_id, mac_tx_handle, PHY_LINK_CCA_PREPARE, 0, 0);
00795     if (status == PHY_TX_NOT_ALLOWED) {
00796         rf_flush_tx_fifo();
00797         if (rf_state == RF_CSMA_STARTED) {
00798             rf_state = RF_IDLE;
00799         }
00800         return;
00801     }
00802     if ((cca_enabled == true) && ((rf_state != RF_CSMA_STARTED && rf_state != RF_IDLE) || (read_irq_status() & (1 << SYNC_WORD)) || rf_cca_check())) {
00803         if (rf_state == RF_CSMA_STARTED) {
00804             rf_state = RF_IDLE;
00805         }
00806         rf_flush_tx_fifo();
00807         tx_finnish_time = rf_get_timestamp();
00808         if (device_driver.phy_tx_done_cb) {
00809             device_driver.phy_tx_done_cb(rf_radio_driver_id, mac_tx_handle, PHY_LINK_CCA_FAIL, 0, 0);
00810         }
00811     } else {
00812         if (status == PHY_RESTART_CSMA) {
00813             if (device_driver.phy_tx_done_cb) {
00814                 device_driver.phy_tx_done_cb(rf_radio_driver_id, mac_tx_handle, PHY_LINK_CCA_OK, 0, 0);
00815             }
00816             if (tx_time) {
00817                 uint32_t backoff_time = tx_time - rf_get_timestamp();
00818                 // Max. time to TX can be 65ms, otherwise time has passed already -> send immediately
00819                 if (backoff_time > 65000) {
00820                     backoff_time = 1;
00821                 }
00822                 rf_cca_timer_start(backoff_time);
00823             }
00824         } else {
00825             rf_start_tx();
00826             rf_state = RF_TX_STARTED;
00827             TEST_TX_STARTED
00828         }
00829     }
00830 }
00831 
00832 static void rf_cca_timer_stop(void)
00833 {
00834     rf->cca_timer.detach();
00835 }
00836 
00837 static void rf_cca_timer_start(uint32_t slots)
00838 {
00839     rf->cca_timer.attach_us(rf_cca_timer_signal, slots);
00840 }
00841 
00842 static void rf_backup_timer_interrupt(void)
00843 {
00844     tx_finnish_time = rf_get_timestamp();
00845     if (rf_state == RF_RX_STARTED) {
00846         if (device_driver.phy_rf_statistics) {
00847             device_driver.phy_rf_statistics->rx_timeouts++;
00848         }
00849     } else {
00850         if (device_driver.phy_rf_statistics) {
00851             device_driver.phy_rf_statistics->tx_timeouts++;
00852         }
00853     }
00854     if (rf_state == RF_TX_STARTED) {
00855         if (device_driver.phy_tx_done_cb) {
00856             device_driver.phy_tx_done_cb(rf_radio_driver_id, mac_tx_handle, PHY_LINK_TX_SUCCESS, 0, 0);
00857         }
00858     }
00859     rf_flush_tx_fifo();
00860     TEST_TX_DONE
00861     TEST_RX_DONE
00862     rf_state = RF_IDLE;
00863     rf_receive(rf_rx_channel);
00864 }
00865 
00866 static void rf_backup_timer_stop(void)
00867 {
00868     rf->backup_timer.detach();
00869 }
00870 
00871 static void rf_backup_timer_start(uint32_t slots)
00872 {
00873     rf->backup_timer.attach_us(rf_backup_timer_signal, slots);
00874 }
00875 
00876 static int8_t rf_start_cca(uint8_t *data_ptr, uint16_t data_length, uint8_t tx_handle, data_protocol_e data_protocol)
00877 {
00878     rf_lock();
00879     if (rf_state != RF_IDLE) {
00880         rf_unlock();
00881         return -1;
00882     }
00883     rf_state = RF_CSMA_STARTED;
00884     uint8_t written_length = rf_write_tx_fifo(data_ptr, data_length);
00885     if (written_length < data_length) {
00886         tx_data_ptr = data_ptr + written_length;
00887         tx_data_length = data_length - written_length;
00888     } else {
00889         tx_data_ptr = NULL;
00890     }
00891     // If Ack is requested, store the MAC sequence. This will be compared with received Ack.
00892     uint8_t version = ((*(data_ptr + 1) & VERSION_FIELD_MASK) >> SHIFT_VERSION_FIELD);
00893     if ((version != MAC_FRAME_VERSION_2) && (*data_ptr & FC_AR)) {
00894         tx_sequence = *(data_ptr + 2);
00895     }
00896     // TODO: Define this better
00897     rf_write_packet_length(data_length + 4);
00898     mac_tx_handle = tx_handle;
00899     if (tx_time) {
00900         uint32_t backoff_time = tx_time - rf_get_timestamp();
00901         // Max. time to TX can be 65ms, otherwise time has passed already -> send immediately
00902         if (backoff_time <= 65000) {
00903             rf_cca_timer_start(backoff_time);
00904             rf_unlock();
00905             return 0;
00906         }
00907     }
00908     // Short timeout to start CCA immediately.
00909     rf_cca_timer_start(1);
00910     rf_unlock();
00911     return 0;
00912 }
00913 
00914 static void rf_send_ack(uint8_t seq)
00915 {
00916     rf_state = RF_TX_ACK;
00917     uint8_t ack_frame[3] = {MAC_TYPE_ACK, 0, seq};
00918     rf_write_tx_fifo(ack_frame, sizeof(ack_frame));
00919     rf_write_packet_length(sizeof(ack_frame) + 4);
00920     tx_data_ptr = NULL;
00921     rf_start_tx();
00922     TEST_ACK_TX_STARTED
00923     rf_backup_timer_start(ACK_SENDING_TIME);
00924 }
00925 
00926 static void rf_handle_ack(uint8_t seq_number, uint8_t pending)
00927 {
00928     phy_link_tx_status_e phy_status;
00929     if (tx_sequence == (uint16_t)seq_number) {
00930         tx_finnish_time = rf_get_timestamp();
00931         if (pending) {
00932             phy_status = PHY_LINK_TX_DONE_PENDING;
00933         } else {
00934             phy_status = PHY_LINK_TX_DONE;
00935         }
00936         // No CCA attempts done, just waited Ack
00937         device_driver.phy_tx_done_cb(rf_radio_driver_id, mac_tx_handle, phy_status, 0, 0);
00938         // Clear TX sequence when Ack is received to avoid duplicate Acks
00939         tx_sequence = 0xffff;
00940     }
00941 }
00942 
00943 static void rf_rx_ready_handler(void)
00944 {
00945     rf_backup_timer_stop();
00946     TEST_RX_DONE
00947     rf_flush_tx_fifo();
00948     int rx_read_length = rf_read_rx_fifo(rx_data_length, rf_read_register(RX_FIFO_STATUS));
00949     if (rx_read_length < 0) {
00950         rf_receive(rf_rx_channel);
00951         return;
00952     }
00953     rx_data_length += rx_read_length;
00954     if (rf_mode != RF_MODE_SNIFFER) {
00955         rf_state = RF_IDLE;
00956         uint8_t version = ((rx_buffer[1] & VERSION_FIELD_MASK) >> SHIFT_VERSION_FIELD);
00957         if (((rx_buffer[0] & MAC_FRAME_TYPE_MASK) == MAC_TYPE_ACK) && (version < MAC_FRAME_VERSION_2)) {
00958             rf_handle_ack(rx_buffer[2], rx_buffer[0] & MAC_DATA_PENDING);
00959         } else if (rf_rx_filter(rx_buffer, s2lp_MAC, s2lp_short_address, s2lp_PAN_ID)) {
00960             int8_t rssi = (rf_read_register(RSSI_LEVEL) - RSSI_OFFSET);
00961             if (device_driver.phy_rx_cb) {
00962                 device_driver.phy_rx_cb(rx_buffer, rx_data_length, 0xf0, rssi, rf_radio_driver_id);
00963             }
00964             // Check Ack request
00965             if ((version != MAC_FRAME_VERSION_2) && (rx_buffer[0] & FC_AR)) {
00966                 rf_send_ack(rx_buffer[2]);
00967             }
00968         }
00969     } else {
00970         rf_state = RF_IDLE;
00971         int8_t rssi = (rf_read_register(RSSI_LEVEL) - RSSI_OFFSET);
00972         if (device_driver.phy_rx_cb) {
00973             device_driver.phy_rx_cb(rx_buffer, rx_data_length, 0xf0, rssi, rf_radio_driver_id);
00974         }
00975     }
00976     if ((rf_state != RF_TX_ACK) && (rf_state != RF_CSMA_STARTED)) {
00977         rf_receive(rf_rx_channel);
00978     }
00979 }
00980 
00981 static void rf_rx_threshold_handler(void)
00982 {
00983     rf_backup_timer_stop();
00984     int rx_read_length = rf_read_rx_fifo(rx_data_length, rf_read_register(RX_FIFO_STATUS));
00985     if (rx_read_length < 0) {
00986         rf_receive(rf_rx_channel);
00987         return;
00988     }
00989     rx_data_length += rx_read_length;
00990     rf_backup_timer_start(MAX_PACKET_SENDING_TIME);
00991 }
00992 
00993 static void rf_sync_detected_handler(void)
00994 {
00995     rx_time = rf_get_timestamp();
00996     rf_state = RF_RX_STARTED;
00997     TEST_RX_STARTED
00998     rf_disable_interrupt(SYNC_WORD);
00999     rf_enable_interrupt(RX_FIFO_ALMOST_FULL);
01000     rf_enable_interrupt(RX_DATA_READY);
01001     rf_backup_timer_start(MAX_PACKET_SENDING_TIME);
01002 }
01003 
01004 static void rf_receive(uint8_t rx_channel)
01005 {
01006     if (rf_state == RF_TX_STARTED) {
01007         return;
01008     }
01009     rf_lock();
01010     rf_send_command(S2LP_CMD_SABORT);
01011     rf_disable_all_interrupts();
01012     rf_poll_state_change(S2LP_STATE_READY);
01013     rf_flush_rx_fifo();
01014     if (rf_update_config == true) {
01015         rf_channel_multiplier = 1;
01016         rf_update_config = false;
01017         rf_set_channel_configuration_registers();
01018     }
01019     if (rx_channel != rf_rx_channel) {
01020         rf_write_register(CHNUM, rx_channel * rf_channel_multiplier);
01021         rf_rx_channel = rf_new_channel = rx_channel;
01022     }
01023     rf_send_command(S2LP_CMD_RX);
01024     rf_enable_interrupt(SYNC_WORD);
01025     rf_enable_interrupt(RX_FIFO_UNF_OVF);
01026     rx_data_length = 0;
01027     if (rf_state != RF_CSMA_STARTED) {
01028         rf_state = RF_IDLE;
01029     }
01030     rf_poll_state_change(S2LP_STATE_RX);
01031     receiver_ready_timestamp = rf_get_timestamp();
01032     rf_unlock();
01033 }
01034 
01035 static void rf_interrupt_handler(void)
01036 {
01037     rf->irq_thread.flags_set(SIG_RADIO);
01038 }
01039 
01040 void RFPins::rf_irq_task(void)
01041 {
01042     for (;;) {
01043         uint32_t flags = ThisThread::flags_wait_any(SIG_ALL);
01044         rf_lock();
01045         if (flags & SIG_RADIO) {
01046             rf_irq_task_process_irq();
01047         }
01048         if (flags & SIG_TIMER_CCA) {
01049             rf_cca_timer_interrupt();
01050         }
01051         if (flags & SIG_TIMER_BACKUP) {
01052             rf_backup_timer_interrupt();
01053         }
01054         rf_unlock();
01055     }
01056 }
01057 
01058 static void rf_irq_task_process_irq(void)
01059 {
01060     rf_lock();
01061     uint32_t irq_status = read_irq_status();
01062     if (rf_state == RF_TX_STARTED || rf_state == RF_TX_ACK) {
01063         if ((irq_status & (1 << TX_DATA_SENT)) && (enabled_interrupts & (1 << TX_DATA_SENT))) {
01064             rf_tx_sent_handler();
01065         }
01066     }
01067     if (rf_state == RF_TX_STARTED) {
01068         if ((irq_status & (1 << TX_FIFO_ALMOST_EMPTY)) && (enabled_interrupts & (1 << TX_FIFO_ALMOST_EMPTY))) {
01069             rf_tx_threshold_handler();
01070         }
01071     }
01072     if ((irq_status & (1 << TX_FIFO_UNF_OVF)) && (enabled_interrupts & (1 << TX_FIFO_UNF_OVF))) {
01073         rf_backup_timer_stop();
01074         tx_finnish_time = rf_get_timestamp();
01075         TEST_TX_DONE
01076         device_driver.phy_tx_done_cb(rf_radio_driver_id, mac_tx_handle, PHY_LINK_CCA_FAIL, 1, 0);
01077         rf_send_command(S2LP_CMD_SABORT);
01078         rf_poll_state_change(S2LP_STATE_READY);
01079         rf_send_command(S2LP_CMD_FLUSHTXFIFO);
01080         rf_poll_state_change(S2LP_STATE_READY);
01081         rf_state = RF_IDLE;
01082         rf_receive(rf_rx_channel);
01083     }
01084     if (rf_state == RF_IDLE || rf_state == RF_CSMA_STARTED || rf_state == RF_TX_STARTED) {
01085         if ((irq_status & (1 << SYNC_WORD)) && (enabled_interrupts & (1 << SYNC_WORD))) {
01086             rf_sync_detected_handler();
01087         }
01088     } else if (rf_state == RF_RX_STARTED) {
01089         if ((irq_status & (1 << RX_DATA_READY)) && (enabled_interrupts & (1 << RX_DATA_READY))) {
01090             if (!(irq_status & (1 << CRC_ERROR))) {
01091                 rf_rx_ready_handler();
01092             } else {
01093                 TEST_RX_DONE
01094                 rf_backup_timer_stop();
01095                 rf_flush_tx_fifo();
01096                 rf_state = RF_IDLE;
01097                 // In case the channel change was called during reception, driver is responsible to change the channel if CRC failed.
01098                 rf_receive(rf_new_channel);
01099                 if (device_driver.phy_rf_statistics) {
01100                     device_driver.phy_rf_statistics->crc_fails++;
01101                 }
01102             }
01103         }
01104         if ((irq_status & (1 << RX_FIFO_ALMOST_FULL)) && (enabled_interrupts & (1 << RX_FIFO_ALMOST_FULL))) {
01105             rf_rx_threshold_handler();
01106         }
01107         if ((irq_status & (1 << RX_DATA_DISCARDED)) && (enabled_interrupts & (1 << RX_DATA_DISCARDED))) {
01108 
01109         }
01110         if ((irq_status & (1 << CRC_ERROR)) && (enabled_interrupts & (1 << CRC_ERROR))) {
01111 
01112         }
01113     }
01114     if ((irq_status & (1 << RX_FIFO_UNF_OVF)) && (enabled_interrupts & (1 << RX_FIFO_UNF_OVF))) {
01115         TEST_RX_DONE
01116         rf_backup_timer_stop();
01117         rf_send_command(S2LP_CMD_SABORT);
01118         rf_poll_state_change(S2LP_STATE_READY);
01119         rf_send_command(S2LP_CMD_FLUSHRXFIFO);
01120         rf_poll_state_change(S2LP_STATE_READY);
01121         rf_flush_tx_fifo();
01122         rf_state = RF_IDLE;
01123         rf_receive(rf_rx_channel);
01124     }
01125     rf_unlock();
01126 }
01127 
01128 static void rf_reset(void)
01129 {
01130     // Shutdown
01131     rf->SDN = 1;
01132     ThisThread::sleep_for(10);
01133     // Wake up
01134     rf->SDN = 0;
01135     ThisThread::sleep_for(10);
01136 }
01137 
01138 static void rf_init(void)
01139 {
01140 #ifdef TEST_GPIOS_ENABLED
01141     fhss_bc_switch = test1_toggle;
01142     fhss_uc_switch = test2_toggle;
01143 #endif //TEST_GPIOS_ENABLED
01144     rf_reset();
01145     rf->spi.frequency(10000000);
01146     CS_RELEASE();
01147     rf_init_registers();
01148     rf_enable_gpio_interrupt();
01149     rf_calculate_symbol_rate(phy_subghz.datarate, phy_subghz.modulation);
01150     rf->tx_timer.start();
01151 }
01152 
01153 static int8_t rf_device_register(const uint8_t *mac_addr)
01154 {
01155     rf_init();
01156     /*Set pointer to MAC address*/
01157     device_driver.PHY_MAC = (uint8_t *)mac_addr;
01158     device_driver.driver_description = (char *)"S2LP_MAC";
01159     device_driver.link_type = PHY_LINK_15_4_SUBGHZ_TYPE;
01160     device_driver.phy_channel_pages = phy_channel_pages;
01161     device_driver.phy_MTU = RF_MTU;
01162     /*No header in PHY*/
01163     device_driver.phy_header_length = 0;
01164     /*No tail in PHY*/
01165     device_driver.phy_tail_length = 0;
01166     /*Set address write function*/
01167     device_driver.address_write = &rf_address_write;
01168     /*Set RF extension function*/
01169     device_driver.extension = &rf_extension;
01170     /*Set RF state control function*/
01171     device_driver.state_control = &rf_interface_state_control;
01172     /*Set transmit function*/
01173     device_driver.tx = &rf_start_cca;
01174     /*NULLIFY rx and tx_done callbacks*/
01175     device_driver.phy_rx_cb = NULL;
01176     device_driver.phy_tx_done_cb = NULL;
01177     /*Register device driver*/
01178     rf_radio_driver_id = arm_net_phy_register(&device_driver);
01179     return rf_radio_driver_id;
01180 }
01181 
01182 static void rf_device_unregister()
01183 {
01184     if (rf_radio_driver_id >= 0) {
01185         arm_net_phy_unregister(rf_radio_driver_id);
01186         rf_radio_driver_id = -1;
01187     }
01188 }
01189 
01190 void NanostackRfPhys2lp::get_mac_address(uint8_t *mac)
01191 {
01192     rf_lock();
01193 
01194     if (NULL == rf) {
01195         error("NanostackRfPhys2lp Must be registered to read mac address");
01196         rf_unlock();
01197         return;
01198     }
01199     memcpy((void *)mac, (void *)_mac_addr, sizeof(_mac_addr));
01200 
01201     rf_unlock();
01202 }
01203 
01204 void NanostackRfPhys2lp::set_mac_address(uint8_t *mac)
01205 {
01206     rf_lock();
01207 
01208     if (NULL != rf) {
01209         error("NanostackRfPhys2lp cannot change mac address when running");
01210         rf_unlock();
01211         return;
01212     }
01213     memcpy((void *)_mac_addr, (void *)mac, sizeof(_mac_addr));
01214     _mac_set = true;
01215 
01216     rf_unlock();
01217 }
01218 
01219 int8_t NanostackRfPhys2lp::rf_register()
01220 {
01221     if (NULL == _rf) {
01222         return -1;
01223     }
01224     rf_lock();
01225     if (rf != NULL) {
01226         rf_unlock();
01227         error("Multiple registrations of NanostackRfPhyAtmel not supported");
01228         return -1;
01229     }
01230 
01231     if (!_mac_set) {
01232 #ifdef AT24MAC
01233         int ret = _mac.read_eui64((void *)s2lp_MAC);
01234         if (ret < 0) {
01235             rf = NULL;
01236             rf_unlock();
01237             return -1;
01238         }
01239 #else
01240         randLIB_seed_random();
01241         randLIB_get_n_bytes_random(s2lp_MAC, 8);
01242         s2lp_MAC[0] |= 2; //Set Local Bit
01243         s2lp_MAC[0] &= ~1; //Clear multicast bit
01244 #endif
01245         set_mac_address(s2lp_MAC);
01246     }
01247 
01248     rf = _rf;
01249 
01250     int8_t radio_id = rf_device_register(_mac_addr);
01251     if (radio_id < 0) {
01252         rf = NULL;
01253     }
01254     rf_unlock();
01255     return radio_id;
01256 }
01257 
01258 void NanostackRfPhys2lp::rf_unregister()
01259 {
01260     rf_lock();
01261     if (NULL == rf) {
01262         rf_unlock();
01263         return;
01264     }
01265     rf_device_unregister();
01266     rf = NULL;
01267     rf_unlock();
01268 }
01269 
01270 NanostackRfPhys2lp::NanostackRfPhys2lp(PinName spi_sdi, PinName spi_sdo, PinName spi_sclk, PinName spi_cs, PinName spi_sdn
01271 #ifdef TEST_GPIOS_ENABLED
01272                                        ,PinName spi_test1, PinName spi_test2, PinName spi_test3, PinName spi_test4, PinName spi_test5
01273 #endif //TEST_GPIOS_ENABLED
01274                                        ,PinName spi_gpio0, PinName spi_gpio1, PinName spi_gpio2, PinName spi_gpio3
01275 #ifdef AT24MAC
01276                                        ,PinName i2c_sda, PinName i2c_scl
01277 #endif //AT24MAC
01278                                        )
01279     :
01280 #ifdef AT24MAC
01281                     _mac(i2c_sda, i2c_scl),
01282 #endif //AT24MAC
01283                     _mac_addr(), _rf(NULL), _mac_set(false),
01284       _spi_sdi(spi_sdi), _spi_sdo(spi_sdo), _spi_sclk(spi_sclk), _spi_cs(spi_cs), _spi_sdn(spi_sdn),
01285 #ifdef TEST_GPIOS_ENABLED
01286       _spi_test1(spi_test1), _spi_test2(spi_test2), _spi_test3(spi_test3), _spi_test4(spi_test4), _spi_test5(spi_test5),
01287 #endif //TEST_GPIOS_ENABLED
01288       _spi_gpio0(spi_gpio0), _spi_gpio1(spi_gpio1), _spi_gpio2(spi_gpio2), _spi_gpio3(spi_gpio3)
01289 {
01290     _rf = new RFPins(_spi_sdi, _spi_sdo, _spi_sclk, _spi_cs, _spi_sdn,
01291 #ifdef TEST_GPIOS_ENABLED
01292                      _spi_test1, _spi_test2, _spi_test3, _spi_test4, _spi_test5,
01293 #endif //TEST_GPIOS_ENABLED
01294                      _spi_gpio0, _spi_gpio1, _spi_gpio2, _spi_gpio3);
01295 }
01296 
01297 NanostackRfPhys2lp::~NanostackRfPhys2lp()
01298 {
01299     delete _rf;
01300 }
01301 
01302 static bool rf_panid_filter_common(uint8_t *panid_start, uint8_t *pan_id, uint8_t frame_type)
01303 {
01304     // PHY driver shouldn't drop received Beacon frames as they might be used by load balancing
01305     if (frame_type == MAC_FRAME_BEACON) {
01306         return true;
01307     }
01308     bool retval = true;
01309     uint8_t cmp_table[2] = {0xff, 0xff};
01310     if (!(pan_id[0] == 0xff && pan_id[1] == 0xff)) {
01311         if (memcmp((uint8_t *)panid_start, (uint8_t *) cmp_table, 2)) {
01312             retval = false;
01313         }
01314         if (!retval) {
01315             for (uint8_t i = 0; i < 2; i++) {
01316                 cmp_table[1 - i] = panid_start[i];
01317             }
01318             if (!memcmp(pan_id, cmp_table, 2)) {
01319                 retval = true;
01320             }
01321         }
01322     }
01323     return retval;
01324 }
01325 
01326 static bool rf_panid_v1_v0_filter(uint8_t *ptr, uint8_t *pan_id, uint8_t frame_type)
01327 {
01328     return rf_panid_filter_common(ptr, pan_id, frame_type);
01329 }
01330 
01331 static bool rf_addr_filter_common(uint8_t *ptr, uint8_t addr_mode, uint8_t *mac_64bit_addr, uint8_t *mac_16bit_addr)
01332 {
01333     uint8_t cmp_table[8] = {0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff};
01334     bool retval = true;
01335     switch (addr_mode) {
01336         case FC_DST_16_BITS:
01337             if (memcmp((uint8_t *)ptr, (uint8_t *) cmp_table, 2)) {
01338                 retval = false;
01339             }
01340             if (!retval) {
01341                 for (uint8_t i = 0; i < 2; i++) {
01342                     cmp_table[1 - i] = ptr[i];
01343                 }
01344 
01345                 if (!memcmp((uint8_t *)mac_16bit_addr, (uint8_t *) cmp_table, 2)) {
01346                     retval = true;
01347                 }
01348             }
01349             break;
01350         case FC_DST_64_BITS:
01351             if (memcmp((uint8_t *)ptr, (uint8_t *) cmp_table, 8)) {
01352                 retval = false;
01353             }
01354             if (!retval) {
01355                 for (uint8_t i = 0; i < 8; i++) {
01356                     cmp_table[7 - i] = ptr[i];
01357                 }
01358 
01359                 if (!memcmp((uint8_t *)mac_64bit_addr, (uint8_t *) cmp_table, 8)) {
01360                     retval = true;
01361                 }
01362             }
01363             break;
01364         case FC_DST_ADDR_NONE:
01365             retval = true;
01366             break;
01367         default:
01368             retval = false;
01369             break;
01370     }
01371     return retval;
01372 }
01373 
01374 static bool rf_addr_v1_v0_filter(uint8_t *ptr, uint8_t *mac_64bit_addr, uint8_t *mac_16bit_addr, uint8_t dst_mode)
01375 {
01376     return rf_addr_filter_common(ptr, dst_mode, mac_64bit_addr, mac_16bit_addr);
01377 }
01378 
01379 static bool rf_rx_filter(uint8_t *mac_header, uint8_t *mac_64bit_addr, uint8_t *mac_16bit_addr, uint8_t *pan_id)
01380 {
01381     uint8_t dst_mode = (mac_header[1] & FC_DST_MODE);
01382     uint8_t frame_type = mac_header[0] & MAC_FRAME_TYPE_MASK;
01383     uint8_t version = ((mac_header[1] & VERSION_FIELD_MASK) >> SHIFT_VERSION_FIELD);
01384     if (version != MAC_FRAME_VERSION_2) {
01385         if (!rf_panid_v1_v0_filter(mac_header + OFFSET_DST_PAN_ID, pan_id, frame_type)) {
01386             return false;
01387         }
01388         if (!rf_addr_v1_v0_filter(mac_header + OFFSET_DST_ADDR, mac_64bit_addr, mac_16bit_addr, dst_mode)) {
01389             return false;
01390         }
01391     }
01392     return true;
01393 }
01394 
01395 #if MBED_CONF_S2LP_PROVIDE_DEFAULT
01396 NanostackRfPhy &NanostackRfPhy::get_default_instance()
01397 {
01398     static NanostackRfPhys2lp rf_phy(S2LP_SPI_SDI, S2LP_SPI_SDO, S2LP_SPI_SCLK, S2LP_SPI_CS, S2LP_SPI_SDN
01399 #ifdef TEST_GPIOS_ENABLED
01400                                      ,S2LP_SPI_TEST1, S2LP_SPI_TEST2, S2LP_SPI_TEST3, S2LP_SPI_TEST4, S2LP_SPI_TEST5
01401 #endif //TEST_GPIOS_ENABLED
01402                                      ,S2LP_SPI_GPIO0, S2LP_SPI_GPIO1, S2LP_SPI_GPIO2, S2LP_SPI_GPIO3
01403 #ifdef AT24MAC
01404                                      ,S2LP_I2C_SDA, S2LP_I2C_SCL
01405 #endif //AT24MAC
01406                                      );
01407     return rf_phy;
01408 }
01409 #endif // MBED_CONF_S2LP_PROVIDE_DEFAULT
01410 #endif // MBED_CONF_NANOSTACK_CONFIGURATION && DEVICE_SPI