LoRa node acquiring random float value and sending to LoRa Server - Working ok

Fork of SX1276GenericLib by Helmut Tschemernjak

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers radio.h Source File

radio.h

00001 /*
00002  / _____)             _              | |
00003 ( (____  _____ ____ _| |_ _____  ____| |__
00004  \____ \| ___ |    (_   _) ___ |/ ___)  _ \
00005  _____) ) ____| | | || |_| ____( (___| | | |
00006 (______/|_____)_|_|_| \__)_____)\____)_| |_|
00007     (C) 2014 Semtech
00008 
00009 Description: Interface for the radios, contains the main functions that a radio needs, and 5 callback functions
00010 
00011 License: Revised BSD License, see LICENSE.TXT file include in the project
00012 
00013 Maintainers: Miguel Luis, Gregory Cristian and Nicolas Huguenin
00014 */
00015 #ifndef __RADIO_H__
00016 #define __RADIO_H__
00017 
00018 #ifdef __MBED__
00019 #include "mbed.h"
00020 #endif
00021 #ifdef ARDUINO
00022 #include <arduino.h>
00023 #endif
00024 
00025 /*!
00026  * Radio driver internal state machine states definition
00027  */
00028 typedef enum RadioState
00029 {
00030     RF_IDLE = 0,
00031     RF_RX_RUNNING,
00032     RF_TX_RUNNING,
00033     RF_CAD,
00034 } RadioState_t;
00035 
00036 
00037 /*!
00038  *    Type of the modem. [LORA / FSK]
00039  */
00040 typedef enum ModemType
00041 {
00042     MODEM_FSK = 0,
00043     MODEM_LORA
00044 }RadioModems_t;
00045 
00046 
00047 /*!
00048  * Radio LoRa modem parameters
00049  */
00050 typedef struct
00051 {
00052     int8_t   Power;
00053     uint32_t Bandwidth;
00054     uint32_t Datarate;
00055     bool     LowDatarateOptimize;
00056     uint8_t  Coderate;
00057     uint16_t PreambleLen;
00058     bool     FixLen;
00059     uint8_t  PayloadLen;
00060     bool     CrcOn;
00061     bool     FreqHopOn;
00062     uint8_t  HopPeriod;
00063     bool     IqInverted;
00064     bool     RxContinuous;
00065     uint32_t TxTimeout;
00066     bool     PublicNetwork;
00067 }RadioLoRaSettings_t ;
00068 
00069 /*!
00070  * Radio FSK modem parameters
00071  */
00072 typedef struct
00073 {
00074     int8_t   Power;
00075     uint32_t Fdev;
00076     uint32_t Bandwidth;
00077     uint32_t BandwidthAfc;
00078     uint32_t Datarate;
00079     uint16_t PreambleLen;
00080     bool     FixLen;
00081     uint8_t  PayloadLen;
00082     bool     CrcOn;
00083     bool     IqInverted;
00084     bool     RxContinuous;
00085     uint32_t TxTimeout;
00086     uint32_t RxSingleTimeout;
00087 }RadioFskSettings_t ;
00088 
00089 /*!
00090  * Radio FSK packet handler state
00091  */
00092 typedef struct
00093 {
00094     uint8_t  PreambleDetected;
00095     uint8_t  SyncWordDetected;
00096     int8_t   RssiValue;
00097     int32_t  AfcValue;
00098     uint8_t  RxGain;
00099     uint16_t Size;
00100     uint16_t NbBytes;
00101     uint8_t  FifoThresh;
00102     uint8_t  ChunkSize;
00103 }RadioFskPacketHandler_t ;
00104 
00105 /*!
00106  * Radio LoRa packet handler state
00107  */
00108 typedef struct
00109 {
00110     int8_t SnrValue;
00111     int8_t RssiValue;
00112     uint8_t Size;
00113 }RadioLoRaPacketHandler_t ;
00114 
00115 /*!
00116  * Radio Settings
00117  */
00118 typedef struct
00119 {
00120     RadioState               State;
00121     ModemType                Modem;
00122     uint32_t                 Channel;
00123     RadioFskSettings_t        Fsk;
00124     RadioFskPacketHandler_t   FskPacketHandler;
00125     RadioLoRaSettings_t       LoRa;
00126     RadioLoRaPacketHandler_t  LoRaPacketHandler;
00127 }RadioSettings_t ;
00128 
00129 /*!
00130  * @brief Radio driver callback functions
00131  */
00132 typedef struct
00133 {
00134     /*!
00135      * @brief  Tx Done callback prototype.
00136      */
00137     void    ( *TxDone )(void *radio, void *userThisPtr, void *userData);
00138     /*!
00139      * @brief  Tx Timeout callback prototype.
00140      */
00141     void    ( *TxTimeout )(void *radio, void *userThisPtr, void *userData);
00142     /*!
00143      * @brief Rx Done callback prototype.
00144      *
00145      * @param [IN] payload Received buffer pointer
00146      * @param [IN] size    Received buffer size
00147      * @param [IN] rssi    RSSI value computed while receiving the frame [dBm]
00148      * @param [IN] snr     Raw SNR value given by the radio hardware
00149      *                     FSK : N/A ( set to 0 )
00150      *                     LoRa: SNR value in dB
00151      */
00152     void    ( *RxDone )(void *radio, void *userThisPtr, void *userData, uint8_t *payload, uint16_t size, int16_t rssi, int8_t snr );
00153     /*!
00154      * @brief  Rx Timeout callback prototype.
00155      */
00156     void    ( *RxTimeout )(void *radio, void *userThisPtr, void *userData);
00157     /*!
00158      * @brief Rx Error callback prototype.
00159      */
00160     void    ( *RxError )(void *radio, void *userThisPtr, void *userData);
00161     /*!
00162      * \brief  FHSS Change Channel callback prototype.
00163      *
00164      * \param [IN] currentChannel   Index number of the current channel
00165      */
00166     void ( *FhssChangeChannel )(void *radio, void *userThisPtr, void *userData, uint8_t currentChannel );
00167 
00168     /*!
00169      * @brief CAD Done callback prototype.
00170      *
00171      * @param [IN] channelDetected    Channel Activity detected during the CAD
00172      */
00173     void ( *CadDone ) (void *radio, void *userThisPtr, void *userData, bool channelActivityDetected );
00174     
00175     /*
00176      * Optional data which is being provided in callbacks
00177      * can be used e.g. for the C++ this pointer.
00178      */
00179     void *userThisPtr;
00180     
00181     /*
00182      * Optional data which allows to bring in data structures pointer 
00183      * for a given radio. As callbacks are being called in interrupt level
00184      * the userData is perfect to know the context without iterating this
00185      * data structures.
00186      */
00187     void *userData;
00188 
00189 }RadioEvents_t;
00190 
00191 /*!
00192  *    Interface for the radios, contains the main functions that a radio needs, and 5 callback functions
00193  */
00194 class Radio 
00195 {
00196 protected:
00197     RadioEvents_t* RadioEvents;
00198 
00199 public:
00200     //-------------------------------------------------------------------------
00201     //                        Constructor
00202     //-------------------------------------------------------------------------
00203     /*!
00204      * @brief Constructor of the radio object, the parameters are the callback functions described in the header.
00205      *
00206      * @param [IN] events Structure containing the driver callback functions
00207      */
00208     Radio( RadioEvents_t *events );
00209     virtual ~Radio ( ) {};
00210 
00211     //-------------------------------------------------------------------------
00212     //                        Pure virtual functions
00213     //-------------------------------------------------------------------------
00214 
00215     /*!
00216      * @brief Initializes the radio
00217      *
00218      * @param [IN] events Structure containing the driver callback functions
00219      */
00220     virtual bool Init( RadioEvents_t *events ) = 0;
00221 
00222     /*!
00223      * @brief Return current radio status, returns true if a radios has been found.
00224      *
00225      * @param status Radio status. [RF_IDLE, RX_RUNNING, TX_RUNNING, CAD_RUNNING]
00226      */
00227     virtual RadioState GetStatus( void ) = 0; 
00228 
00229     /*!
00230      * @brief Configures the radio with the given modem
00231      *
00232      * @param [IN] modem Modem to be used [0: FSK, 1: LoRa] 
00233      */
00234     virtual void SetModem( RadioModems_t modem ) = 0;
00235 
00236     /*!
00237      * @brief Sets the channel frequency
00238      *
00239      * @param [IN] freq         Channel RF frequency
00240      */
00241     virtual void SetChannel( uint32_t freq ) = 0;
00242     
00243     /*!
00244      * @brief Sets the channels configuration
00245      *
00246      * @param [IN] modem      Radio modem to be used [0: FSK, 1: LoRa]
00247      * @param [IN] freq       Channel RF frequency
00248      * @param [IN] rssiThresh RSSI threshold
00249      *
00250      * @retval isFree         [true: Channel is free, false: Channel is not free]
00251      */
00252     virtual bool IsChannelFree( RadioModems_t modem, uint32_t freq, int16_t rssiThresh ) = 0;
00253     
00254     /*!
00255      * @brief Generates a 32 bits random value based on the RSSI readings
00256      *
00257      * \remark This function sets the radio in LoRa modem mode and disables
00258      *         all interrupts.
00259      *         After calling this function either Radio.SetRxConfig or
00260      *         Radio.SetTxConfig functions must be called.
00261      *
00262      * @retval randomValue    32 bits random value
00263      */
00264     virtual uint32_t Random( void )= 0;
00265     
00266     /*!
00267      * @brief Sets the reception parameters
00268      *
00269      * @param [IN] modem        Radio modem to be used [0: FSK, 1: LoRa]
00270      * @param [IN] bandwidth    Sets the bandwidth
00271      *                          FSK : >= 2600 and <= 250000 Hz
00272      *                          LoRa: [0: 125 kHz, 1: 250 kHz,
00273      *                                 2: 500 kHz, 3: Reserved]
00274      * @param [IN] datarate     Sets the Datarate
00275      *                          FSK : 600..300000 bits/s
00276      *                          LoRa: [6: 64, 7: 128, 8: 256, 9: 512,
00277      *                                10: 1024, 11: 2048, 12: 4096  chips]
00278      * @param [IN] coderate     Sets the coding rate ( LoRa only )
00279      *                          FSK : N/A ( set to 0 )
00280      *                          LoRa: [1: 4/5, 2: 4/6, 3: 4/7, 4: 4/8]
00281      * @param [IN] bandwidthAfc Sets the AFC Bandwidth ( FSK only )
00282      *                          FSK : >= 2600 and <= 250000 Hz
00283      *                          LoRa: N/A ( set to 0 )
00284      * @param [IN] preambleLen  Sets the Preamble length ( LoRa only )
00285      *                          FSK : N/A ( set to 0 )
00286      *                          LoRa: Length in symbols ( the hardware adds 4 more symbols )
00287      * @param [IN] symbTimeout  Sets the RxSingle timeout value
00288      *                          FSK : timeout number of bytes
00289      *                          LoRa: timeout in symbols
00290      * @param [IN] fixLen       Fixed length packets [0: variable, 1: fixed]
00291      * @param [IN] payloadLen   Sets payload length when fixed lenght is used
00292      * @param [IN] crcOn        Enables/Disables the CRC [0: OFF, 1: ON]
00293      * @param [IN] freqHopOn    Enables disables the intra-packet frequency hopping  [0: OFF, 1: ON] (LoRa only)
00294      * @param [IN] hopPeriod    Number of symbols bewteen each hop (LoRa only)
00295      * @param [IN] iqInverted   Inverts IQ signals ( LoRa only )
00296      *                          FSK : N/A ( set to 0 )
00297      *                          LoRa: [0: not inverted, 1: inverted]
00298      * @param [IN] rxContinuous Sets the reception in continuous mode
00299      *                          [false: single mode, true: continuous mode]
00300      */
00301     virtual void SetRxConfig ( RadioModems_t modem, uint32_t bandwidth,
00302                                uint32_t datarate, uint8_t coderate,
00303                                uint32_t bandwidthAfc, uint16_t preambleLen,
00304                                uint16_t symbTimeout, bool fixLen,
00305                                uint8_t payloadLen,
00306                                bool crcOn, bool freqHopOn, uint8_t hopPeriod,
00307                                bool iqInverted, bool rxContinuous ) = 0;
00308 
00309     /*!
00310      * @brief Sets the transmission parameters
00311      *
00312      * @param [IN] modem        Radio modem to be used [0: FSK, 1: LoRa]
00313      * @param [IN] power        Sets the output power [dBm]
00314      * @param [IN] fdev         Sets the frequency deviation ( FSK only )
00315      *                          FSK : [Hz]
00316      *                          LoRa: 0
00317      * @param [IN] bandwidth    Sets the bandwidth ( LoRa only )
00318      *                          FSK : 0
00319      *                          LoRa: [0: 125 kHz, 1: 250 kHz,
00320      *                                 2: 500 kHz, 3: Reserved]
00321      * @param [IN] datarate     Sets the Datarate
00322      *                          FSK : 600..300000 bits/s
00323      *                          LoRa: [6: 64, 7: 128, 8: 256, 9: 512,
00324      *                                10: 1024, 11: 2048, 12: 4096  chips]
00325      * @param [IN] coderate     Sets the coding rate ( LoRa only )
00326      *                          FSK : N/A ( set to 0 )
00327      *                          LoRa: [1: 4/5, 2: 4/6, 3: 4/7, 4: 4/8]
00328      * @param [IN] preambleLen  Sets the preamble length
00329      * @param [IN] fixLen       Fixed length packets [0: variable, 1: fixed]
00330      * @param [IN] crcOn        Enables disables the CRC [0: OFF, 1: ON]
00331      * @param [IN] freqHopOn    Enables disables the intra-packet frequency hopping  [0: OFF, 1: ON] (LoRa only)
00332      * @param [IN] hopPeriod    Number of symbols bewteen each hop (LoRa only)
00333      * @param [IN] iqInverted   Inverts IQ signals ( LoRa only )
00334      *                          FSK : N/A ( set to 0 )
00335      *                          LoRa: [0: not inverted, 1: inverted]
00336      * @param [IN] timeout      Transmission timeout [us]
00337      */
00338     virtual void SetTxConfig( RadioModems_t modem, int8_t power, uint32_t fdev,
00339                               uint32_t bandwidth, uint32_t datarate,
00340                               uint8_t coderate, uint16_t preambleLen,
00341                               bool fixLen, bool crcOn, bool freqHopOn,
00342                               uint8_t hopPeriod, bool iqInverted, uint32_t timeout ) = 0;
00343 
00344     /*!
00345      * @brief Checks if the given RF frequency is supported by the hardware
00346      *
00347      * @param [IN] frequency RF frequency to be checked
00348      * @retval isSupported [true: supported, false: unsupported]
00349      */
00350     virtual bool CheckRfFrequency( uint32_t frequency ) = 0;
00351     
00352     /*!
00353      * @brief Computes the packet time on air for the given payload
00354      *
00355      * \Remark Can only be called once SetRxConfig or SetTxConfig have been called
00356      *
00357      * @param [IN] modem      Radio modem to be used [0: FSK, 1: LoRa]
00358      * @param [IN] pktLen     Packet payload length
00359      *
00360      * @retval airTime        Computed airTime for the given packet payload length
00361      */
00362     virtual uint32_t TimeOnAir ( RadioModems_t modem, int16_t pktLen ) = 0;
00363     
00364     /*!
00365      * @brief Sends the buffer of size. Prepares the packet to be sent and sets
00366      *        the radio in transmission
00367      *
00368      * @param [IN]: buffer     Buffer pointer
00369      * @param [IN]: size       Buffer size
00370      * @param [IN]: buffer     Header pointer
00371      * @param [IN]: size       Header size
00372      */
00373     virtual void Send( void *buffer, int16_t size, void *header = NULL, int16_t hsize = 0) = 0;
00374 
00375     /*!
00376      * @brief Sets the radio in sleep mode
00377      */
00378     virtual void Sleep( void ) = 0;
00379 
00380     /*!
00381      * @brief Sets the radio in standby mode
00382      */
00383     virtual void Standby( void ) = 0;
00384 
00385     /*!
00386      * @brief Sets the radio in CAD mode
00387      */
00388     virtual void StartCad( void ) = 0;
00389 
00390     /*!
00391      * @brief Sets the radio in reception mode for the given time
00392      * @param [IN] timeout Reception timeout [us]
00393      *                     [0: continuous, others timeout]
00394      */
00395     virtual void Rx( uint32_t timeout ) = 0;
00396     
00397     /*!
00398      * @brief Check is radio receives a signal
00399      */
00400     virtual bool RxSignalPending() = 0;
00401 
00402 
00403     /*!
00404      * @brief Sets the radio in transmission mode for the given time
00405      * @param [IN] timeout Transmission timeout [us]
00406      *                     [0: continuous, others timeout]
00407      */
00408     virtual void Tx( uint32_t timeout ) = 0;
00409 
00410     /*!
00411      * @brief Sets the radio in continuous wave transmission mode
00412      *
00413      * @param [IN]: freq       Channel RF frequency
00414      * @param [IN]: power      Sets the output power [dBm]
00415      * @param [IN]: time       Transmission mode timeout [s]
00416      */
00417     virtual void SetTxContinuousWave( uint32_t freq, int8_t power, uint16_t time ) = 0;
00418 
00419     /*!
00420      * @brief Returns the maximal transfer unit for a given modem
00421      *
00422      * @retval MTU size in bytes
00423      */
00424     virtual int16_t MaxMTUSize( RadioModems_t modem ) = 0;
00425     
00426     /*!
00427      * @brief Reads the current RSSI value
00428      *
00429      * @retval rssiValue Current RSSI value in [dBm]
00430      */
00431     virtual int16_t GetRssi ( RadioModems_t modem ) = 0;
00432 
00433     /*!
00434      * @brief Reads the current frequency error
00435      *
00436      * @retval frequency error value in [Hz]
00437      */
00438     virtual int32_t GetFrequencyError( RadioModems_t modem ) = 0;
00439 
00440     /*!
00441      * @brief Writes the radio register at the specified address
00442      *
00443      * @param [IN]: addr Register address
00444      * @param [IN]: data New register value
00445      */
00446     virtual void Write ( uint8_t addr, uint8_t data ) = 0;
00447 
00448     /*!
00449      * @brief Reads the radio register at the specified address
00450      *
00451      * @param [IN]: addr Register address
00452      * @retval data Register value
00453      */
00454     virtual uint8_t Read ( uint8_t addr ) = 0;
00455 
00456     /*!
00457      * @brief Writes multiple radio registers starting at address
00458      *
00459      * @param [IN] addr   First Radio register address
00460      * @param [IN] buffer Buffer containing the new register's values
00461      * @param [IN] size   Number of registers to be written
00462      */
00463     virtual void Write( uint8_t addr, void *buffer, uint8_t size ) = 0;
00464 
00465     /*!
00466      * @brief Reads multiple radio registers starting at address
00467      *
00468      * @param [IN] addr First Radio register address
00469      * @param [OUT] buffer Buffer where to copy the registers data
00470      * @param [IN] size Number of registers to be read
00471      */
00472     virtual void Read ( uint8_t addr, void *buffer, uint8_t size ) = 0;
00473 
00474     /*!
00475      * @brief Writes the buffer contents to the Radio FIFO
00476      *
00477      * @param [IN] buffer Buffer containing data to be put on the FIFO.
00478      * @param [IN] size Number of bytes to be written to the FIFO
00479      */
00480     virtual void WriteFifo( void *buffer, uint8_t size ) = 0;
00481 
00482     /*!
00483      * @brief Reads the contents of the Radio FIFO
00484      *
00485      * @param [OUT] buffer Buffer where to copy the FIFO read data.
00486      * @param [IN] size Number of bytes to be read from the FIFO
00487      */
00488     virtual void ReadFifo( void *buffer, uint8_t size ) = 0;
00489 
00490     /*!
00491      * @brief Sets the maximum payload length.
00492      *
00493      * @param [IN] modem      Radio modem to be used [0: FSK, 1: LoRa]
00494      * @param [IN] max        Maximum payload length in bytes
00495      */
00496     virtual void SetMaxPayloadLength( RadioModems_t modem, uint8_t max ) = 0;
00497 
00498     /*!
00499      * @brief Sets the network to public or private. Updates the sync byte.
00500      *
00501      * @remark Applies to LoRa modem only
00502      *
00503      * @param [IN] enable if true, it enables a public network
00504      */
00505     virtual void SetPublicNetwork( bool enable ) = 0;
00506     
00507     /*!
00508      * \brief Sets the radio output power.
00509      *
00510      * @param [IN] power Sets the RF output power
00511      */
00512     virtual void SetRfTxPower( int8_t power ) = 0;
00513 
00514 };
00515 
00516 #endif // __RADIO_H__