stephen mathenge / Mbed OS Level_estimation_Maesurement

Dependencies:   Cayenne-LPP SDBlockDevice

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers SX1276_LoRaRadio.h Source File

SX1276_LoRaRadio.h

00001 /**
00002  / _____)             _              | |
00003 ( (____  _____ ____ _| |_ _____  ____| |__
00004  \____ \| ___ |    (_   _) ___ |/ ___)  _ \
00005  _____) ) ____| | | || |_| ____( (___| | | |
00006 (______/|_____)_|_|_| \__)_____)\____)_| |_|
00007     (C)2013 Semtech
00008  ___ _____ _   ___ _  _____ ___  ___  ___ ___
00009 / __|_   _/_\ / __| |/ / __/ _ \| _ \/ __| __|
00010 \__ \ | |/ _ \ (__| ' <| _| (_) |   / (__| _|
00011 |___/ |_/_/ \_\___|_|\_\_| \___/|_|_\\___|___|
00012 embedded.connectivity.solutions===============
00013 
00014 Description: LoRaWAN stack layer that controls both MAC and PHY underneath
00015 
00016 License: Revised BSD License, see LICENSE.TXT file include in the project
00017 
00018 Maintainer: Miguel Luis ( Semtech ), Gregory Cristian ( Semtech ) and Daniel Jaeckle ( STACKFORCE )
00019 
00020 
00021 Copyright (c) 2017, Arm Limited and affiliates.
00022 
00023 SPDX-License-Identifier: BSD-3-Clause
00024 */
00025 
00026 #ifndef SX1276_LORARADIO_H_
00027 #define SX1276_LORARADIO_H_
00028 
00029 #include "PinNames.h"
00030 #include "InterruptIn.h"
00031 #include "DigitalOut.h"
00032 #include "DigitalInOut.h"
00033 #include "SPI.h"
00034 #include "Timeout.h"
00035 #include "platform/PlatformMutex.h"
00036 #ifdef MBED_CONF_RTOS_PRESENT
00037  #include "rtos/Thread.h"
00038 #endif
00039 
00040 #include "lorawan/LoRaRadio.h"
00041 
00042 #ifdef MBED_CONF_SX1276_LORA_DRIVER_BUFFER_SIZE
00043 #define MAX_DATA_BUFFER_SIZE_SX1276                        MBED_CONF_SX1276_LORA_DRIVER_BUFFER_SIZE
00044 #else
00045 #define MAX_DATA_BUFFER_SIZE_SX1276                        256
00046 #endif
00047 
00048 #ifdef DEVICE_SPI
00049 
00050 /**
00051  * Radio driver implementation for Semtech SX1272 plus variants.
00052  * Supports only SPI at the moment. Implements pure virtual LoRaRadio class.
00053  */
00054 class SX1276_LoRaRadio: public LoRaRadio {
00055 public:
00056     /**
00057      * Use this constructor if pin definitions are provided manually.
00058      * The pins that are marked NC are optional. It is assumed that these
00059      * pins are not connected until/unless configured otherwise.
00060      *
00061      * Note: Pin ant_switch is equivalent to RxTx pin at
00062      * https://developer.mbed.org/components/SX1276MB1xAS/.
00063      * Reading the state of this pin indicates if the radio module type is
00064      * SX1276MB1LAS(North American frequency band supported) or SX1276MAS
00065      * (European frequency band supported).
00066      * Pin dio4 can be mapped to multiple pins on the board, please refer to
00067      * schematic of your board. For reference look at
00068      * https://developer.mbed.org/components/SX1276MB1xAS/
00069      *
00070      * Most of the radio module control pins are not being used at the moment as
00071      * the SX1276MB1xAS shield has not connected them. For consistency and future
00072      * use we are leaving the pins in the constructor. For example, if in some
00073      * setting SX1276 radio module gets connected to an external power amplifier
00074      * or radio  latch controls are connected.
00075      */
00076     SX1276_LoRaRadio(PinName mosi,
00077                      PinName miso,
00078                      PinName sclk,
00079                      PinName nss,
00080                      PinName reset,
00081                      PinName dio0,
00082                      PinName dio1,
00083                      PinName dio2,
00084                      PinName dio3,
00085                      PinName dio4,
00086                      PinName dio5,
00087                      PinName rf_switch_ctl1 = NC,
00088                      PinName rf_switch_ctl2 = NC,
00089                      PinName txctl = NC,
00090                      PinName rxctl = NC,
00091                      PinName ant_switch = NC,
00092                      PinName pwr_amp_ctl = NC,
00093                      PinName tcxo = NC);
00094 
00095     /**
00096      * Destructor
00097      */
00098     virtual ~SX1276_LoRaRadio();
00099 
00100     /**
00101      * Registers radio events with the Mbed LoRaWAN stack and
00102      * undergoes initialization steps if any
00103      *
00104      *  @param events Structure containing the driver callback functions
00105      */
00106     virtual void init_radio(radio_events_t *events);
00107 
00108     /**
00109      * Resets the radio module
00110      */
00111     virtual void radio_reset();
00112 
00113     /**
00114      *  Put the RF module in sleep mode
00115      */
00116     virtual void sleep(void);
00117 
00118     /**
00119      *  Sets the radio in standby mode
00120      */
00121     virtual void standby(void);
00122 
00123     /**
00124      *  Sets the reception parameters
00125      *
00126      *  @param modem         Radio modem to be used [0: FSK, 1: LoRa]
00127      *  @param bandwidth     Sets the bandwidth
00128      *                          FSK : >= 2600 and <= 250000 Hz
00129      *                          LoRa: [0: 125 kHz, 1: 250 kHz,
00130      *                                 2: 500 kHz, 3: Reserved]
00131      *  @param datarate      Sets the Datarate
00132      *                          FSK : 600..300000 bits/s
00133      *                          LoRa: [6: 64, 7: 128, 8: 256, 9: 512,
00134      *                                10: 1024, 11: 2048, 12: 4096  chips]
00135      *  @param coderate      Sets the coding rate ( LoRa only )
00136      *                          FSK : N/A ( set to 0 )
00137      *                          LoRa: [1: 4/5, 2: 4/6, 3: 4/7, 4: 4/8]
00138      *  @param bandwidth_afc Sets the AFC Bandwidth ( FSK only )
00139      *                          FSK : >= 2600 and <= 250000 Hz
00140      *                          LoRa: N/A ( set to 0 )
00141      *  @param preamble_len  Sets the Preamble length ( LoRa only )
00142      *                          FSK : N/A ( set to 0 )
00143      *                          LoRa: Length in symbols ( the hardware adds 4 more symbols )
00144      *  @param symb_timeout  Sets the RxSingle timeout value
00145      *                          FSK : timeout number of bytes
00146      *                          LoRa: timeout in symbols
00147      *  @param fixLen        Fixed length packets [0: variable, 1: fixed]
00148      *  @param payload_len   Sets payload length when fixed lenght is used
00149      *  @param crc_on        Enables/Disables the CRC [0: OFF, 1: ON]
00150      *  @param freq_hop_on   Enables disables the intra-packet frequency hopping  [0: OFF, 1: ON] (LoRa only)
00151      *  @param hop_period    Number of symbols bewteen each hop (LoRa only)
00152      *  @param iq_inverted   Inverts IQ signals ( LoRa only )
00153      *                          FSK : N/A ( set to 0 )
00154      *                          LoRa: [0: not inverted, 1: inverted]
00155      *  @param rx_continuous Sets the reception in continuous mode
00156      *                          [false: single mode, true: continuous mode]
00157      */
00158     virtual void set_rx_config (radio_modems_t modem, uint32_t bandwidth,
00159                                uint32_t datarate, uint8_t coderate,
00160                                uint32_t bandwidth_afc, uint16_t preamble_len,
00161                                uint16_t symb_timeout, bool fix_len,
00162                                uint8_t payload_len,
00163                                bool crc_on, bool freq_hop_on, uint8_t hop_period,
00164                                bool iq_inverted, bool rx_continuous);
00165 
00166     /**
00167      *  Sets the transmission parameters
00168      *
00169      *  @param modem         Radio modem to be used [0: FSK, 1: LoRa]
00170      *  @param power         Sets the output power [dBm]
00171      *  @param fdev          Sets the frequency deviation ( FSK only )
00172      *                          FSK : [Hz]
00173      *                          LoRa: 0
00174      *  @param bandwidth     Sets the bandwidth ( LoRa only )
00175      *                          FSK : 0
00176      *                          LoRa: [0: 125 kHz, 1: 250 kHz,
00177      *                                 2: 500 kHz, 3: Reserved]
00178      *  @param datarate      Sets the Datarate
00179      *                          FSK : 600..300000 bits/s
00180      *                          LoRa: [6: 64, 7: 128, 8: 256, 9: 512,
00181      *                                10: 1024, 11: 2048, 12: 4096  chips]
00182      *  @param coderate      Sets the coding rate ( LoRa only )
00183      *                          FSK : N/A ( set to 0 )
00184      *                          LoRa: [1: 4/5, 2: 4/6, 3: 4/7, 4: 4/8]
00185      *  @param preamble_len  Sets the preamble length
00186      *  @param fix_len       Fixed length packets [0: variable, 1: fixed]
00187      *  @param crc_on        Enables disables the CRC [0: OFF, 1: ON]
00188      *  @param freq_hop_on   Enables disables the intra-packet frequency hopping  [0: OFF, 1: ON] (LoRa only)
00189      *  @param hop_period    Number of symbols bewteen each hop (LoRa only)
00190      *  @param iq_inverted   Inverts IQ signals ( LoRa only )
00191      *                          FSK : N/A ( set to 0 )
00192      *                          LoRa: [0: not inverted, 1: inverted]
00193      *  @param timeout       Transmission timeout [us]
00194      */
00195     virtual void set_tx_config(radio_modems_t modem, int8_t power, uint32_t fdev,
00196                               uint32_t bandwidth, uint32_t datarate,
00197                               uint8_t coderate, uint16_t preamble_len,
00198                               bool fix_len, bool crc_on, bool freq_hop_on,
00199                               uint8_t hop_period, bool iq_inverted, uint32_t timeout);
00200 
00201     /**
00202      *  Sends the buffer of size
00203      *
00204      *  Prepares the packet to be sent and sets the radio in transmission
00205      *
00206      *  @param buffer        Buffer pointer
00207      *  @param size          Buffer size
00208      */
00209     virtual void send(uint8_t *buffer, uint8_t size);
00210 
00211     /**
00212      *  Sets the radio in reception mode for the given time
00213      *
00214      *  It should be noted that if the timeout is set to 0, it essentially
00215      *  puts the receiver in continuous mode and hence from thereon it should
00216      *  be treated as if in continuous mode. However, an appropriate way of
00217      *  setting the receiver in continuous mode is by using set_rx_config()
00218      *  API.
00219      *
00220      *  @param timeout       Reception timeout [ms]
00221      *
00222      */
00223     virtual void receive(uint32_t timeout);
00224 
00225     /**
00226      *  Sets the carrier frequency
00227      *
00228      *  @param freq          Channel RF frequency
00229      */
00230     virtual void set_channel(uint32_t freq);
00231 
00232     /**
00233      *  Generates a 32 bits random value based on the RSSI readings
00234      *
00235      *  Remark this function sets the radio in LoRa modem mode and disables
00236      *         all interrupts.
00237      *         After calling this function either Radio.SetRxConfig or
00238      *         Radio.SetTxConfig functions must be called.
00239      *
00240      *  @return             32 bits random value
00241      */
00242     virtual uint32_t random(void);
00243 
00244     /**
00245      *  Get radio status
00246      *
00247      *  @param status        Radio status [RF_IDLE, RF_RX_RUNNING, RF_TX_RUNNING]
00248      *  @return              Return current radio status
00249      */
00250     virtual uint8_t get_status(void);
00251 
00252     /**
00253      *  Sets the maximum payload length
00254      *
00255      *  @param modem         Radio modem to be used [0: FSK, 1: LoRa]
00256      *  @param max           Maximum payload length in bytes
00257      */
00258     virtual void set_max_payload_length(radio_modems_t modem, uint8_t max);
00259 
00260     /**
00261      *  Sets the network to public or private
00262      *
00263      *  Updates the sync byte. Applies to LoRa modem only
00264      *
00265      *  @param enable        if true, it enables a public network
00266      */
00267     virtual void set_public_network(bool enable);
00268 
00269     /**
00270      *  Computes the packet time on air for the given payload
00271      *
00272      *  Remark can only be called once SetRxConfig or SetTxConfig have been called
00273      *
00274      *  @param modem         Radio modem to be used [0: FSK, 1: LoRa]
00275      *  @param pkt_len       Packet payload length
00276      *  @return              Computed airTime for the given packet payload length
00277      */
00278     virtual uint32_t time_on_air(radio_modems_t modem, uint8_t pkt_len);
00279 
00280     /**
00281      * Perform carrier sensing
00282      *
00283      * Checks for a certain time if the RSSI is above a given threshold.
00284      * This threshold determines if there is already a transmission going on
00285      * in the channel or not.
00286      *
00287      * @param modem                     Type of the radio modem
00288      * @param freq                      Carrier frequency
00289      * @param rssi_threshold            Threshold value of RSSI
00290      * @param max_carrier_sense_time    time to sense the channel
00291      *
00292      * @return                          true if there is no active transmission
00293      *                                  in the channel, false otherwise
00294      */
00295     virtual bool perform_carrier_sense(radio_modems_t modem,
00296                                        uint32_t freq,
00297                                        int16_t rssi_threshold,
00298                                        uint32_t max_carrier_sense_time);
00299 
00300     /**
00301      *  Sets the radio in CAD mode
00302      *
00303      */
00304     virtual void start_cad(void);
00305 
00306     /**
00307      *  Check if the given RF is in range
00308      *
00309      *  @param frequency       frequency needed to be checked
00310      */
00311     virtual bool check_rf_frequency(uint32_t frequency);
00312 
00313     /** Sets the radio in continuous wave transmission mode
00314      *
00315      *  @param freq          Channel RF frequency
00316      *  @param power         Sets the output power [dBm]
00317      *  @param time          Transmission mode timeout [s]
00318      */
00319     virtual void set_tx_continuous_wave(uint32_t freq, int8_t power, uint16_t time);
00320 
00321     /**
00322      * Acquire exclusive access
00323      */
00324     virtual void lock(void);
00325 
00326     /**
00327      * Release exclusive access
00328      */
00329     virtual void unlock(void);
00330 
00331 private:
00332 
00333     // SPI and chip select control
00334     mbed::SPI _spi;
00335     mbed::DigitalOut _chip_select;
00336 
00337     // module rest control
00338     mbed::DigitalInOut _reset_ctl;
00339 
00340     // Interrupt controls
00341     mbed::InterruptIn _dio0_ctl;
00342     mbed::InterruptIn _dio1_ctl;
00343     mbed::InterruptIn _dio2_ctl;
00344     mbed::InterruptIn _dio3_ctl;
00345     mbed::InterruptIn _dio4_ctl;
00346     mbed::InterruptIn _dio5_ctl;
00347 
00348     // Radio specific controls
00349     mbed::DigitalOut _rf_switch_ctl1;
00350     mbed::DigitalOut _rf_switch_ctl2;
00351     mbed::DigitalOut _txctl;
00352     mbed::DigitalOut _rxctl;
00353     mbed::DigitalInOut _ant_switch;
00354     mbed::DigitalOut _pwr_amp_ctl;
00355     mbed::DigitalOut _tcxo;
00356 
00357     // Contains all RF control pin names
00358     // This storage is needed even after assigning the
00359     // pins to corresponding object, as the driver needs to know
00360     // which control pins are connected and which are not. This
00361     // variation is inherent to driver because of target configuration.
00362     rf_ctrls _rf_ctrls;
00363 
00364     // We need these PinNames as not all modules have those connected
00365     PinName _dio4_pin;
00366     PinName _dio5_pin;
00367 
00368     // Structure containing all user and network specified settings
00369     // for radio module
00370     radio_settings_t _rf_settings;
00371 
00372     // Structure containing function pointers to the stack callbacks
00373     radio_events_t *_radio_events;
00374 
00375     // Data buffer used for both TX and RX
00376     // Size of this buffer is configurable via Mbed config system
00377     // Default is 256 bytes
00378     uint8_t _data_buffer[MAX_DATA_BUFFER_SIZE_SX1276];
00379 
00380     // TX/RX Timers - all use milisecond units
00381     mbed::Timeout tx_timeout_timer;
00382     mbed::Timeout rx_timeout_timer;
00383     mbed::Timeout rx_timeout_sync_word;
00384 
00385 #ifdef MBED_CONF_RTOS_PRESENT
00386     // Thread to handle interrupts
00387     rtos::Thread irq_thread;
00388 #endif
00389 
00390     // Access protection
00391     PlatformMutex mutex;
00392 
00393     uint8_t radio_variant;
00394 
00395     // helper functions
00396     void setup_registers();
00397     void default_antenna_switch_ctrls();
00398     void set_antenna_switch(uint8_t operation_mode);
00399     void setup_spi();
00400     void gpio_init();
00401     void gpio_deinit();
00402     void setup_interrupts();
00403     void set_operation_mode(uint8_t operation_mode);
00404     void set_low_power_mode();
00405     void set_sx1276_variant_type();
00406     uint8_t get_pa_conf_reg(uint32_t channel);
00407     void set_rf_tx_power(int8_t power);
00408     int16_t get_rssi(radio_modems_t modem);
00409     uint8_t get_fsk_bw_reg_val(uint32_t bandwidth);
00410     void write_to_register(uint8_t addr, uint8_t data);
00411     void write_to_register(uint8_t addr, uint8_t *data, uint8_t size);
00412     uint8_t read_register(uint8_t addr);
00413     void read_register(uint8_t addr, uint8_t *buffer, uint8_t size);
00414     void write_fifo(uint8_t *buffer, uint8_t size);
00415     void read_fifo(uint8_t *buffer, uint8_t size);
00416     void transmit(uint32_t timeout);
00417     void rf_irq_task(void);
00418     void set_modem(uint8_t modem);
00419     void rx_chain_calibration(void);
00420 
00421     // ISRs
00422     void  dio0_irq_isr();
00423     void  dio1_irq_isr();
00424     void  dio2_irq_isr();
00425     void  dio3_irq_isr();
00426     void  dio4_irq_isr();
00427     void  dio5_irq_isr();
00428     void  timeout_irq_isr();
00429 
00430     // Handlers called by thread in response to signal
00431     void handle_dio0_irq();
00432     void handle_dio1_irq();
00433     void handle_dio2_irq();
00434     void handle_dio3_irq();
00435     void handle_dio4_irq();
00436     void handle_dio5_irq();
00437     void handle_timeout_irq();
00438 };
00439 
00440 #endif //DEVICE_SPI
00441 
00442 #endif // SX1276_LORARADIO_H_