NRF52_esb

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers nrf_esb.c Source File

nrf_esb.c

00001 /**
00002  * Copyright (c) 2016 - 2018, Nordic Semiconductor ASA
00003  * 
00004  * All rights reserved.
00005  * 
00006  * Redistribution and use in source and binary forms, with or without modification,
00007  * are permitted provided that the following conditions are met:
00008  * 
00009  * 1. Redistributions of source code must retain the above copyright notice, this
00010  *    list of conditions and the following disclaimer.
00011  * 
00012  * 2. Redistributions in binary form, except as embedded into a Nordic
00013  *    Semiconductor ASA integrated circuit in a product or a software update for
00014  *    such product, must reproduce the above copyright notice, this list of
00015  *    conditions and the following disclaimer in the documentation and/or other
00016  *    materials provided with the distribution.
00017  * 
00018  * 3. Neither the name of Nordic Semiconductor ASA nor the names of its
00019  *    contributors may be used to endorse or promote products derived from this
00020  *    software without specific prior written permission.
00021  * 
00022  * 4. This software, with or without modification, must only be used with a
00023  *    Nordic Semiconductor ASA integrated circuit.
00024  * 
00025  * 5. Any software provided in binary form under this license must not be reverse
00026  *    engineered, decompiled, modified and/or disassembled.
00027  * 
00028  * THIS SOFTWARE IS PROVIDED BY NORDIC SEMICONDUCTOR ASA "AS IS" AND ANY EXPRESS
00029  * OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
00030  * OF MERCHANTABILITY, NONINFRINGEMENT, AND FITNESS FOR A PARTICULAR PURPOSE ARE
00031  * DISCLAIMED. IN NO EVENT SHALL NORDIC SEMICONDUCTOR ASA OR CONTRIBUTORS BE
00032  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00033  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE
00034  * GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
00035  * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00036  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
00037  * OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00038  * 
00039  */
00040 
00041 #include "nrf_error.h"
00042 #include "nrf_esb.h"
00043 #include "nrf_esb_error_codes.h"
00044 #include "nrf_gpio.h"
00045 #include <string.h>
00046 #include <stddef.h>
00047 #include "sdk_common.h"
00048 #include "sdk_macros.h"
00049 #include "app_util.h"
00050 #include "nrf_log.h"
00051 #include "nrf_delay.h"
00052 
00053 #define BIT_MASK_UINT_8(x) (0xFF >> (8 - (x)))
00054 #define NRF_ESB_PIPE_COUNT 8
00055 
00056 // Constant parameters
00057 #define RX_WAIT_FOR_ACK_TIMEOUT_US_2MBPS        (48)        /**< 2 Mb RX wait for acknowledgment time-out value. Smallest reliable value - 43. */
00058 #define RX_WAIT_FOR_ACK_TIMEOUT_US_1MBPS        (64)        /**< 1 Mb RX wait for acknowledgment time-out value. Smallest reliable value - 59. */
00059 #define RX_WAIT_FOR_ACK_TIMEOUT_US_250KBPS      (250)       /**< 250 Kb RX wait for acknowledgment time-out value. */
00060 #define RX_WAIT_FOR_ACK_TIMEOUT_US_1MBPS_BLE    (73)        /**< 1 Mb RX wait for acknowledgment time-out (combined with BLE). Smallest reliable value - 68.*/
00061 
00062 // Interrupt flags
00063 #define     NRF_ESB_INT_TX_SUCCESS_MSK          0x01        /**< Interrupt mask value for TX success. */
00064 #define     NRF_ESB_INT_TX_FAILED_MSK           0x02        /**< Interrupt mask value for TX failure. */
00065 #define     NRF_ESB_INT_RX_DATA_RECEIVED_MSK    0x04        /**< Interrupt mask value for RX_DR. */
00066 
00067 #define     NRF_ESB_PID_RESET_VALUE             0xFF        /**< Invalid PID value which is guaranteed to not collide with any valid PID value. */
00068 #define     NRF_ESB_PID_MAX                     3           /**< Maximum value for PID. */
00069 #define     NRF_ESB_CRC_RESET_VALUE             0xFFFF      /**< CRC reset value. */
00070 
00071 // Internal Enhanced ShockBurst module state.
00072 typedef enum {
00073     NRF_ESB_STATE_IDLE,                                     /**< Module idle. */
00074     NRF_ESB_STATE_PTX_TX,                                   /**< Module transmitting without acknowledgment. */
00075     NRF_ESB_STATE_PTX_TX_ACK,                               /**< Module transmitting with acknowledgment. */
00076     NRF_ESB_STATE_PTX_RX_ACK,                               /**< Module transmitting with acknowledgment and reception of payload with the acknowledgment response. */
00077     NRF_ESB_STATE_PRX,                                      /**< Module receiving packets without acknowledgment. */
00078     NRF_ESB_STATE_PRX_SEND_ACK,                             /**< Module transmitting acknowledgment in RX mode. */
00079 } nrf_esb_mainstate_t;
00080 
00081 
00082 #define DISABLE_RF_IRQ()      NVIC_DisableIRQ(RADIO_IRQn)
00083 #define ENABLE_RF_IRQ()       NVIC_EnableIRQ(RADIO_IRQn)
00084 
00085 #define _RADIO_SHORTS_COMMON ( RADIO_SHORTS_READY_START_Msk | RADIO_SHORTS_END_DISABLE_Msk | \
00086             RADIO_SHORTS_ADDRESS_RSSISTART_Msk | RADIO_SHORTS_DISABLED_RSSISTOP_Msk )
00087 
00088 #define VERIFY_PAYLOAD_LENGTH(p)                            \
00089 do                                                          \
00090 {                                                           \
00091     if (p->length == 0 ||                                    \
00092        p->length > NRF_ESB_MAX_PAYLOAD_LENGTH ||            \
00093        (m_config_local.protocol == NRF_ESB_PROTOCOL_ESB &&  \
00094         p->length > m_config_local.payload_length))         \
00095     {                                                       \
00096         return NRF_ERROR_INVALID_LENGTH;                    \
00097     }                                                       \
00098 }while (0)
00099 
00100 
00101 /* @brief Structure holding pipe info PID and CRC and acknowledgment payload. */
00102 typedef struct
00103 {
00104     uint16_t    crc;                                      /**< CRC value of the last received packet (Used to detect retransmits). */
00105     uint8_t     pid;                                      /**< Packet ID of the last received packet (Used to detect retransmits). */
00106     bool        ack_payload;                              /**< Flag indicating the state of the transmission of acknowledgment payloads. */
00107 } pipe_info_t;
00108 
00109 
00110 /* @brief  First-in, first-out queue of payloads to be transmitted. */
00111 typedef struct
00112 {
00113     nrf_esb_payload_t * p_payload[NRF_ESB_TX_FIFO_SIZE];  /**< Pointer to the actual queue. */
00114     uint32_t            entry_point;                      /**< Current start of queue. */
00115     uint32_t            exit_point;                       /**< Current end of queue. */
00116     uint32_t            count;                            /**< Current number of elements in the queue. */
00117 } nrf_esb_payload_tx_fifo_t;
00118 
00119 
00120 /* @brief First-in, first-out queue of received payloads. */
00121 typedef struct
00122 {
00123     nrf_esb_payload_t * p_payload[NRF_ESB_RX_FIFO_SIZE];  /**< Pointer to the actual queue. */
00124     uint32_t            entry_point;                      /**< Current start of queue. */
00125     uint32_t            exit_point;                       /**< Current end of queue. */
00126     uint32_t            count;                            /**< Current number of elements in the queue. */
00127 } nrf_esb_payload_rx_fifo_t;
00128 
00129 
00130 /**@brief Enhanced ShockBurst address.
00131  *
00132  * Enhanced ShockBurst addresses consist of a base address and a prefix
00133  *          that is unique for each pipe. See @ref esb_addressing in the ESB user
00134  *          guide for more information.
00135 */
00136 typedef struct
00137 {
00138     uint8_t base_addr_p0[4];        /**< Base address for pipe 0 encoded in big endian. */
00139     uint8_t base_addr_p1[4];        /**< Base address for pipe 1-7 encoded in big endian. */
00140     uint8_t pipe_prefixes[8];       /**< Address prefix for pipe 0 to 7. */
00141     uint8_t num_pipes;              /**< Number of pipes available. */
00142     uint8_t addr_length;            /**< Length of the address including the prefix. */
00143     uint8_t rx_pipes_enabled;       /**< Bitfield for enabled pipes. */
00144     uint8_t rf_channel;             /**< Channel to use (must be between 0 and 100). */
00145 } nrf_esb_address_t;
00146 
00147 
00148 // Module state
00149 static bool                         m_esb_initialized           = false;
00150 static nrf_esb_mainstate_t          m_nrf_esb_mainstate         = NRF_ESB_STATE_IDLE;
00151 static nrf_esb_payload_t          * mp_current_payload;
00152 
00153 static nrf_esb_event_handler_t      m_event_handler;
00154 
00155 // Address parameters
00156 __ALIGN(4) static nrf_esb_address_t m_esb_addr = NRF_ESB_ADDR_DEFAULT;
00157 
00158 // RF parameters
00159 static nrf_esb_config_t             m_config_local;
00160 
00161 // TX FIFO
00162 static nrf_esb_payload_t            m_tx_fifo_payload[NRF_ESB_TX_FIFO_SIZE];
00163 static nrf_esb_payload_tx_fifo_t    m_tx_fifo;
00164 
00165 // RX FIFO
00166 static nrf_esb_payload_t            m_rx_fifo_payload[NRF_ESB_RX_FIFO_SIZE];
00167 static nrf_esb_payload_rx_fifo_t    m_rx_fifo;
00168 
00169 // Payload buffers
00170 static  uint8_t                     m_tx_payload_buffer[NRF_ESB_MAX_PAYLOAD_LENGTH + 2];
00171 static  uint8_t                     m_rx_payload_buffer[NRF_ESB_MAX_PAYLOAD_LENGTH + 2];
00172 
00173 // Run time variables
00174 static volatile uint32_t            m_interrupt_flags = 0;
00175 static uint8_t                      m_pids[NRF_ESB_PIPE_COUNT];
00176 static pipe_info_t                  m_rx_pipe_info[NRF_ESB_PIPE_COUNT];
00177 static volatile uint32_t            m_retransmits_remaining;
00178 static volatile uint32_t            m_last_tx_attempts;
00179 static volatile uint32_t            m_wait_for_ack_timeout_us;
00180 
00181 // nRF52 address workaround enable
00182 #ifdef NRF52
00183 static bool                         m_address_hang_fix_enable = true;
00184 #endif
00185 static uint32_t                     m_radio_shorts_common = _RADIO_SHORTS_COMMON;
00186 
00187 // These function pointers are changed dynamically, depending on protocol configuration and state.
00188 static void (*on_radio_disabled)(void) = 0;
00189 static void (*on_radio_end)(void) = 0;
00190 static void (*update_rf_payload_format)(uint32_t payload_length) = 0;
00191 
00192 
00193 // The following functions are assigned to the function pointers above.
00194 static void on_radio_disabled_tx_noack(void);
00195 static void on_radio_disabled_tx(void);
00196 static void on_radio_disabled_tx_wait_for_ack(void);
00197 static void on_radio_disabled_rx(void);
00198 static void on_radio_disabled_rx_ack(void);
00199 
00200 
00201 #define NRF_ESB_ADDR_UPDATE_MASK_BASE0          (1 << 0)    /*< Mask value to signal updating BASE0 radio address. */
00202 #define NRF_ESB_ADDR_UPDATE_MASK_BASE1          (1 << 1)    /*< Mask value to signal updating BASE1 radio address. */
00203 #define NRF_ESB_ADDR_UPDATE_MASK_PREFIX         (1 << 2)    /*< Mask value to signal updating radio prefixes. */
00204 
00205 
00206 // Function to do bytewise bit-swap on an unsigned 32-bit value
00207 static uint32_t bytewise_bit_swap(uint8_t const * p_inp)
00208 {
00209     uint32_t inp = (*(uint32_t*)p_inp);
00210 #if __CORTEX_M == (0x04U)
00211     return __REV((uint32_t)__RBIT(inp)); //lint -esym(628, __rev) -esym(526, __rev) -esym(628, __rbit) -esym(526, __rbit) */
00212 #else
00213     inp = (inp & 0xF0F0F0F0) >> 4 | (inp & 0x0F0F0F0F) << 4;
00214     inp = (inp & 0xCCCCCCCC) >> 2 | (inp & 0x33333333) << 2;
00215     inp = (inp & 0xAAAAAAAA) >> 1 | (inp & 0x55555555) << 1;
00216     return inp;
00217 #endif
00218 }
00219 
00220 
00221 // Internal function to convert base addresses from nRF24L type addressing to nRF51 type addressing
00222 static uint32_t addr_conv(uint8_t const* p_addr)
00223 {
00224     return __REV(bytewise_bit_swap(p_addr)); //lint -esym(628, __rev) -esym(526, __rev) */
00225 }
00226 
00227 
00228 static ret_code_t apply_address_workarounds()
00229 {
00230 #ifdef NRF52
00231     //  Set up radio parameters.
00232     NRF_RADIO->MODECNF0 = (NRF_RADIO->MODECNF0 & ~RADIO_MODECNF0_RU_Msk) | RADIO_MODECNF0_RU_Default << RADIO_MODECNF0_RU_Pos;
00233 
00234     // Workaround for nRF52832 Rev 1 Errata 102 and nRF52832 Rev 1 Errata 106. This will reduce sensitivity by 3dB.
00235     *((volatile uint32_t *)0x40001774) = (*((volatile uint32_t *)0x40001774) & 0xFFFFFFFE) | 0x01000000;
00236 #endif
00237     return NRF_SUCCESS;
00238 }
00239 
00240 
00241 static void update_rf_payload_format_esb_dpl(uint32_t payload_length)
00242 {
00243 #if (NRF_ESB_MAX_PAYLOAD_LENGTH <= 32)
00244     // Using 6 bits for length
00245     NRF_RADIO->PCNF0 = (0 << RADIO_PCNF0_S0LEN_Pos) |
00246                        (6 << RADIO_PCNF0_LFLEN_Pos) |
00247                        (3 << RADIO_PCNF0_S1LEN_Pos) ;
00248 #else
00249     // Using 8 bits for length
00250     NRF_RADIO->PCNF0 = (0 << RADIO_PCNF0_S0LEN_Pos) |
00251                        (8 << RADIO_PCNF0_LFLEN_Pos) |
00252                        (3 << RADIO_PCNF0_S1LEN_Pos) ;
00253 #endif
00254     NRF_RADIO->PCNF1 = (RADIO_PCNF1_WHITEEN_Disabled    << RADIO_PCNF1_WHITEEN_Pos) |
00255                        (RADIO_PCNF1_ENDIAN_Big          << RADIO_PCNF1_ENDIAN_Pos)  |
00256                        ((m_esb_addr.addr_length - 1)    << RADIO_PCNF1_BALEN_Pos)   |
00257                        (0                               << RADIO_PCNF1_STATLEN_Pos) |
00258                        (NRF_ESB_MAX_PAYLOAD_LENGTH      << RADIO_PCNF1_MAXLEN_Pos);
00259 }
00260 
00261 
00262 static void update_rf_payload_format_esb(uint32_t payload_length)
00263 {
00264     NRF_RADIO->PCNF0 = (1 << RADIO_PCNF0_S0LEN_Pos) |
00265                        (0 << RADIO_PCNF0_LFLEN_Pos) |
00266                        (1 << RADIO_PCNF0_S1LEN_Pos);
00267 
00268     NRF_RADIO->PCNF1 = (RADIO_PCNF1_WHITEEN_Disabled    << RADIO_PCNF1_WHITEEN_Pos) |
00269                        (RADIO_PCNF1_ENDIAN_Big          << RADIO_PCNF1_ENDIAN_Pos)  |
00270                        ((m_esb_addr.addr_length - 1)    << RADIO_PCNF1_BALEN_Pos)   |
00271                        (payload_length                  << RADIO_PCNF1_STATLEN_Pos) |
00272                        (payload_length                  << RADIO_PCNF1_MAXLEN_Pos);
00273 }
00274 
00275 
00276 static void update_radio_addresses(uint8_t update_mask)
00277 {
00278     if ((update_mask & NRF_ESB_ADDR_UPDATE_MASK_BASE0) != 0)
00279     {
00280         NRF_RADIO->BASE0 = addr_conv(m_esb_addr.base_addr_p0);
00281     }
00282 
00283     if ((update_mask & NRF_ESB_ADDR_UPDATE_MASK_BASE1) != 0)
00284     {
00285         NRF_RADIO->BASE1 = addr_conv(m_esb_addr.base_addr_p1);
00286     }
00287 
00288     if ((update_mask & NRF_ESB_ADDR_UPDATE_MASK_PREFIX) != 0)
00289     {
00290         NRF_RADIO->PREFIX0 = bytewise_bit_swap(&m_esb_addr.pipe_prefixes[0]);
00291         NRF_RADIO->PREFIX1 = bytewise_bit_swap(&m_esb_addr.pipe_prefixes[4]);
00292     }
00293 }
00294 
00295 
00296 static void update_radio_tx_power()
00297 {
00298     NRF_RADIO->TXPOWER = m_config_local.tx_output_power << RADIO_TXPOWER_TXPOWER_Pos;
00299 }
00300 
00301 
00302 static bool update_radio_bitrate()
00303 {
00304     NRF_RADIO->MODE = m_config_local.bitrate << RADIO_MODE_MODE_Pos;
00305 
00306     switch (m_config_local.bitrate)
00307     {
00308         case NRF_ESB_BITRATE_2MBPS:
00309 #ifdef NRF52
00310         case NRF_ESB_BITRATE_2MBPS_BLE:
00311 #endif
00312             m_wait_for_ack_timeout_us = RX_WAIT_FOR_ACK_TIMEOUT_US_2MBPS;
00313             break;
00314 
00315         case NRF_ESB_BITRATE_1MBPS:
00316             m_wait_for_ack_timeout_us = RX_WAIT_FOR_ACK_TIMEOUT_US_1MBPS;
00317             break;
00318 
00319 #ifdef NRF51
00320         case NRF_ESB_BITRATE_250KBPS:
00321             m_wait_for_ack_timeout_us = RX_WAIT_FOR_ACK_TIMEOUT_US_250KBPS;
00322             break;
00323 #endif
00324         
00325         case NRF_ESB_BITRATE_1MBPS_BLE:
00326             m_wait_for_ack_timeout_us = RX_WAIT_FOR_ACK_TIMEOUT_US_1MBPS_BLE;
00327             break;
00328 
00329         default:
00330             // Should not be reached
00331             return false;
00332     }
00333     return true;
00334 }
00335 
00336 
00337 static bool update_radio_protocol()
00338 {
00339     switch (m_config_local.protocol)
00340     {
00341         case NRF_ESB_PROTOCOL_ESB_DPL:
00342             update_rf_payload_format = update_rf_payload_format_esb_dpl;
00343             break;
00344 
00345         case NRF_ESB_PROTOCOL_ESB:
00346             update_rf_payload_format = update_rf_payload_format_esb;
00347             break;
00348 
00349         default:
00350             // Should not be reached
00351             return false;
00352     }
00353     return true;
00354 }
00355 
00356 
00357 static bool update_radio_crc()
00358 {
00359     switch(m_config_local.crc)
00360     {
00361         case NRF_ESB_CRC_16BIT:
00362             NRF_RADIO->CRCINIT = 0xFFFFUL;      // Initial value
00363             NRF_RADIO->CRCPOLY = 0x11021UL;     // CRC poly: x^16+x^12^x^5+1
00364             break;
00365         
00366         case NRF_ESB_CRC_8BIT:
00367             NRF_RADIO->CRCINIT = 0xFFUL;        // Initial value
00368             NRF_RADIO->CRCPOLY = 0x107UL;       // CRC poly: x^8+x^2^x^1+1
00369             break;
00370         
00371         case NRF_ESB_CRC_OFF:
00372             break;
00373         
00374         default:
00375             return false;
00376     }
00377     NRF_RADIO->CRCCNF = m_config_local.crc << RADIO_CRCCNF_LEN_Pos;
00378     return true;
00379 }
00380 
00381 
00382 static bool update_radio_parameters()
00383 {
00384     bool params_valid = true;
00385     update_radio_tx_power();
00386     params_valid &= update_radio_bitrate();
00387     params_valid &= update_radio_protocol();
00388     params_valid &= update_radio_crc();
00389     update_rf_payload_format(m_config_local.payload_length);
00390     params_valid &= (m_config_local.retransmit_delay >= NRF_ESB_RETRANSMIT_DELAY_MIN);
00391     return params_valid;
00392 }
00393 
00394 
00395 static void reset_fifos()
00396 {
00397     m_tx_fifo.entry_point = 0;
00398     m_tx_fifo.exit_point  = 0;
00399     m_tx_fifo.count       = 0;
00400 
00401     m_rx_fifo.entry_point = 0;
00402     m_rx_fifo.exit_point  = 0;
00403     m_rx_fifo.count       = 0;
00404 }
00405 
00406 
00407 static void initialize_fifos()
00408 {
00409     reset_fifos();
00410 
00411     for (int i = 0; i < NRF_ESB_TX_FIFO_SIZE; i++)
00412     {
00413         m_tx_fifo.p_payload[i] = &m_tx_fifo_payload[i];
00414     }
00415 
00416     for (int i = 0; i < NRF_ESB_RX_FIFO_SIZE; i++)
00417     {
00418         m_rx_fifo.p_payload[i] = &m_rx_fifo_payload[i];
00419     }
00420 }
00421 
00422 
00423 static void tx_fifo_remove_last()
00424 {
00425     if (m_tx_fifo.count > 0)
00426     {
00427         DISABLE_RF_IRQ();
00428 
00429         m_tx_fifo.count--;
00430         if (++m_tx_fifo.exit_point >= NRF_ESB_TX_FIFO_SIZE)
00431         {
00432             m_tx_fifo.exit_point = 0;
00433         }
00434 
00435         ENABLE_RF_IRQ();
00436     }
00437 }
00438 
00439 /** @brief  Function to push the content of the rx_buffer to the RX FIFO.
00440  *
00441  *  The module will point the register NRF_RADIO->PACKETPTR to a buffer for receiving packets.
00442  *  After receiving a packet the module will call this function to copy the received data to
00443  *  the RX FIFO.
00444  *
00445  *  @param  pipe Pipe number to set for the packet.
00446  *  @param  pid  Packet ID.
00447  *
00448  *  @retval true   Operation successful.
00449  *  @retval false  Operation failed.
00450  */
00451 static bool rx_fifo_push_rfbuf(uint8_t pipe, uint8_t pid)
00452 {
00453     if (m_rx_fifo.count < NRF_ESB_RX_FIFO_SIZE)
00454     {
00455         if (m_config_local.protocol == NRF_ESB_PROTOCOL_ESB_DPL)
00456         {
00457             if (m_rx_payload_buffer[0] > NRF_ESB_MAX_PAYLOAD_LENGTH)
00458             {
00459                 return false;
00460             }
00461 
00462             m_rx_fifo.p_payload[m_rx_fifo.entry_point]->length = m_rx_payload_buffer[0];
00463         }
00464         else if (m_config_local.mode == NRF_ESB_MODE_PTX)
00465         {
00466             // Received packet is an acknowledgment
00467             m_rx_fifo.p_payload[m_rx_fifo.entry_point]->length = 0;
00468         }
00469         else
00470         {
00471             m_rx_fifo.p_payload[m_rx_fifo.entry_point]->length = m_config_local.payload_length;
00472         }
00473 
00474         memcpy(m_rx_fifo.p_payload[m_rx_fifo.entry_point]->data, &m_rx_payload_buffer[2],
00475                m_rx_fifo.p_payload[m_rx_fifo.entry_point]->length);
00476 
00477         m_rx_fifo.p_payload[m_rx_fifo.entry_point]->pipe  = pipe;
00478         m_rx_fifo.p_payload[m_rx_fifo.entry_point]->rssi  = NRF_RADIO->RSSISAMPLE;
00479         m_rx_fifo.p_payload[m_rx_fifo.entry_point]->pid   = pid;
00480         m_rx_fifo.p_payload[m_rx_fifo.entry_point]->noack = !(m_rx_payload_buffer[1] & 0x01);
00481         if (++m_rx_fifo.entry_point >= NRF_ESB_RX_FIFO_SIZE)
00482         {
00483             m_rx_fifo.entry_point = 0;
00484         }
00485         m_rx_fifo.count++;
00486 
00487         return true;
00488     }
00489 
00490     return false;
00491 }
00492 
00493 
00494 static void sys_timer_init()
00495 {
00496     // Configure the system timer with a 1 MHz base frequency
00497     NRF_ESB_SYS_TIMER->PRESCALER = 4;
00498     NRF_ESB_SYS_TIMER->BITMODE   = TIMER_BITMODE_BITMODE_16Bit;
00499     NRF_ESB_SYS_TIMER->SHORTS    = TIMER_SHORTS_COMPARE1_CLEAR_Msk | TIMER_SHORTS_COMPARE1_STOP_Msk;
00500 }
00501 
00502 
00503 static void ppi_init()
00504 {
00505     NRF_PPI->CH[NRF_ESB_PPI_TIMER_START].EEP = (uint32_t)&NRF_RADIO->EVENTS_READY;
00506     NRF_PPI->CH[NRF_ESB_PPI_TIMER_START].TEP = (uint32_t)&NRF_ESB_SYS_TIMER->TASKS_START;
00507 
00508     NRF_PPI->CH[NRF_ESB_PPI_TIMER_STOP].EEP  = (uint32_t)&NRF_RADIO->EVENTS_ADDRESS;
00509     NRF_PPI->CH[NRF_ESB_PPI_TIMER_STOP].TEP  = (uint32_t)&NRF_ESB_SYS_TIMER->TASKS_STOP;
00510 
00511     NRF_PPI->CH[NRF_ESB_PPI_RX_TIMEOUT].EEP  = (uint32_t)&NRF_ESB_SYS_TIMER->EVENTS_COMPARE[0];
00512     NRF_PPI->CH[NRF_ESB_PPI_RX_TIMEOUT].TEP  = (uint32_t)&NRF_RADIO->TASKS_DISABLE;
00513 
00514     NRF_PPI->CH[NRF_ESB_PPI_TX_START].EEP    = (uint32_t)&NRF_ESB_SYS_TIMER->EVENTS_COMPARE[1];
00515     NRF_PPI->CH[NRF_ESB_PPI_TX_START].TEP    = (uint32_t)&NRF_RADIO->TASKS_TXEN;
00516 }
00517 
00518 
00519 static void start_tx_transaction()
00520 {
00521     bool ack;
00522 
00523     m_last_tx_attempts = 1;
00524     // Prepare the payload
00525     mp_current_payload = m_tx_fifo.p_payload[m_tx_fifo.exit_point];
00526 
00527 
00528     switch (m_config_local.protocol)
00529     {
00530         case NRF_ESB_PROTOCOL_ESB:
00531             update_rf_payload_format(mp_current_payload->length);
00532             m_tx_payload_buffer[0] = mp_current_payload->pid;
00533             m_tx_payload_buffer[1] = 0;
00534             memcpy(&m_tx_payload_buffer[2], mp_current_payload->data, mp_current_payload->length);
00535 
00536             NRF_RADIO->SHORTS   = m_radio_shorts_common | RADIO_SHORTS_DISABLED_RXEN_Msk;
00537             NRF_RADIO->INTENSET = RADIO_INTENSET_DISABLED_Msk | RADIO_INTENSET_READY_Msk;
00538 
00539             // Configure the retransmit counter
00540             m_retransmits_remaining = m_config_local.retransmit_count;
00541             on_radio_disabled = on_radio_disabled_tx;
00542             m_nrf_esb_mainstate = NRF_ESB_STATE_PTX_TX_ACK;
00543             break;
00544 
00545         case NRF_ESB_PROTOCOL_ESB_DPL:
00546             ack = !mp_current_payload->noack || !m_config_local.selective_auto_ack;
00547             m_tx_payload_buffer[0] = mp_current_payload->length;
00548             m_tx_payload_buffer[1] = mp_current_payload->pid << 1;
00549             m_tx_payload_buffer[1] |= mp_current_payload->noack ? 0x00 : 0x01;
00550             memcpy(&m_tx_payload_buffer[2], mp_current_payload->data, mp_current_payload->length);
00551 
00552             // Handling ack if noack is set to false or if selective auto ack is turned off
00553             if (ack)
00554             {
00555                 NRF_RADIO->SHORTS   = m_radio_shorts_common | RADIO_SHORTS_DISABLED_RXEN_Msk;
00556                 NRF_RADIO->INTENSET = RADIO_INTENSET_DISABLED_Msk | RADIO_INTENSET_READY_Msk;
00557 
00558                 // Configure the retransmit counter
00559                 m_retransmits_remaining = m_config_local.retransmit_count;
00560                 on_radio_disabled = on_radio_disabled_tx;
00561                 m_nrf_esb_mainstate = NRF_ESB_STATE_PTX_TX_ACK;
00562             }
00563             else
00564             {
00565                 NRF_RADIO->SHORTS   = m_radio_shorts_common;
00566                 NRF_RADIO->INTENSET = RADIO_INTENSET_DISABLED_Msk;
00567                 on_radio_disabled   = on_radio_disabled_tx_noack;
00568                 m_nrf_esb_mainstate = NRF_ESB_STATE_PTX_TX;
00569             }
00570             break;
00571 
00572         default:
00573             // Should not be reached
00574             break;
00575     }
00576 
00577     NRF_RADIO->TXADDRESS    = mp_current_payload->pipe;
00578     NRF_RADIO->RXADDRESSES  = 1 << mp_current_payload->pipe;
00579 
00580     NRF_RADIO->FREQUENCY    = m_esb_addr.rf_channel;
00581     NRF_RADIO->PACKETPTR    = (uint32_t)m_tx_payload_buffer;
00582 
00583     NVIC_ClearPendingIRQ(RADIO_IRQn);
00584     NVIC_EnableIRQ(RADIO_IRQn);
00585 
00586     NRF_RADIO->EVENTS_ADDRESS = 0;
00587     NRF_RADIO->EVENTS_PAYLOAD = 0;
00588     NRF_RADIO->EVENTS_DISABLED = 0;
00589 
00590     DEBUG_PIN_SET(DEBUGPIN4);
00591     NRF_RADIO->TASKS_TXEN  = 1;
00592 }
00593 
00594 
00595 static void on_radio_disabled_tx_noack()
00596 {
00597     m_interrupt_flags |= NRF_ESB_INT_TX_SUCCESS_MSK;
00598     tx_fifo_remove_last();
00599 
00600     if (m_tx_fifo.count == 0)
00601     {
00602         m_nrf_esb_mainstate = NRF_ESB_STATE_IDLE;
00603         NVIC_SetPendingIRQ(ESB_EVT_IRQ);
00604     }
00605     else
00606     {
00607         NVIC_SetPendingIRQ(ESB_EVT_IRQ);
00608         start_tx_transaction();
00609     }
00610 }
00611 
00612 
00613 static void on_radio_disabled_tx()
00614 {
00615     // Remove the DISABLED -> RXEN shortcut, to make sure the radio stays
00616     // disabled after the RX window
00617     NRF_RADIO->SHORTS           = m_radio_shorts_common;
00618 
00619     // Make sure the timer is started the next time the radio is ready,
00620     // and that it will disable the radio automatically if no packet is
00621     // received by the time defined in m_wait_for_ack_timeout_us
00622     NRF_ESB_SYS_TIMER->CC[0]    = m_wait_for_ack_timeout_us;
00623     NRF_ESB_SYS_TIMER->CC[1]    = m_config_local.retransmit_delay - 130;
00624     NRF_ESB_SYS_TIMER->TASKS_CLEAR = 1;
00625     NRF_ESB_SYS_TIMER->EVENTS_COMPARE[0] = 0;
00626     NRF_ESB_SYS_TIMER->EVENTS_COMPARE[1] = 0;
00627 
00628     NRF_PPI->CHENSET            = (1 << NRF_ESB_PPI_TIMER_START) |
00629                                   (1 << NRF_ESB_PPI_RX_TIMEOUT) |
00630                                   (1 << NRF_ESB_PPI_TIMER_STOP);
00631     NRF_PPI->CHENCLR            = (1 << NRF_ESB_PPI_TX_START);
00632     NRF_RADIO->EVENTS_END       = 0;
00633 
00634     if (m_config_local.protocol == NRF_ESB_PROTOCOL_ESB)
00635     {
00636         update_rf_payload_format(0);
00637     }
00638 
00639     NRF_RADIO->PACKETPTR        = (uint32_t)m_rx_payload_buffer;
00640     on_radio_disabled           = on_radio_disabled_tx_wait_for_ack;
00641     m_nrf_esb_mainstate         = NRF_ESB_STATE_PTX_RX_ACK;
00642 }
00643 
00644 
00645 static void on_radio_disabled_tx_wait_for_ack()
00646 {
00647     // This marks the completion of a TX_RX sequence (TX with ACK)
00648 
00649     // Make sure the timer will not deactivate the radio if a packet is received
00650     NRF_PPI->CHENCLR = (1 << NRF_ESB_PPI_TIMER_START) |
00651                        (1 << NRF_ESB_PPI_RX_TIMEOUT)  |
00652                        (1 << NRF_ESB_PPI_TIMER_STOP);
00653 
00654     // If the radio has received a packet and the CRC status is OK
00655     if (NRF_RADIO->EVENTS_END && NRF_RADIO->CRCSTATUS != 0)
00656     {
00657         NRF_ESB_SYS_TIMER->TASKS_STOP = 1;
00658         NRF_PPI->CHENCLR = (1 << NRF_ESB_PPI_TX_START);
00659         m_interrupt_flags |= NRF_ESB_INT_TX_SUCCESS_MSK;
00660         m_last_tx_attempts = m_config_local.retransmit_count - m_retransmits_remaining + 1;
00661 
00662         tx_fifo_remove_last();
00663 
00664         if (m_config_local.protocol != NRF_ESB_PROTOCOL_ESB && m_rx_payload_buffer[0] > 0)
00665         {
00666             if (rx_fifo_push_rfbuf((uint8_t)NRF_RADIO->TXADDRESS, m_rx_payload_buffer[1] >> 1))
00667             {
00668                 m_interrupt_flags |= NRF_ESB_INT_RX_DATA_RECEIVED_MSK;
00669             }
00670         }
00671 
00672         if ((m_tx_fifo.count == 0) || (m_config_local.tx_mode == NRF_ESB_TXMODE_MANUAL))
00673         {
00674             m_nrf_esb_mainstate = NRF_ESB_STATE_IDLE;
00675             NVIC_SetPendingIRQ(ESB_EVT_IRQ);
00676         }
00677         else
00678         {
00679             NVIC_SetPendingIRQ(ESB_EVT_IRQ);
00680             start_tx_transaction();
00681         }
00682     }
00683     else
00684     {
00685         if (m_retransmits_remaining-- == 0)
00686         {
00687             NRF_ESB_SYS_TIMER->TASKS_STOP = 1;
00688             NRF_PPI->CHENCLR = (1 << NRF_ESB_PPI_TX_START);
00689             // All retransmits are expended, and the TX operation is suspended
00690             m_last_tx_attempts = m_config_local.retransmit_count + 1;
00691             m_interrupt_flags |= NRF_ESB_INT_TX_FAILED_MSK;
00692 
00693             m_nrf_esb_mainstate = NRF_ESB_STATE_IDLE;
00694             NVIC_SetPendingIRQ(ESB_EVT_IRQ);
00695         }
00696         else
00697         {
00698             // There are still more retransmits left, TX mode should be
00699             // entered again as soon as the system timer reaches CC[1].
00700             NRF_RADIO->SHORTS = m_radio_shorts_common | RADIO_SHORTS_DISABLED_RXEN_Msk;
00701             update_rf_payload_format(mp_current_payload->length);
00702             NRF_RADIO->PACKETPTR = (uint32_t)m_tx_payload_buffer;
00703             on_radio_disabled = on_radio_disabled_tx;
00704             m_nrf_esb_mainstate = NRF_ESB_STATE_PTX_TX_ACK;
00705             NRF_ESB_SYS_TIMER->TASKS_START = 1;
00706             NRF_PPI->CHENSET = (1 << NRF_ESB_PPI_TX_START);
00707             if (NRF_ESB_SYS_TIMER->EVENTS_COMPARE[1])
00708             {
00709                 NRF_RADIO->TASKS_TXEN = 1;
00710             }
00711         }
00712     }
00713 }
00714 
00715 static void clear_events_restart_rx(void)
00716 {
00717     NRF_RADIO->SHORTS = m_radio_shorts_common;
00718     update_rf_payload_format(m_config_local.payload_length);
00719     NRF_RADIO->PACKETPTR = (uint32_t)m_rx_payload_buffer;
00720     NRF_RADIO->EVENTS_DISABLED = 0;
00721     NRF_RADIO->TASKS_DISABLE = 1;
00722 
00723     while (NRF_RADIO->EVENTS_DISABLED == 0);
00724 
00725     NRF_RADIO->EVENTS_DISABLED = 0;
00726     NRF_RADIO->SHORTS = m_radio_shorts_common | RADIO_SHORTS_DISABLED_TXEN_Msk;
00727 
00728     NRF_RADIO->TASKS_RXEN = 1;
00729 }
00730 
00731 static void on_radio_disabled_rx(void)
00732 {
00733     bool            ack                = false;
00734     bool            retransmit_payload = false;
00735     bool            send_rx_event      = true;
00736     pipe_info_t *   p_pipe_info;
00737 
00738     if (NRF_RADIO->CRCSTATUS == 0)
00739     {
00740         clear_events_restart_rx();
00741         return;
00742     }
00743 
00744     if (m_rx_fifo.count >= NRF_ESB_RX_FIFO_SIZE)
00745     {
00746         clear_events_restart_rx();
00747         return;
00748     }
00749 
00750     p_pipe_info = &m_rx_pipe_info[NRF_RADIO->RXMATCH];
00751     if (NRF_RADIO->RXCRC             == p_pipe_info->crc &&
00752         (m_rx_payload_buffer[1] >> 1) == p_pipe_info->pid
00753        )
00754     {
00755         retransmit_payload = true;
00756         send_rx_event = false;
00757     }
00758 
00759     p_pipe_info->pid = m_rx_payload_buffer[1] >> 1;
00760     p_pipe_info->crc = NRF_RADIO->RXCRC;
00761 
00762     if ((m_config_local.selective_auto_ack == false) || ((m_rx_payload_buffer[1] & 0x01) == 1))
00763     {
00764         ack = true;
00765     }
00766 
00767     if (ack)
00768     {
00769         NRF_RADIO->SHORTS = m_radio_shorts_common | RADIO_SHORTS_DISABLED_RXEN_Msk;
00770 
00771         switch (m_config_local.protocol)
00772         {
00773             case NRF_ESB_PROTOCOL_ESB_DPL:
00774                 {
00775                     if (m_tx_fifo.count > 0 &&
00776                         (m_tx_fifo.p_payload[m_tx_fifo.exit_point]->pipe == NRF_RADIO->RXMATCH)
00777                        )
00778                     {
00779                         // Pipe stays in ACK with payload until TX FIFO is empty
00780                         // Do not report TX success on first ack payload or retransmit
00781                         if (p_pipe_info->ack_payload == true && !retransmit_payload)
00782                         {
00783                             if (++m_tx_fifo.exit_point >= NRF_ESB_TX_FIFO_SIZE)
00784                             {
00785                                 m_tx_fifo.exit_point = 0;
00786                             }
00787 
00788                             m_tx_fifo.count--;
00789 
00790                             // ACK payloads also require TX_DS
00791                             // (page 40 of the 'nRF24LE1_Product_Specification_rev1_6.pdf').
00792                             m_interrupt_flags |= NRF_ESB_INT_TX_SUCCESS_MSK;
00793                         }
00794 
00795                         p_pipe_info->ack_payload = true;
00796 
00797                         mp_current_payload = m_tx_fifo.p_payload[m_tx_fifo.exit_point];
00798 
00799                         update_rf_payload_format(mp_current_payload->length);
00800                         m_tx_payload_buffer[0] = mp_current_payload->length;
00801                         memcpy(&m_tx_payload_buffer[2],
00802                                mp_current_payload->data,
00803                                mp_current_payload->length);
00804                     }
00805                     else
00806                     {
00807                         p_pipe_info->ack_payload = false;
00808                         update_rf_payload_format(0);
00809                         m_tx_payload_buffer[0] = 0;
00810                     }
00811 
00812                     m_tx_payload_buffer[1] = m_rx_payload_buffer[1];
00813                 }
00814                 break;
00815 
00816             case NRF_ESB_PROTOCOL_ESB:
00817                 {
00818                     update_rf_payload_format(0);
00819                     m_tx_payload_buffer[0] = m_rx_payload_buffer[0];
00820                     m_tx_payload_buffer[1] = 0;
00821                 }
00822                 break;
00823         }
00824 
00825         m_nrf_esb_mainstate = NRF_ESB_STATE_PRX_SEND_ACK;
00826         NRF_RADIO->TXADDRESS = NRF_RADIO->RXMATCH;
00827         NRF_RADIO->PACKETPTR = (uint32_t)m_tx_payload_buffer;
00828         on_radio_disabled = on_radio_disabled_rx_ack;
00829     }
00830     else
00831     {
00832         clear_events_restart_rx();
00833     }
00834 
00835     if (send_rx_event)
00836     {
00837         // Push the new packet to the RX buffer and trigger a received event if the operation was
00838         // successful.
00839         if (rx_fifo_push_rfbuf(NRF_RADIO->RXMATCH, p_pipe_info->pid))
00840         {
00841             m_interrupt_flags |= NRF_ESB_INT_RX_DATA_RECEIVED_MSK;
00842             NVIC_SetPendingIRQ(ESB_EVT_IRQ);
00843         }
00844     }
00845 }
00846 
00847 
00848 static void on_radio_disabled_rx_ack(void)
00849 {
00850     NRF_RADIO->SHORTS = m_radio_shorts_common | RADIO_SHORTS_DISABLED_TXEN_Msk;
00851     update_rf_payload_format(m_config_local.payload_length);
00852 
00853     NRF_RADIO->PACKETPTR = (uint32_t)m_rx_payload_buffer;
00854     on_radio_disabled = on_radio_disabled_rx;
00855 
00856     m_nrf_esb_mainstate = NRF_ESB_STATE_PRX;
00857 }
00858 
00859 
00860 /**@brief Function for clearing pending interrupts.
00861  *
00862  * @param[in,out]   p_interrupts        Pointer to the value that holds the current interrupts.
00863  *
00864  * @retval  NRF_SUCCESS                     If the interrupts were cleared successfully.
00865  * @retval  NRF_ERROR_NULL                  If the required parameter was NULL.
00866  * @retval  NRF_INVALID_STATE               If the module is not initialized.
00867  */
00868 static uint32_t nrf_esb_get_clear_interrupts(uint32_t * p_interrupts)
00869 {
00870     VERIFY_TRUE(m_esb_initialized, NRF_ERROR_INVALID_STATE);
00871     VERIFY_PARAM_NOT_NULL(p_interrupts);
00872 
00873     DISABLE_RF_IRQ();
00874 
00875     *p_interrupts = m_interrupt_flags;
00876     m_interrupt_flags = 0;
00877 
00878     ENABLE_RF_IRQ();
00879 
00880     return NRF_SUCCESS;
00881 }
00882 
00883 
00884 /*
00885 void RADIO_IRQHandler()
00886 {
00887     if (NRF_RADIO->EVENTS_READY && (NRF_RADIO->INTENSET & RADIO_INTENSET_READY_Msk))
00888     {
00889         NRF_RADIO->EVENTS_READY = 0;
00890         DEBUG_PIN_SET(DEBUGPIN1);
00891     }
00892 
00893     if (NRF_RADIO->EVENTS_END && (NRF_RADIO->INTENSET & RADIO_INTENSET_END_Msk))
00894     {
00895         NRF_RADIO->EVENTS_END = 0;
00896         DEBUG_PIN_SET(DEBUGPIN2);
00897 
00898         // Call the correct on_radio_end function, depending on the current protocol state
00899         if (on_radio_end)
00900         {
00901             on_radio_end();
00902         }
00903     }
00904 
00905     if (NRF_RADIO->EVENTS_DISABLED && (NRF_RADIO->INTENSET & RADIO_INTENSET_DISABLED_Msk))
00906     {
00907         NRF_RADIO->EVENTS_DISABLED = 0;
00908         DEBUG_PIN_SET(DEBUGPIN3);
00909 
00910         // Call the correct on_radio_disable function, depending on the current protocol state
00911         if (on_radio_disabled)
00912         {
00913             on_radio_disabled();
00914         }
00915     }
00916 
00917     DEBUG_PIN_CLR(DEBUGPIN1);
00918     DEBUG_PIN_CLR(DEBUGPIN2);
00919     DEBUG_PIN_CLR(DEBUGPIN3);
00920     DEBUG_PIN_CLR(DEBUGPIN4);
00921 } */
00922 
00923 
00924 uint32_t nrf_esb_init(nrf_esb_config_t const * p_config)
00925 {
00926     uint32_t err_code;
00927 
00928     VERIFY_PARAM_NOT_NULL(p_config);
00929 
00930     if (m_esb_initialized)
00931     {
00932         err_code = nrf_esb_disable();
00933         if (err_code != NRF_SUCCESS)
00934         {
00935             return err_code;
00936         }
00937     }
00938 
00939     m_event_handler = p_config->event_handler;
00940 
00941     memcpy(&m_config_local, p_config, sizeof(nrf_esb_config_t));
00942     
00943     m_interrupt_flags    = 0;
00944 
00945     memset(m_rx_pipe_info, 0, sizeof(m_rx_pipe_info));
00946     memset(m_pids, 0, sizeof(m_pids));
00947 
00948     VERIFY_TRUE(update_radio_parameters(), NRF_ERROR_INVALID_PARAM);
00949 
00950     // Configure radio address registers according to ESB default values
00951     NRF_RADIO->BASE0   = 0xE7E7E7E7;
00952     NRF_RADIO->BASE1   = 0x43434343;
00953     NRF_RADIO->PREFIX0 = 0x23C343E7;
00954     NRF_RADIO->PREFIX1 = 0x13E363A3;
00955     
00956     initialize_fifos();
00957 
00958     sys_timer_init();
00959 
00960     ppi_init();
00961 
00962     NVIC_SetPriority(RADIO_IRQn, m_config_local.radio_irq_priority & ESB_IRQ_PRIORITY_MSK);
00963     NVIC_SetPriority(ESB_EVT_IRQ, m_config_local.event_irq_priority & ESB_IRQ_PRIORITY_MSK);
00964     NVIC_EnableIRQ(ESB_EVT_IRQ);
00965 
00966 #ifdef NRF52
00967     if(m_address_hang_fix_enable)
00968     {
00969         // Setup a timeout timer to start on an ADDRESS match, and stop on a BCMATCH event.
00970         // If the BCMATCH event never occurs the CC[0] event will fire, and the timer interrupt will disable the radio to recover.
00971         m_radio_shorts_common |= RADIO_SHORTS_ADDRESS_BCSTART_Msk;
00972         NRF_RADIO->BCC = 2;
00973         NRF_ESB_BUGFIX_TIMER->BITMODE = TIMER_BITMODE_BITMODE_32Bit << TIMER_BITMODE_BITMODE_Pos;
00974         NRF_ESB_BUGFIX_TIMER->PRESCALER = 4;
00975         NRF_ESB_BUGFIX_TIMER->CC[0] = 5;
00976         NRF_ESB_BUGFIX_TIMER->SHORTS = TIMER_SHORTS_COMPARE0_STOP_Msk | TIMER_SHORTS_COMPARE0_CLEAR_Msk;
00977         NRF_ESB_BUGFIX_TIMER->MODE = TIMER_MODE_MODE_Timer << TIMER_MODE_MODE_Pos;
00978         NRF_ESB_BUGFIX_TIMER->INTENSET = TIMER_INTENSET_COMPARE0_Msk;
00979         NRF_ESB_BUGFIX_TIMER->TASKS_CLEAR = 1;
00980         NVIC_SetPriority(NRF_ESB_BUGFIX_TIMER_IRQn, 5);
00981         NVIC_EnableIRQ(NRF_ESB_BUGFIX_TIMER_IRQn);
00982 
00983         NRF_PPI->CH[NRF_ESB_PPI_BUGFIX1].EEP = (uint32_t)&NRF_RADIO->EVENTS_ADDRESS;
00984         NRF_PPI->CH[NRF_ESB_PPI_BUGFIX1].TEP = (uint32_t)&NRF_ESB_BUGFIX_TIMER->TASKS_START;
00985 
00986         NRF_PPI->CH[NRF_ESB_PPI_BUGFIX2].EEP = (uint32_t)&NRF_RADIO->EVENTS_BCMATCH;
00987         NRF_PPI->CH[NRF_ESB_PPI_BUGFIX2].TEP = (uint32_t)&NRF_ESB_BUGFIX_TIMER->TASKS_STOP;
00988 
00989         NRF_PPI->CH[NRF_ESB_PPI_BUGFIX3].EEP = (uint32_t)&NRF_RADIO->EVENTS_BCMATCH;
00990         NRF_PPI->CH[NRF_ESB_PPI_BUGFIX3].TEP = (uint32_t)&NRF_ESB_BUGFIX_TIMER->TASKS_CLEAR;
00991 
00992         NRF_PPI->CHENSET = (1 << NRF_ESB_PPI_BUGFIX1) | (1 << NRF_ESB_PPI_BUGFIX2) | (1 << NRF_ESB_PPI_BUGFIX3);
00993     }
00994 #endif
00995 
00996     m_nrf_esb_mainstate = NRF_ESB_STATE_IDLE;
00997     m_esb_initialized = true;
00998 
00999     return NRF_SUCCESS;
01000 }
01001 
01002 
01003 uint32_t nrf_esb_suspend(void)
01004 {
01005     VERIFY_TRUE(m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE, NRF_ERROR_BUSY);
01006 
01007     // Clear PPI
01008     NRF_PPI->CHENCLR = (1 << NRF_ESB_PPI_TIMER_START) |
01009                        (1 << NRF_ESB_PPI_TIMER_STOP)  |
01010                        (1 << NRF_ESB_PPI_RX_TIMEOUT)  |
01011                        (1 << NRF_ESB_PPI_TX_START);
01012 
01013     m_nrf_esb_mainstate = NRF_ESB_STATE_IDLE;
01014 
01015     return NRF_SUCCESS;
01016 }
01017 
01018 
01019 uint32_t nrf_esb_disable(void)
01020 {
01021     // Clear PPI
01022     NRF_PPI->CHENCLR = (1 << NRF_ESB_PPI_TIMER_START) |
01023                        (1 << NRF_ESB_PPI_TIMER_STOP)  |
01024                        (1 << NRF_ESB_PPI_RX_TIMEOUT)  |
01025                        (1 << NRF_ESB_PPI_TX_START);
01026 
01027     m_nrf_esb_mainstate = NRF_ESB_STATE_IDLE;
01028 
01029     reset_fifos();
01030 
01031     memset(m_rx_pipe_info, 0, sizeof(m_rx_pipe_info));
01032     memset(m_pids, 0, sizeof(m_pids));
01033 
01034     // Disable the radio
01035     NVIC_DisableIRQ(ESB_EVT_IRQ);
01036     NRF_RADIO->SHORTS = RADIO_SHORTS_READY_START_Enabled << RADIO_SHORTS_READY_START_Pos |
01037                         RADIO_SHORTS_END_DISABLE_Enabled << RADIO_SHORTS_END_DISABLE_Pos;
01038 
01039     return NRF_SUCCESS;
01040 }
01041 
01042 
01043 bool nrf_esb_is_idle(void)
01044 {
01045     return m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE;
01046 }
01047 
01048 
01049 void ESB_EVT_IRQHandler(void)
01050 {
01051     ret_code_t      err_code;
01052     uint32_t        interrupts;
01053     nrf_esb_evt_t   event;
01054 
01055     event.tx_attempts = m_last_tx_attempts;
01056 
01057     err_code = nrf_esb_get_clear_interrupts(&interrupts);
01058     if (err_code == NRF_SUCCESS && m_event_handler != 0)
01059     {
01060         if (interrupts & NRF_ESB_INT_TX_SUCCESS_MSK)
01061         {
01062             event.evt_id = NRF_ESB_EVENT_TX_SUCCESS;
01063             m_event_handler(&event);
01064         }
01065         if (interrupts & NRF_ESB_INT_TX_FAILED_MSK)
01066         {
01067             event.evt_id = NRF_ESB_EVENT_TX_FAILED;
01068             m_event_handler(&event);
01069         }
01070         if (interrupts & NRF_ESB_INT_RX_DATA_RECEIVED_MSK)
01071         {
01072             event.evt_id = NRF_ESB_EVENT_RX_RECEIVED;
01073             m_event_handler(&event);
01074         }
01075     }
01076 }
01077 
01078 uint32_t nrf_esb_write_payload(nrf_esb_payload_t const * p_payload)
01079 {
01080     VERIFY_TRUE(m_esb_initialized, NRF_ERROR_INVALID_STATE);
01081     VERIFY_PARAM_NOT_NULL(p_payload);
01082     VERIFY_PAYLOAD_LENGTH(p_payload);
01083     VERIFY_FALSE(m_tx_fifo.count >= NRF_ESB_TX_FIFO_SIZE, NRF_ERROR_NO_MEM);
01084     VERIFY_TRUE(p_payload->pipe < NRF_ESB_PIPE_COUNT, NRF_ERROR_INVALID_PARAM);
01085 
01086     DISABLE_RF_IRQ();
01087 
01088     memcpy(m_tx_fifo.p_payload[m_tx_fifo.entry_point], p_payload, sizeof(nrf_esb_payload_t));
01089 
01090     m_pids[p_payload->pipe] = (m_pids[p_payload->pipe] + 1) % (NRF_ESB_PID_MAX + 1);
01091     m_tx_fifo.p_payload[m_tx_fifo.entry_point]->pid = m_pids[p_payload->pipe];
01092 
01093     if (++m_tx_fifo.entry_point >= NRF_ESB_TX_FIFO_SIZE)
01094     {
01095         m_tx_fifo.entry_point = 0;
01096     }
01097 
01098     m_tx_fifo.count++;
01099 
01100     ENABLE_RF_IRQ();
01101 
01102 
01103     if (m_config_local.mode == NRF_ESB_MODE_PTX &&
01104         m_config_local.tx_mode == NRF_ESB_TXMODE_AUTO &&
01105         m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE)
01106     {
01107         start_tx_transaction();
01108     }
01109 
01110     return NRF_SUCCESS;
01111 }
01112 
01113 
01114 uint32_t nrf_esb_read_rx_payload(nrf_esb_payload_t * p_payload)
01115 {
01116     VERIFY_TRUE(m_esb_initialized, NRF_ERROR_INVALID_STATE);
01117     VERIFY_PARAM_NOT_NULL(p_payload);
01118 
01119     if (m_rx_fifo.count == 0)
01120     {
01121         return NRF_ERROR_NOT_FOUND;
01122     }
01123 
01124     DISABLE_RF_IRQ();
01125 
01126     p_payload->length = m_rx_fifo.p_payload[m_rx_fifo.exit_point]->length;
01127     p_payload->pipe   = m_rx_fifo.p_payload[m_rx_fifo.exit_point]->pipe;
01128     p_payload->rssi   = m_rx_fifo.p_payload[m_rx_fifo.exit_point]->rssi;
01129     p_payload->pid    = m_rx_fifo.p_payload[m_rx_fifo.exit_point]->pid;
01130     p_payload->noack  = m_rx_fifo.p_payload[m_rx_fifo.exit_point]->noack; 
01131     memcpy(p_payload->data, m_rx_fifo.p_payload[m_rx_fifo.exit_point]->data, p_payload->length);
01132 
01133     if (++m_rx_fifo.exit_point >= NRF_ESB_RX_FIFO_SIZE)
01134     {
01135         m_rx_fifo.exit_point = 0;
01136     }
01137 
01138     m_rx_fifo.count--;
01139 
01140     ENABLE_RF_IRQ();
01141 
01142     return NRF_SUCCESS;
01143 }
01144 
01145 
01146 uint32_t nrf_esb_start_tx(void)
01147 {
01148     VERIFY_TRUE(m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE, NRF_ERROR_BUSY);
01149 
01150     if (m_tx_fifo.count == 0)
01151     {
01152         return NRF_ERROR_BUFFER_EMPTY;
01153     }
01154 
01155     start_tx_transaction();
01156 
01157     return NRF_SUCCESS;
01158 }
01159 
01160 
01161 uint32_t nrf_esb_start_rx(void)
01162 {
01163     VERIFY_TRUE(m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE, NRF_ERROR_BUSY);
01164 
01165     NRF_RADIO->INTENCLR = 0xFFFFFFFF;
01166     NRF_RADIO->EVENTS_DISABLED = 0;
01167     on_radio_disabled = on_radio_disabled_rx;
01168 
01169     NRF_RADIO->SHORTS      = m_radio_shorts_common | RADIO_SHORTS_DISABLED_TXEN_Msk;
01170     NRF_RADIO->INTENSET    = RADIO_INTENSET_DISABLED_Msk;
01171     m_nrf_esb_mainstate    = NRF_ESB_STATE_PRX;
01172 
01173     NRF_RADIO->RXADDRESSES  = m_esb_addr.rx_pipes_enabled;
01174     NRF_RADIO->FREQUENCY    = m_esb_addr.rf_channel;
01175     NRF_RADIO->PACKETPTR    = (uint32_t)m_rx_payload_buffer;
01176 
01177     NVIC_ClearPendingIRQ(RADIO_IRQn);
01178     NVIC_EnableIRQ(RADIO_IRQn);
01179 
01180     NRF_RADIO->EVENTS_ADDRESS = 0;
01181     NRF_RADIO->EVENTS_PAYLOAD = 0;
01182     NRF_RADIO->EVENTS_DISABLED = 0;
01183 
01184     NRF_RADIO->TASKS_RXEN  = 1;
01185 
01186     return NRF_SUCCESS;
01187 }
01188 
01189 
01190 uint32_t nrf_esb_stop_rx(void)
01191 {
01192     if (m_nrf_esb_mainstate == NRF_ESB_STATE_PRX)
01193     {
01194         NRF_RADIO->SHORTS = 0;
01195         NRF_RADIO->INTENCLR = 0xFFFFFFFF;
01196         on_radio_disabled = NULL;
01197         NRF_RADIO->EVENTS_DISABLED = 0;
01198         NRF_RADIO->TASKS_DISABLE = 1;
01199         while (NRF_RADIO->EVENTS_DISABLED == 0);
01200         m_nrf_esb_mainstate = NRF_ESB_STATE_IDLE;
01201 
01202         return NRF_SUCCESS;
01203     }
01204 
01205     return NRF_ESB_ERROR_NOT_IN_RX_MODE;
01206 }
01207 
01208 
01209 uint32_t nrf_esb_flush_tx(void)
01210 {
01211     VERIFY_TRUE(m_esb_initialized, NRF_ERROR_INVALID_STATE);
01212 
01213     DISABLE_RF_IRQ();
01214 
01215     m_tx_fifo.count = 0;
01216     m_tx_fifo.entry_point = 0;
01217     m_tx_fifo.exit_point = 0;
01218 
01219     ENABLE_RF_IRQ();
01220 
01221     return NRF_SUCCESS;
01222 }
01223 
01224 
01225 uint32_t nrf_esb_pop_tx(void)
01226 {
01227     VERIFY_TRUE(m_esb_initialized, NRF_ERROR_INVALID_STATE);
01228     VERIFY_TRUE(m_tx_fifo.count > 0, NRF_ERROR_BUFFER_EMPTY);
01229 
01230     DISABLE_RF_IRQ();
01231 
01232     if (++m_tx_fifo.entry_point >= NRF_ESB_TX_FIFO_SIZE)
01233     {
01234         m_tx_fifo.entry_point = 0;
01235     }
01236     m_tx_fifo.count--;
01237 
01238     ENABLE_RF_IRQ();
01239 
01240     return NRF_SUCCESS;
01241 }
01242 
01243 
01244 uint32_t nrf_esb_flush_rx(void)
01245 {
01246     VERIFY_TRUE(m_esb_initialized, NRF_ERROR_INVALID_STATE);
01247 
01248     DISABLE_RF_IRQ();
01249 
01250     m_rx_fifo.count = 0;
01251     m_rx_fifo.entry_point = 0;
01252     m_rx_fifo.exit_point = 0;
01253 
01254     memset(m_rx_pipe_info, 0, sizeof(m_rx_pipe_info));
01255 
01256     ENABLE_RF_IRQ();
01257 
01258     return NRF_SUCCESS;
01259 }
01260 
01261 
01262 uint32_t nrf_esb_set_address_length(uint8_t length)
01263 {
01264     VERIFY_TRUE(m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE, NRF_ERROR_BUSY);
01265     VERIFY_TRUE(length > 2 && length < 6, NRF_ERROR_INVALID_PARAM);
01266     
01267     /* 
01268     Workaround for nRF52832 Rev 1 Errata 107
01269     Check if pipe 0 or pipe 1-7 has a 'zero address'.
01270     Avoid using access addresses in the following pattern (where X is don't care): 
01271     ADDRLEN=5 
01272     BASE0 = 0x0000XXXX, PREFIX0 = 0xXXXXXX00 
01273     BASE1 = 0x0000XXXX, PREFIX0 = 0xXXXX00XX 
01274     BASE1 = 0x0000XXXX, PREFIX0 = 0xXX00XXXX 
01275     BASE1 = 0x0000XXXX, PREFIX0 = 0x00XXXXXX 
01276     BASE1 = 0x0000XXXX, PREFIX1 = 0xXXXXXX00 
01277     BASE1 = 0x0000XXXX, PREFIX1 = 0xXXXX00XX 
01278     BASE1 = 0x0000XXXX, PREFIX1 = 0xXX00XXXX 
01279     BASE1 = 0x0000XXXX, PREFIX1 = 0x00XXXXXX 
01280 
01281     ADDRLEN=4 
01282     BASE0 = 0x00XXXXXX, PREFIX0 = 0xXXXXXX00 
01283     BASE1 = 0x00XXXXXX, PREFIX0 = 0xXXXX00XX 
01284     BASE1 = 0x00XXXXXX, PREFIX0 = 0xXX00XXXX 
01285     BASE1 = 0x00XXXXXX, PREFIX0 = 0x00XXXXXX 
01286     BASE1 = 0x00XXXXXX, PREFIX1 = 0xXXXXXX00 
01287     BASE1 = 0x00XXXXXX, PREFIX1 = 0xXXXX00XX 
01288     BASE1 = 0x00XXXXXX, PREFIX1 = 0xXX00XXXX 
01289     BASE1 = 0x00XXXXXX, PREFIX1 = 0x00XXXXXX
01290     */
01291     uint32_t base_address_mask = length == 5 ? 0xFFFF0000 : 0xFF000000;
01292     if((NRF_RADIO->BASE0 & base_address_mask) == 0 && (NRF_RADIO->PREFIX0 & 0x000000FF) == 0)
01293     {
01294         return NRF_ERROR_INVALID_PARAM;
01295     }
01296     if((NRF_RADIO->BASE1 & base_address_mask) == 0 && ((NRF_RADIO->PREFIX0 & 0x0000FF00) == 0 ||(NRF_RADIO->PREFIX0 & 0x00FF0000) == 0 || (NRF_RADIO->PREFIX0 & 0xFF000000) == 0 ||
01297        (NRF_RADIO->PREFIX1 & 0xFF000000) == 0 || (NRF_RADIO->PREFIX1 & 0x00FF0000) == 0 ||(NRF_RADIO->PREFIX1 & 0x0000FF00) == 0 || (NRF_RADIO->PREFIX1 & 0x000000FF) == 0))
01298     {
01299         return NRF_ERROR_INVALID_PARAM;
01300     }
01301     
01302     m_esb_addr.addr_length = length;
01303 
01304     update_rf_payload_format(m_config_local.payload_length);
01305 
01306     return NRF_SUCCESS;
01307 }
01308 
01309 
01310 uint32_t nrf_esb_set_base_address_0(uint8_t const * p_addr)
01311 {
01312     VERIFY_TRUE(m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE, NRF_ERROR_BUSY);
01313     VERIFY_PARAM_NOT_NULL(p_addr);
01314     
01315     /*
01316     Workaround for nRF52832 Rev 1 Errata 107
01317     Check if pipe 0 or pipe 1-7 has a 'zero address'.
01318     Avoid using access addresses in the following pattern (where X is don't care): 
01319     ADDRLEN=5 
01320     BASE0 = 0x0000XXXX, PREFIX0 = 0xXXXXXX00 
01321     BASE1 = 0x0000XXXX, PREFIX0 = 0xXXXX00XX 
01322     BASE1 = 0x0000XXXX, PREFIX0 = 0xXX00XXXX 
01323     BASE1 = 0x0000XXXX, PREFIX0 = 0x00XXXXXX 
01324     BASE1 = 0x0000XXXX, PREFIX1 = 0xXXXXXX00 
01325     BASE1 = 0x0000XXXX, PREFIX1 = 0xXXXX00XX 
01326     BASE1 = 0x0000XXXX, PREFIX1 = 0xXX00XXXX 
01327     BASE1 = 0x0000XXXX, PREFIX1 = 0x00XXXXXX 
01328 
01329     ADDRLEN=4 
01330     BASE0 = 0x00XXXXXX, PREFIX0 = 0xXXXXXX00 
01331     BASE1 = 0x00XXXXXX, PREFIX0 = 0xXXXX00XX 
01332     BASE1 = 0x00XXXXXX, PREFIX0 = 0xXX00XXXX 
01333     BASE1 = 0x00XXXXXX, PREFIX0 = 0x00XXXXXX 
01334     BASE1 = 0x00XXXXXX, PREFIX1 = 0xXXXXXX00 
01335     BASE1 = 0x00XXXXXX, PREFIX1 = 0xXXXX00XX 
01336     BASE1 = 0x00XXXXXX, PREFIX1 = 0xXX00XXXX 
01337     BASE1 = 0x00XXXXXX, PREFIX1 = 0x00XXXXXX
01338     */
01339     uint32_t base_address_mask = m_esb_addr.addr_length == 5 ? 0xFFFF0000 : 0xFF000000;
01340     if((addr_conv(p_addr) & base_address_mask) == 0 && (NRF_RADIO->PREFIX0 & 0x000000FF) == 0)
01341     {
01342         return NRF_ERROR_INVALID_PARAM;
01343     }
01344 
01345     memcpy(m_esb_addr.base_addr_p0, p_addr, 4);
01346 
01347     update_radio_addresses(NRF_ESB_ADDR_UPDATE_MASK_BASE0);
01348 
01349     return apply_address_workarounds();
01350 }
01351 
01352 
01353 uint32_t nrf_esb_set_base_address_1(uint8_t const * p_addr)
01354 {
01355     VERIFY_TRUE(m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE, NRF_ERROR_BUSY);
01356     VERIFY_PARAM_NOT_NULL(p_addr);
01357     
01358     /*
01359     Workaround for nRF52832 Rev 1 Errata 107
01360     Check if pipe 0 or pipe 1-7 has a 'zero address'.
01361     Avoid using access addresses in the following pattern (where X is don't care): 
01362     ADDRLEN=5 
01363     BASE0 = 0x0000XXXX, PREFIX0 = 0xXXXXXX00 
01364     BASE1 = 0x0000XXXX, PREFIX0 = 0xXXXX00XX 
01365     BASE1 = 0x0000XXXX, PREFIX0 = 0xXX00XXXX 
01366     BASE1 = 0x0000XXXX, PREFIX0 = 0x00XXXXXX 
01367     BASE1 = 0x0000XXXX, PREFIX1 = 0xXXXXXX00 
01368     BASE1 = 0x0000XXXX, PREFIX1 = 0xXXXX00XX 
01369     BASE1 = 0x0000XXXX, PREFIX1 = 0xXX00XXXX 
01370     BASE1 = 0x0000XXXX, PREFIX1 = 0x00XXXXXX 
01371 
01372     ADDRLEN=4 
01373     BASE0 = 0x00XXXXXX, PREFIX0 = 0xXXXXXX00 
01374     BASE1 = 0x00XXXXXX, PREFIX0 = 0xXXXX00XX 
01375     BASE1 = 0x00XXXXXX, PREFIX0 = 0xXX00XXXX 
01376     BASE1 = 0x00XXXXXX, PREFIX0 = 0x00XXXXXX 
01377     BASE1 = 0x00XXXXXX, PREFIX1 = 0xXXXXXX00 
01378     BASE1 = 0x00XXXXXX, PREFIX1 = 0xXXXX00XX 
01379     BASE1 = 0x00XXXXXX, PREFIX1 = 0xXX00XXXX 
01380     BASE1 = 0x00XXXXXX, PREFIX1 = 0x00XXXXXX
01381     */
01382     uint32_t base_address_mask = m_esb_addr.addr_length == 5 ? 0xFFFF0000 : 0xFF000000;
01383     if((addr_conv(p_addr) & base_address_mask) == 0 && ((NRF_RADIO->PREFIX0 & 0x0000FF00) == 0 ||(NRF_RADIO->PREFIX0 & 0x00FF0000) == 0 || (NRF_RADIO->PREFIX0 & 0xFF000000) == 0 ||
01384        (NRF_RADIO->PREFIX1 & 0xFF000000) == 0 || (NRF_RADIO->PREFIX1 & 0x00FF0000) == 0 ||(NRF_RADIO->PREFIX1 & 0x0000FF00) == 0 || (NRF_RADIO->PREFIX1 & 0x000000FF) == 0))
01385     {
01386         return NRF_ERROR_INVALID_PARAM;
01387     }
01388     
01389     memcpy(m_esb_addr.base_addr_p1, p_addr, 4);
01390 
01391     update_radio_addresses(NRF_ESB_ADDR_UPDATE_MASK_BASE1);
01392 
01393     return apply_address_workarounds();
01394 }
01395 
01396 
01397 uint32_t nrf_esb_set_prefixes(uint8_t const * p_prefixes, uint8_t num_pipes)
01398 {
01399     VERIFY_TRUE(m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE, NRF_ERROR_BUSY);
01400     VERIFY_PARAM_NOT_NULL(p_prefixes);
01401     VERIFY_TRUE(num_pipes < 9, NRF_ERROR_INVALID_PARAM);
01402     
01403     /*
01404     Workaround for nRF52832 Rev 1 Errata 107
01405     Check if pipe 0 or pipe 1-7 has a 'zero address'.
01406     Avoid using access addresses in the following pattern (where X is don't care): 
01407     ADDRLEN=5 
01408     BASE0 = 0x0000XXXX, PREFIX0 = 0xXXXXXX00 
01409     BASE1 = 0x0000XXXX, PREFIX0 = 0xXXXX00XX 
01410     BASE1 = 0x0000XXXX, PREFIX0 = 0xXX00XXXX 
01411     BASE1 = 0x0000XXXX, PREFIX0 = 0x00XXXXXX 
01412     BASE1 = 0x0000XXXX, PREFIX1 = 0xXXXXXX00 
01413     BASE1 = 0x0000XXXX, PREFIX1 = 0xXXXX00XX 
01414     BASE1 = 0x0000XXXX, PREFIX1 = 0xXX00XXXX 
01415     BASE1 = 0x0000XXXX, PREFIX1 = 0x00XXXXXX 
01416 
01417     ADDRLEN=4 
01418     BASE0 = 0x00XXXXXX, PREFIX0 = 0xXXXXXX00 
01419     BASE1 = 0x00XXXXXX, PREFIX0 = 0xXXXX00XX 
01420     BASE1 = 0x00XXXXXX, PREFIX0 = 0xXX00XXXX 
01421     BASE1 = 0x00XXXXXX, PREFIX0 = 0x00XXXXXX 
01422     BASE1 = 0x00XXXXXX, PREFIX1 = 0xXXXXXX00 
01423     BASE1 = 0x00XXXXXX, PREFIX1 = 0xXXXX00XX 
01424     BASE1 = 0x00XXXXXX, PREFIX1 = 0xXX00XXXX 
01425     BASE1 = 0x00XXXXXX, PREFIX1 = 0x00XXXXXX
01426     */
01427     uint32_t base_address_mask = m_esb_addr.addr_length == 5 ? 0xFFFF0000 : 0xFF000000;
01428     if(num_pipes >= 1 && (NRF_RADIO->BASE0 & base_address_mask) == 0 && p_prefixes[0] == 0)
01429     {
01430         return NRF_ERROR_INVALID_PARAM;
01431     }
01432 
01433     if((NRF_RADIO->BASE1 & base_address_mask) == 0)
01434     {
01435         for (uint8_t i = 1; i < num_pipes; i++)
01436         {
01437             if (p_prefixes[i] == 0)
01438             {
01439                 return NRF_ERROR_INVALID_PARAM;
01440             }
01441         }
01442     }
01443     
01444     memcpy(m_esb_addr.pipe_prefixes, p_prefixes, num_pipes);
01445     m_esb_addr.num_pipes = num_pipes;
01446     m_esb_addr.rx_pipes_enabled = BIT_MASK_UINT_8(num_pipes);
01447 
01448     update_radio_addresses(NRF_ESB_ADDR_UPDATE_MASK_PREFIX);
01449 
01450     return apply_address_workarounds();
01451 }
01452 
01453 
01454 uint32_t nrf_esb_update_prefix(uint8_t pipe, uint8_t prefix)
01455 {
01456     VERIFY_TRUE(m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE, NRF_ERROR_BUSY);
01457     VERIFY_TRUE(pipe < 8, NRF_ERROR_INVALID_PARAM);
01458     
01459     /*
01460     Workaround for nRF52832 Rev 1 Errata 107
01461     Check if pipe 0 or pipe 1-7 has a 'zero address'.
01462     Avoid using access addresses in the following pattern (where X is don't care): 
01463     ADDRLEN=5 
01464     BASE0 = 0x0000XXXX, PREFIX0 = 0xXXXXXX00 
01465     BASE1 = 0x0000XXXX, PREFIX0 = 0xXXXX00XX 
01466     BASE1 = 0x0000XXXX, PREFIX0 = 0xXX00XXXX 
01467     BASE1 = 0x0000XXXX, PREFIX0 = 0x00XXXXXX 
01468     BASE1 = 0x0000XXXX, PREFIX1 = 0xXXXXXX00 
01469     BASE1 = 0x0000XXXX, PREFIX1 = 0xXXXX00XX 
01470     BASE1 = 0x0000XXXX, PREFIX1 = 0xXX00XXXX 
01471     BASE1 = 0x0000XXXX, PREFIX1 = 0x00XXXXXX 
01472 
01473     ADDRLEN=4 
01474     BASE0 = 0x00XXXXXX, PREFIX0 = 0xXXXXXX00 
01475     BASE1 = 0x00XXXXXX, PREFIX0 = 0xXXXX00XX 
01476     BASE1 = 0x00XXXXXX, PREFIX0 = 0xXX00XXXX 
01477     BASE1 = 0x00XXXXXX, PREFIX0 = 0x00XXXXXX 
01478     BASE1 = 0x00XXXXXX, PREFIX1 = 0xXXXXXX00 
01479     BASE1 = 0x00XXXXXX, PREFIX1 = 0xXXXX00XX 
01480     BASE1 = 0x00XXXXXX, PREFIX1 = 0xXX00XXXX 
01481     BASE1 = 0x00XXXXXX, PREFIX1 = 0x00XXXXXX
01482     */
01483     uint32_t base_address_mask = m_esb_addr.addr_length == 5 ? 0xFFFF0000 : 0xFF000000;
01484     if (pipe == 0)
01485     {
01486         if((NRF_RADIO->BASE0 & base_address_mask) == 0 && prefix == 0)
01487         {
01488             return NRF_ERROR_INVALID_PARAM;
01489         }
01490     }
01491     else{
01492         if((NRF_RADIO->BASE1 & base_address_mask) == 0 && prefix == 0)
01493         {
01494             return NRF_ERROR_INVALID_PARAM;
01495         }
01496     }
01497     
01498     m_esb_addr.pipe_prefixes[pipe] = prefix;
01499 
01500     update_radio_addresses(NRF_ESB_ADDR_UPDATE_MASK_PREFIX);
01501 
01502     return apply_address_workarounds();
01503 }
01504 
01505 
01506 uint32_t nrf_esb_enable_pipes(uint8_t enable_mask)
01507 {
01508     VERIFY_TRUE(m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE, NRF_ERROR_BUSY);
01509 
01510     m_esb_addr.rx_pipes_enabled = enable_mask;
01511 
01512     return apply_address_workarounds();
01513 }
01514 
01515 
01516 uint32_t nrf_esb_set_rf_channel(uint32_t channel)
01517 {
01518     VERIFY_TRUE(m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE, NRF_ERROR_BUSY);
01519     VERIFY_TRUE(channel <= 100, NRF_ERROR_INVALID_PARAM);
01520 
01521     m_esb_addr.rf_channel = channel;
01522 
01523     return NRF_SUCCESS;
01524 }
01525 
01526 
01527 uint32_t nrf_esb_get_rf_channel(uint32_t * p_channel)
01528 {
01529     VERIFY_PARAM_NOT_NULL(p_channel);
01530 
01531     *p_channel = m_esb_addr.rf_channel;
01532 
01533     return NRF_SUCCESS;
01534 }
01535 
01536 
01537 uint32_t nrf_esb_set_tx_power(nrf_esb_tx_power_t tx_output_power)
01538 {
01539     VERIFY_TRUE(m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE, NRF_ERROR_BUSY);
01540 
01541     if ( m_config_local.tx_output_power != tx_output_power )
01542     {
01543         m_config_local.tx_output_power = tx_output_power;
01544         update_radio_tx_power();
01545     }
01546 
01547     return NRF_SUCCESS;
01548 }
01549 
01550 
01551 uint32_t nrf_esb_set_retransmit_delay(uint16_t delay)
01552 {
01553     VERIFY_TRUE(m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE, NRF_ERROR_BUSY);
01554     VERIFY_TRUE(delay >= NRF_ESB_RETRANSMIT_DELAY_MIN, NRF_ERROR_INVALID_PARAM);
01555 
01556     m_config_local.retransmit_delay = delay;
01557     return NRF_SUCCESS;
01558 }
01559 
01560 
01561 uint32_t nrf_esb_set_retransmit_count(uint16_t count)
01562 {
01563     VERIFY_TRUE(m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE, NRF_ERROR_BUSY);
01564 
01565     m_config_local.retransmit_count = count;
01566     return NRF_SUCCESS;
01567 }
01568 
01569 
01570 uint32_t nrf_esb_set_bitrate(nrf_esb_bitrate_t bitrate)
01571 {
01572     VERIFY_TRUE(m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE, NRF_ERROR_BUSY);
01573 
01574     m_config_local.bitrate = bitrate;
01575     return update_radio_bitrate() ? NRF_SUCCESS : NRF_ERROR_INVALID_PARAM;
01576 }
01577 
01578 
01579 uint32_t nrf_esb_reuse_pid(uint8_t pipe)
01580 {
01581     VERIFY_TRUE(m_nrf_esb_mainstate == NRF_ESB_STATE_IDLE, NRF_ERROR_BUSY);
01582     VERIFY_TRUE(pipe < 8, NRF_ERROR_INVALID_PARAM);
01583 
01584     m_pids[pipe] = (m_pids[pipe] + NRF_ESB_PID_MAX) % (NRF_ESB_PID_MAX + 1);
01585     return NRF_SUCCESS;
01586 }
01587 
01588 
01589 // Handler for 
01590 #ifdef NRF52
01591 void NRF_ESB_BUGFIX_TIMER_IRQHandler(void)
01592 {
01593     if(NRF_ESB_BUGFIX_TIMER->EVENTS_COMPARE[0])
01594     {
01595         NRF_ESB_BUGFIX_TIMER->EVENTS_COMPARE[0] = 0;
01596 
01597         // If the timeout timer fires and we are in the PTX receive ACK state, disable the radio
01598         if(m_nrf_esb_mainstate == NRF_ESB_STATE_PTX_RX_ACK)
01599         {
01600             NRF_RADIO->TASKS_DISABLE = 1;
01601         }
01602     }
01603 }
01604 #endif