Patched version of nrf51822 FOTA compatible driver, with GPTIO disabled, as it clashed with the mbed definitions...

Fork of nRF51822 by Nordic Semiconductor

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers nrf51.h Source File

nrf51.h

00001 
00002 /****************************************************************************************************//**
00003  * @file     nRF51.h
00004  *
00005  * @brief    CMSIS Cortex-M0 Peripheral Access Layer Header File for
00006  *           nRF51 from Nordic Semiconductor.
00007  *
00008  * @version  V522
00009  * @date     31. October 2014
00010  *
00011  * @note     Generated with SVDConv V2.81d 
00012  *           from CMSIS SVD File 'nRF51.xml' Version 522,
00013  *
00014  * @par      Copyright (c) 2013, Nordic Semiconductor ASA
00015  *           All rights reserved.
00016  *           
00017  *           Redistribution and use in source and binary forms, with or without
00018  *           modification, are permitted provided that the following conditions are met:
00019  *           
00020  *           * Redistributions of source code must retain the above copyright notice, this
00021  *           list of conditions and the following disclaimer.
00022  *           
00023  *           * Redistributions in binary form must reproduce the above copyright notice,
00024  *           this list of conditions and the following disclaimer in the documentation
00025  *           and/or other materials provided with the distribution.
00026  *           
00027  *           * Neither the name of Nordic Semiconductor ASA nor the names of its
00028  *           contributors may be used to endorse or promote products derived from
00029  *           this software without specific prior written permission.
00030  *           
00031  *           THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00032  *           AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00033  *           IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00034  *           DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00035  *           FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00036  *           DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00037  *           SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00038  *           CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00039  *           OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00040  *           OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00041  *           
00042  *
00043  *******************************************************************************************************/
00044 
00045 
00046 
00047 /** @addtogroup Nordic Semiconductor
00048   * @{
00049   */
00050 
00051 /** @addtogroup nRF51
00052   * @{
00053   */
00054 
00055 #ifndef NRF51_H
00056 #define NRF51_H
00057 
00058 #ifdef __cplusplus
00059 extern "C" {
00060 #endif
00061 
00062 
00063 /* -------------------------  Interrupt Number Definition  ------------------------ */
00064 
00065 typedef enum {
00066 /* -------------------  Cortex-M0 Processor Exceptions Numbers  ------------------- */
00067   Reset_IRQn                     = -15,              /*!<   1  Reset Vector, invoked on Power up and warm reset                 */
00068   NonMaskableInt_IRQn            = -14,              /*!<   2  Non maskable Interrupt, cannot be stopped or preempted           */
00069   HardFault_IRQn                 = -13,              /*!<   3  Hard Fault, all classes of Fault                                 */
00070   SVCall_IRQn                    =  -5,              /*!<  11  System Service Call via SVC instruction                          */
00071   DebugMonitor_IRQn              =  -4,              /*!<  12  Debug Monitor                                                    */
00072   PendSV_IRQn                    =  -2,              /*!<  14  Pendable request for system service                              */
00073   SysTick_IRQn                   =  -1,              /*!<  15  System Tick Timer                                                */
00074 /* ----------------------  nRF51 Specific Interrupt Numbers  ---------------------- */
00075   POWER_CLOCK_IRQn               =   0,              /*!<   0  POWER_CLOCK                                                      */
00076   RADIO_IRQn                     =   1,              /*!<   1  RADIO                                                            */
00077   UART0_IRQn                     =   2,              /*!<   2  UART0                                                            */
00078   SPI0_TWI0_IRQn                 =   3,              /*!<   3  SPI0_TWI0                                                        */
00079   SPI1_TWI1_IRQn                 =   4,              /*!<   4  SPI1_TWI1                                                        */
00080   GPIOTE_IRQn                    =   6,              /*!<   6  GPIOTE                                                           */
00081   ADC_IRQn                       =   7,              /*!<   7  ADC                                                              */
00082   TIMER0_IRQn                    =   8,              /*!<   8  TIMER0                                                           */
00083   TIMER1_IRQn                    =   9,              /*!<   9  TIMER1                                                           */
00084   TIMER2_IRQn                    =  10,              /*!<  10  TIMER2                                                           */
00085   RTC0_IRQn                      =  11,              /*!<  11  RTC0                                                             */
00086   TEMP_IRQn                      =  12,              /*!<  12  TEMP                                                             */
00087   RNG_IRQn                       =  13,              /*!<  13  RNG                                                              */
00088   ECB_IRQn                       =  14,              /*!<  14  ECB                                                              */
00089   CCM_AAR_IRQn                   =  15,              /*!<  15  CCM_AAR                                                          */
00090   WDT_IRQn                       =  16,              /*!<  16  WDT                                                              */
00091   RTC1_IRQn                      =  17,              /*!<  17  RTC1                                                             */
00092   QDEC_IRQn                      =  18,              /*!<  18  QDEC                                                             */
00093   LPCOMP_IRQn                    =  19,              /*!<  19  LPCOMP                                                           */
00094   SWI0_IRQn                      =  20,              /*!<  20  SWI0                                                             */
00095   SWI1_IRQn                      =  21,              /*!<  21  SWI1                                                             */
00096   SWI2_IRQn                      =  22,              /*!<  22  SWI2                                                             */
00097   SWI3_IRQn                      =  23,              /*!<  23  SWI3                                                             */
00098   SWI4_IRQn                      =  24,              /*!<  24  SWI4                                                             */
00099   SWI5_IRQn                      =  25               /*!<  25  SWI5                                                             */
00100 } IRQn_Type ;
00101 
00102 
00103 /** @addtogroup Configuration_of_CMSIS
00104   * @{
00105   */
00106 
00107 
00108 /* ================================================================================ */
00109 /* ================      Processor and Core Peripheral Section     ================ */
00110 /* ================================================================================ */
00111 
00112 /* ----------------Configuration of the Cortex-M0 Processor and Core Peripherals---------------- */
00113 #define __CM0_REV                 0x0301            /*!< Cortex-M0 Core Revision                                               */
00114 #define __MPU_PRESENT                  0            /*!< MPU present or not                                                    */
00115 #define __NVIC_PRIO_BITS               2            /*!< Number of Bits used for Priority Levels                               */
00116 #define __Vendor_SysTickConfig         0            /*!< Set to 1 if different SysTick Config is used                          */
00117 /** @} */ /* End of group Configuration_of_CMSIS */
00118 
00119 #include "core_cm0.h"                               /*!< Cortex-M0 processor and core peripherals                              */
00120 #include "system_nrf51.h"                           /*!< nRF51 System                                                          */
00121 
00122 
00123 /* ================================================================================ */
00124 /* ================       Device Specific Peripheral Section       ================ */
00125 /* ================================================================================ */
00126 
00127 
00128 /** @addtogroup Device_Peripheral_Registers
00129   * @{
00130   */
00131 
00132 
00133 /* -------------------  Start of section using anonymous unions  ------------------ */
00134 #if defined(__CC_ARM)
00135   #pragma push
00136   #pragma anon_unions
00137 #elif defined(__ICCARM__)
00138   #pragma language=extended
00139 #elif defined(__GNUC__)
00140   /* anonymous unions are enabled by default */
00141 #elif defined(__TMS470__)
00142 /* anonymous unions are enabled by default */
00143 #elif defined(__TASKING__)
00144   #pragma warning 586
00145 #else
00146   #warning Not supported compiler type
00147 #endif
00148 
00149 
00150 typedef struct {
00151   __IO uint32_t  CPU0;                              /*!< Configurable priority configuration register for CPU0.                */
00152   __IO uint32_t  SPIS1;                             /*!< Configurable priority configuration register for SPIS1.               */
00153   __IO uint32_t  RADIO;                             /*!< Configurable priority configuration register for RADIO.               */
00154   __IO uint32_t  ECB;                               /*!< Configurable priority configuration register for ECB.                 */
00155   __IO uint32_t  CCM;                               /*!< Configurable priority configuration register for CCM.                 */
00156   __IO uint32_t  AAR;                               /*!< Configurable priority configuration register for AAR.                 */
00157 } AMLI_RAMPRI_Type;
00158 
00159 typedef struct {
00160   __IO uint32_t  SCK;                               /*!< Pin select for SCK.                                                   */
00161   __IO uint32_t  MOSI;                              /*!< Pin select for MOSI.                                                  */
00162   __IO uint32_t  MISO;                              /*!< Pin select for MISO.                                                  */
00163 } SPIM_PSEL_Type;
00164 
00165 typedef struct {
00166   __IO uint32_t  PTR;                               /*!< Data pointer.                                                         */
00167   __IO uint32_t  MAXCNT;                            /*!< Maximum number of buffer bytes to receive.                            */
00168   __I  uint32_t  AMOUNT;                            /*!< Number of bytes received in the last transaction.                     */
00169 } SPIM_RXD_Type;
00170 
00171 typedef struct {
00172   __IO uint32_t  PTR;                               /*!< Data pointer.                                                         */
00173   __IO uint32_t  MAXCNT;                            /*!< Maximum number of buffer bytes to send.                               */
00174   __I  uint32_t  AMOUNT;                            /*!< Number of bytes sent in the last transaction.                         */
00175 } SPIM_TXD_Type;
00176 
00177 typedef struct {
00178   __O  uint32_t  EN;                                /*!< Enable channel group.                                                 */
00179   __O  uint32_t  DIS;                               /*!< Disable channel group.                                                */
00180 } PPI_TASKS_CHG_Type;
00181 
00182 typedef struct {
00183   __IO uint32_t  EEP;                               /*!< Channel event end-point.                                              */
00184   __IO uint32_t  TEP;                               /*!< Channel task end-point.                                               */
00185 } PPI_CH_Type;
00186 
00187 typedef struct {
00188   __I  uint32_t  PART;                              /*!< Part code                                                             */
00189   __I  uint32_t  VARIANT;                           /*!< Part variant                                                          */
00190   __I  uint32_t  PACKAGE;                           /*!< Package option                                                        */
00191   __I  uint32_t  RAM;                               /*!< RAM variant                                                           */
00192   __I  uint32_t  FLASH;                             /*!< Flash variant                                                         */
00193   __I  uint32_t  RESERVED[3];                       /*!< Reserved                                                              */
00194 } FICR_INFO_Type;
00195 
00196 
00197 /* ================================================================================ */
00198 /* ================                      POWER                     ================ */
00199 /* ================================================================================ */
00200 
00201 
00202 /**
00203   * @brief Power Control. (POWER)
00204   */
00205 
00206 typedef struct {                                    /*!< POWER Structure                                                       */
00207   __I  uint32_t  RESERVED0[30];
00208   __O  uint32_t  TASKS_CONSTLAT ;                    /*!< Enable constant latency mode.                                         */
00209   __O  uint32_t  TASKS_LOWPWR ;                      /*!< Enable low power mode (variable latency).                             */
00210   __I  uint32_t  RESERVED1[34];
00211   __IO uint32_t  EVENTS_POFWARN ;                    /*!< Power failure warning.                                                */
00212   __I  uint32_t  RESERVED2[126];
00213   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00214   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00215   __I  uint32_t  RESERVED3[61];
00216   __IO uint32_t  RESETREAS ;                         /*!< Reset reason.                                                         */
00217   __I  uint32_t  RESERVED4[9];
00218   __I  uint32_t  RAMSTATUS ;                         /*!< Ram status register.                                                  */
00219   __I  uint32_t  RESERVED5[53];
00220   __O  uint32_t  SYSTEMOFF ;                         /*!< System off register.                                                  */
00221   __I  uint32_t  RESERVED6[3];
00222   __IO uint32_t  POFCON ;                            /*!< Power failure configuration.                                          */
00223   __I  uint32_t  RESERVED7[2];
00224   __IO uint32_t  GPREGRET;                          /*!< General purpose retention register. This register is a retained
00225                                                          register.                                                             */
00226   __I  uint32_t  RESERVED8;
00227   __IO uint32_t  RAMON ;                             /*!< Ram on/off.                                                           */
00228   __I  uint32_t  RESERVED9[7];
00229   __IO uint32_t  RESET;                             /*!< Pin reset functionality configuration register. This register
00230                                                          is a retained register.                                               */
00231   __I  uint32_t  RESERVED10[3];
00232   __IO uint32_t  RAMONB ;                            /*!< Ram on/off.                                                           */
00233   __I  uint32_t  RESERVED11[8];
00234   __IO uint32_t  DCDCEN ;                            /*!< DCDC converter enable configuration register.                         */
00235   __I  uint32_t  RESERVED12[291];
00236   __IO uint32_t  DCDCFORCE ;                         /*!< DCDC power-up force register.                                         */
00237 } NRF_POWER_Type;
00238 
00239 
00240 /* ================================================================================ */
00241 /* ================                      CLOCK                     ================ */
00242 /* ================================================================================ */
00243 
00244 
00245 /**
00246   * @brief Clock control. (CLOCK)
00247   */
00248 
00249 typedef struct {                                    /*!< CLOCK Structure                                                       */
00250   __O  uint32_t  TASKS_HFCLKSTART ;                  /*!< Start HFCLK clock source.                                             */
00251   __O  uint32_t  TASKS_HFCLKSTOP ;                   /*!< Stop HFCLK clock source.                                              */
00252   __O  uint32_t  TASKS_LFCLKSTART ;                  /*!< Start LFCLK clock source.                                             */
00253   __O  uint32_t  TASKS_LFCLKSTOP ;                   /*!< Stop LFCLK clock source.                                              */
00254   __O  uint32_t  TASKS_CAL ;                         /*!< Start calibration of LFCLK RC oscillator.                             */
00255   __O  uint32_t  TASKS_CTSTART ;                     /*!< Start calibration timer.                                              */
00256   __O  uint32_t  TASKS_CTSTOP ;                      /*!< Stop calibration timer.                                               */
00257   __I  uint32_t  RESERVED0[57];
00258   __IO uint32_t  EVENTS_HFCLKSTARTED ;               /*!< HFCLK oscillator started.                                             */
00259   __IO uint32_t  EVENTS_LFCLKSTARTED ;               /*!< LFCLK oscillator started.                                             */
00260   __I  uint32_t  RESERVED1;
00261   __IO uint32_t  EVENTS_DONE ;                       /*!< Calibration of LFCLK RC oscillator completed.                         */
00262   __IO uint32_t  EVENTS_CTTO ;                       /*!< Calibration timer timeout.                                            */
00263   __I  uint32_t  RESERVED2[124];
00264   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00265   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00266   __I  uint32_t  RESERVED3[63];
00267   __I  uint32_t  HFCLKRUN ;                          /*!< Task HFCLKSTART trigger status.                                       */
00268   __I  uint32_t  HFCLKSTAT ;                         /*!< High frequency clock status.                                          */
00269   __I  uint32_t  RESERVED4;
00270   __I  uint32_t  LFCLKRUN ;                          /*!< Task LFCLKSTART triggered status.                                     */
00271   __I  uint32_t  LFCLKSTAT ;                         /*!< Low frequency clock status.                                           */
00272   __I  uint32_t  LFCLKSRCCOPY;                      /*!< Clock source for the LFCLK clock, set when task LKCLKSTART is
00273                                                          triggered.                                                            */
00274   __I  uint32_t  RESERVED5[62];
00275   __IO uint32_t  LFCLKSRC ;                          /*!< Clock source for the LFCLK clock.                                     */
00276   __I  uint32_t  RESERVED6[7];
00277   __IO uint32_t  CTIV ;                              /*!< Calibration timer interval.                                           */
00278   __I  uint32_t  RESERVED7[5];
00279   __IO uint32_t  XTALFREQ ;                          /*!< Crystal frequency.                                                    */
00280 } NRF_CLOCK_Type;
00281 
00282 
00283 /* ================================================================================ */
00284 /* ================                       MPU                      ================ */
00285 /* ================================================================================ */
00286 
00287 
00288 /**
00289   * @brief Memory Protection Unit. (MPU)
00290   */
00291 
00292 typedef struct {                                    /*!< MPU Structure                                                         */
00293   __I  uint32_t  RESERVED0[330];
00294   __IO uint32_t  PERR0 ;                             /*!< Configuration of peripherals in mpu regions.                          */
00295   __IO uint32_t  RLENR0 ;                            /*!< Length of RAM region 0.                                               */
00296   __I  uint32_t  RESERVED1[52];
00297   __IO uint32_t  PROTENSET0 ;                        /*!< Erase and write protection bit enable set register.                   */
00298   __IO uint32_t  PROTENSET1 ;                        /*!< Erase and write protection bit enable set register.                   */
00299   __IO uint32_t  DISABLEINDEBUG ;                    /*!< Disable erase and write protection mechanism in debug mode.           */
00300   __IO uint32_t  PROTBLOCKSIZE ;                     /*!< Erase and write protection block size.                                */
00301 } NRF_MPU_Type;
00302 
00303 
00304 /* ================================================================================ */
00305 /* ================                       PU                       ================ */
00306 /* ================================================================================ */
00307 
00308 
00309 /**
00310   * @brief Patch unit. (PU)
00311   */
00312 
00313 typedef struct {                                    /*!< PU Structure                                                          */
00314   __I  uint32_t  RESERVED0[448];
00315   __IO uint32_t  REPLACEADDR[8];                    /*!< Address of first instruction to replace.                              */
00316   __I  uint32_t  RESERVED1[24];
00317   __IO uint32_t  PATCHADDR[8];                      /*!< Relative address of patch instructions.                               */
00318   __I  uint32_t  RESERVED2[24];
00319   __IO uint32_t  PATCHEN ;                           /*!< Patch enable register.                                                */
00320   __IO uint32_t  PATCHENSET ;                        /*!< Patch enable register.                                                */
00321   __IO uint32_t  PATCHENCLR ;                        /*!< Patch disable register.                                               */
00322 } NRF_PU_Type;
00323 
00324 
00325 /* ================================================================================ */
00326 /* ================                      AMLI                      ================ */
00327 /* ================================================================================ */
00328 
00329 
00330 /**
00331   * @brief AHB Multi-Layer Interface. (AMLI)
00332   */
00333 
00334 typedef struct {                                    /*!< AMLI Structure                                                        */
00335   __I  uint32_t  RESERVED0[896];
00336   AMLI_RAMPRI_Type RAMPRI ;                          /*!< RAM configurable priority configuration structure.                    */
00337 } NRF_AMLI_Type;
00338 
00339 
00340 /* ================================================================================ */
00341 /* ================                      RADIO                     ================ */
00342 /* ================================================================================ */
00343 
00344 
00345 /**
00346   * @brief The radio. (RADIO)
00347   */
00348 
00349 typedef struct {                                    /*!< RADIO Structure                                                       */
00350   __O  uint32_t  TASKS_TXEN ;                        /*!< Enable radio in TX mode.                                              */
00351   __O  uint32_t  TASKS_RXEN ;                        /*!< Enable radio in RX mode.                                              */
00352   __O  uint32_t  TASKS_START ;                       /*!< Start radio.                                                          */
00353   __O  uint32_t  TASKS_STOP ;                        /*!< Stop radio.                                                           */
00354   __O  uint32_t  TASKS_DISABLE ;                     /*!< Disable radio.                                                        */
00355   __O  uint32_t  TASKS_RSSISTART ;                   /*!< Start the RSSI and take one sample of the receive signal strength.    */
00356   __O  uint32_t  TASKS_RSSISTOP ;                    /*!< Stop the RSSI measurement.                                            */
00357   __O  uint32_t  TASKS_BCSTART ;                     /*!< Start the bit counter.                                                */
00358   __O  uint32_t  TASKS_BCSTOP ;                      /*!< Stop the bit counter.                                                 */
00359   __I  uint32_t  RESERVED0[55];
00360   __IO uint32_t  EVENTS_READY ;                      /*!< Ready event.                                                          */
00361   __IO uint32_t  EVENTS_ADDRESS ;                    /*!< Address event.                                                        */
00362   __IO uint32_t  EVENTS_PAYLOAD ;                    /*!< Payload event.                                                        */
00363   __IO uint32_t  EVENTS_END ;                        /*!< End event.                                                            */
00364   __IO uint32_t  EVENTS_DISABLED ;                   /*!< Disable event.                                                        */
00365   __IO uint32_t  EVENTS_DEVMATCH ;                   /*!< A device address match occurred on the last received packet.          */
00366   __IO uint32_t  EVENTS_DEVMISS ;                    /*!< No device address match occurred on the last received packet.         */
00367   __IO uint32_t  EVENTS_RSSIEND;                    /*!< Sampling of the receive signal strength complete. A new RSSI
00368                                                          sample is ready for readout at the RSSISAMPLE register.               */
00369   __I  uint32_t  RESERVED1[2];
00370   __IO uint32_t  EVENTS_BCMATCH ;                    /*!< Bit counter reached bit count value specified in BC register.         */
00371   __I  uint32_t  RESERVED2[53];
00372   __IO uint32_t  SHORTS ;                            /*!< Shortcuts for the radio.                                              */
00373   __I  uint32_t  RESERVED3[64];
00374   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00375   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00376   __I  uint32_t  RESERVED4[61];
00377   __I  uint32_t  CRCSTATUS ;                         /*!< CRC status of received packet.                                        */
00378   __I  uint32_t  CD ;                                /*!< Carrier detect.                                                       */
00379   __I  uint32_t  RXMATCH ;                           /*!< Received address.                                                     */
00380   __I  uint32_t  RXCRC ;                             /*!< Received CRC.                                                         */
00381   __I  uint32_t  DAI ;                               /*!< Device address match index.                                           */
00382   __I  uint32_t  RESERVED5[60];
00383   __IO uint32_t  PACKETPTR ;                         /*!< Packet pointer. Decision point: START task.                           */
00384   __IO uint32_t  FREQUENCY ;                         /*!< Frequency.                                                            */
00385   __IO uint32_t  TXPOWER ;                           /*!< Output power.                                                         */
00386   __IO uint32_t  MODE ;                              /*!< Data rate and modulation.                                             */
00387   __IO uint32_t  PCNF0 ;                             /*!< Packet configuration 0.                                               */
00388   __IO uint32_t  PCNF1 ;                             /*!< Packet configuration 1.                                               */
00389   __IO uint32_t  BASE0 ;                             /*!< Radio base address 0. Decision point: START task.                     */
00390   __IO uint32_t  BASE1 ;                             /*!< Radio base address 1. Decision point: START task.                     */
00391   __IO uint32_t  PREFIX0 ;                           /*!< Prefixes bytes for logical addresses 0 to 3.                          */
00392   __IO uint32_t  PREFIX1 ;                           /*!< Prefixes bytes for logical addresses 4 to 7.                          */
00393   __IO uint32_t  TXADDRESS ;                         /*!< Transmit address select.                                              */
00394   __IO uint32_t  RXADDRESSES ;                       /*!< Receive address select.                                               */
00395   __IO uint32_t  CRCCNF ;                            /*!< CRC configuration.                                                    */
00396   __IO uint32_t  CRCPOLY ;                           /*!< CRC polynomial.                                                       */
00397   __IO uint32_t  CRCINIT ;                           /*!< CRC initial value.                                                    */
00398   __IO uint32_t  TEST ;                              /*!< Test features enable register.                                        */
00399   __IO uint32_t  TIFS ;                              /*!< Inter Frame Spacing in microseconds.                                  */
00400   __I  uint32_t  RSSISAMPLE ;                        /*!< RSSI sample.                                                          */
00401   __I  uint32_t  RESERVED6;
00402   __I  uint32_t  STATE ;                             /*!< Current radio state.                                                  */
00403   __IO uint32_t  DATAWHITEIV ;                       /*!< Data whitening initial value.                                         */
00404   __I  uint32_t  RESERVED7[2];
00405   __IO uint32_t  BCC ;                               /*!< Bit counter compare.                                                  */
00406   __I  uint32_t  RESERVED8[39];
00407   __IO uint32_t  DAB[8];                            /*!< Device address base segment.                                          */
00408   __IO uint32_t  DAP[8];                            /*!< Device address prefix.                                                */
00409   __IO uint32_t  DACNF ;                             /*!< Device address match configuration.                                   */
00410   __I  uint32_t  RESERVED9[56];
00411   __IO uint32_t  OVERRIDE0 ;                         /*!< Trim value override register 0.                                       */
00412   __IO uint32_t  OVERRIDE1 ;                         /*!< Trim value override register 1.                                       */
00413   __IO uint32_t  OVERRIDE2 ;                         /*!< Trim value override register 2.                                       */
00414   __IO uint32_t  OVERRIDE3 ;                         /*!< Trim value override register 3.                                       */
00415   __IO uint32_t  OVERRIDE4 ;                         /*!< Trim value override register 4.                                       */
00416   __I  uint32_t  RESERVED10[561];
00417   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
00418 } NRF_RADIO_Type;
00419 
00420 
00421 /* ================================================================================ */
00422 /* ================                      UART                      ================ */
00423 /* ================================================================================ */
00424 
00425 
00426 /**
00427   * @brief Universal Asynchronous Receiver/Transmitter. (UART)
00428   */
00429 
00430 typedef struct {                                    /*!< UART Structure                                                        */
00431   __O  uint32_t  TASKS_STARTRX ;                     /*!< Start UART receiver.                                                  */
00432   __O  uint32_t  TASKS_STOPRX ;                      /*!< Stop UART receiver.                                                   */
00433   __O  uint32_t  TASKS_STARTTX ;                     /*!< Start UART transmitter.                                               */
00434   __O  uint32_t  TASKS_STOPTX ;                      /*!< Stop UART transmitter.                                                */
00435   __I  uint32_t  RESERVED0[3];
00436   __O  uint32_t  TASKS_SUSPEND ;                     /*!< Suspend UART.                                                         */
00437   __I  uint32_t  RESERVED1[56];
00438   __IO uint32_t  EVENTS_CTS ;                        /*!< CTS activated.                                                        */
00439   __IO uint32_t  EVENTS_NCTS ;                       /*!< CTS deactivated.                                                      */
00440   __IO uint32_t  EVENTS_RXDRDY ;                     /*!< Data received in RXD.                                                 */
00441   __I  uint32_t  RESERVED2[4];
00442   __IO uint32_t  EVENTS_TXDRDY ;                     /*!< Data sent from TXD.                                                   */
00443   __I  uint32_t  RESERVED3;
00444   __IO uint32_t  EVENTS_ERROR ;                      /*!< Error detected.                                                       */
00445   __I  uint32_t  RESERVED4[7];
00446   __IO uint32_t  EVENTS_RXTO ;                       /*!< Receiver timeout.                                                     */
00447   __I  uint32_t  RESERVED5[46];
00448   __IO uint32_t  SHORTS ;                            /*!< Shortcuts for UART.                                                   */
00449   __I  uint32_t  RESERVED6[64];
00450   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00451   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00452   __I  uint32_t  RESERVED7[93];
00453   __IO uint32_t  ERRORSRC ;                          /*!< Error source. Write error field to 1 to clear error.                  */
00454   __I  uint32_t  RESERVED8[31];
00455   __IO uint32_t  ENABLE ;                            /*!< Enable UART and acquire IOs.                                          */
00456   __I  uint32_t  RESERVED9;
00457   __IO uint32_t  PSELRTS ;                           /*!< Pin select for RTS.                                                   */
00458   __IO uint32_t  PSELTXD ;                           /*!< Pin select for TXD.                                                   */
00459   __IO uint32_t  PSELCTS ;                           /*!< Pin select for CTS.                                                   */
00460   __IO uint32_t  PSELRXD ;                           /*!< Pin select for RXD.                                                   */
00461   __I  uint32_t  RXD;                               /*!< RXD register. On read action the buffer pointer is displaced.
00462                                                          Once read the character is consumed. If read when no character
00463                                                           available, the UART will stop working.                               */
00464   __O  uint32_t  TXD ;                               /*!< TXD register.                                                         */
00465   __I  uint32_t  RESERVED10;
00466   __IO uint32_t  BAUDRATE ;                          /*!< UART Baudrate.                                                        */
00467   __I  uint32_t  RESERVED11[17];
00468   __IO uint32_t  CONFIG ;                            /*!< Configuration of parity and hardware flow control register.           */
00469   __I  uint32_t  RESERVED12[675];
00470   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
00471 } NRF_UART_Type;
00472 
00473 
00474 /* ================================================================================ */
00475 /* ================                       SPI                      ================ */
00476 /* ================================================================================ */
00477 
00478 
00479 /**
00480   * @brief SPI master 0. (SPI)
00481   */
00482 
00483 typedef struct {                                    /*!< SPI Structure                                                         */
00484   __I  uint32_t  RESERVED0[66];
00485   __IO uint32_t  EVENTS_READY ;                      /*!< TXD byte sent and RXD byte received.                                  */
00486   __I  uint32_t  RESERVED1[126];
00487   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00488   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00489   __I  uint32_t  RESERVED2[125];
00490   __IO uint32_t  ENABLE ;                            /*!< Enable SPI.                                                           */
00491   __I  uint32_t  RESERVED3;
00492   __IO uint32_t  PSELSCK ;                           /*!< Pin select for SCK.                                                   */
00493   __IO uint32_t  PSELMOSI ;                          /*!< Pin select for MOSI.                                                  */
00494   __IO uint32_t  PSELMISO ;                          /*!< Pin select for MISO.                                                  */
00495   __I  uint32_t  RESERVED4;
00496   __I  uint32_t  RXD ;                               /*!< RX data.                                                              */
00497   __IO uint32_t  TXD ;                               /*!< TX data.                                                              */
00498   __I  uint32_t  RESERVED5;
00499   __IO uint32_t  FREQUENCY ;                         /*!< SPI frequency                                                         */
00500   __I  uint32_t  RESERVED6[11];
00501   __IO uint32_t  CONFIG ;                            /*!< Configuration register.                                               */
00502   __I  uint32_t  RESERVED7[681];
00503   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
00504 } NRF_SPI_Type;
00505 
00506 
00507 /* ================================================================================ */
00508 /* ================                       TWI                      ================ */
00509 /* ================================================================================ */
00510 
00511 
00512 /**
00513   * @brief Two-wire interface master 0. (TWI)
00514   */
00515 
00516 typedef struct {                                    /*!< TWI Structure                                                         */
00517   __O  uint32_t  TASKS_STARTRX ;                     /*!< Start 2-Wire master receive sequence.                                 */
00518   __I  uint32_t  RESERVED0;
00519   __O  uint32_t  TASKS_STARTTX ;                     /*!< Start 2-Wire master transmit sequence.                                */
00520   __I  uint32_t  RESERVED1[2];
00521   __O  uint32_t  TASKS_STOP ;                        /*!< Stop 2-Wire transaction.                                              */
00522   __I  uint32_t  RESERVED2;
00523   __O  uint32_t  TASKS_SUSPEND ;                     /*!< Suspend 2-Wire transaction.                                           */
00524   __O  uint32_t  TASKS_RESUME ;                      /*!< Resume 2-Wire transaction.                                            */
00525   __I  uint32_t  RESERVED3[56];
00526   __IO uint32_t  EVENTS_STOPPED ;                    /*!< Two-wire stopped.                                                     */
00527   __IO uint32_t  EVENTS_RXDREADY ;                   /*!< Two-wire ready to deliver new RXD byte received.                      */
00528   __I  uint32_t  RESERVED4[4];
00529   __IO uint32_t  EVENTS_TXDSENT ;                    /*!< Two-wire finished sending last TXD byte.                              */
00530   __I  uint32_t  RESERVED5;
00531   __IO uint32_t  EVENTS_ERROR ;                      /*!< Two-wire error detected.                                              */
00532   __I  uint32_t  RESERVED6[4];
00533   __IO uint32_t  EVENTS_BB ;                         /*!< Two-wire byte boundary.                                               */
00534   __I  uint32_t  RESERVED7[3];
00535   __IO uint32_t  EVENTS_SUSPENDED ;                  /*!< Two-wire suspended.                                                   */
00536   __I  uint32_t  RESERVED8[45];
00537   __IO uint32_t  SHORTS ;                            /*!< Shortcuts for TWI.                                                    */
00538   __I  uint32_t  RESERVED9[64];
00539   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00540   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00541   __I  uint32_t  RESERVED10[110];
00542   __IO uint32_t  ERRORSRC ;                          /*!< Two-wire error source. Write error field to 1 to clear error.         */
00543   __I  uint32_t  RESERVED11[14];
00544   __IO uint32_t  ENABLE ;                            /*!< Enable two-wire master.                                               */
00545   __I  uint32_t  RESERVED12;
00546   __IO uint32_t  PSELSCL ;                           /*!< Pin select for SCL.                                                   */
00547   __IO uint32_t  PSELSDA ;                           /*!< Pin select for SDA.                                                   */
00548   __I  uint32_t  RESERVED13[2];
00549   __I  uint32_t  RXD ;                               /*!< RX data register.                                                     */
00550   __IO uint32_t  TXD ;                               /*!< TX data register.                                                     */
00551   __I  uint32_t  RESERVED14;
00552   __IO uint32_t  FREQUENCY ;                         /*!< Two-wire frequency.                                                   */
00553   __I  uint32_t  RESERVED15[24];
00554   __IO uint32_t  ADDRESS ;                           /*!< Address used in the two-wire transfer.                                */
00555   __I  uint32_t  RESERVED16[668];
00556   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
00557 } NRF_TWI_Type;
00558 
00559 
00560 /* ================================================================================ */
00561 /* ================                      SPIS                      ================ */
00562 /* ================================================================================ */
00563 
00564 
00565 /**
00566   * @brief SPI slave 1. (SPIS)
00567   */
00568 
00569 typedef struct {                                    /*!< SPIS Structure                                                        */
00570   __I  uint32_t  RESERVED0[9];
00571   __O  uint32_t  TASKS_ACQUIRE ;                     /*!< Acquire SPI semaphore.                                                */
00572   __O  uint32_t  TASKS_RELEASE ;                     /*!< Release SPI semaphore.                                                */
00573   __I  uint32_t  RESERVED1[54];
00574   __IO uint32_t  EVENTS_END ;                        /*!< Granted transaction completed.                                        */
00575   __I  uint32_t  RESERVED2[8];
00576   __IO uint32_t  EVENTS_ACQUIRED ;                   /*!< Semaphore acquired.                                                   */
00577   __I  uint32_t  RESERVED3[53];
00578   __IO uint32_t  SHORTS ;                            /*!< Shortcuts for SPIS.                                                   */
00579   __I  uint32_t  RESERVED4[64];
00580   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00581   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00582   __I  uint32_t  RESERVED5[61];
00583   __I  uint32_t  SEMSTAT ;                           /*!< Semaphore status.                                                     */
00584   __I  uint32_t  RESERVED6[15];
00585   __IO uint32_t  STATUS ;                            /*!< Status from last transaction.                                         */
00586   __I  uint32_t  RESERVED7[47];
00587   __IO uint32_t  ENABLE ;                            /*!< Enable SPIS.                                                          */
00588   __I  uint32_t  RESERVED8;
00589   __IO uint32_t  PSELSCK ;                           /*!< Pin select for SCK.                                                   */
00590   __IO uint32_t  PSELMISO ;                          /*!< Pin select for MISO.                                                  */
00591   __IO uint32_t  PSELMOSI ;                          /*!< Pin select for MOSI.                                                  */
00592   __IO uint32_t  PSELCSN ;                           /*!< Pin select for CSN.                                                   */
00593   __I  uint32_t  RESERVED9[7];
00594   __IO uint32_t  RXDPTR ;                            /*!< RX data pointer.                                                      */
00595   __IO uint32_t  MAXRX ;                             /*!< Maximum number of bytes in the receive buffer.                        */
00596   __I  uint32_t  AMOUNTRX ;                          /*!< Number of bytes received in last granted transaction.                 */
00597   __I  uint32_t  RESERVED10;
00598   __IO uint32_t  TXDPTR ;                            /*!< TX data pointer.                                                      */
00599   __IO uint32_t  MAXTX ;                             /*!< Maximum number of bytes in the transmit buffer.                       */
00600   __I  uint32_t  AMOUNTTX ;                          /*!< Number of bytes transmitted in last granted transaction.              */
00601   __I  uint32_t  RESERVED11;
00602   __IO uint32_t  CONFIG ;                            /*!< Configuration register.                                               */
00603   __I  uint32_t  RESERVED12;
00604   __IO uint32_t  DEF ;                               /*!< Default character.                                                    */
00605   __I  uint32_t  RESERVED13[24];
00606   __IO uint32_t  ORC ;                               /*!< Over-read character.                                                  */
00607   __I  uint32_t  RESERVED14[654];
00608   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
00609 } NRF_SPIS_Type;
00610 
00611 
00612 /* ================================================================================ */
00613 /* ================                      SPIM                      ================ */
00614 /* ================================================================================ */
00615 
00616 
00617 /**
00618   * @brief SPI master with easyDMA 1. (SPIM)
00619   */
00620 
00621 typedef struct {                                    /*!< SPIM Structure                                                        */
00622   __I  uint32_t  RESERVED0[4];
00623   __O  uint32_t  TASKS_START ;                       /*!< Start SPI transaction.                                                */
00624   __O  uint32_t  TASKS_STOP ;                        /*!< Stop SPI transaction.                                                 */
00625   __I  uint32_t  RESERVED1;
00626   __O  uint32_t  TASKS_SUSPEND ;                     /*!< Suspend SPI transaction.                                              */
00627   __O  uint32_t  TASKS_RESUME ;                      /*!< Resume SPI transaction.                                               */
00628   __I  uint32_t  RESERVED2[56];
00629   __IO uint32_t  EVENTS_STOPPED ;                    /*!< SPI transaction has stopped.                                          */
00630   __I  uint32_t  RESERVED3[2];
00631   __IO uint32_t  EVENTS_ENDRX ;                      /*!< End of RXD buffer reached.                                            */
00632   __I  uint32_t  RESERVED4;
00633   __IO uint32_t  EVENTS_END ;                        /*!< End of RXD buffer and TXD buffer reached.                             */
00634   __I  uint32_t  RESERVED5;
00635   __IO uint32_t  EVENTS_ENDTX ;                      /*!< End of TXD buffer reached.                                            */
00636   __I  uint32_t  RESERVED6[10];
00637   __IO uint32_t  EVENTS_STARTED ;                    /*!< Transaction started.                                                  */
00638   __I  uint32_t  RESERVED7[44];
00639   __IO uint32_t  SHORTS ;                            /*!< Shortcuts for SPIM.                                                   */
00640   __I  uint32_t  RESERVED8[64];
00641   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00642   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00643   __I  uint32_t  RESERVED9[125];
00644   __IO uint32_t  ENABLE ;                            /*!< Enable SPIM.                                                          */
00645   __I  uint32_t  RESERVED10;
00646   SPIM_PSEL_Type PSEL ;                              /*!< Pin select configuration.                                             */
00647   __I  uint32_t  RESERVED11;
00648   __I  uint32_t  RXDDATA ;                           /*!< RXD register.                                                         */
00649   __IO uint32_t  TXDDATA ;                           /*!< TXD register.                                                         */
00650   __I  uint32_t  RESERVED12;
00651   __IO uint32_t  FREQUENCY ;                         /*!< SPI frequency.                                                        */
00652   __I  uint32_t  RESERVED13[3];
00653   SPIM_RXD_Type RXD ;                                /*!< RXD EasyDMA configuration and status.                                 */
00654   __I  uint32_t  RESERVED14;
00655   SPIM_TXD_Type TXD ;                                /*!< TXD EasyDMA configuration and status.                                 */
00656   __I  uint32_t  RESERVED15;
00657   __IO uint32_t  CONFIG ;                            /*!< Configuration register.                                               */
00658   __I  uint32_t  RESERVED16[26];
00659   __IO uint32_t  ORC ;                               /*!< Over-read character.                                                  */
00660   __I  uint32_t  RESERVED17[654];
00661   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
00662 } NRF_SPIM_Type;
00663 
00664 
00665 /* ================================================================================ */
00666 /* ================                     GPIOTE                     ================ */
00667 /* ================================================================================ */
00668 
00669 
00670 /**
00671   * @brief GPIO tasks and events. (GPIOTE)
00672   */
00673 
00674 typedef struct {                                    /*!< GPIOTE Structure                                                      */
00675   __O  uint32_t  TASKS_OUT[4];                      /*!< Tasks asssociated with GPIOTE channels.                               */
00676   __I  uint32_t  RESERVED0[60];
00677   __IO uint32_t  EVENTS_IN[4];                      /*!< Tasks asssociated with GPIOTE channels.                               */
00678   __I  uint32_t  RESERVED1[27];
00679   __IO uint32_t  EVENTS_PORT ;                       /*!< Event generated from multiple pins.                                   */
00680   __I  uint32_t  RESERVED2[97];
00681   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00682   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00683   __I  uint32_t  RESERVED3[129];
00684   __IO uint32_t  CONFIG[4];                         /*!< Channel configuration registers.                                      */
00685   __I  uint32_t  RESERVED4[695];
00686   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
00687 } NRF_GPIOTE_Type;
00688 
00689 
00690 /* ================================================================================ */
00691 /* ================                       ADC                      ================ */
00692 /* ================================================================================ */
00693 
00694 
00695 /**
00696   * @brief Analog to digital converter. (ADC)
00697   */
00698 
00699 typedef struct {                                    /*!< ADC Structure                                                         */
00700   __O  uint32_t  TASKS_START ;                       /*!< Start an ADC conversion.                                              */
00701   __O  uint32_t  TASKS_STOP ;                        /*!< Stop ADC.                                                             */
00702   __I  uint32_t  RESERVED0[62];
00703   __IO uint32_t  EVENTS_END ;                        /*!< ADC conversion complete.                                              */
00704   __I  uint32_t  RESERVED1[128];
00705   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00706   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00707   __I  uint32_t  RESERVED2[61];
00708   __I  uint32_t  BUSY ;                              /*!< ADC busy register.                                                    */
00709   __I  uint32_t  RESERVED3[63];
00710   __IO uint32_t  ENABLE ;                            /*!< ADC enable.                                                           */
00711   __IO uint32_t  CONFIG ;                            /*!< ADC configuration register.                                           */
00712   __I  uint32_t  RESULT ;                            /*!< Result of ADC conversion.                                             */
00713   __I  uint32_t  RESERVED4[700];
00714   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
00715 } NRF_ADC_Type;
00716 
00717 
00718 /* ================================================================================ */
00719 /* ================                      TIMER                     ================ */
00720 /* ================================================================================ */
00721 
00722 
00723 /**
00724   * @brief Timer 0. (TIMER)
00725   */
00726 
00727 typedef struct {                                    /*!< TIMER Structure                                                       */
00728   __O  uint32_t  TASKS_START ;                       /*!< Start Timer.                                                          */
00729   __O  uint32_t  TASKS_STOP ;                        /*!< Stop Timer.                                                           */
00730   __O  uint32_t  TASKS_COUNT ;                       /*!< Increment Timer (In counter mode).                                    */
00731   __O  uint32_t  TASKS_CLEAR ;                       /*!< Clear timer.                                                          */
00732   __O  uint32_t  TASKS_SHUTDOWN ;                    /*!< Shutdown timer.                                                       */
00733   __I  uint32_t  RESERVED0[11];
00734   __O  uint32_t  TASKS_CAPTURE[4];                  /*!< Capture Timer value to CC[n] registers.                               */
00735   __I  uint32_t  RESERVED1[60];
00736   __IO uint32_t  EVENTS_COMPARE[4];                 /*!< Compare event on CC[n] match.                                         */
00737   __I  uint32_t  RESERVED2[44];
00738   __IO uint32_t  SHORTS ;                            /*!< Shortcuts for Timer.                                                  */
00739   __I  uint32_t  RESERVED3[64];
00740   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00741   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00742   __I  uint32_t  RESERVED4[126];
00743   __IO uint32_t  MODE ;                              /*!< Timer Mode selection.                                                 */
00744   __IO uint32_t  BITMODE ;                           /*!< Sets timer behaviour.                                                 */
00745   __I  uint32_t  RESERVED5;
00746   __IO uint32_t  PRESCALER;                         /*!< 4-bit prescaler to source clock frequency (max value 9). Source
00747                                                          clock frequency is divided by 2^SCALE.                                */
00748   __I  uint32_t  RESERVED6[11];
00749   __IO uint32_t  CC[4];                             /*!< Capture/compare registers.                                            */
00750   __I  uint32_t  RESERVED7[683];
00751   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
00752 } NRF_TIMER_Type;
00753 
00754 
00755 /* ================================================================================ */
00756 /* ================                       RTC                      ================ */
00757 /* ================================================================================ */
00758 
00759 
00760 /**
00761   * @brief Real time counter 0. (RTC)
00762   */
00763 
00764 typedef struct {                                    /*!< RTC Structure                                                         */
00765   __O  uint32_t  TASKS_START ;                       /*!< Start RTC Counter.                                                    */
00766   __O  uint32_t  TASKS_STOP ;                        /*!< Stop RTC Counter.                                                     */
00767   __O  uint32_t  TASKS_CLEAR ;                       /*!< Clear RTC Counter.                                                    */
00768   __O  uint32_t  TASKS_TRIGOVRFLW ;                  /*!< Set COUNTER to 0xFFFFFFF0.                                            */
00769   __I  uint32_t  RESERVED0[60];
00770   __IO uint32_t  EVENTS_TICK ;                       /*!< Event on COUNTER increment.                                           */
00771   __IO uint32_t  EVENTS_OVRFLW ;                     /*!< Event on COUNTER overflow.                                            */
00772   __I  uint32_t  RESERVED1[14];
00773   __IO uint32_t  EVENTS_COMPARE[4];                 /*!< Compare event on CC[n] match.                                         */
00774   __I  uint32_t  RESERVED2[109];
00775   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00776   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00777   __I  uint32_t  RESERVED3[13];
00778   __IO uint32_t  EVTEN ;                             /*!< Configures event enable routing to PPI for each RTC event.            */
00779   __IO uint32_t  EVTENSET;                          /*!< Enable events routing to PPI. The reading of this register gives
00780                                                          the value of EVTEN.                                                   */
00781   __IO uint32_t  EVTENCLR;                          /*!< Disable events routing to PPI. The reading of this register
00782                                                          gives the value of EVTEN.                                             */
00783   __I  uint32_t  RESERVED4[110];
00784   __I  uint32_t  COUNTER ;                           /*!< Current COUNTER value.                                                */
00785   __IO uint32_t  PRESCALER;                         /*!< 12-bit prescaler for COUNTER frequency (32768/(PRESCALER+1)).
00786                                                          Must be written when RTC is STOPed.                                   */
00787   __I  uint32_t  RESERVED5[13];
00788   __IO uint32_t  CC[4];                             /*!< Capture/compare registers.                                            */
00789   __I  uint32_t  RESERVED6[683];
00790   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
00791 } NRF_RTC_Type;
00792 
00793 
00794 /* ================================================================================ */
00795 /* ================                      TEMP                      ================ */
00796 /* ================================================================================ */
00797 
00798 
00799 /**
00800   * @brief Temperature Sensor. (TEMP)
00801   */
00802 
00803 typedef struct {                                    /*!< TEMP Structure                                                        */
00804   __O  uint32_t  TASKS_START ;                       /*!< Start temperature measurement.                                        */
00805   __O  uint32_t  TASKS_STOP ;                        /*!< Stop temperature measurement.                                         */
00806   __I  uint32_t  RESERVED0[62];
00807   __IO uint32_t  EVENTS_DATARDY ;                    /*!< Temperature measurement complete, data ready event.                   */
00808   __I  uint32_t  RESERVED1[128];
00809   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00810   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00811   __I  uint32_t  RESERVED2[127];
00812   __I  int32_t   TEMP ;                              /*!< Die temperature in degC, 2's complement format, 0.25 degC pecision.   */
00813   __I  uint32_t  RESERVED3[700];
00814   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
00815 } NRF_TEMP_Type;
00816 
00817 
00818 /* ================================================================================ */
00819 /* ================                       RNG                      ================ */
00820 /* ================================================================================ */
00821 
00822 
00823 /**
00824   * @brief Random Number Generator. (RNG)
00825   */
00826 
00827 typedef struct {                                    /*!< RNG Structure                                                         */
00828   __O  uint32_t  TASKS_START ;                       /*!< Start the random number generator.                                    */
00829   __O  uint32_t  TASKS_STOP ;                        /*!< Stop the random number generator.                                     */
00830   __I  uint32_t  RESERVED0[62];
00831   __IO uint32_t  EVENTS_VALRDY ;                     /*!< New random number generated and written to VALUE register.            */
00832   __I  uint32_t  RESERVED1[63];
00833   __IO uint32_t  SHORTS ;                            /*!< Shortcuts for the RNG.                                                */
00834   __I  uint32_t  RESERVED2[64];
00835   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register                                         */
00836   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register                                       */
00837   __I  uint32_t  RESERVED3[126];
00838   __IO uint32_t  CONFIG ;                            /*!< Configuration register.                                               */
00839   __I  uint32_t  VALUE ;                             /*!< RNG random number.                                                    */
00840   __I  uint32_t  RESERVED4[700];
00841   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
00842 } NRF_RNG_Type;
00843 
00844 
00845 /* ================================================================================ */
00846 /* ================                       ECB                      ================ */
00847 /* ================================================================================ */
00848 
00849 
00850 /**
00851   * @brief AES ECB Mode Encryption. (ECB)
00852   */
00853 
00854 typedef struct {                                    /*!< ECB Structure                                                         */
00855   __O  uint32_t  TASKS_STARTECB;                    /*!< Start ECB block encrypt. If a crypto operation is running, this
00856                                                          will not initiate a new encryption and the ERRORECB event will
00857                                                           be triggered.                                                        */
00858   __O  uint32_t  TASKS_STOPECB;                     /*!< Stop current ECB encryption. If a crypto operation is running,
00859                                                          this will will trigger the ERRORECB event.                            */
00860   __I  uint32_t  RESERVED0[62];
00861   __IO uint32_t  EVENTS_ENDECB ;                     /*!< ECB block encrypt complete.                                           */
00862   __IO uint32_t  EVENTS_ERRORECB;                   /*!< ECB block encrypt aborted due to a STOPECB task or due to an
00863                                                          error.                                                                */
00864   __I  uint32_t  RESERVED1[127];
00865   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00866   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00867   __I  uint32_t  RESERVED2[126];
00868   __IO uint32_t  ECBDATAPTR ;                        /*!< ECB block encrypt memory pointer.                                     */
00869   __I  uint32_t  RESERVED3[701];
00870   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
00871 } NRF_ECB_Type;
00872 
00873 
00874 /* ================================================================================ */
00875 /* ================                       AAR                      ================ */
00876 /* ================================================================================ */
00877 
00878 
00879 /**
00880   * @brief Accelerated Address Resolver. (AAR)
00881   */
00882 
00883 typedef struct {                                    /*!< AAR Structure                                                         */
00884   __O  uint32_t  TASKS_START;                       /*!< Start resolving addresses based on IRKs specified in the IRK
00885                                                          data structure.                                                       */
00886   __I  uint32_t  RESERVED0;
00887   __O  uint32_t  TASKS_STOP ;                        /*!< Stop resolving addresses.                                             */
00888   __I  uint32_t  RESERVED1[61];
00889   __IO uint32_t  EVENTS_END ;                        /*!< Address resolution procedure completed.                               */
00890   __IO uint32_t  EVENTS_RESOLVED ;                   /*!< Address resolved.                                                     */
00891   __IO uint32_t  EVENTS_NOTRESOLVED ;                /*!< Address not resolved.                                                 */
00892   __I  uint32_t  RESERVED2[126];
00893   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00894   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00895   __I  uint32_t  RESERVED3[61];
00896   __I  uint32_t  STATUS ;                            /*!< Resolution status.                                                    */
00897   __I  uint32_t  RESERVED4[63];
00898   __IO uint32_t  ENABLE ;                            /*!< Enable AAR.                                                           */
00899   __IO uint32_t  NIRK ;                              /*!< Number of Identity root Keys in the IRK data structure.               */
00900   __IO uint32_t  IRKPTR ;                            /*!< Pointer to the IRK data structure.                                    */
00901   __I  uint32_t  RESERVED5;
00902   __IO uint32_t  ADDRPTR ;                           /*!< Pointer to the resolvable address (6 bytes).                          */
00903   __IO uint32_t  SCRATCHPTR;                        /*!< Pointer to a "scratch" data area used for temporary storage
00904                                                          during resolution. A minimum of 3 bytes must be reserved.             */
00905   __I  uint32_t  RESERVED6[697];
00906   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
00907 } NRF_AAR_Type;
00908 
00909 
00910 /* ================================================================================ */
00911 /* ================                       CCM                      ================ */
00912 /* ================================================================================ */
00913 
00914 
00915 /**
00916   * @brief AES CCM Mode Encryption. (CCM)
00917   */
00918 
00919 typedef struct {                                    /*!< CCM Structure                                                         */
00920   __O  uint32_t  TASKS_KSGEN;                       /*!< Start generation of key-stream. This operation will stop by
00921                                                          itself when completed.                                                */
00922   __O  uint32_t  TASKS_CRYPT;                       /*!< Start encrypt/decrypt. This operation will stop by itself when
00923                                                          completed.                                                            */
00924   __O  uint32_t  TASKS_STOP ;                        /*!< Stop encrypt/decrypt.                                                 */
00925   __I  uint32_t  RESERVED0[61];
00926   __IO uint32_t  EVENTS_ENDKSGEN ;                   /*!< Keystream generation completed.                                       */
00927   __IO uint32_t  EVENTS_ENDCRYPT ;                   /*!< Encrypt/decrypt completed.                                            */
00928   __IO uint32_t  EVENTS_ERROR ;                      /*!< Error happened.                                                       */
00929   __I  uint32_t  RESERVED1[61];
00930   __IO uint32_t  SHORTS ;                            /*!< Shortcuts for the CCM.                                                */
00931   __I  uint32_t  RESERVED2[64];
00932   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00933   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00934   __I  uint32_t  RESERVED3[61];
00935   __I  uint32_t  MICSTATUS ;                         /*!< CCM RX MIC check result.                                              */
00936   __I  uint32_t  RESERVED4[63];
00937   __IO uint32_t  ENABLE ;                            /*!< CCM enable.                                                           */
00938   __IO uint32_t  MODE ;                              /*!< Operation mode.                                                       */
00939   __IO uint32_t  CNFPTR ;                            /*!< Pointer to a data structure holding AES key and NONCE vector.         */
00940   __IO uint32_t  INPTR ;                             /*!< Pointer to the input packet.                                          */
00941   __IO uint32_t  OUTPTR ;                            /*!< Pointer to the output packet.                                         */
00942   __IO uint32_t  SCRATCHPTR;                        /*!< Pointer to a "scratch" data area used for temporary storage
00943                                                          during resolution. A minimum of 43 bytes must be reserved.            */
00944   __I  uint32_t  RESERVED5[697];
00945   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
00946 } NRF_CCM_Type;
00947 
00948 
00949 /* ================================================================================ */
00950 /* ================                       WDT                      ================ */
00951 /* ================================================================================ */
00952 
00953 
00954 /**
00955   * @brief Watchdog Timer. (WDT)
00956   */
00957 
00958 typedef struct {                                    /*!< WDT Structure                                                         */
00959   __O  uint32_t  TASKS_START ;                       /*!< Start the watchdog.                                                   */
00960   __I  uint32_t  RESERVED0[63];
00961   __IO uint32_t  EVENTS_TIMEOUT ;                    /*!< Watchdog timeout.                                                     */
00962   __I  uint32_t  RESERVED1[128];
00963   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
00964   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
00965   __I  uint32_t  RESERVED2[61];
00966   __I  uint32_t  RUNSTATUS ;                         /*!< Watchdog running status.                                              */
00967   __I  uint32_t  REQSTATUS ;                         /*!< Request status.                                                       */
00968   __I  uint32_t  RESERVED3[63];
00969   __IO uint32_t  CRV ;                               /*!< Counter reload value in number of 32kiHz clock cycles.                */
00970   __IO uint32_t  RREN ;                              /*!< Reload request enable.                                                */
00971   __IO uint32_t  CONFIG ;                            /*!< Configuration register.                                               */
00972   __I  uint32_t  RESERVED4[60];
00973   __O  uint32_t  RR[8];                             /*!< Reload requests registers.                                            */
00974   __I  uint32_t  RESERVED5[631];
00975   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
00976 } NRF_WDT_Type;
00977 
00978 
00979 /* ================================================================================ */
00980 /* ================                      QDEC                      ================ */
00981 /* ================================================================================ */
00982 
00983 
00984 /**
00985   * @brief Rotary decoder. (QDEC)
00986   */
00987 
00988 typedef struct {                                    /*!< QDEC Structure                                                        */
00989   __O  uint32_t  TASKS_START ;                       /*!< Start the quadrature decoder.                                         */
00990   __O  uint32_t  TASKS_STOP ;                        /*!< Stop the quadrature decoder.                                          */
00991   __O  uint32_t  TASKS_READCLRACC;                  /*!< Transfers the content from ACC registers to ACCREAD registers,
00992                                                          and clears the ACC registers.                                         */
00993   __I  uint32_t  RESERVED0[61];
00994   __IO uint32_t  EVENTS_SAMPLERDY ;                  /*!< A new sample is written to the sample register.                       */
00995   __IO uint32_t  EVENTS_REPORTRDY;                  /*!< REPORTPER number of samples accumulated in ACC register, and
00996                                                          ACC register different than zero.                                     */
00997   __IO uint32_t  EVENTS_ACCOF ;                      /*!< ACC or ACCDBL register overflow.                                      */
00998   __I  uint32_t  RESERVED1[61];
00999   __IO uint32_t  SHORTS ;                            /*!< Shortcuts for the QDEC.                                               */
01000   __I  uint32_t  RESERVED2[64];
01001   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
01002   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
01003   __I  uint32_t  RESERVED3[125];
01004   __IO uint32_t  ENABLE ;                            /*!< Enable the QDEC.                                                      */
01005   __IO uint32_t  LEDPOL ;                            /*!< LED output pin polarity.                                              */
01006   __IO uint32_t  SAMPLEPER ;                         /*!< Sample period.                                                        */
01007   __I  int32_t   SAMPLE ;                            /*!< Motion sample value.                                                  */
01008   __IO uint32_t  REPORTPER ;                         /*!< Number of samples to generate an EVENT_REPORTRDY.                     */
01009   __I  int32_t   ACC ;                               /*!< Accumulated valid transitions register.                               */
01010   __I  int32_t   ACCREAD;                           /*!< Snapshot of ACC register. Value generated by the TASKS_READCLEACC
01011                                                          task.                                                                 */
01012   __IO uint32_t  PSELLED ;                           /*!< Pin select for LED output.                                            */
01013   __IO uint32_t  PSELA ;                             /*!< Pin select for phase A input.                                         */
01014   __IO uint32_t  PSELB ;                             /*!< Pin select for phase B input.                                         */
01015   __IO uint32_t  DBFEN ;                             /*!< Enable debouncer input filters.                                       */
01016   __I  uint32_t  RESERVED4[5];
01017   __IO uint32_t  LEDPRE ;                            /*!< Time LED is switched ON before the sample.                            */
01018   __I  uint32_t  ACCDBL ;                            /*!< Accumulated double (error) transitions register.                      */
01019   __I  uint32_t  ACCDBLREAD;                        /*!< Snapshot of ACCDBL register. Value generated by the TASKS_READCLEACC
01020                                                          task.                                                                 */
01021   __I  uint32_t  RESERVED5[684];
01022   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
01023 } NRF_QDEC_Type;
01024 
01025 
01026 /* ================================================================================ */
01027 /* ================                     LPCOMP                     ================ */
01028 /* ================================================================================ */
01029 
01030 
01031 /**
01032   * @brief Low power comparator. (LPCOMP)
01033   */
01034 
01035 typedef struct {                                    /*!< LPCOMP Structure                                                      */
01036   __O  uint32_t  TASKS_START ;                       /*!< Start the comparator.                                                 */
01037   __O  uint32_t  TASKS_STOP ;                        /*!< Stop the comparator.                                                  */
01038   __O  uint32_t  TASKS_SAMPLE ;                      /*!< Sample comparator value.                                              */
01039   __I  uint32_t  RESERVED0[61];
01040   __IO uint32_t  EVENTS_READY ;                      /*!< LPCOMP is ready and output is valid.                                  */
01041   __IO uint32_t  EVENTS_DOWN ;                       /*!< Input voltage crossed the threshold going down.                       */
01042   __IO uint32_t  EVENTS_UP ;                         /*!< Input voltage crossed the threshold going up.                         */
01043   __IO uint32_t  EVENTS_CROSS ;                      /*!< Input voltage crossed the threshold in any direction.                 */
01044   __I  uint32_t  RESERVED1[60];
01045   __IO uint32_t  SHORTS ;                            /*!< Shortcuts for the LPCOMP.                                             */
01046   __I  uint32_t  RESERVED2[64];
01047   __IO uint32_t  INTENSET ;                          /*!< Interrupt enable set register.                                        */
01048   __IO uint32_t  INTENCLR ;                          /*!< Interrupt enable clear register.                                      */
01049   __I  uint32_t  RESERVED3[61];
01050   __I  uint32_t  RESULT ;                            /*!< Result of last compare.                                               */
01051   __I  uint32_t  RESERVED4[63];
01052   __IO uint32_t  ENABLE ;                            /*!< Enable the LPCOMP.                                                    */
01053   __IO uint32_t  PSEL ;                              /*!< Input pin select.                                                     */
01054   __IO uint32_t  REFSEL ;                            /*!< Reference select.                                                     */
01055   __IO uint32_t  EXTREFSEL ;                         /*!< External reference select.                                            */
01056   __I  uint32_t  RESERVED5[4];
01057   __IO uint32_t  ANADETECT ;                         /*!< Analog detect configuration.                                          */
01058   __I  uint32_t  RESERVED6[694];
01059   __IO uint32_t  POWER ;                             /*!< Peripheral power control.                                             */
01060 } NRF_LPCOMP_Type;
01061 
01062 
01063 /* ================================================================================ */
01064 /* ================                       SWI                      ================ */
01065 /* ================================================================================ */
01066 
01067 
01068 /**
01069   * @brief SW Interrupts. (SWI)
01070   */
01071 
01072 typedef struct {                                    /*!< SWI Structure                                                         */
01073   __I  uint32_t  UNUSED ;                            /*!< Unused.                                                               */
01074 } NRF_SWI_Type;
01075 
01076 
01077 /* ================================================================================ */
01078 /* ================                      NVMC                      ================ */
01079 /* ================================================================================ */
01080 
01081 
01082 /**
01083   * @brief Non Volatile Memory Controller. (NVMC)
01084   */
01085 
01086 typedef struct {                                    /*!< NVMC Structure                                                        */
01087   __I  uint32_t  RESERVED0[256];
01088   __I  uint32_t  READY ;                             /*!< Ready flag.                                                           */
01089   __I  uint32_t  RESERVED1[64];
01090   __IO uint32_t  CONFIG ;                            /*!< Configuration register.                                               */
01091   __IO uint32_t  ERASEPAGE ;                         /*!< Register for erasing a non-protected non-volatile memory page.        */
01092   __IO uint32_t  ERASEALL ;                          /*!< Register for erasing all non-volatile user memory.                    */
01093   __IO uint32_t  ERASEPROTECTEDPAGE ;                /*!< Register for erasing a protected non-volatile memory page.            */
01094   __IO uint32_t  ERASEUICR ;                         /*!< Register for start erasing User Information Congfiguration Registers. */
01095 } NRF_NVMC_Type;
01096 
01097 
01098 /* ================================================================================ */
01099 /* ================                       PPI                      ================ */
01100 /* ================================================================================ */
01101 
01102 
01103 /**
01104   * @brief PPI controller. (PPI)
01105   */
01106 
01107 typedef struct {                                    /*!< PPI Structure                                                         */
01108   PPI_TASKS_CHG_Type TASKS_CHG[4];                  /*!< Channel group tasks.                                                  */
01109   __I  uint32_t  RESERVED0[312];
01110   __IO uint32_t  CHEN ;                              /*!< Channel enable.                                                       */
01111   __IO uint32_t  CHENSET ;                           /*!< Channel enable set.                                                   */
01112   __IO uint32_t  CHENCLR ;                           /*!< Channel enable clear.                                                 */
01113   __I  uint32_t  RESERVED1;
01114   PPI_CH_Type CH[16];                               /*!< PPI Channel.                                                          */
01115   __I  uint32_t  RESERVED2[156];
01116   __IO uint32_t  CHG[4];                            /*!< Channel group configuration.                                          */
01117 } NRF_PPI_Type;
01118 
01119 
01120 /* ================================================================================ */
01121 /* ================                      FICR                      ================ */
01122 /* ================================================================================ */
01123 
01124 
01125 /**
01126   * @brief Factory Information Configuration. (FICR)
01127   */
01128 
01129 typedef struct {                                    /*!< FICR Structure                                                        */
01130   __I  uint32_t  RESERVED0[4];
01131   __I  uint32_t  CODEPAGESIZE ;                      /*!< Code memory page size in bytes.                                       */
01132   __I  uint32_t  CODESIZE ;                          /*!< Code memory size in pages.                                            */
01133   __I  uint32_t  RESERVED1[4];
01134   __I  uint32_t  CLENR0 ;                            /*!< Length of code region 0 in bytes.                                     */
01135   __I  uint32_t  PPFC ;                              /*!< Pre-programmed factory code present.                                  */
01136   __I  uint32_t  RESERVED2;
01137   __I  uint32_t  NUMRAMBLOCK ;                       /*!< Number of individualy controllable RAM blocks.                        */
01138   
01139   union {
01140     __I  uint32_t  SIZERAMBLOCK[4];                 /*!< Deprecated array of size of RAM block in bytes. This name is
01141                                                          kept for backward compatinility purposes. Use SIZERAMBLOCKS
01142                                                           instead.                                                             */
01143     __I  uint32_t  SIZERAMBLOCKS ;                   /*!< Size of RAM blocks in bytes.                                          */
01144   };
01145   __I  uint32_t  RESERVED3[5];
01146   __I  uint32_t  CONFIGID ;                          /*!< Configuration identifier.                                             */
01147   __I  uint32_t  DEVICEID[2];                       /*!< Device identifier.                                                    */
01148   __I  uint32_t  RESERVED4[6];
01149   __I  uint32_t  ER[4];                             /*!< Encryption root.                                                      */
01150   __I  uint32_t  IR[4];                             /*!< Identity root.                                                        */
01151   __I  uint32_t  DEVICEADDRTYPE ;                    /*!< Device address type.                                                  */
01152   __I  uint32_t  DEVICEADDR[2];                     /*!< Device address.                                                       */
01153   __I  uint32_t  OVERRIDEEN ;                        /*!< Radio calibration override enable.                                    */
01154   __I  uint32_t  NRF_1MBIT[5];                      /*!< Override values for the OVERRIDEn registers in RADIO for NRF_1Mbit
01155                                                          mode.                                                                 */
01156   __I  uint32_t  RESERVED5[10];
01157   __I  uint32_t  BLE_1MBIT[5];                      /*!< Override values for the OVERRIDEn registers in RADIO for BLE_1Mbit
01158                                                          mode.                                                                 */
01159   FICR_INFO_Type INFO ;                              /*!< Device info                                                           */
01160 } NRF_FICR_Type;
01161 
01162 
01163 /* ================================================================================ */
01164 /* ================                      UICR                      ================ */
01165 /* ================================================================================ */
01166 
01167 
01168 /**
01169   * @brief User Information Configuration. (UICR)
01170   */
01171 
01172 typedef struct {                                    /*!< UICR Structure                                                        */
01173   __IO uint32_t  CLENR0 ;                            /*!< Length of code region 0.                                              */
01174   __IO uint32_t  RBPCONF ;                           /*!< Readback protection configuration.                                    */
01175   __IO uint32_t  XTALFREQ ;                          /*!< Reset value for CLOCK XTALFREQ register.                              */
01176   __I  uint32_t  RESERVED0;
01177   __I  uint32_t  FWID ;                              /*!< Firmware ID.                                                          */
01178   __IO uint32_t  BOOTLOADERADDR ;                    /*!< Bootloader start address.                                             */
01179 } NRF_UICR_Type;
01180 
01181 
01182 /* ================================================================================ */
01183 /* ================                      GPIO                      ================ */
01184 /* ================================================================================ */
01185 
01186 
01187 /**
01188   * @brief General purpose input and output. (GPIO)
01189   */
01190 
01191 typedef struct {                                    /*!< GPIO Structure                                                        */
01192   __I  uint32_t  RESERVED0[321];
01193   __IO uint32_t  OUT ;                               /*!< Write GPIO port.                                                      */
01194   __IO uint32_t  OUTSET ;                            /*!< Set individual bits in GPIO port.                                     */
01195   __IO uint32_t  OUTCLR ;                            /*!< Clear individual bits in GPIO port.                                   */
01196   __I  uint32_t  IN ;                                /*!< Read GPIO port.                                                       */
01197   __IO uint32_t  DIR ;                               /*!< Direction of GPIO pins.                                               */
01198   __IO uint32_t  DIRSET ;                            /*!< DIR set register.                                                     */
01199   __IO uint32_t  DIRCLR ;                            /*!< DIR clear register.                                                   */
01200   __I  uint32_t  RESERVED1[120];
01201   __IO uint32_t  PIN_CNF[32];                       /*!< Configuration of GPIO pins.                                           */
01202 } NRF_GPIO_Type;
01203 
01204 
01205 /* --------------------  End of section using anonymous unions  ------------------- */
01206 #if defined(__CC_ARM)
01207   #pragma pop
01208 #elif defined(__ICCARM__)
01209   /* leave anonymous unions enabled */
01210 #elif defined(__GNUC__)
01211   /* anonymous unions are enabled by default */
01212 #elif defined(__TMS470__)
01213   /* anonymous unions are enabled by default */
01214 #elif defined(__TASKING__)
01215   #pragma warning restore
01216 #else
01217   #warning Not supported compiler type
01218 #endif
01219 
01220 
01221 
01222 
01223 /* ================================================================================ */
01224 /* ================              Peripheral memory map             ================ */
01225 /* ================================================================================ */
01226 
01227 #define NRF_POWER_BASE                  0x40000000UL
01228 #define NRF_CLOCK_BASE                  0x40000000UL
01229 #define NRF_MPU_BASE                    0x40000000UL
01230 #define NRF_PU_BASE                     0x40000000UL
01231 #define NRF_AMLI_BASE                   0x40000000UL
01232 #define NRF_RADIO_BASE                  0x40001000UL
01233 #define NRF_UART0_BASE                  0x40002000UL
01234 #define NRF_SPI0_BASE                   0x40003000UL
01235 #define NRF_TWI0_BASE                   0x40003000UL
01236 #define NRF_SPI1_BASE                   0x40004000UL
01237 #define NRF_TWI1_BASE                   0x40004000UL
01238 #define NRF_SPIS1_BASE                  0x40004000UL
01239 #define NRF_SPIM1_BASE                  0x40004000UL
01240 #define NRF_GPIOTE_BASE                 0x40006000UL
01241 #define NRF_ADC_BASE                    0x40007000UL
01242 #define NRF_TIMER0_BASE                 0x40008000UL
01243 #define NRF_TIMER1_BASE                 0x40009000UL
01244 #define NRF_TIMER2_BASE                 0x4000A000UL
01245 #define NRF_RTC0_BASE                   0x4000B000UL
01246 #define NRF_TEMP_BASE                   0x4000C000UL
01247 #define NRF_RNG_BASE                    0x4000D000UL
01248 #define NRF_ECB_BASE                    0x4000E000UL
01249 #define NRF_AAR_BASE                    0x4000F000UL
01250 #define NRF_CCM_BASE                    0x4000F000UL
01251 #define NRF_WDT_BASE                    0x40010000UL
01252 #define NRF_RTC1_BASE                   0x40011000UL
01253 #define NRF_QDEC_BASE                   0x40012000UL
01254 #define NRF_LPCOMP_BASE                 0x40013000UL
01255 #define NRF_SWI_BASE                    0x40014000UL
01256 #define NRF_NVMC_BASE                   0x4001E000UL
01257 #define NRF_PPI_BASE                    0x4001F000UL
01258 #define NRF_FICR_BASE                   0x10000000UL
01259 #define NRF_UICR_BASE                   0x10001000UL
01260 #define NRF_GPIO_BASE                   0x50000000UL
01261 
01262 
01263 /* ================================================================================ */
01264 /* ================             Peripheral declaration             ================ */
01265 /* ================================================================================ */
01266 
01267 #define NRF_POWER                       ((NRF_POWER_Type          *) NRF_POWER_BASE)
01268 #define NRF_CLOCK                       ((NRF_CLOCK_Type          *) NRF_CLOCK_BASE)
01269 #define NRF_MPU                         ((NRF_MPU_Type            *) NRF_MPU_BASE)
01270 #define NRF_PU                          ((NRF_PU_Type             *) NRF_PU_BASE)
01271 #define NRF_AMLI                        ((NRF_AMLI_Type           *) NRF_AMLI_BASE)
01272 #define NRF_RADIO                       ((NRF_RADIO_Type          *) NRF_RADIO_BASE)
01273 #define NRF_UART0                       ((NRF_UART_Type           *) NRF_UART0_BASE)
01274 #define NRF_SPI0                        ((NRF_SPI_Type            *) NRF_SPI0_BASE)
01275 #define NRF_TWI0                        ((NRF_TWI_Type            *) NRF_TWI0_BASE)
01276 #define NRF_SPI1                        ((NRF_SPI_Type            *) NRF_SPI1_BASE)
01277 #define NRF_TWI1                        ((NRF_TWI_Type            *) NRF_TWI1_BASE)
01278 #define NRF_SPIS1                       ((NRF_SPIS_Type           *) NRF_SPIS1_BASE)
01279 #define NRF_SPIM1                       ((NRF_SPIM_Type           *) NRF_SPIM1_BASE)
01280 #define NRF_GPIOTE                      ((NRF_GPIOTE_Type         *) NRF_GPIOTE_BASE)
01281 #define NRF_ADC                         ((NRF_ADC_Type            *) NRF_ADC_BASE)
01282 #define NRF_TIMER0                      ((NRF_TIMER_Type          *) NRF_TIMER0_BASE)
01283 #define NRF_TIMER1                      ((NRF_TIMER_Type          *) NRF_TIMER1_BASE)
01284 #define NRF_TIMER2                      ((NRF_TIMER_Type          *) NRF_TIMER2_BASE)
01285 #define NRF_RTC0                        ((NRF_RTC_Type            *) NRF_RTC0_BASE)
01286 #define NRF_TEMP                        ((NRF_TEMP_Type           *) NRF_TEMP_BASE)
01287 #define NRF_RNG                         ((NRF_RNG_Type            *) NRF_RNG_BASE)
01288 #define NRF_ECB                         ((NRF_ECB_Type            *) NRF_ECB_BASE)
01289 #define NRF_AAR                         ((NRF_AAR_Type            *) NRF_AAR_BASE)
01290 #define NRF_CCM                         ((NRF_CCM_Type            *) NRF_CCM_BASE)
01291 #define NRF_WDT                         ((NRF_WDT_Type            *) NRF_WDT_BASE)
01292 #define NRF_RTC1                        ((NRF_RTC_Type            *) NRF_RTC1_BASE)
01293 #define NRF_QDEC                        ((NRF_QDEC_Type           *) NRF_QDEC_BASE)
01294 #define NRF_LPCOMP                      ((NRF_LPCOMP_Type         *) NRF_LPCOMP_BASE)
01295 #define NRF_SWI                         ((NRF_SWI_Type            *) NRF_SWI_BASE)
01296 #define NRF_NVMC                        ((NRF_NVMC_Type           *) NRF_NVMC_BASE)
01297 #define NRF_PPI                         ((NRF_PPI_Type            *) NRF_PPI_BASE)
01298 #define NRF_FICR                        ((NRF_FICR_Type           *) NRF_FICR_BASE)
01299 #define NRF_UICR                        ((NRF_UICR_Type           *) NRF_UICR_BASE)
01300 #define NRF_GPIO                        ((NRF_GPIO_Type           *) NRF_GPIO_BASE)
01301 
01302 
01303 /** @} */ /* End of group Device_Peripheral_Registers */
01304 /** @} */ /* End of group nRF51 */
01305 /** @} */ /* End of group Nordic Semiconductor */
01306 
01307 #ifdef __cplusplus
01308 }
01309 #endif
01310 
01311 
01312 #endif  /* nRF51_H */
01313