From e07ebbcac3f9a6bf871ad23b4c6cd0eb0d72809e Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Wed, 29 Apr 2015 19:48:06 -0300 Subject: Add initial system header + makefile --- os/hal/ports/NRF51/NRF51822/nrf51.h | 1313 +++++++++++++++++++++++++++++++ os/hal/ports/NRF51/NRF51822/platform.mk | 8 + 2 files changed, 1321 insertions(+) create mode 100644 os/hal/ports/NRF51/NRF51822/nrf51.h create mode 100644 os/hal/ports/NRF51/NRF51822/platform.mk (limited to 'os') diff --git a/os/hal/ports/NRF51/NRF51822/nrf51.h b/os/hal/ports/NRF51/NRF51822/nrf51.h new file mode 100644 index 0000000..8a9cea2 --- /dev/null +++ b/os/hal/ports/NRF51/NRF51822/nrf51.h @@ -0,0 +1,1313 @@ + +/****************************************************************************************************//** + * @file nrf51.h + * + * @brief CMSIS Cortex-M0 Peripheral Access Layer Header File for + * nrf51 from Nordic Semiconductor. + * + * @version V522 + * @date 26. January 2015 + * + * @note Generated with SVDConv V2.81d + * from CMSIS SVD File 'nrf51.xml' Version 522, + * + * @par Copyright (c) 2013, Nordic Semiconductor ASA + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of Nordic Semiconductor ASA nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + * + *******************************************************************************************************/ + + + +/** @addtogroup Nordic Semiconductor + * @{ + */ + +/** @addtogroup nrf51 + * @{ + */ + +#ifndef NRF51_H +#define NRF51_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* ------------------------- Interrupt Number Definition ------------------------ */ + +typedef enum { +/* ------------------- Cortex-M0 Processor Exceptions Numbers ------------------- */ + Reset_IRQn = -15, /*!< 1 Reset Vector, invoked on Power up and warm reset */ + NonMaskableInt_IRQn = -14, /*!< 2 Non maskable Interrupt, cannot be stopped or preempted */ + HardFault_IRQn = -13, /*!< 3 Hard Fault, all classes of Fault */ + SVCall_IRQn = -5, /*!< 11 System Service Call via SVC instruction */ + DebugMonitor_IRQn = -4, /*!< 12 Debug Monitor */ + PendSV_IRQn = -2, /*!< 14 Pendable request for system service */ + SysTick_IRQn = -1, /*!< 15 System Tick Timer */ +/* ---------------------- nrf51 Specific Interrupt Numbers ---------------------- */ + POWER_CLOCK_IRQn = 0, /*!< 0 POWER_CLOCK */ + RADIO_IRQn = 1, /*!< 1 RADIO */ + UART0_IRQn = 2, /*!< 2 UART0 */ + SPI0_TWI0_IRQn = 3, /*!< 3 SPI0_TWI0 */ + SPI1_TWI1_IRQn = 4, /*!< 4 SPI1_TWI1 */ + GPIOTE_IRQn = 6, /*!< 6 GPIOTE */ + ADC_IRQn = 7, /*!< 7 ADC */ + TIMER0_IRQn = 8, /*!< 8 TIMER0 */ + TIMER1_IRQn = 9, /*!< 9 TIMER1 */ + TIMER2_IRQn = 10, /*!< 10 TIMER2 */ + RTC0_IRQn = 11, /*!< 11 RTC0 */ + TEMP_IRQn = 12, /*!< 12 TEMP */ + RNG_IRQn = 13, /*!< 13 RNG */ + ECB_IRQn = 14, /*!< 14 ECB */ + CCM_AAR_IRQn = 15, /*!< 15 CCM_AAR */ + WDT_IRQn = 16, /*!< 16 WDT */ + RTC1_IRQn = 17, /*!< 17 RTC1 */ + QDEC_IRQn = 18, /*!< 18 QDEC */ + LPCOMP_IRQn = 19, /*!< 19 LPCOMP */ + SWI0_IRQn = 20, /*!< 20 SWI0 */ + SWI1_IRQn = 21, /*!< 21 SWI1 */ + SWI2_IRQn = 22, /*!< 22 SWI2 */ + SWI3_IRQn = 23, /*!< 23 SWI3 */ + SWI4_IRQn = 24, /*!< 24 SWI4 */ + SWI5_IRQn = 25 /*!< 25 SWI5 */ +} IRQn_Type; + + +/** @addtogroup Configuration_of_CMSIS + * @{ + */ + + +/* ================================================================================ */ +/* ================ Processor and Core Peripheral Section ================ */ +/* ================================================================================ */ + +/* ----------------Configuration of the Cortex-M0 Processor and Core Peripherals---------------- */ +#define __CM0_REV 0x0301 /*!< Cortex-M0 Core Revision */ +#define __MPU_PRESENT 0 /*!< MPU present or not */ +#define __NVIC_PRIO_BITS 2 /*!< Number of Bits used for Priority Levels */ +#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ +/** @} */ /* End of group Configuration_of_CMSIS */ + +#include "core_cm0.h" /*!< Cortex-M0 processor and core peripherals */ + + +/* ================================================================================ */ +/* ================ Device Specific Peripheral Section ================ */ +/* ================================================================================ */ + + +/** @addtogroup Device_Peripheral_Registers + * @{ + */ + + +/* ------------------- Start of section using anonymous unions ------------------ */ +#if defined(__CC_ARM) + #pragma push + #pragma anon_unions +#elif defined(__ICCARM__) + #pragma language=extended +#elif defined(__GNUC__) + /* anonymous unions are enabled by default */ +#elif defined(__TMS470__) +/* anonymous unions are enabled by default */ +#elif defined(__TASKING__) + #pragma warning 586 +#else + #warning Not supported compiler type +#endif + + +typedef struct { + __IO uint32_t CPU0; /*!< Configurable priority configuration register for CPU0. */ + __IO uint32_t SPIS1; /*!< Configurable priority configuration register for SPIS1. */ + __IO uint32_t RADIO; /*!< Configurable priority configuration register for RADIO. */ + __IO uint32_t ECB; /*!< Configurable priority configuration register for ECB. */ + __IO uint32_t CCM; /*!< Configurable priority configuration register for CCM. */ + __IO uint32_t AAR; /*!< Configurable priority configuration register for AAR. */ +} AMLI_RAMPRI_Type; + +typedef struct { + __IO uint32_t SCK; /*!< Pin select for SCK. */ + __IO uint32_t MOSI; /*!< Pin select for MOSI. */ + __IO uint32_t MISO; /*!< Pin select for MISO. */ +} SPIM_PSEL_Type; + +typedef struct { + __IO uint32_t PTR; /*!< Data pointer. */ + __IO uint32_t MAXCNT; /*!< Maximum number of buffer bytes to receive. */ + __I uint32_t AMOUNT; /*!< Number of bytes received in the last transaction. */ +} SPIM_RXD_Type; + +typedef struct { + __IO uint32_t PTR; /*!< Data pointer. */ + __IO uint32_t MAXCNT; /*!< Maximum number of buffer bytes to send. */ + __I uint32_t AMOUNT; /*!< Number of bytes sent in the last transaction. */ +} SPIM_TXD_Type; + +typedef struct { + __O uint32_t EN; /*!< Enable channel group. */ + __O uint32_t DIS; /*!< Disable channel group. */ +} PPI_TASKS_CHG_Type; + +typedef struct { + __IO uint32_t EEP; /*!< Channel event end-point. */ + __IO uint32_t TEP; /*!< Channel task end-point. */ +} PPI_CH_Type; + + +/* ================================================================================ */ +/* ================ POWER ================ */ +/* ================================================================================ */ + + +/** + * @brief Power Control. (POWER) + */ + +typedef struct { /*!< POWER Structure */ + __I uint32_t RESERVED0[30]; + __O uint32_t TASKS_CONSTLAT; /*!< Enable constant latency mode. */ + __O uint32_t TASKS_LOWPWR; /*!< Enable low power mode (variable latency). */ + __I uint32_t RESERVED1[34]; + __IO uint32_t EVENTS_POFWARN; /*!< Power failure warning. */ + __I uint32_t RESERVED2[126]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED3[61]; + __IO uint32_t RESETREAS; /*!< Reset reason. */ + __I uint32_t RESERVED4[9]; + __I uint32_t RAMSTATUS; /*!< Ram status register. */ + __I uint32_t RESERVED5[53]; + __O uint32_t SYSTEMOFF; /*!< System off register. */ + __I uint32_t RESERVED6[3]; + __IO uint32_t POFCON; /*!< Power failure configuration. */ + __I uint32_t RESERVED7[2]; + __IO uint32_t GPREGRET; /*!< General purpose retention register. This register is a retained + register. */ + __I uint32_t RESERVED8; + __IO uint32_t RAMON; /*!< Ram on/off. */ + __I uint32_t RESERVED9[7]; + __IO uint32_t RESET; /*!< Pin reset functionality configuration register. This register + is a retained register. */ + __I uint32_t RESERVED10[3]; + __IO uint32_t RAMONB; /*!< Ram on/off. */ + __I uint32_t RESERVED11[8]; + __IO uint32_t DCDCEN; /*!< DCDC converter enable configuration register. */ + __I uint32_t RESERVED12[291]; + __IO uint32_t DCDCFORCE; /*!< DCDC power-up force register. */ +} NRF_POWER_Type; + + +/* ================================================================================ */ +/* ================ CLOCK ================ */ +/* ================================================================================ */ + + +/** + * @brief Clock control. (CLOCK) + */ + +typedef struct { /*!< CLOCK Structure */ + __O uint32_t TASKS_HFCLKSTART; /*!< Start HFCLK clock source. */ + __O uint32_t TASKS_HFCLKSTOP; /*!< Stop HFCLK clock source. */ + __O uint32_t TASKS_LFCLKSTART; /*!< Start LFCLK clock source. */ + __O uint32_t TASKS_LFCLKSTOP; /*!< Stop LFCLK clock source. */ + __O uint32_t TASKS_CAL; /*!< Start calibration of LFCLK RC oscillator. */ + __O uint32_t TASKS_CTSTART; /*!< Start calibration timer. */ + __O uint32_t TASKS_CTSTOP; /*!< Stop calibration timer. */ + __I uint32_t RESERVED0[57]; + __IO uint32_t EVENTS_HFCLKSTARTED; /*!< HFCLK oscillator started. */ + __IO uint32_t EVENTS_LFCLKSTARTED; /*!< LFCLK oscillator started. */ + __I uint32_t RESERVED1; + __IO uint32_t EVENTS_DONE; /*!< Calibration of LFCLK RC oscillator completed. */ + __IO uint32_t EVENTS_CTTO; /*!< Calibration timer timeout. */ + __I uint32_t RESERVED2[124]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED3[63]; + __I uint32_t HFCLKRUN; /*!< Task HFCLKSTART trigger status. */ + __I uint32_t HFCLKSTAT; /*!< High frequency clock status. */ + __I uint32_t RESERVED4; + __I uint32_t LFCLKRUN; /*!< Task LFCLKSTART triggered status. */ + __I uint32_t LFCLKSTAT; /*!< Low frequency clock status. */ + __I uint32_t LFCLKSRCCOPY; /*!< Clock source for the LFCLK clock, set when task LKCLKSTART is + triggered. */ + __I uint32_t RESERVED5[62]; + __IO uint32_t LFCLKSRC; /*!< Clock source for the LFCLK clock. */ + __I uint32_t RESERVED6[7]; + __IO uint32_t CTIV; /*!< Calibration timer interval. */ + __I uint32_t RESERVED7[5]; + __IO uint32_t XTALFREQ; /*!< Crystal frequency. */ +} NRF_CLOCK_Type; + + +/* ================================================================================ */ +/* ================ MPU ================ */ +/* ================================================================================ */ + + +/** + * @brief Memory Protection Unit. (MPU) + */ + +typedef struct { /*!< MPU Structure */ + __I uint32_t RESERVED0[330]; + __IO uint32_t PERR0; /*!< Configuration of peripherals in mpu regions. */ + __IO uint32_t RLENR0; /*!< Length of RAM region 0. */ + __I uint32_t RESERVED1[52]; + __IO uint32_t PROTENSET0; /*!< Erase and write protection bit enable set register. */ + __IO uint32_t PROTENSET1; /*!< Erase and write protection bit enable set register. */ + __IO uint32_t DISABLEINDEBUG; /*!< Disable erase and write protection mechanism in debug mode. */ + __IO uint32_t PROTBLOCKSIZE; /*!< Erase and write protection block size. */ +} NRF_MPU_Type; + + +/* ================================================================================ */ +/* ================ PU ================ */ +/* ================================================================================ */ + + +/** + * @brief Patch unit. (PU) + */ + +typedef struct { /*!< PU Structure */ + __I uint32_t RESERVED0[448]; + __IO uint32_t REPLACEADDR[8]; /*!< Address of first instruction to replace. */ + __I uint32_t RESERVED1[24]; + __IO uint32_t PATCHADDR[8]; /*!< Relative address of patch instructions. */ + __I uint32_t RESERVED2[24]; + __IO uint32_t PATCHEN; /*!< Patch enable register. */ + __IO uint32_t PATCHENSET; /*!< Patch enable register. */ + __IO uint32_t PATCHENCLR; /*!< Patch disable register. */ +} NRF_PU_Type; + + +/* ================================================================================ */ +/* ================ AMLI ================ */ +/* ================================================================================ */ + + +/** + * @brief AHB Multi-Layer Interface. (AMLI) + */ + +typedef struct { /*!< AMLI Structure */ + __I uint32_t RESERVED0[896]; + AMLI_RAMPRI_Type RAMPRI; /*!< RAM configurable priority configuration structure. */ +} NRF_AMLI_Type; + + +/* ================================================================================ */ +/* ================ RADIO ================ */ +/* ================================================================================ */ + + +/** + * @brief The radio. (RADIO) + */ + +typedef struct { /*!< RADIO Structure */ + __O uint32_t TASKS_TXEN; /*!< Enable radio in TX mode. */ + __O uint32_t TASKS_RXEN; /*!< Enable radio in RX mode. */ + __O uint32_t TASKS_START; /*!< Start radio. */ + __O uint32_t TASKS_STOP; /*!< Stop radio. */ + __O uint32_t TASKS_DISABLE; /*!< Disable radio. */ + __O uint32_t TASKS_RSSISTART; /*!< Start the RSSI and take one sample of the receive signal strength. */ + __O uint32_t TASKS_RSSISTOP; /*!< Stop the RSSI measurement. */ + __O uint32_t TASKS_BCSTART; /*!< Start the bit counter. */ + __O uint32_t TASKS_BCSTOP; /*!< Stop the bit counter. */ + __I uint32_t RESERVED0[55]; + __IO uint32_t EVENTS_READY; /*!< Ready event. */ + __IO uint32_t EVENTS_ADDRESS; /*!< Address event. */ + __IO uint32_t EVENTS_PAYLOAD; /*!< Payload event. */ + __IO uint32_t EVENTS_END; /*!< End event. */ + __IO uint32_t EVENTS_DISABLED; /*!< Disable event. */ + __IO uint32_t EVENTS_DEVMATCH; /*!< A device address match occurred on the last received packet. */ + __IO uint32_t EVENTS_DEVMISS; /*!< No device address match occurred on the last received packet. */ + __IO uint32_t EVENTS_RSSIEND; /*!< Sampling of the receive signal strength complete. A new RSSI + sample is ready for readout at the RSSISAMPLE register. */ + __I uint32_t RESERVED1[2]; + __IO uint32_t EVENTS_BCMATCH; /*!< Bit counter reached bit count value specified in BCC register. */ + __I uint32_t RESERVED2[53]; + __IO uint32_t SHORTS; /*!< Shortcuts for the radio. */ + __I uint32_t RESERVED3[64]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED4[61]; + __I uint32_t CRCSTATUS; /*!< CRC status of received packet. */ + __I uint32_t CD; /*!< Carrier detect. */ + __I uint32_t RXMATCH; /*!< Received address. */ + __I uint32_t RXCRC; /*!< Received CRC. */ + __I uint32_t DAI; /*!< Device address match index. */ + __I uint32_t RESERVED5[60]; + __IO uint32_t PACKETPTR; /*!< Packet pointer. Decision point: START task. */ + __IO uint32_t FREQUENCY; /*!< Frequency. */ + __IO uint32_t TXPOWER; /*!< Output power. */ + __IO uint32_t MODE; /*!< Data rate and modulation. */ + __IO uint32_t PCNF0; /*!< Packet configuration 0. */ + __IO uint32_t PCNF1; /*!< Packet configuration 1. */ + __IO uint32_t BASE0; /*!< Radio base address 0. Decision point: START task. */ + __IO uint32_t BASE1; /*!< Radio base address 1. Decision point: START task. */ + __IO uint32_t PREFIX0; /*!< Prefixes bytes for logical addresses 0 to 3. */ + __IO uint32_t PREFIX1; /*!< Prefixes bytes for logical addresses 4 to 7. */ + __IO uint32_t TXADDRESS; /*!< Transmit address select. */ + __IO uint32_t RXADDRESSES; /*!< Receive address select. */ + __IO uint32_t CRCCNF; /*!< CRC configuration. */ + __IO uint32_t CRCPOLY; /*!< CRC polynomial. */ + __IO uint32_t CRCINIT; /*!< CRC initial value. */ + __IO uint32_t TEST; /*!< Test features enable register. */ + __IO uint32_t TIFS; /*!< Inter Frame Spacing in microseconds. */ + __I uint32_t RSSISAMPLE; /*!< RSSI sample. */ + __I uint32_t RESERVED6; + __I uint32_t STATE; /*!< Current radio state. */ + __IO uint32_t DATAWHITEIV; /*!< Data whitening initial value. */ + __I uint32_t RESERVED7[2]; + __IO uint32_t BCC; /*!< Bit counter compare. */ + __I uint32_t RESERVED8[39]; + __IO uint32_t DAB[8]; /*!< Device address base segment. */ + __IO uint32_t DAP[8]; /*!< Device address prefix. */ + __IO uint32_t DACNF; /*!< Device address match configuration. */ + __I uint32_t RESERVED9[56]; + __IO uint32_t OVERRIDE0; /*!< Trim value override register 0. */ + __IO uint32_t OVERRIDE1; /*!< Trim value override register 1. */ + __IO uint32_t OVERRIDE2; /*!< Trim value override register 2. */ + __IO uint32_t OVERRIDE3; /*!< Trim value override register 3. */ + __IO uint32_t OVERRIDE4; /*!< Trim value override register 4. */ + __I uint32_t RESERVED10[561]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_RADIO_Type; + + +/* ================================================================================ */ +/* ================ UART ================ */ +/* ================================================================================ */ + + +/** + * @brief Universal Asynchronous Receiver/Transmitter. (UART) + */ + +typedef struct { /*!< UART Structure */ + __O uint32_t TASKS_STARTRX; /*!< Start UART receiver. */ + __O uint32_t TASKS_STOPRX; /*!< Stop UART receiver. */ + __O uint32_t TASKS_STARTTX; /*!< Start UART transmitter. */ + __O uint32_t TASKS_STOPTX; /*!< Stop UART transmitter. */ + __I uint32_t RESERVED0[3]; + __O uint32_t TASKS_SUSPEND; /*!< Suspend UART. */ + __I uint32_t RESERVED1[56]; + __IO uint32_t EVENTS_CTS; /*!< CTS activated. */ + __IO uint32_t EVENTS_NCTS; /*!< CTS deactivated. */ + __IO uint32_t EVENTS_RXDRDY; /*!< Data received in RXD. */ + __I uint32_t RESERVED2[4]; + __IO uint32_t EVENTS_TXDRDY; /*!< Data sent from TXD. */ + __I uint32_t RESERVED3; + __IO uint32_t EVENTS_ERROR; /*!< Error detected. */ + __I uint32_t RESERVED4[7]; + __IO uint32_t EVENTS_RXTO; /*!< Receiver timeout. */ + __I uint32_t RESERVED5[46]; + __IO uint32_t SHORTS; /*!< Shortcuts for UART. */ + __I uint32_t RESERVED6[64]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED7[93]; + __IO uint32_t ERRORSRC; /*!< Error source. Write error field to 1 to clear error. */ + __I uint32_t RESERVED8[31]; + __IO uint32_t ENABLE; /*!< Enable UART and acquire IOs. */ + __I uint32_t RESERVED9; + __IO uint32_t PSELRTS; /*!< Pin select for RTS. */ + __IO uint32_t PSELTXD; /*!< Pin select for TXD. */ + __IO uint32_t PSELCTS; /*!< Pin select for CTS. */ + __IO uint32_t PSELRXD; /*!< Pin select for RXD. */ + __I uint32_t RXD; /*!< RXD register. On read action the buffer pointer is displaced. + Once read the character is consumed. If read when no character + available, the UART will stop working. */ + __O uint32_t TXD; /*!< TXD register. */ + __I uint32_t RESERVED10; + __IO uint32_t BAUDRATE; /*!< UART Baudrate. */ + __I uint32_t RESERVED11[17]; + __IO uint32_t CONFIG; /*!< Configuration of parity and hardware flow control register. */ + __I uint32_t RESERVED12[675]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_UART_Type; + + +/* ================================================================================ */ +/* ================ SPI ================ */ +/* ================================================================================ */ + + +/** + * @brief SPI master 0. (SPI) + */ + +typedef struct { /*!< SPI Structure */ + __I uint32_t RESERVED0[66]; + __IO uint32_t EVENTS_READY; /*!< TXD byte sent and RXD byte received. */ + __I uint32_t RESERVED1[126]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED2[125]; + __IO uint32_t ENABLE; /*!< Enable SPI. */ + __I uint32_t RESERVED3; + __IO uint32_t PSELSCK; /*!< Pin select for SCK. */ + __IO uint32_t PSELMOSI; /*!< Pin select for MOSI. */ + __IO uint32_t PSELMISO; /*!< Pin select for MISO. */ + __I uint32_t RESERVED4; + __I uint32_t RXD; /*!< RX data. */ + __IO uint32_t TXD; /*!< TX data. */ + __I uint32_t RESERVED5; + __IO uint32_t FREQUENCY; /*!< SPI frequency */ + __I uint32_t RESERVED6[11]; + __IO uint32_t CONFIG; /*!< Configuration register. */ + __I uint32_t RESERVED7[681]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_SPI_Type; + + +/* ================================================================================ */ +/* ================ TWI ================ */ +/* ================================================================================ */ + + +/** + * @brief Two-wire interface master 0. (TWI) + */ + +typedef struct { /*!< TWI Structure */ + __O uint32_t TASKS_STARTRX; /*!< Start 2-Wire master receive sequence. */ + __I uint32_t RESERVED0; + __O uint32_t TASKS_STARTTX; /*!< Start 2-Wire master transmit sequence. */ + __I uint32_t RESERVED1[2]; + __O uint32_t TASKS_STOP; /*!< Stop 2-Wire transaction. */ + __I uint32_t RESERVED2; + __O uint32_t TASKS_SUSPEND; /*!< Suspend 2-Wire transaction. */ + __O uint32_t TASKS_RESUME; /*!< Resume 2-Wire transaction. */ + __I uint32_t RESERVED3[56]; + __IO uint32_t EVENTS_STOPPED; /*!< Two-wire stopped. */ + __IO uint32_t EVENTS_RXDREADY; /*!< Two-wire ready to deliver new RXD byte received. */ + __I uint32_t RESERVED4[4]; + __IO uint32_t EVENTS_TXDSENT; /*!< Two-wire finished sending last TXD byte. */ + __I uint32_t RESERVED5; + __IO uint32_t EVENTS_ERROR; /*!< Two-wire error detected. */ + __I uint32_t RESERVED6[4]; + __IO uint32_t EVENTS_BB; /*!< Two-wire byte boundary. */ + __I uint32_t RESERVED7[3]; + __IO uint32_t EVENTS_SUSPENDED; /*!< Two-wire suspended. */ + __I uint32_t RESERVED8[45]; + __IO uint32_t SHORTS; /*!< Shortcuts for TWI. */ + __I uint32_t RESERVED9[64]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED10[110]; + __IO uint32_t ERRORSRC; /*!< Two-wire error source. Write error field to 1 to clear error. */ + __I uint32_t RESERVED11[14]; + __IO uint32_t ENABLE; /*!< Enable two-wire master. */ + __I uint32_t RESERVED12; + __IO uint32_t PSELSCL; /*!< Pin select for SCL. */ + __IO uint32_t PSELSDA; /*!< Pin select for SDA. */ + __I uint32_t RESERVED13[2]; + __I uint32_t RXD; /*!< RX data register. */ + __IO uint32_t TXD; /*!< TX data register. */ + __I uint32_t RESERVED14; + __IO uint32_t FREQUENCY; /*!< Two-wire frequency. */ + __I uint32_t RESERVED15[24]; + __IO uint32_t ADDRESS; /*!< Address used in the two-wire transfer. */ + __I uint32_t RESERVED16[668]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_TWI_Type; + + +/* ================================================================================ */ +/* ================ SPIS ================ */ +/* ================================================================================ */ + + +/** + * @brief SPI slave 1. (SPIS) + */ + +typedef struct { /*!< SPIS Structure */ + __I uint32_t RESERVED0[9]; + __O uint32_t TASKS_ACQUIRE; /*!< Acquire SPI semaphore. */ + __O uint32_t TASKS_RELEASE; /*!< Release SPI semaphore. */ + __I uint32_t RESERVED1[54]; + __IO uint32_t EVENTS_END; /*!< Granted transaction completed. */ + __I uint32_t RESERVED2[8]; + __IO uint32_t EVENTS_ACQUIRED; /*!< Semaphore acquired. */ + __I uint32_t RESERVED3[53]; + __IO uint32_t SHORTS; /*!< Shortcuts for SPIS. */ + __I uint32_t RESERVED4[64]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED5[61]; + __I uint32_t SEMSTAT; /*!< Semaphore status. */ + __I uint32_t RESERVED6[15]; + __IO uint32_t STATUS; /*!< Status from last transaction. */ + __I uint32_t RESERVED7[47]; + __IO uint32_t ENABLE; /*!< Enable SPIS. */ + __I uint32_t RESERVED8; + __IO uint32_t PSELSCK; /*!< Pin select for SCK. */ + __IO uint32_t PSELMISO; /*!< Pin select for MISO. */ + __IO uint32_t PSELMOSI; /*!< Pin select for MOSI. */ + __IO uint32_t PSELCSN; /*!< Pin select for CSN. */ + __I uint32_t RESERVED9[7]; + __IO uint32_t RXDPTR; /*!< RX data pointer. */ + __IO uint32_t MAXRX; /*!< Maximum number of bytes in the receive buffer. */ + __I uint32_t AMOUNTRX; /*!< Number of bytes received in last granted transaction. */ + __I uint32_t RESERVED10; + __IO uint32_t TXDPTR; /*!< TX data pointer. */ + __IO uint32_t MAXTX; /*!< Maximum number of bytes in the transmit buffer. */ + __I uint32_t AMOUNTTX; /*!< Number of bytes transmitted in last granted transaction. */ + __I uint32_t RESERVED11; + __IO uint32_t CONFIG; /*!< Configuration register. */ + __I uint32_t RESERVED12; + __IO uint32_t DEF; /*!< Default character. */ + __I uint32_t RESERVED13[24]; + __IO uint32_t ORC; /*!< Over-read character. */ + __I uint32_t RESERVED14[654]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_SPIS_Type; + + +/* ================================================================================ */ +/* ================ SPIM ================ */ +/* ================================================================================ */ + + +/** + * @brief SPI master with easyDMA 1. (SPIM) + */ + +typedef struct { /*!< SPIM Structure */ + __I uint32_t RESERVED0[4]; + __O uint32_t TASKS_START; /*!< Start SPI transaction. */ + __O uint32_t TASKS_STOP; /*!< Stop SPI transaction. */ + __I uint32_t RESERVED1; + __O uint32_t TASKS_SUSPEND; /*!< Suspend SPI transaction. */ + __O uint32_t TASKS_RESUME; /*!< Resume SPI transaction. */ + __I uint32_t RESERVED2[56]; + __IO uint32_t EVENTS_STOPPED; /*!< SPI transaction has stopped. */ + __I uint32_t RESERVED3[2]; + __IO uint32_t EVENTS_ENDRX; /*!< End of RXD buffer reached. */ + __I uint32_t RESERVED4; + __IO uint32_t EVENTS_END; /*!< End of RXD buffer and TXD buffer reached. */ + __I uint32_t RESERVED5; + __IO uint32_t EVENTS_ENDTX; /*!< End of TXD buffer reached. */ + __I uint32_t RESERVED6[10]; + __IO uint32_t EVENTS_STARTED; /*!< Transaction started. */ + __I uint32_t RESERVED7[44]; + __IO uint32_t SHORTS; /*!< Shortcuts for SPIM. */ + __I uint32_t RESERVED8[64]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED9[125]; + __IO uint32_t ENABLE; /*!< Enable SPIM. */ + __I uint32_t RESERVED10; + SPIM_PSEL_Type PSEL; /*!< Pin select configuration. */ + __I uint32_t RESERVED11[4]; + __IO uint32_t FREQUENCY; /*!< SPI frequency. */ + __I uint32_t RESERVED12[3]; + SPIM_RXD_Type RXD; /*!< RXD EasyDMA configuration and status. */ + __I uint32_t RESERVED13; + SPIM_TXD_Type TXD; /*!< TXD EasyDMA configuration and status. */ + __I uint32_t RESERVED14; + __IO uint32_t CONFIG; /*!< Configuration register. */ + __I uint32_t RESERVED15[26]; + __IO uint32_t ORC; /*!< Over-read character. */ + __I uint32_t RESERVED16[654]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_SPIM_Type; + + +/* ================================================================================ */ +/* ================ GPIOTE ================ */ +/* ================================================================================ */ + + +/** + * @brief GPIO tasks and events. (GPIOTE) + */ + +typedef struct { /*!< GPIOTE Structure */ + __O uint32_t TASKS_OUT[4]; /*!< Tasks asssociated with GPIOTE channels. */ + __I uint32_t RESERVED0[60]; + __IO uint32_t EVENTS_IN[4]; /*!< Tasks asssociated with GPIOTE channels. */ + __I uint32_t RESERVED1[27]; + __IO uint32_t EVENTS_PORT; /*!< Event generated from multiple pins. */ + __I uint32_t RESERVED2[97]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED3[129]; + __IO uint32_t CONFIG[4]; /*!< Channel configuration registers. */ + __I uint32_t RESERVED4[695]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_GPIOTE_Type; + + +/* ================================================================================ */ +/* ================ ADC ================ */ +/* ================================================================================ */ + + +/** + * @brief Analog to digital converter. (ADC) + */ + +typedef struct { /*!< ADC Structure */ + __O uint32_t TASKS_START; /*!< Start an ADC conversion. */ + __O uint32_t TASKS_STOP; /*!< Stop ADC. */ + __I uint32_t RESERVED0[62]; + __IO uint32_t EVENTS_END; /*!< ADC conversion complete. */ + __I uint32_t RESERVED1[128]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED2[61]; + __I uint32_t BUSY; /*!< ADC busy register. */ + __I uint32_t RESERVED3[63]; + __IO uint32_t ENABLE; /*!< ADC enable. */ + __IO uint32_t CONFIG; /*!< ADC configuration register. */ + __I uint32_t RESULT; /*!< Result of ADC conversion. */ + __I uint32_t RESERVED4[700]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_ADC_Type; + + +/* ================================================================================ */ +/* ================ TIMER ================ */ +/* ================================================================================ */ + + +/** + * @brief Timer 0. (TIMER) + */ + +typedef struct { /*!< TIMER Structure */ + __O uint32_t TASKS_START; /*!< Start Timer. */ + __O uint32_t TASKS_STOP; /*!< Stop Timer. */ + __O uint32_t TASKS_COUNT; /*!< Increment Timer (In counter mode). */ + __O uint32_t TASKS_CLEAR; /*!< Clear timer. */ + __O uint32_t TASKS_SHUTDOWN; /*!< Shutdown timer. */ + __I uint32_t RESERVED0[11]; + __O uint32_t TASKS_CAPTURE[4]; /*!< Capture Timer value to CC[n] registers. */ + __I uint32_t RESERVED1[60]; + __IO uint32_t EVENTS_COMPARE[4]; /*!< Compare event on CC[n] match. */ + __I uint32_t RESERVED2[44]; + __IO uint32_t SHORTS; /*!< Shortcuts for Timer. */ + __I uint32_t RESERVED3[64]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED4[126]; + __IO uint32_t MODE; /*!< Timer Mode selection. */ + __IO uint32_t BITMODE; /*!< Sets timer behaviour. */ + __I uint32_t RESERVED5; + __IO uint32_t PRESCALER; /*!< 4-bit prescaler to source clock frequency (max value 9). Source + clock frequency is divided by 2^SCALE. */ + __I uint32_t RESERVED6[11]; + __IO uint32_t CC[4]; /*!< Capture/compare registers. */ + __I uint32_t RESERVED7[683]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_TIMER_Type; + + +/* ================================================================================ */ +/* ================ RTC ================ */ +/* ================================================================================ */ + + +/** + * @brief Real time counter 0. (RTC) + */ + +typedef struct { /*!< RTC Structure */ + __O uint32_t TASKS_START; /*!< Start RTC Counter. */ + __O uint32_t TASKS_STOP; /*!< Stop RTC Counter. */ + __O uint32_t TASKS_CLEAR; /*!< Clear RTC Counter. */ + __O uint32_t TASKS_TRIGOVRFLW; /*!< Set COUNTER to 0xFFFFFFF0. */ + __I uint32_t RESERVED0[60]; + __IO uint32_t EVENTS_TICK; /*!< Event on COUNTER increment. */ + __IO uint32_t EVENTS_OVRFLW; /*!< Event on COUNTER overflow. */ + __I uint32_t RESERVED1[14]; + __IO uint32_t EVENTS_COMPARE[4]; /*!< Compare event on CC[n] match. */ + __I uint32_t RESERVED2[109]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED3[13]; + __IO uint32_t EVTEN; /*!< Configures event enable routing to PPI for each RTC event. */ + __IO uint32_t EVTENSET; /*!< Enable events routing to PPI. The reading of this register gives + the value of EVTEN. */ + __IO uint32_t EVTENCLR; /*!< Disable events routing to PPI. The reading of this register + gives the value of EVTEN. */ + __I uint32_t RESERVED4[110]; + __I uint32_t COUNTER; /*!< Current COUNTER value. */ + __IO uint32_t PRESCALER; /*!< 12-bit prescaler for COUNTER frequency (32768/(PRESCALER+1)). + Must be written when RTC is STOPed. */ + __I uint32_t RESERVED5[13]; + __IO uint32_t CC[4]; /*!< Capture/compare registers. */ + __I uint32_t RESERVED6[683]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_RTC_Type; + + +/* ================================================================================ */ +/* ================ TEMP ================ */ +/* ================================================================================ */ + + +/** + * @brief Temperature Sensor. (TEMP) + */ + +typedef struct { /*!< TEMP Structure */ + __O uint32_t TASKS_START; /*!< Start temperature measurement. */ + __O uint32_t TASKS_STOP; /*!< Stop temperature measurement. */ + __I uint32_t RESERVED0[62]; + __IO uint32_t EVENTS_DATARDY; /*!< Temperature measurement complete, data ready event. */ + __I uint32_t RESERVED1[128]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED2[127]; + __I int32_t TEMP; /*!< Die temperature in degC, 2's complement format, 0.25 degC pecision. */ + __I uint32_t RESERVED3[700]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_TEMP_Type; + + +/* ================================================================================ */ +/* ================ RNG ================ */ +/* ================================================================================ */ + + +/** + * @brief Random Number Generator. (RNG) + */ + +typedef struct { /*!< RNG Structure */ + __O uint32_t TASKS_START; /*!< Start the random number generator. */ + __O uint32_t TASKS_STOP; /*!< Stop the random number generator. */ + __I uint32_t RESERVED0[62]; + __IO uint32_t EVENTS_VALRDY; /*!< New random number generated and written to VALUE register. */ + __I uint32_t RESERVED1[63]; + __IO uint32_t SHORTS; /*!< Shortcuts for the RNG. */ + __I uint32_t RESERVED2[64]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register */ + __I uint32_t RESERVED3[126]; + __IO uint32_t CONFIG; /*!< Configuration register. */ + __I uint32_t VALUE; /*!< RNG random number. */ + __I uint32_t RESERVED4[700]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_RNG_Type; + + +/* ================================================================================ */ +/* ================ ECB ================ */ +/* ================================================================================ */ + + +/** + * @brief AES ECB Mode Encryption. (ECB) + */ + +typedef struct { /*!< ECB Structure */ + __O uint32_t TASKS_STARTECB; /*!< Start ECB block encrypt. If a crypto operation is running, this + will not initiate a new encryption and the ERRORECB event will + be triggered. */ + __O uint32_t TASKS_STOPECB; /*!< Stop current ECB encryption. If a crypto operation is running, + this will will trigger the ERRORECB event. */ + __I uint32_t RESERVED0[62]; + __IO uint32_t EVENTS_ENDECB; /*!< ECB block encrypt complete. */ + __IO uint32_t EVENTS_ERRORECB; /*!< ECB block encrypt aborted due to a STOPECB task or due to an + error. */ + __I uint32_t RESERVED1[127]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED2[126]; + __IO uint32_t ECBDATAPTR; /*!< ECB block encrypt memory pointer. */ + __I uint32_t RESERVED3[701]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_ECB_Type; + + +/* ================================================================================ */ +/* ================ AAR ================ */ +/* ================================================================================ */ + + +/** + * @brief Accelerated Address Resolver. (AAR) + */ + +typedef struct { /*!< AAR Structure */ + __O uint32_t TASKS_START; /*!< Start resolving addresses based on IRKs specified in the IRK + data structure. */ + __I uint32_t RESERVED0; + __O uint32_t TASKS_STOP; /*!< Stop resolving addresses. */ + __I uint32_t RESERVED1[61]; + __IO uint32_t EVENTS_END; /*!< Address resolution procedure completed. */ + __IO uint32_t EVENTS_RESOLVED; /*!< Address resolved. */ + __IO uint32_t EVENTS_NOTRESOLVED; /*!< Address not resolved. */ + __I uint32_t RESERVED2[126]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED3[61]; + __I uint32_t STATUS; /*!< Resolution status. */ + __I uint32_t RESERVED4[63]; + __IO uint32_t ENABLE; /*!< Enable AAR. */ + __IO uint32_t NIRK; /*!< Number of Identity root Keys in the IRK data structure. */ + __IO uint32_t IRKPTR; /*!< Pointer to the IRK data structure. */ + __I uint32_t RESERVED5; + __IO uint32_t ADDRPTR; /*!< Pointer to the resolvable address (6 bytes). */ + __IO uint32_t SCRATCHPTR; /*!< Pointer to a "scratch" data area used for temporary storage + during resolution. A minimum of 3 bytes must be reserved. */ + __I uint32_t RESERVED6[697]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_AAR_Type; + + +/* ================================================================================ */ +/* ================ CCM ================ */ +/* ================================================================================ */ + + +/** + * @brief AES CCM Mode Encryption. (CCM) + */ + +typedef struct { /*!< CCM Structure */ + __O uint32_t TASKS_KSGEN; /*!< Start generation of key-stream. This operation will stop by + itself when completed. */ + __O uint32_t TASKS_CRYPT; /*!< Start encrypt/decrypt. This operation will stop by itself when + completed. */ + __O uint32_t TASKS_STOP; /*!< Stop encrypt/decrypt. */ + __I uint32_t RESERVED0[61]; + __IO uint32_t EVENTS_ENDKSGEN; /*!< Keystream generation completed. */ + __IO uint32_t EVENTS_ENDCRYPT; /*!< Encrypt/decrypt completed. */ + __IO uint32_t EVENTS_ERROR; /*!< Error happened. */ + __I uint32_t RESERVED1[61]; + __IO uint32_t SHORTS; /*!< Shortcuts for the CCM. */ + __I uint32_t RESERVED2[64]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED3[61]; + __I uint32_t MICSTATUS; /*!< CCM RX MIC check result. */ + __I uint32_t RESERVED4[63]; + __IO uint32_t ENABLE; /*!< CCM enable. */ + __IO uint32_t MODE; /*!< Operation mode. */ + __IO uint32_t CNFPTR; /*!< Pointer to a data structure holding AES key and NONCE vector. */ + __IO uint32_t INPTR; /*!< Pointer to the input packet. */ + __IO uint32_t OUTPTR; /*!< Pointer to the output packet. */ + __IO uint32_t SCRATCHPTR; /*!< Pointer to a "scratch" data area used for temporary storage + during resolution. A minimum of 43 bytes must be reserved. */ + __I uint32_t RESERVED5[697]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_CCM_Type; + + +/* ================================================================================ */ +/* ================ WDT ================ */ +/* ================================================================================ */ + + +/** + * @brief Watchdog Timer. (WDT) + */ + +typedef struct { /*!< WDT Structure */ + __O uint32_t TASKS_START; /*!< Start the watchdog. */ + __I uint32_t RESERVED0[63]; + __IO uint32_t EVENTS_TIMEOUT; /*!< Watchdog timeout. */ + __I uint32_t RESERVED1[128]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED2[61]; + __I uint32_t RUNSTATUS; /*!< Watchdog running status. */ + __I uint32_t REQSTATUS; /*!< Request status. */ + __I uint32_t RESERVED3[63]; + __IO uint32_t CRV; /*!< Counter reload value in number of 32kiHz clock cycles. */ + __IO uint32_t RREN; /*!< Reload request enable. */ + __IO uint32_t CONFIG; /*!< Configuration register. */ + __I uint32_t RESERVED4[60]; + __O uint32_t RR[8]; /*!< Reload requests registers. */ + __I uint32_t RESERVED5[631]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_WDT_Type; + + +/* ================================================================================ */ +/* ================ QDEC ================ */ +/* ================================================================================ */ + + +/** + * @brief Rotary decoder. (QDEC) + */ + +typedef struct { /*!< QDEC Structure */ + __O uint32_t TASKS_START; /*!< Start the quadrature decoder. */ + __O uint32_t TASKS_STOP; /*!< Stop the quadrature decoder. */ + __O uint32_t TASKS_READCLRACC; /*!< Transfers the content from ACC registers to ACCREAD registers, + and clears the ACC registers. */ + __I uint32_t RESERVED0[61]; + __IO uint32_t EVENTS_SAMPLERDY; /*!< A new sample is written to the sample register. */ + __IO uint32_t EVENTS_REPORTRDY; /*!< REPORTPER number of samples accumulated in ACC register, and + ACC register different than zero. */ + __IO uint32_t EVENTS_ACCOF; /*!< ACC or ACCDBL register overflow. */ + __I uint32_t RESERVED1[61]; + __IO uint32_t SHORTS; /*!< Shortcuts for the QDEC. */ + __I uint32_t RESERVED2[64]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED3[125]; + __IO uint32_t ENABLE; /*!< Enable the QDEC. */ + __IO uint32_t LEDPOL; /*!< LED output pin polarity. */ + __IO uint32_t SAMPLEPER; /*!< Sample period. */ + __I int32_t SAMPLE; /*!< Motion sample value. */ + __IO uint32_t REPORTPER; /*!< Number of samples to generate an EVENT_REPORTRDY. */ + __I int32_t ACC; /*!< Accumulated valid transitions register. */ + __I int32_t ACCREAD; /*!< Snapshot of ACC register. Value generated by the TASKS_READCLEACC + task. */ + __IO uint32_t PSELLED; /*!< Pin select for LED output. */ + __IO uint32_t PSELA; /*!< Pin select for phase A input. */ + __IO uint32_t PSELB; /*!< Pin select for phase B input. */ + __IO uint32_t DBFEN; /*!< Enable debouncer input filters. */ + __I uint32_t RESERVED4[5]; + __IO uint32_t LEDPRE; /*!< Time LED is switched ON before the sample. */ + __I uint32_t ACCDBL; /*!< Accumulated double (error) transitions register. */ + __I uint32_t ACCDBLREAD; /*!< Snapshot of ACCDBL register. Value generated by the TASKS_READCLEACC + task. */ + __I uint32_t RESERVED5[684]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_QDEC_Type; + + +/* ================================================================================ */ +/* ================ LPCOMP ================ */ +/* ================================================================================ */ + + +/** + * @brief Low power comparator. (LPCOMP) + */ + +typedef struct { /*!< LPCOMP Structure */ + __O uint32_t TASKS_START; /*!< Start the comparator. */ + __O uint32_t TASKS_STOP; /*!< Stop the comparator. */ + __O uint32_t TASKS_SAMPLE; /*!< Sample comparator value. */ + __I uint32_t RESERVED0[61]; + __IO uint32_t EVENTS_READY; /*!< LPCOMP is ready and output is valid. */ + __IO uint32_t EVENTS_DOWN; /*!< Input voltage crossed the threshold going down. */ + __IO uint32_t EVENTS_UP; /*!< Input voltage crossed the threshold going up. */ + __IO uint32_t EVENTS_CROSS; /*!< Input voltage crossed the threshold in any direction. */ + __I uint32_t RESERVED1[60]; + __IO uint32_t SHORTS; /*!< Shortcuts for the LPCOMP. */ + __I uint32_t RESERVED2[64]; + __IO uint32_t INTENSET; /*!< Interrupt enable set register. */ + __IO uint32_t INTENCLR; /*!< Interrupt enable clear register. */ + __I uint32_t RESERVED3[61]; + __I uint32_t RESULT; /*!< Result of last compare. */ + __I uint32_t RESERVED4[63]; + __IO uint32_t ENABLE; /*!< Enable the LPCOMP. */ + __IO uint32_t PSEL; /*!< Input pin select. */ + __IO uint32_t REFSEL; /*!< Reference select. */ + __IO uint32_t EXTREFSEL; /*!< External reference select. */ + __I uint32_t RESERVED5[4]; + __IO uint32_t ANADETECT; /*!< Analog detect configuration. */ + __I uint32_t RESERVED6[694]; + __IO uint32_t POWER; /*!< Peripheral power control. */ +} NRF_LPCOMP_Type; + + +/* ================================================================================ */ +/* ================ SWI ================ */ +/* ================================================================================ */ + + +/** + * @brief SW Interrupts. (SWI) + */ + +typedef struct { /*!< SWI Structure */ + __I uint32_t UNUSED; /*!< Unused. */ +} NRF_SWI_Type; + + +/* ================================================================================ */ +/* ================ NVMC ================ */ +/* ================================================================================ */ + + +/** + * @brief Non Volatile Memory Controller. (NVMC) + */ + +typedef struct { /*!< NVMC Structure */ + __I uint32_t RESERVED0[256]; + __I uint32_t READY; /*!< Ready flag. */ + __I uint32_t RESERVED1[64]; + __IO uint32_t CONFIG; /*!< Configuration register. */ + + union { + __IO uint32_t ERASEPCR1; /*!< Register for erasing a non-protected non-volatile memory page. */ + __IO uint32_t ERASEPAGE; /*!< Register for erasing a non-protected non-volatile memory page. */ + }; + __IO uint32_t ERASEALL; /*!< Register for erasing all non-volatile user memory. */ + + union { + __IO uint32_t ERASEPCR0; /*!< Register for erasing a protected non-volatile memory page. */ + __IO uint32_t ERASEPROTECTEDPAGE; /*!< Register for erasing a protected non-volatile memory page. */ + }; + __IO uint32_t ERASEUICR; /*!< Register for start erasing User Information Congfiguration Registers. */ +} NRF_NVMC_Type; + + +/* ================================================================================ */ +/* ================ PPI ================ */ +/* ================================================================================ */ + + +/** + * @brief PPI controller. (PPI) + */ + +typedef struct { /*!< PPI Structure */ + PPI_TASKS_CHG_Type TASKS_CHG[4]; /*!< Channel group tasks. */ + __I uint32_t RESERVED0[312]; + __IO uint32_t CHEN; /*!< Channel enable. */ + __IO uint32_t CHENSET; /*!< Channel enable set. */ + __IO uint32_t CHENCLR; /*!< Channel enable clear. */ + __I uint32_t RESERVED1; + PPI_CH_Type CH[16]; /*!< PPI Channel. */ + __I uint32_t RESERVED2[156]; + __IO uint32_t CHG[4]; /*!< Channel group configuration. */ +} NRF_PPI_Type; + + +/* ================================================================================ */ +/* ================ FICR ================ */ +/* ================================================================================ */ + + +/** + * @brief Factory Information Configuration. (FICR) + */ + +typedef struct { /*!< FICR Structure */ + __I uint32_t RESERVED0[4]; + __I uint32_t CODEPAGESIZE; /*!< Code memory page size in bytes. */ + __I uint32_t CODESIZE; /*!< Code memory size in pages. */ + __I uint32_t RESERVED1[4]; + __I uint32_t CLENR0; /*!< Length of code region 0 in bytes. */ + __I uint32_t PPFC; /*!< Pre-programmed factory code present. */ + __I uint32_t RESERVED2; + __I uint32_t NUMRAMBLOCK; /*!< Number of individualy controllable RAM blocks. */ + + union { + __I uint32_t SIZERAMBLOCK[4]; /*!< Deprecated array of size of RAM block in bytes. This name is + kept for backward compatinility purposes. Use SIZERAMBLOCKS + instead. */ + __I uint32_t SIZERAMBLOCKS; /*!< Size of RAM blocks in bytes. */ + }; + __I uint32_t RESERVED3[5]; + __I uint32_t CONFIGID; /*!< Configuration identifier. */ + __I uint32_t DEVICEID[2]; /*!< Device identifier. */ + __I uint32_t RESERVED4[6]; + __I uint32_t ER[4]; /*!< Encryption root. */ + __I uint32_t IR[4]; /*!< Identity root. */ + __I uint32_t DEVICEADDRTYPE; /*!< Device address type. */ + __I uint32_t DEVICEADDR[2]; /*!< Device address. */ + __I uint32_t OVERRIDEEN; /*!< Radio calibration override enable. */ + __I uint32_t NRF_1MBIT[5]; /*!< Override values for the OVERRIDEn registers in RADIO for NRF_1Mbit + mode. */ + __I uint32_t RESERVED5[10]; + __I uint32_t BLE_1MBIT[5]; /*!< Override values for the OVERRIDEn registers in RADIO for BLE_1Mbit + mode. */ +} NRF_FICR_Type; + + +/* ================================================================================ */ +/* ================ UICR ================ */ +/* ================================================================================ */ + + +/** + * @brief User Information Configuration. (UICR) + */ + +typedef struct { /*!< UICR Structure */ + __IO uint32_t CLENR0; /*!< Length of code region 0. */ + __IO uint32_t RBPCONF; /*!< Readback protection configuration. */ + __IO uint32_t XTALFREQ; /*!< Reset value for CLOCK XTALFREQ register. */ + __I uint32_t RESERVED0; + __I uint32_t FWID; /*!< Firmware ID. */ + + union { + __IO uint32_t NRFFW[15]; /*!< Reserved for Nordic firmware design. */ + __IO uint32_t BOOTLOADERADDR; /*!< Bootloader start address. */ + }; + __IO uint32_t NRFHW[12]; /*!< Reserved for Nordic hardware design. */ + __IO uint32_t CUSTOMER[32]; /*!< Reserved for customer. */ +} NRF_UICR_Type; + + +/* ================================================================================ */ +/* ================ GPIO ================ */ +/* ================================================================================ */ + + +/** + * @brief General purpose input and output. (GPIO) + */ + +typedef struct { /*!< GPIO Structure */ + __I uint32_t RESERVED0[321]; + __IO uint32_t OUT; /*!< Write GPIO port. */ + __IO uint32_t OUTSET; /*!< Set individual bits in GPIO port. */ + __IO uint32_t OUTCLR; /*!< Clear individual bits in GPIO port. */ + __I uint32_t IN; /*!< Read GPIO port. */ + __IO uint32_t DIR; /*!< Direction of GPIO pins. */ + __IO uint32_t DIRSET; /*!< DIR set register. */ + __IO uint32_t DIRCLR; /*!< DIR clear register. */ + __I uint32_t RESERVED1[120]; + __IO uint32_t PIN_CNF[32]; /*!< Configuration of GPIO pins. */ +} NRF_GPIO_Type; + + +/* -------------------- End of section using anonymous unions ------------------- */ +#if defined(__CC_ARM) + #pragma pop +#elif defined(__ICCARM__) + /* leave anonymous unions enabled */ +#elif defined(__GNUC__) + /* anonymous unions are enabled by default */ +#elif defined(__TMS470__) + /* anonymous unions are enabled by default */ +#elif defined(__TASKING__) + #pragma warning restore +#else + #warning Not supported compiler type +#endif + + + + +/* ================================================================================ */ +/* ================ Peripheral memory map ================ */ +/* ================================================================================ */ + +#define NRF_POWER_BASE 0x40000000UL +#define NRF_CLOCK_BASE 0x40000000UL +#define NRF_MPU_BASE 0x40000000UL +#define NRF_PU_BASE 0x40000000UL +#define NRF_AMLI_BASE 0x40000000UL +#define NRF_RADIO_BASE 0x40001000UL +#define NRF_UART0_BASE 0x40002000UL +#define NRF_SPI0_BASE 0x40003000UL +#define NRF_TWI0_BASE 0x40003000UL +#define NRF_SPI1_BASE 0x40004000UL +#define NRF_TWI1_BASE 0x40004000UL +#define NRF_SPIS1_BASE 0x40004000UL +#define NRF_SPIM1_BASE 0x40004000UL +#define NRF_GPIOTE_BASE 0x40006000UL +#define NRF_ADC_BASE 0x40007000UL +#define NRF_TIMER0_BASE 0x40008000UL +#define NRF_TIMER1_BASE 0x40009000UL +#define NRF_TIMER2_BASE 0x4000A000UL +#define NRF_RTC0_BASE 0x4000B000UL +#define NRF_TEMP_BASE 0x4000C000UL +#define NRF_RNG_BASE 0x4000D000UL +#define NRF_ECB_BASE 0x4000E000UL +#define NRF_AAR_BASE 0x4000F000UL +#define NRF_CCM_BASE 0x4000F000UL +#define NRF_WDT_BASE 0x40010000UL +#define NRF_RTC1_BASE 0x40011000UL +#define NRF_QDEC_BASE 0x40012000UL +#define NRF_LPCOMP_BASE 0x40013000UL +#define NRF_SWI_BASE 0x40014000UL +#define NRF_NVMC_BASE 0x4001E000UL +#define NRF_PPI_BASE 0x4001F000UL +#define NRF_FICR_BASE 0x10000000UL +#define NRF_UICR_BASE 0x10001000UL +#define NRF_GPIO_BASE 0x50000000UL + + +/* ================================================================================ */ +/* ================ Peripheral declaration ================ */ +/* ================================================================================ */ + +#define NRF_POWER ((NRF_POWER_Type *) NRF_POWER_BASE) +#define NRF_CLOCK ((NRF_CLOCK_Type *) NRF_CLOCK_BASE) +#define NRF_MPU ((NRF_MPU_Type *) NRF_MPU_BASE) +#define NRF_PU ((NRF_PU_Type *) NRF_PU_BASE) +#define NRF_AMLI ((NRF_AMLI_Type *) NRF_AMLI_BASE) +#define NRF_RADIO ((NRF_RADIO_Type *) NRF_RADIO_BASE) +#define NRF_UART0 ((NRF_UART_Type *) NRF_UART0_BASE) +#define NRF_SPI0 ((NRF_SPI_Type *) NRF_SPI0_BASE) +#define NRF_TWI0 ((NRF_TWI_Type *) NRF_TWI0_BASE) +#define NRF_SPI1 ((NRF_SPI_Type *) NRF_SPI1_BASE) +#define NRF_TWI1 ((NRF_TWI_Type *) NRF_TWI1_BASE) +#define NRF_SPIS1 ((NRF_SPIS_Type *) NRF_SPIS1_BASE) +#define NRF_SPIM1 ((NRF_SPIM_Type *) NRF_SPIM1_BASE) +#define NRF_GPIOTE ((NRF_GPIOTE_Type *) NRF_GPIOTE_BASE) +#define NRF_ADC ((NRF_ADC_Type *) NRF_ADC_BASE) +#define NRF_TIMER0 ((NRF_TIMER_Type *) NRF_TIMER0_BASE) +#define NRF_TIMER1 ((NRF_TIMER_Type *) NRF_TIMER1_BASE) +#define NRF_TIMER2 ((NRF_TIMER_Type *) NRF_TIMER2_BASE) +#define NRF_RTC0 ((NRF_RTC_Type *) NRF_RTC0_BASE) +#define NRF_TEMP ((NRF_TEMP_Type *) NRF_TEMP_BASE) +#define NRF_RNG ((NRF_RNG_Type *) NRF_RNG_BASE) +#define NRF_ECB ((NRF_ECB_Type *) NRF_ECB_BASE) +#define NRF_AAR ((NRF_AAR_Type *) NRF_AAR_BASE) +#define NRF_CCM ((NRF_CCM_Type *) NRF_CCM_BASE) +#define NRF_WDT ((NRF_WDT_Type *) NRF_WDT_BASE) +#define NRF_RTC1 ((NRF_RTC_Type *) NRF_RTC1_BASE) +#define NRF_QDEC ((NRF_QDEC_Type *) NRF_QDEC_BASE) +#define NRF_LPCOMP ((NRF_LPCOMP_Type *) NRF_LPCOMP_BASE) +#define NRF_SWI ((NRF_SWI_Type *) NRF_SWI_BASE) +#define NRF_NVMC ((NRF_NVMC_Type *) NRF_NVMC_BASE) +#define NRF_PPI ((NRF_PPI_Type *) NRF_PPI_BASE) +#define NRF_FICR ((NRF_FICR_Type *) NRF_FICR_BASE) +#define NRF_UICR ((NRF_UICR_Type *) NRF_UICR_BASE) +#define NRF_GPIO ((NRF_GPIO_Type *) NRF_GPIO_BASE) + + +/** @} */ /* End of group Device_Peripheral_Registers */ +/** @} */ /* End of group nrf51 */ +/** @} */ /* End of group Nordic Semiconductor */ + +#ifdef __cplusplus +} +#endif + + +#endif /* nrf51_H */ + diff --git a/os/hal/ports/NRF51/NRF51822/platform.mk b/os/hal/ports/NRF51/NRF51822/platform.mk new file mode 100644 index 0000000..5e8588d --- /dev/null +++ b/os/hal/ports/NRF51/NRF51822/platform.mk @@ -0,0 +1,8 @@ +# List of all the NRF51x platform files. +PLATFORMSRC = ${CHIBIOS}/os/hal/ports/common/ARMCMx/nvic.c \ + ${CHIBIOS}/community/os/hal/ports/NRF51/NRF51822/hal_lld.c \ + ${CHIBIOS}/community/os/hal/ports/NRF51/NRF51822/pal_lld.c + +# Required include directories +PLATFORMINC = ${CHIBIOS}/os/hal/ports/common/ARMCMx \ + ${CHIBIOS}/community/os/hal/ports/NRF51/NRF51822 -- cgit v1.2.3 From 2e9ed23874a1b43cb7bf70df1c019dbf4024278c Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Wed, 29 Apr 2015 19:48:40 -0300 Subject: Add initial cmparams --- os/common/ports/ARMCMx/devices/NRF51822/cmparams.h | 82 ++++++++++++++++++++++ 1 file changed, 82 insertions(+) create mode 100644 os/common/ports/ARMCMx/devices/NRF51822/cmparams.h (limited to 'os') diff --git a/os/common/ports/ARMCMx/devices/NRF51822/cmparams.h b/os/common/ports/ARMCMx/devices/NRF51822/cmparams.h new file mode 100644 index 0000000..645a438 --- /dev/null +++ b/os/common/ports/ARMCMx/devices/NRF51822/cmparams.h @@ -0,0 +1,82 @@ +/* + ChibiOS - Copyright (C) 2015 Fabio Utzig + + This file is part of ChibiOS. + + ChibiOS is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + ChibiOS is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +/** + * @file NRF51822/cmparams.h + * @brief ARM Cortex-M0 parameters for the Nordic Semi NRF51822 family. + * + * @defgroup ARMCMx_NRF51x Nordic semiconductor NRF51x. + * @ingroup ARMCMx_SPECIFIC + * @details This file contains the Cortex-M0 specific parameters for the + * NRF51x platform. + * @{ + */ + +#ifndef _CMPARAMS_H_ +#define _CMPARAMS_H_ + +/** + * @brief Cortex core model. + */ +#define CORTEX_MODEL 0 + +/** + * @brief Systick unit presence. + */ +#define CORTEX_HAS_ST FALSE + +/** + * @brief Floating Point unit presence. + */ +#define CORTEX_HAS_FPU FALSE + +/** + * @brief Number of bits in priority masks. + */ +#define CORTEX_PRIORITY_BITS 2 + +/** + * @brief Number of interrupt vectors. + * @note This number does not include the 16 system vectors and must be + * rounded to a multiple of 8. + */ +#define CORTEX_NUM_VECTORS 32 + +/* The following code is not processed when the file is included from an + asm module.*/ +#if !defined(_FROM_ASM_) + +/* Including the device CMSIS header. Note, we are not using the definitions + from this header because we need this file to be usable also from + assembler source files. We verify that the info matches instead.*/ +#include "nrf51.h" + +#if CORTEX_MODEL != __CORTEX_M +#error "CMSIS __CORTEX_M mismatch" +#endif + +#if CORTEX_PRIORITY_BITS != __NVIC_PRIO_BITS +#error "CMSIS __NVIC_PRIO_BITS mismatch" +#endif + +#endif /* !defined(_FROM_ASM_) */ + +#endif /* _CMPARAMS_H_ */ + +/** @} */ -- cgit v1.2.3 From 203bb92de1b57af6c88db33882275135424badd7 Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Wed, 29 Apr 2015 20:08:16 -0300 Subject: Add statup makefile --- os/common/ports/ARMCMx/compilers/GCC/mk/startup_nrf51.mk | 11 +++++++++++ 1 file changed, 11 insertions(+) create mode 100644 os/common/ports/ARMCMx/compilers/GCC/mk/startup_nrf51.mk (limited to 'os') diff --git a/os/common/ports/ARMCMx/compilers/GCC/mk/startup_nrf51.mk b/os/common/ports/ARMCMx/compilers/GCC/mk/startup_nrf51.mk new file mode 100644 index 0000000..7433ba2 --- /dev/null +++ b/os/common/ports/ARMCMx/compilers/GCC/mk/startup_nrf51.mk @@ -0,0 +1,11 @@ +# List of the ChibiOS generic NRF51 startup and CMSIS files. +STARTUPSRC = $(CHIBIOS)/os/common/ports/ARMCMx/compilers/GCC/crt1.c \ + $(CHIBIOS)/os/common/ports/ARMCMx/compilers/GCC/vectors.c + +STARTUPASM = $(CHIBIOS)/os/common/ports/ARMCMx/compilers/GCC/crt0_v6m.s + +STARTUPINC = $(CHIBIOS)/community/os/common/ports/ARMCMx/devices/NRF51822 \ + $(CHIBIOS)/os/ext/CMSIS/include + +STARTUPLD = $(CHIBIOS)/community/os/common/ports/ARMCMx/compilers/GCC/ld + -- cgit v1.2.3 From 37f70691a9f5244099d5dc9b87e888b2f40405f0 Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Wed, 29 Apr 2015 20:33:13 -0300 Subject: Add linker script --- .../ports/ARMCMx/compilers/GCC/ld/NRF51822.LD | 48 ++++++++++++++++++++++ 1 file changed, 48 insertions(+) create mode 100644 os/common/ports/ARMCMx/compilers/GCC/ld/NRF51822.LD (limited to 'os') diff --git a/os/common/ports/ARMCMx/compilers/GCC/ld/NRF51822.LD b/os/common/ports/ARMCMx/compilers/GCC/ld/NRF51822.LD new file mode 100644 index 0000000..86718d0 --- /dev/null +++ b/os/common/ports/ARMCMx/compilers/GCC/ld/NRF51822.LD @@ -0,0 +1,48 @@ +/* + Copyright (C) 2015 Fabio Utzig + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/* + * NRF51822 memory setup. + */ +MEMORY +{ + flash : org = 0x00000000, len = 256k + ram0 : org = 0x20000000, len = 16k + ram1 : org = 0x00000000, len = 0 + ram2 : org = 0x00000000, len = 0 + ram3 : org = 0x00000000, len = 0 + ram4 : org = 0x00000000, len = 0 + ram5 : org = 0x00000000, len = 0 + ram6 : org = 0x00000000, len = 0 + ram7 : org = 0x00000000, len = 0 +} + +/* RAM region to be used for Main stack. This stack accommodates the processing + of all exceptions and interrupts*/ +REGION_ALIAS("MAIN_STACK_RAM", ram0); + +/* RAM region to be used for the process stack. This is the stack used by + the main() function.*/ +REGION_ALIAS("PROCESS_STACK_RAM", ram0); + +/* RAM region to be used for data segment.*/ +REGION_ALIAS("DATA_RAM", ram0); + +/* RAM region to be used for BSS segment.*/ +REGION_ALIAS("BSS_RAM", ram0); + + +INCLUDE rules.ld -- cgit v1.2.3 From 9b1feee2e7523a7a99e3881e76360ee2dcfb8a42 Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Tue, 12 May 2015 22:05:23 -0300 Subject: Remove PAL, add ST --- os/hal/ports/NRF51/NRF51822/platform.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'os') diff --git a/os/hal/ports/NRF51/NRF51822/platform.mk b/os/hal/ports/NRF51/NRF51822/platform.mk index 5e8588d..4ed0722 100644 --- a/os/hal/ports/NRF51/NRF51822/platform.mk +++ b/os/hal/ports/NRF51/NRF51822/platform.mk @@ -1,7 +1,7 @@ # List of all the NRF51x platform files. PLATFORMSRC = ${CHIBIOS}/os/hal/ports/common/ARMCMx/nvic.c \ ${CHIBIOS}/community/os/hal/ports/NRF51/NRF51822/hal_lld.c \ - ${CHIBIOS}/community/os/hal/ports/NRF51/NRF51822/pal_lld.c + ${CHIBIOS}/community/os/hal/ports/NRF51/NRF51822/st_lld.c # Required include directories PLATFORMINC = ${CHIBIOS}/os/hal/ports/common/ARMCMx \ -- cgit v1.2.3 From 5afd99de17e294d130b426aff43aeef962233415 Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Tue, 12 May 2015 22:06:28 -0300 Subject: Add basic HAL/ST drivers --- os/hal/ports/NRF51/NRF51822/hal_lld.c | 70 +++++++++++++++++ os/hal/ports/NRF51/NRF51822/hal_lld.h | 77 +++++++++++++++++++ os/hal/ports/NRF51/NRF51822/st_lld.c | 67 ++++++++++++++++ os/hal/ports/NRF51/NRF51822/st_lld.h | 141 ++++++++++++++++++++++++++++++++++ 4 files changed, 355 insertions(+) create mode 100644 os/hal/ports/NRF51/NRF51822/hal_lld.c create mode 100644 os/hal/ports/NRF51/NRF51822/hal_lld.h create mode 100644 os/hal/ports/NRF51/NRF51822/st_lld.c create mode 100644 os/hal/ports/NRF51/NRF51822/st_lld.h (limited to 'os') diff --git a/os/hal/ports/NRF51/NRF51822/hal_lld.c b/os/hal/ports/NRF51/NRF51822/hal_lld.c new file mode 100644 index 0000000..b1a0d34 --- /dev/null +++ b/os/hal/ports/NRF51/NRF51822/hal_lld.c @@ -0,0 +1,70 @@ +/* + Copyright (C) 2015 Fabio Utzig + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/** + * @file NRF51/NRF51822/hal_lld.c + * @brief NRF51822 HAL Driver subsystem low level driver source. + * + * @addtogroup HAL + * @{ + */ + +#include "hal.h" + +/*===========================================================================*/ +/* Driver local definitions. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver exported variables. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver local variables and types. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver local functions. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver interrupt handlers. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver exported functions. */ +/*===========================================================================*/ + +/** + * @brief Low level HAL driver initialization. + * + * @notapi + */ +void hal_lld_init(void) +{ + // XXX: LED at PIN0.20 was initialized at __early_init + + NRF_GPIO->PIN_CNF[18] = 1; + NRF_GPIO->PIN_CNF[19] = 1; + NRF_GPIO->OUTSET = ((uint32_t) 1 << 18) | ((uint32_t) 1 << 19); + + //FIXME! + while (1) {} +} + +/** + * @} + */ diff --git a/os/hal/ports/NRF51/NRF51822/hal_lld.h b/os/hal/ports/NRF51/NRF51822/hal_lld.h new file mode 100644 index 0000000..1cc9057 --- /dev/null +++ b/os/hal/ports/NRF51/NRF51822/hal_lld.h @@ -0,0 +1,77 @@ +/* + Copyright (C) 2015 Fabio Utzig + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/** + * @file NRF51/NRF51822/hal_lld.h + * @brief NRF51822 HAL subsystem low level driver header. + * + * @addtogroup HAL + * @{ + */ + +#ifndef _HAL_LLD_H_ +#define _HAL_LLD_H_ + +/*===========================================================================*/ +/* Driver constants. */ +/*===========================================================================*/ + +/** + * @name Platform identification + * @{ + */ +#define PLATFORM_NAME "Nordic Semiconductor nRF51822" + +/** + * @} + */ + +/*===========================================================================*/ +/* Driver pre-compile time settings. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Derived constants and error checks. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver data structures and types. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver macros. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* External declarations. */ +/*===========================================================================*/ + +#include "nvic.h" + +#ifdef __cplusplus +extern "C" { +#endif + void hal_lld_init(void); + void nrf51_clock_init(void); +#ifdef __cplusplus +} +#endif + +#endif /* _HAL_LLD_H_ */ + +/** + * @} + */ diff --git a/os/hal/ports/NRF51/NRF51822/st_lld.c b/os/hal/ports/NRF51/NRF51822/st_lld.c new file mode 100644 index 0000000..d439f63 --- /dev/null +++ b/os/hal/ports/NRF51/NRF51822/st_lld.c @@ -0,0 +1,67 @@ +/* + ChibiOS - Copyright (C) 2015 Fabio Utzig + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/** + * @file st_lld.c + * @brief NRF51822 ST subsystem low level driver source. + * + * @addtogroup ST + * @{ + */ + +#include "hal.h" + +#if (OSAL_ST_MODE != OSAL_ST_MODE_NONE) || defined(__DOXYGEN__) + +/*===========================================================================*/ +/* Driver local definitions. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver exported variables. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver local types. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver local variables and types. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver local functions. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver interrupt handlers. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver exported functions. */ +/*===========================================================================*/ + +/** + * @brief Low level ST driver initialization. + * + * @notapi + */ +void st_lld_init(void) { +} + +#endif /* OSAL_ST_MODE != OSAL_ST_MODE_NONE */ + +/** @} */ diff --git a/os/hal/ports/NRF51/NRF51822/st_lld.h b/os/hal/ports/NRF51/NRF51822/st_lld.h new file mode 100644 index 0000000..2e0672e --- /dev/null +++ b/os/hal/ports/NRF51/NRF51822/st_lld.h @@ -0,0 +1,141 @@ +/* + ChibiOS - Copyright (C) 2015 Fabio Utzig + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/** + * @file st_lld.h + * @brief NRF51822 ST subsystem low level driver header. + * @details This header is designed to be include-able without having to + * include other files from the HAL. + * + * @addtogroup ST + * @{ + */ + +#ifndef _ST_LLD_H_ +#define _ST_LLD_H_ + +/*===========================================================================*/ +/* Driver constants. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver pre-compile time settings. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Derived constants and error checks. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver data structures and types. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver macros. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* External declarations. */ +/*===========================================================================*/ + +#ifdef __cplusplus +extern "C" { +#endif + void st_lld_init(void); +#ifdef __cplusplus +} +#endif + +/*===========================================================================*/ +/* Driver inline functions. */ +/*===========================================================================*/ + +/** + * @brief Returns the time counter value. + * + * @return The counter value. + * + * @notapi + */ +static inline systime_t st_lld_get_counter(void) { + + return (systime_t)0; +} + +/** + * @brief Starts the alarm. + * @note Makes sure that no spurious alarms are triggered after + * this call. + * + * @param[in] abstime the time to be set for the first alarm + * + * @notapi + */ +static inline void st_lld_start_alarm(systime_t abstime) { + + (void)abstime; +} + +/** + * @brief Stops the alarm interrupt. + * + * @notapi + */ +static inline void st_lld_stop_alarm(void) { + +} + +/** + * @brief Sets the alarm time. + * + * @param[in] abstime the time to be set for the next alarm + * + * @notapi + */ +static inline void st_lld_set_alarm(systime_t abstime) { + + (void)abstime; +} + +/** + * @brief Returns the current alarm time. + * + * @return The currently set alarm time. + * + * @notapi + */ +static inline systime_t st_lld_get_alarm(void) { + + return (systime_t)0; +} + +/** + * @brief Determines if the alarm is active. + * + * @return The alarm status. + * @retval false if the alarm is not active. + * @retval true is the alarm is active + * + * @notapi + */ +static inline bool st_lld_is_alarm_active(void) { + + return false; +} + +#endif /* _ST_LLD_H_ */ + +/** @} */ -- cgit v1.2.3 From 18c1b38d550ea8500ca11bb20a8fc52bbc26534a Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Tue, 12 May 2015 22:07:41 -0300 Subject: Rename linker script --- .../ports/ARMCMx/compilers/GCC/ld/NRF51822.LD | 48 ---------------------- .../ports/ARMCMx/compilers/GCC/ld/NRF51822.ld | 48 ++++++++++++++++++++++ 2 files changed, 48 insertions(+), 48 deletions(-) delete mode 100644 os/common/ports/ARMCMx/compilers/GCC/ld/NRF51822.LD create mode 100644 os/common/ports/ARMCMx/compilers/GCC/ld/NRF51822.ld (limited to 'os') diff --git a/os/common/ports/ARMCMx/compilers/GCC/ld/NRF51822.LD b/os/common/ports/ARMCMx/compilers/GCC/ld/NRF51822.LD deleted file mode 100644 index 86718d0..0000000 --- a/os/common/ports/ARMCMx/compilers/GCC/ld/NRF51822.LD +++ /dev/null @@ -1,48 +0,0 @@ -/* - Copyright (C) 2015 Fabio Utzig - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -/* - * NRF51822 memory setup. - */ -MEMORY -{ - flash : org = 0x00000000, len = 256k - ram0 : org = 0x20000000, len = 16k - ram1 : org = 0x00000000, len = 0 - ram2 : org = 0x00000000, len = 0 - ram3 : org = 0x00000000, len = 0 - ram4 : org = 0x00000000, len = 0 - ram5 : org = 0x00000000, len = 0 - ram6 : org = 0x00000000, len = 0 - ram7 : org = 0x00000000, len = 0 -} - -/* RAM region to be used for Main stack. This stack accommodates the processing - of all exceptions and interrupts*/ -REGION_ALIAS("MAIN_STACK_RAM", ram0); - -/* RAM region to be used for the process stack. This is the stack used by - the main() function.*/ -REGION_ALIAS("PROCESS_STACK_RAM", ram0); - -/* RAM region to be used for data segment.*/ -REGION_ALIAS("DATA_RAM", ram0); - -/* RAM region to be used for BSS segment.*/ -REGION_ALIAS("BSS_RAM", ram0); - - -INCLUDE rules.ld diff --git a/os/common/ports/ARMCMx/compilers/GCC/ld/NRF51822.ld b/os/common/ports/ARMCMx/compilers/GCC/ld/NRF51822.ld new file mode 100644 index 0000000..ba12060 --- /dev/null +++ b/os/common/ports/ARMCMx/compilers/GCC/ld/NRF51822.ld @@ -0,0 +1,48 @@ +/* + Copyright (C) 2015 Fabio Utzig + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/* + * NRF51822 memory setup. + */ +MEMORY +{ + flash : org = 0x00000000, len = 256k + ram0 : org = 0x20000000, len = 32k + ram1 : org = 0x00000000, len = 0 + ram2 : org = 0x00000000, len = 0 + ram3 : org = 0x00000000, len = 0 + ram4 : org = 0x00000000, len = 0 + ram5 : org = 0x00000000, len = 0 + ram6 : org = 0x00000000, len = 0 + ram7 : org = 0x00000000, len = 0 +} + +/* RAM region to be used for Main stack. This stack accommodates the processing + of all exceptions and interrupts*/ +REGION_ALIAS("MAIN_STACK_RAM", ram0); + +/* RAM region to be used for the process stack. This is the stack used by + the main() function.*/ +REGION_ALIAS("PROCESS_STACK_RAM", ram0); + +/* RAM region to be used for data segment.*/ +REGION_ALIAS("DATA_RAM", ram0); + +/* RAM region to be used for BSS segment.*/ +REGION_ALIAS("BSS_RAM", ram0); + + +INCLUDE rules.ld -- cgit v1.2.3 From c1427ae07dbeead3729cc2402e977f4ebc7fc578 Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Tue, 12 May 2015 22:08:57 -0300 Subject: Add basic board support --- os/hal/boards/WVSHARE_BLE400/board.c | 42 +++++++++++++++++++++++++++++++++++ os/hal/boards/WVSHARE_BLE400/board.h | 41 ++++++++++++++++++++++++++++++++++ os/hal/boards/WVSHARE_BLE400/board.mk | 5 +++++ 3 files changed, 88 insertions(+) create mode 100644 os/hal/boards/WVSHARE_BLE400/board.c create mode 100644 os/hal/boards/WVSHARE_BLE400/board.h create mode 100644 os/hal/boards/WVSHARE_BLE400/board.mk (limited to 'os') diff --git a/os/hal/boards/WVSHARE_BLE400/board.c b/os/hal/boards/WVSHARE_BLE400/board.c new file mode 100644 index 0000000..3c33e5d --- /dev/null +++ b/os/hal/boards/WVSHARE_BLE400/board.c @@ -0,0 +1,42 @@ +/* + Copyright (C) 2015 Fabio Utzig + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +#include "hal.h" + +/** + * @brief Early initialization code. + * @details This initialization is performed just after reset before BSS and + * DATA segments initialization. + */ +void __early_init(void) +{ + NRF_GPIO->PIN_CNF[20] = 1; + NRF_GPIO->OUTSET = (uint32_t) 1 << 20; +} + +/** + * @brief Late initialization code. + * @note This initialization is performed after BSS and DATA segments + * initialization and before invoking the main() function. + */ +void boardInit(void) +{ + //FIXME: not really needed yet + NRF_CLOCK->XTALFREQ = 0xff; + NRF_CLOCK->EVENTS_HFCLKSTARTED = 0; + NRF_CLOCK->TASKS_HFCLKSTART = 1; + while (!NRF_CLOCK->EVENTS_HFCLKSTARTED) {} +} diff --git a/os/hal/boards/WVSHARE_BLE400/board.h b/os/hal/boards/WVSHARE_BLE400/board.h new file mode 100644 index 0000000..4755609 --- /dev/null +++ b/os/hal/boards/WVSHARE_BLE400/board.h @@ -0,0 +1,41 @@ +/* + Copyright (C) 2015 Fabio Utzig + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +#ifndef _BOARD_H_ +#define _BOARD_H_ + +/* + * Board identifier. + */ +#define BOARD_WVSHARE_BLE400 +#define BOARD_NAME "WvShare BLE400" + +/* + * Board oscillators-related settings. + */ +#define XTAL_VALUE 16000000 + +#if !defined(_FROM_ASM_) +#ifdef __cplusplus +extern "C" { +#endif + void boardInit(void); +#ifdef __cplusplus +} +#endif +#endif /* _FROM_ASM_ */ + +#endif /* _BOARD_H_ */ diff --git a/os/hal/boards/WVSHARE_BLE400/board.mk b/os/hal/boards/WVSHARE_BLE400/board.mk new file mode 100644 index 0000000..1fddc87 --- /dev/null +++ b/os/hal/boards/WVSHARE_BLE400/board.mk @@ -0,0 +1,5 @@ +# List of all the board related files. +BOARDSRC = ${CHIBIOS}/community/os/hal/boards/WVSHARE_BLE400/board.c + +# Required include directories +BOARDINC = ${CHIBIOS}/community/os/hal/boards/WVSHARE_BLE400 -- cgit v1.2.3 From d594ac327c8fe72c77de5b422dab12c078baead6 Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Wed, 13 May 2015 20:29:02 -0300 Subject: Fix port params --- os/common/ports/ARMCMx/devices/NRF51822/cmparams.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) (limited to 'os') diff --git a/os/common/ports/ARMCMx/devices/NRF51822/cmparams.h b/os/common/ports/ARMCMx/devices/NRF51822/cmparams.h index 645a438..0cb4ee4 100644 --- a/os/common/ports/ARMCMx/devices/NRF51822/cmparams.h +++ b/os/common/ports/ARMCMx/devices/NRF51822/cmparams.h @@ -37,14 +37,14 @@ #define CORTEX_MODEL 0 /** - * @brief Systick unit presence. + * @brief Memory Protection unit presence. */ -#define CORTEX_HAS_ST FALSE +#define CORTEX_HAS_MPU 1 /** * @brief Floating Point unit presence. */ -#define CORTEX_HAS_FPU FALSE +#define CORTEX_HAS_FPU 0 /** * @brief Number of bits in priority masks. -- cgit v1.2.3 From f0bcca7b4670b2b8fa5f69009e68d2fefeac67e4 Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Wed, 13 May 2015 20:29:45 -0300 Subject: Don't hang boot --- os/hal/ports/NRF51/NRF51822/hal_lld.c | 3 --- 1 file changed, 3 deletions(-) (limited to 'os') diff --git a/os/hal/ports/NRF51/NRF51822/hal_lld.c b/os/hal/ports/NRF51/NRF51822/hal_lld.c index b1a0d34..57caf9e 100644 --- a/os/hal/ports/NRF51/NRF51822/hal_lld.c +++ b/os/hal/ports/NRF51/NRF51822/hal_lld.c @@ -60,9 +60,6 @@ void hal_lld_init(void) NRF_GPIO->PIN_CNF[18] = 1; NRF_GPIO->PIN_CNF[19] = 1; NRF_GPIO->OUTSET = ((uint32_t) 1 << 18) | ((uint32_t) 1 << 19); - - //FIXME! - while (1) {} } /** -- cgit v1.2.3 From 825c8ea30bf3e13698221c918a1a4dfc04bcec5e Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Wed, 13 May 2015 20:30:12 -0300 Subject: Add TIMER0 based ticker for OS --- os/hal/ports/NRF51/NRF51822/st_lld.c | 48 ++++++++++++++++++++++++++++++++++++ 1 file changed, 48 insertions(+) (limited to 'os') diff --git a/os/hal/ports/NRF51/NRF51822/st_lld.c b/os/hal/ports/NRF51/NRF51822/st_lld.c index d439f63..526db35 100644 --- a/os/hal/ports/NRF51/NRF51822/st_lld.c +++ b/os/hal/ports/NRF51/NRF51822/st_lld.c @@ -50,6 +50,29 @@ /* Driver interrupt handlers. */ /*===========================================================================*/ +#if (OSAL_ST_MODE == OSAL_ST_MODE_PERIODIC) || defined(__DOXYGEN__) +/** + * @brief System Timer vector. + * @details This interrupt is used for system tick in periodic mode. + * + * @isr + */ +OSAL_IRQ_HANDLER(Vector60) { + + OSAL_IRQ_PROLOGUE(); + + /* Clear timer compare event */ + if (NRF_TIMER0->EVENTS_COMPARE[0] != 0) + NRF_TIMER0->EVENTS_COMPARE[0] = 0; + + osalSysLockFromISR(); + osalOsTimerHandlerI(); + osalSysUnlockFromISR(); + + OSAL_IRQ_EPILOGUE(); +} +#endif /* OSAL_ST_MODE == OSAL_ST_MODE_PERIODIC */ + /*===========================================================================*/ /* Driver exported functions. */ /*===========================================================================*/ @@ -60,6 +83,31 @@ * @notapi */ void st_lld_init(void) { + +#if OSAL_ST_MODE == OSAL_ST_MODE_PERIODIC + NRF_TIMER0->TASKS_CLEAR = 1; + + /* + * Using 32-bit mode with prescaler 16 configures this + * timer with a 1MHz clock. + */ + NRF_TIMER0->BITMODE = 3; + NRF_TIMER0->PRESCALER = 4; + + /* + * Configure timer 0 compare capture 0 to generate interrupt + * and clear timer value when event is generated. + */ + NRF_TIMER0->CC[0] = (1000000 / OSAL_ST_FREQUENCY) - 1; + NRF_TIMER0->SHORTS = 1; + NRF_TIMER0->INTENSET = 0x10000; + + nvicEnableVector(TIMER0_IRQn, 8); + + /* Start timer */ + NRF_TIMER0->TASKS_START = 1; +#endif + } #endif /* OSAL_ST_MODE != OSAL_ST_MODE_NONE */ -- cgit v1.2.3 From c37554ca20e450bffa0fc3201ceda5283795e3db Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Wed, 13 May 2015 22:19:05 -0300 Subject: Add initial serial driver --- os/hal/ports/NRF51/NRF51822/platform.mk | 1 + os/hal/ports/NRF51/NRF51822/serial_lld.c | 207 +++++++++++++++++++++++++++++++ os/hal/ports/NRF51/NRF51822/serial_lld.h | 119 ++++++++++++++++++ 3 files changed, 327 insertions(+) create mode 100644 os/hal/ports/NRF51/NRF51822/serial_lld.c create mode 100644 os/hal/ports/NRF51/NRF51822/serial_lld.h (limited to 'os') diff --git a/os/hal/ports/NRF51/NRF51822/platform.mk b/os/hal/ports/NRF51/NRF51822/platform.mk index 4ed0722..c905684 100644 --- a/os/hal/ports/NRF51/NRF51822/platform.mk +++ b/os/hal/ports/NRF51/NRF51822/platform.mk @@ -1,6 +1,7 @@ # List of all the NRF51x platform files. PLATFORMSRC = ${CHIBIOS}/os/hal/ports/common/ARMCMx/nvic.c \ ${CHIBIOS}/community/os/hal/ports/NRF51/NRF51822/hal_lld.c \ + ${CHIBIOS}/community/os/hal/ports/NRF51/NRF51822/serial_lld.c \ ${CHIBIOS}/community/os/hal/ports/NRF51/NRF51822/st_lld.c # Required include directories diff --git a/os/hal/ports/NRF51/NRF51822/serial_lld.c b/os/hal/ports/NRF51/NRF51822/serial_lld.c new file mode 100644 index 0000000..c98405d --- /dev/null +++ b/os/hal/ports/NRF51/NRF51822/serial_lld.c @@ -0,0 +1,207 @@ +/* + Copyright (C) 2015 Fabio Utzig + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/** + * @file serial_lld.c + * @brief NRF51822 serial subsystem low level driver source. + * + * @addtogroup SERIAL + * @{ + */ + +#include "hal.h" + +#if (HAL_USE_SERIAL == TRUE) || defined(__DOXYGEN__) + +#include "nrf51.h" + +/*===========================================================================*/ +/* Driver local definitions. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver exported variables. */ +/*===========================================================================*/ + +/** @brief USART1 serial driver identifier.*/ +#if (NRF51_SERIAL_USE_UART0 == TRUE) || defined(__DOXYGEN__) +SerialDriver SD1; +#endif + +/*===========================================================================*/ +/* Driver local variables and types. */ +/*===========================================================================*/ + +/** + * @brief Driver default configuration. + */ +static const SerialConfig default_config = { + 38400 +}; + +/*===========================================================================*/ +/* Driver local functions. */ +/*===========================================================================*/ + +/** + * @brief Driver output notification. + */ +#if NRF51_SERIAL_USE_UART0 || defined(__DOXYGEN__) +static void notify1(io_queue_t *qp) +{ + (void)qp; + + //if (NRF_UART0->EVENTS_TXDRDY) { + msg_t b = oqGetI(&SD1.oqueue); + if (b < Q_OK) { + chnAddFlagsI(&SD1, CHN_OUTPUT_EMPTY); + return; + } + NRF_UART0->TXD = b; + //NRF_UART0->INTENCLR = 0x80; // clear TX interrupt + //} +} +#endif + + +/*===========================================================================*/ +/* Driver interrupt handlers. */ +/*===========================================================================*/ + +#if NRF51_SERIAL_USE_UART0 || defined(__DOXYGEN__) +OSAL_IRQ_HANDLER(Vector48) { + + OSAL_IRQ_PROLOGUE(); + + if (NRF_UART0->EVENTS_RXDRDY) { + osalSysLockFromISR(); + if (iqIsEmptyI(&SD1.iqueue)) + chnAddFlagsI(&SD1, CHN_INPUT_AVAILABLE); + if (iqPutI(&SD1.iqueue, NRF_UART0->RXD) < Q_OK) + chnAddFlagsI(&SD1, SD_OVERRUN_ERROR); + //NRF_UART0->INTENCLR = 4; + osalSysUnlockFromISR(); + } + + if (NRF_UART0->EVENTS_TXDRDY) { + msg_t b; + + osalSysLockFromISR(); + b = oqGetI(&SD1.oqueue); + osalSysUnlockFromISR(); + + if (b < Q_OK) { + osalSysLockFromISR(); + chnAddFlagsI(&SD1, CHN_OUTPUT_EMPTY); + osalSysUnlockFromISR(); + NRF_UART0->INTENCLR = 0x80; // clear TX interrupt + } else { + NRF_UART0->TXD = b; + } + } + + OSAL_IRQ_EPILOGUE(); +} +#endif + +/*===========================================================================*/ +/* Driver exported functions. */ +/*===========================================================================*/ + +/** + * @brief Low level serial driver initialization. + * + * @notapi + */ +void sd_lld_init(void) { + +#if NRF51_SERIAL_USE_UART0 == TRUE + sdObjectInit(&SD1, NULL, notify1); +#endif +} + +/** + * @brief Low level serial driver configuration and (re)start. + * + * @param[in] sdp pointer to a @p SerialDriver object + * @param[in] config the architecture-dependent serial driver configuration. + * If this parameter is set to @p NULL then a default + * configuration is used. + * + * @notapi + */ +void sd_lld_start(SerialDriver *sdp, const SerialConfig *config) { + + if (config == NULL) { + config = &default_config; + } + + if (sdp->state == SD_STOP) { + +#if NRF51_SERIAL_USE_UART0 == TRUE + if (sdp == &SD1) { + /* FIXME: some board specific, some hardcodeds! */ + + /* Configure PINs */ + NRF_UART0->PSELRTS = ~0; + NRF_UART0->PSELCTS = ~0; + + NRF_GPIO->PIN_CNF[9] = 1; + NRF_UART0->PSELTXD = 9; + NRF_UART0->PSELRXD = 11; + + /* 38400!!! */ + NRF_UART0->BAUDRATE = 0x009D5000; + + /* Enable interrupts for RX, TX and ERROR */ + NRF_UART0->INTENSET = 0x284; + + nvicEnableVector(UART0_IRQn, 12); + + NRF_UART0->ENABLE = 4; + NRF_UART0->TASKS_STARTRX = 1; + NRF_UART0->TASKS_STARTTX = 1; + } +#endif + + } +} + +/** + * @brief Low level serial driver stop. + * @details De-initializes the USART, stops the associated clock, resets the + * interrupt vector. + * + * @param[in] sdp pointer to a @p SerialDriver object + * + * @notapi + */ +void sd_lld_stop(SerialDriver *sdp) { + + if (sdp->state == SD_READY) { + +#if NRF51_SERIAL_USE_UART0 == TRUE + if (&SD1 == sdp) { + nvicDisableVector(UART0_IRQn); + } +#endif + + } +} + +#endif /* HAL_USE_SERIAL == TRUE */ + +/** @} */ diff --git a/os/hal/ports/NRF51/NRF51822/serial_lld.h b/os/hal/ports/NRF51/NRF51822/serial_lld.h new file mode 100644 index 0000000..ae8e46e --- /dev/null +++ b/os/hal/ports/NRF51/NRF51822/serial_lld.h @@ -0,0 +1,119 @@ +/* + Copyright (C) 2015 Fabio Utzig + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/** + * @file serial_lld.h + * @brief NRF51822 serial subsystem low level driver header. + * + * @addtogroup SERIAL + * @{ + */ + +#ifndef _SERIAL_LLD_H_ +#define _SERIAL_LLD_H_ + +#if (HAL_USE_SERIAL == TRUE) || defined(__DOXYGEN__) + +/*===========================================================================*/ +/* Driver constants. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver pre-compile time settings. */ +/*===========================================================================*/ + +/** + * @name PLATFORM configuration options + * @{ + */ +/** + * @brief USART1 driver enable switch. + * @details If set to @p TRUE the support for USART1 is included. + * @note The default is @p FALSE. + */ +#if !defined(NRF51_SERIAL_USE_UART0) || defined(__DOXYGEN__) +#define NRF51_SERIAL_USE_UART0 FALSE +#endif +/** @} */ + +/*===========================================================================*/ +/* Derived constants and error checks. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver data structures and types. */ +/*===========================================================================*/ + +/** + * @brief NRF51 Serial Driver configuration structure. + * @details An instance of this structure must be passed to @p sdStart() + * in order to configure and start a serial driver operations. + * @note This structure content is architecture dependent, each driver + * implementation defines its own version and the custom static + * initializers. + */ +typedef struct { + /** + * @brief Bit rate. + */ + uint32_t speed; + /* End of the mandatory fields.*/ +} SerialConfig; + +/** + * @brief @p SerialDriver specific data. + */ +#define _serial_driver_data \ + _base_asynchronous_channel_data \ + /* Driver state.*/ \ + sdstate_t state; \ + /* Input queue.*/ \ + input_queue_t iqueue; \ + /* Output queue.*/ \ + output_queue_t oqueue; \ + /* Input circular buffer.*/ \ + uint8_t ib[SERIAL_BUFFERS_SIZE]; \ + /* Output circular buffer.*/ \ + uint8_t ob[SERIAL_BUFFERS_SIZE]; \ + /* End of the mandatory fields.*/ + +/*===========================================================================*/ +/* Driver macros. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* External declarations. */ +/*===========================================================================*/ + +#if (NRF51_SERIAL_USE_UART0 == TRUE) && !defined(__DOXYGEN__) +extern SerialDriver SD1; +#endif + +#ifdef __cplusplus +extern "C" { +#endif + void sd_lld_init(void); + void sd_lld_start(SerialDriver *sdp, const SerialConfig *config); + void sd_lld_stop(SerialDriver *sdp); +#ifdef __cplusplus +} +#endif + +#endif /* HAL_USE_SERIAL == TRUE */ + +#endif /* _SERIAL_LLD_H_ */ + +/** @} */ -- cgit v1.2.3 From 776fc2910771562d74d2aa2bd47d454ae33450ee Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Thu, 14 May 2015 22:12:57 -0300 Subject: Fix some issues with serial driver --- os/hal/ports/NRF51/NRF51822/serial_lld.c | 62 +++++++++++++++++++++++++------- 1 file changed, 49 insertions(+), 13 deletions(-) (limited to 'os') diff --git a/os/hal/ports/NRF51/NRF51822/serial_lld.c b/os/hal/ports/NRF51/NRF51822/serial_lld.c index c98405d..6cb6943 100644 --- a/os/hal/ports/NRF51/NRF51822/serial_lld.c +++ b/os/hal/ports/NRF51/NRF51822/serial_lld.c @@ -32,6 +32,8 @@ /* Driver local definitions. */ /*===========================================================================*/ +#define INVALID_BAUDRATE 0xFFFFFFFF + /*===========================================================================*/ /* Driver exported variables. */ /*===========================================================================*/ @@ -56,6 +58,33 @@ static const SerialConfig default_config = { /* Driver local functions. */ /*===========================================================================*/ +/* + * @brief Maps a baudrate speed to a BAUDRATE register value. + */ +static uint32_t regval_from_baudrate(uint32_t speed) +{ + switch (speed) { + case 1200: return 0x0004F000; + case 2400: return 0x0009D000; + case 4800: return 0x0013B000; + case 9600: return 0x00275000; + case 14400: return 0x003B0000; + case 19200: return 0x004EA000; + case 28800: return 0x0075F000; + case 38400: return 0x009D5000; + case 57600: return 0x00EBF000; + case 76800: return 0x013A9000; + case 115200: return 0x01D7E000; + case 230400: return 0x03AFB000; + case 250000: return 0x04000000; + case 460800: return 0x075F7000; + case 921600: return 0x0EBEDFA4; + case 1000000: return 0x10000000; + } + return INVALID_BAUDRATE; +} + + /** * @brief Driver output notification. */ @@ -64,15 +93,12 @@ static void notify1(io_queue_t *qp) { (void)qp; - //if (NRF_UART0->EVENTS_TXDRDY) { - msg_t b = oqGetI(&SD1.oqueue); - if (b < Q_OK) { - chnAddFlagsI(&SD1, CHN_OUTPUT_EMPTY); - return; - } - NRF_UART0->TXD = b; - //NRF_UART0->INTENCLR = 0x80; // clear TX interrupt - //} + msg_t b = oqGetI(&SD1.oqueue); + if (b < Q_OK) { + chnAddFlagsI(&SD1, CHN_OUTPUT_EMPTY); + return; + } + NRF_UART0->TXD = b; } #endif @@ -87,18 +113,20 @@ OSAL_IRQ_HANDLER(Vector48) { OSAL_IRQ_PROLOGUE(); if (NRF_UART0->EVENTS_RXDRDY) { + NRF_UART0->EVENTS_RXDRDY = 0; osalSysLockFromISR(); if (iqIsEmptyI(&SD1.iqueue)) chnAddFlagsI(&SD1, CHN_INPUT_AVAILABLE); if (iqPutI(&SD1.iqueue, NRF_UART0->RXD) < Q_OK) chnAddFlagsI(&SD1, SD_OVERRUN_ERROR); - //NRF_UART0->INTENCLR = 4; osalSysUnlockFromISR(); } if (NRF_UART0->EVENTS_TXDRDY) { msg_t b; + NRF_UART0->EVENTS_TXDRDY = 0; + osalSysLockFromISR(); b = oqGetI(&SD1.oqueue); osalSysUnlockFromISR(); @@ -107,12 +135,14 @@ OSAL_IRQ_HANDLER(Vector48) { osalSysLockFromISR(); chnAddFlagsI(&SD1, CHN_OUTPUT_EMPTY); osalSysUnlockFromISR(); - NRF_UART0->INTENCLR = 0x80; // clear TX interrupt } else { NRF_UART0->TXD = b; } } + //TODO + NRF_UART0->EVENTS_ERROR = 0; + OSAL_IRQ_EPILOGUE(); } #endif @@ -153,6 +183,8 @@ void sd_lld_start(SerialDriver *sdp, const SerialConfig *config) { #if NRF51_SERIAL_USE_UART0 == TRUE if (sdp == &SD1) { + uint32_t regval; + /* FIXME: some board specific, some hardcodeds! */ /* Configure PINs */ @@ -163,12 +195,16 @@ void sd_lld_start(SerialDriver *sdp, const SerialConfig *config) { NRF_UART0->PSELTXD = 9; NRF_UART0->PSELRXD = 11; - /* 38400!!! */ - NRF_UART0->BAUDRATE = 0x009D5000; + regval = regval_from_baudrate(config->speed); + osalDbgAssert(regval != INVALID_BAUDRATE, "invalid baudrate speed"); + NRF_UART0->BAUDRATE = regval; /* Enable interrupts for RX, TX and ERROR */ NRF_UART0->INTENSET = 0x284; + NRF_UART0->EVENTS_RXDRDY = 0; + NRF_UART0->EVENTS_TXDRDY = 0; + nvicEnableVector(UART0_IRQn, 12); NRF_UART0->ENABLE = 4; -- cgit v1.2.3 From aa43fd6554c1d35360c857a1b5d5fddcf1577a32 Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Thu, 14 May 2015 23:07:10 -0300 Subject: Use sleep/wakeup for serial driver top-half --- os/hal/ports/NRF51/NRF51822/serial_lld.c | 17 ++++------------- os/hal/ports/NRF51/NRF51822/serial_lld.h | 3 ++- 2 files changed, 6 insertions(+), 14 deletions(-) (limited to 'os') diff --git a/os/hal/ports/NRF51/NRF51822/serial_lld.c b/os/hal/ports/NRF51/NRF51822/serial_lld.c index 6cb6943..ea687c8 100644 --- a/os/hal/ports/NRF51/NRF51822/serial_lld.c +++ b/os/hal/ports/NRF51/NRF51822/serial_lld.c @@ -98,7 +98,9 @@ static void notify1(io_queue_t *qp) chnAddFlagsI(&SD1, CHN_OUTPUT_EMPTY); return; } + SD1.thread = chThdGetSelfX(); NRF_UART0->TXD = b; + chEvtWaitAny((eventmask_t) 1); } #endif @@ -123,25 +125,14 @@ OSAL_IRQ_HANDLER(Vector48) { } if (NRF_UART0->EVENTS_TXDRDY) { - msg_t b; - NRF_UART0->EVENTS_TXDRDY = 0; - osalSysLockFromISR(); - b = oqGetI(&SD1.oqueue); + chEvtSignalI(SD1.thread, (eventmask_t) 1); osalSysUnlockFromISR(); - - if (b < Q_OK) { - osalSysLockFromISR(); - chnAddFlagsI(&SD1, CHN_OUTPUT_EMPTY); - osalSysUnlockFromISR(); - } else { - NRF_UART0->TXD = b; - } } //TODO - NRF_UART0->EVENTS_ERROR = 0; + //NRF_UART0->EVENTS_ERROR = 0; OSAL_IRQ_EPILOGUE(); } diff --git a/os/hal/ports/NRF51/NRF51822/serial_lld.h b/os/hal/ports/NRF51/NRF51822/serial_lld.h index ae8e46e..b7b1beb 100644 --- a/os/hal/ports/NRF51/NRF51822/serial_lld.h +++ b/os/hal/ports/NRF51/NRF51822/serial_lld.h @@ -88,7 +88,8 @@ typedef struct { uint8_t ib[SERIAL_BUFFERS_SIZE]; \ /* Output circular buffer.*/ \ uint8_t ob[SERIAL_BUFFERS_SIZE]; \ - /* End of the mandatory fields.*/ + /* End of the mandatory fields.*/ \ + thread_t *thread; /*===========================================================================*/ /* Driver macros. */ -- cgit v1.2.3 From 4ac0b638b92db47625d729b938e71b262dadbb43 Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Fri, 15 May 2015 20:44:03 -0300 Subject: Add basic PAL driver --- os/hal/ports/NRF51/NRF51822/pal_lld.c | 129 +++++++++++ os/hal/ports/NRF51/NRF51822/pal_lld.h | 373 ++++++++++++++++++++++++++++++++ os/hal/ports/NRF51/NRF51822/platform.mk | 1 + 3 files changed, 503 insertions(+) create mode 100644 os/hal/ports/NRF51/NRF51822/pal_lld.c create mode 100644 os/hal/ports/NRF51/NRF51822/pal_lld.h (limited to 'os') diff --git a/os/hal/ports/NRF51/NRF51822/pal_lld.c b/os/hal/ports/NRF51/NRF51822/pal_lld.c new file mode 100644 index 0000000..ccbe20e --- /dev/null +++ b/os/hal/ports/NRF51/NRF51822/pal_lld.c @@ -0,0 +1,129 @@ +/* + Copyright (C) 2015 Fabio Utzig + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/** + * @file pal_lld.c + * @brief NRF51822 PAL subsystem low level driver source. + * + * @addtogroup PAL + * @{ + */ + +#include "osal.h" +#include "hal.h" + +#if (HAL_USE_PAL == TRUE) || defined(__DOXYGEN__) + +/*===========================================================================*/ +/* Driver local definitions. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver exported variables. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver local variables and types. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver local functions. */ +/*===========================================================================*/ + +void _pal_lld_setpadmode(uint8_t pad, iomode_t mode) +{ + uint8_t value = 0; + + osalDbgAssert(pad < 32, "invalid pad"); + + switch (mode) { + case PAL_MODE_RESET: + case PAL_MODE_UNCONNECTED: + value = 2; + break; + case PAL_MODE_INPUT: + case PAL_MODE_INPUT_ANALOG: + value = 0; + break; + case PAL_MODE_INPUT_PULLUP: + value = 0xC; + break; + case PAL_MODE_INPUT_PULLDOWN: + value = 4; + break; + case PAL_MODE_OUTPUT_PUSHPULL: + value = 1; + break; + case PAL_MODE_OUTPUT_OPENDRAIN: + value = 0x61; + break; + } + + NRF_GPIO->PIN_CNF[pad] = value; +} + +/*===========================================================================*/ +/* Driver interrupt handlers. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver exported functions. */ +/*===========================================================================*/ + +/** + * @brief STM32 I/O ports configuration. + * @details Ports A-D(E, F, G, H) clocks enabled. + * + * @param[in] config the STM32 ports configuration + * + * @notapi + */ +void _pal_lld_init(const PALConfig *config) +{ + uint8_t i; + + for (i = 0; i < TOTAL_GPIO_PADS; i++) { + pal_lld_setpadmode(IOPORT1, i, config->pads[i]); + } +} + +/** + * @brief Pads mode setup. + * @details This function programs a pads group belonging to the same port + * with the specified mode. + * + * @param[in] port the port identifier + * @param[in] mask the group mask + * @param[in] mode the mode + * + * @notapi + */ +void _pal_lld_setgroupmode(ioportid_t port, + ioportmask_t mask, + iomode_t mode) +{ + uint8_t i; + + (void)mask; + + for (i = 0; i < TOTAL_GPIO_PADS; i++) { + pal_lld_setpadmode(port, i, mode); + } +} + +#endif /* HAL_USE_PAL == TRUE */ + +/** @} */ diff --git a/os/hal/ports/NRF51/NRF51822/pal_lld.h b/os/hal/ports/NRF51/NRF51822/pal_lld.h new file mode 100644 index 0000000..2383cfe --- /dev/null +++ b/os/hal/ports/NRF51/NRF51822/pal_lld.h @@ -0,0 +1,373 @@ +/* + Copyright (C) 2015 Fabio Utzig + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/** + * @file pal_lld.h + * @brief NRF51822 PAL subsystem low level driver header. + * + * @addtogroup PAL + * @{ + */ + +#ifndef _PAL_LLD_H_ +#define _PAL_LLD_H_ + +#if (HAL_USE_PAL == TRUE) || defined(__DOXYGEN__) + +/*===========================================================================*/ +/* Unsupported modes and specific modes */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* I/O Ports Types and constants. */ +/*===========================================================================*/ + +#define TOTAL_GPIO_PADS 32 + +/** + * @brief Generic I/O ports static initializer. + * @details An instance of this structure must be passed to @p palInit() at + * system startup time in order to initialized the digital I/O + * subsystem. This represents only the initial setup, specific pads + * or whole ports can be reprogrammed at later time. + * @note Implementations may extend this structure to contain more, + * architecture dependent, fields. + */ +typedef struct { + uint32_t pads[TOTAL_GPIO_PADS]; +} PALConfig; + +/** + * @brief Width, in bits, of an I/O port. + */ +#define PAL_IOPORTS_WIDTH 32U + +/** + * @brief Whole port mask. + * @brief This macro specifies all the valid bits into a port. + */ +#define PAL_WHOLE_PORT ((ioportmask_t)0xFFFFFFFFU) + +/** + * @brief Digital I/O port sized unsigned type. + */ +typedef uint32_t ioportmask_t; + +/** + * @brief Digital I/O modes. + */ +typedef uint32_t iomode_t; + +/** + * @brief Port Identifier. + * @details This type can be a scalar or some kind of pointer, do not make + * any assumption about it, use the provided macros when populating + * variables of this type. + */ +typedef uint32_t ioportid_t; + +/*===========================================================================*/ +/* I/O Ports Identifiers. */ +/*===========================================================================*/ + +/** + * @brief First I/O port identifier. + * @details Low level drivers can define multiple ports, it is suggested to + * use this naming convention. + */ +#define IOPORT1 NRF_GPIO + +/*===========================================================================*/ +/* Implementation, some of the following macros could be implemented as */ +/* functions, if so please put them in pal_lld.c. */ +/*===========================================================================*/ + +void _pal_lld_setpadmode(uint8_t pad, iomode_t mode); + +/** + * @brief Low level PAL subsystem initialization. + * + * @param[in] config architecture-dependent ports configuration + * + * @notapi + */ +#define pal_lld_init(config) _pal_lld_init(config) + +/** + * @brief Reads the physical I/O port states. + * + * @param[in] port port identifier + * @return The port bits. + * + * @notapi + */ +#define pal_lld_readport(port) 0U + +/** + * @brief Reads the output latch. + * @details The purpose of this function is to read back the latched output + * value. + * + * @param[in] port port identifier + * @return The latched logical states. + * + * @notapi + */ +#define pal_lld_readlatch(port) 0U + +/** + * @brief Writes a bits mask on a I/O port. + * + * @param[in] port port identifier + * @param[in] bits bits to be written on the specified port + * + * @notapi + */ +#define pal_lld_writeport(port, bits) \ + do { \ + (void)port; \ + (void)bits; \ + } while (false) + + +/** + * @brief Sets a bits mask on a I/O port. + * @note The @ref PAL provides a default software implementation of this + * functionality, implement this function if can optimize it by using + * special hardware functionalities or special coding. + * + * @param[in] port port identifier + * @param[in] bits bits to be ORed on the specified port + * + * @notapi + */ +#define pal_lld_setport(port, bits) \ + do { \ + (void)port; \ + (void)bits; \ + } while (false) + + +/** + * @brief Clears a bits mask on a I/O port. + * @note The @ref PAL provides a default software implementation of this + * functionality, implement this function if can optimize it by using + * special hardware functionalities or special coding. + * + * @param[in] port port identifier + * @param[in] bits bits to be cleared on the specified port + * + * @notapi + */ +#define pal_lld_clearport(port, bits) \ + do { \ + (void)port; \ + (void)bits; \ + } while (false) + + +/** + * @brief Toggles a bits mask on a I/O port. + * @note The @ref PAL provides a default software implementation of this + * functionality, implement this function if can optimize it by using + * special hardware functionalities or special coding. + * + * @param[in] port port identifier + * @param[in] bits bits to be XORed on the specified port + * + * @notapi + */ +#define pal_lld_toggleport(port, bits) \ + do { \ + (void)port; \ + (void)bits; \ + } while (false) + + +/** + * @brief Reads a group of bits. + * @note The @ref PAL provides a default software implementation of this + * functionality, implement this function if can optimize it by using + * special hardware functionalities or special coding. + * + * @param[in] port port identifier + * @param[in] mask group mask + * @param[in] offset group bit offset within the port + * @return The group logical states. + * + * @notapi + */ +#define pal_lld_readgroup(port, mask, offset) 0U + +/** + * @brief Writes a group of bits. + * @note The @ref PAL provides a default software implementation of this + * functionality, implement this function if can optimize it by using + * special hardware functionalities or special coding. + * + * @param[in] port port identifier + * @param[in] mask group mask + * @param[in] offset group bit offset within the port + * @param[in] bits bits to be written. Values exceeding the group width + * are masked. + * + * @notapi + */ +#define pal_lld_writegroup(port, mask, offset, bits) \ + do { \ + (void)port; \ + (void)mask; \ + (void)offset; \ + (void)bits; \ + } while (false) + +/** + * @brief Pads group mode setup. + * @details This function programs a pads group belonging to the same port + * with the specified mode. + * @note Programming an unknown or unsupported mode is silently ignored. + * + * @param[in] port port identifier + * @param[in] mask group mask + * @param[in] offset group bit offset within the port + * @param[in] mode group mode + * + * @notapi + */ +#define pal_lld_setgroupmode(port, mask, offset, mode) \ + _pal_lld_setgroupmode(port, mask << offset, mode) + +/** + * @brief Reads a logical state from an I/O pad. + * @note The @ref PAL provides a default software implementation of this + * functionality, implement this function if can optimize it by using + * special hardware functionalities or special coding. + * + * @param[in] port port identifier + * @param[in] pad pad number within the port + * @return The logical state. + * @retval PAL_LOW low logical state. + * @retval PAL_HIGH high logical state. + * + * @notapi + */ +#define pal_lld_readpad(port, pad) PAL_LOW + +/** + * @brief Writes a logical state on an output pad. + * @note This function is not meant to be invoked directly by the + * application code. + * @note The @ref PAL provides a default software implementation of this + * functionality, implement this function if can optimize it by using + * special hardware functionalities or special coding. + * + * @param[in] port port identifier + * @param[in] pad pad number within the port + * @param[in] bit logical value, the value must be @p PAL_LOW or + * @p PAL_HIGH + * + * @notapi + */ +#define pal_lld_writepad(port, pad, bit) \ + do { \ + (void)port; \ + (void)pad; \ + (void)bit; \ + } while (false) + +/** + * @brief Sets a pad logical state to @p PAL_HIGH. + * @note The @ref PAL provides a default software implementation of this + * functionality, implement this function if can optimize it by using + * special hardware functionalities or special coding. + * + * @param[in] port port identifier + * @param[in] pad pad number within the port + * + * @notapi + */ +#define pal_lld_setpad(port, pad) (NRF_GPIO->OUTSET = (uint32_t) 1 << (pad)) + +/** + * @brief Clears a pad logical state to @p PAL_LOW. + * @note The @ref PAL provides a default software implementation of this + * functionality, implement this function if can optimize it by using + * special hardware functionalities or special coding. + * + * @param[in] port port identifier + * @param[in] pad pad number within the port + * + * @notapi + */ +#define pal_lld_clearpad(port, pad) (NRF_GPIO->OUTCLR = (uint32_t) 1 << (pad)) + +/** + * @brief Toggles a pad logical state. + * @note The @ref PAL provides a default software implementation of this + * functionality, implement this function if can optimize it by using + * special hardware functionalities or special coding. + * + * @param[in] port port identifier + * @param[in] pad pad number within the port + * + * @notapi + */ +#define pal_lld_togglepad(port, pad) \ + do { \ + uint8_t bit = (NRF_GPIO->IN >> (pad)) & 1; \ + if (bit) \ + NRF_GPIO->OUTCLR = 1 << (pad); \ + else \ + NRF_GPIO->OUTSET = 1 << (pad); \ + } while (0) + + +/** + * @brief Pad mode setup. + * @details This function programs a pad with the specified mode. + * @note The @ref PAL provides a default software implementation of this + * functionality, implement this function if can optimize it by using + * special hardware functionalities or special coding. + * @note Programming an unknown or unsupported mode is silently ignored. + * + * @param[in] port port identifier + * @param[in] pad pad number within the port + * @param[in] mode pad mode + * + * @notapi + */ +#define pal_lld_setpadmode(port, pad, mode) _pal_lld_setpadmode(pad, mode) + +#if !defined(__DOXYGEN__) +extern const PALConfig pal_default_config; +#endif + +#ifdef __cplusplus +extern "C" { +#endif + void _pal_lld_init(const PALConfig *config); + void _pal_lld_setgroupmode(ioportid_t port, + ioportmask_t mask, + iomode_t mode); +#ifdef __cplusplus +} +#endif + +#endif /* HAL_USE_PAL == TRUE */ + +#endif /* _PAL_LLD_H_ */ + +/** @} */ diff --git a/os/hal/ports/NRF51/NRF51822/platform.mk b/os/hal/ports/NRF51/NRF51822/platform.mk index c905684..10aad23 100644 --- a/os/hal/ports/NRF51/NRF51822/platform.mk +++ b/os/hal/ports/NRF51/NRF51822/platform.mk @@ -1,6 +1,7 @@ # List of all the NRF51x platform files. PLATFORMSRC = ${CHIBIOS}/os/hal/ports/common/ARMCMx/nvic.c \ ${CHIBIOS}/community/os/hal/ports/NRF51/NRF51822/hal_lld.c \ + ${CHIBIOS}/community/os/hal/ports/NRF51/NRF51822/pal_lld.c \ ${CHIBIOS}/community/os/hal/ports/NRF51/NRF51822/serial_lld.c \ ${CHIBIOS}/community/os/hal/ports/NRF51/NRF51822/st_lld.c -- cgit v1.2.3 From 621e7198d7ed975152fc2902e3625dcf42285e5e Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Fri, 15 May 2015 20:44:37 -0300 Subject: Remove GPIO pin initialization --- os/hal/ports/NRF51/NRF51822/hal_lld.c | 5 ----- 1 file changed, 5 deletions(-) (limited to 'os') diff --git a/os/hal/ports/NRF51/NRF51822/hal_lld.c b/os/hal/ports/NRF51/NRF51822/hal_lld.c index 57caf9e..e1d2ed5 100644 --- a/os/hal/ports/NRF51/NRF51822/hal_lld.c +++ b/os/hal/ports/NRF51/NRF51822/hal_lld.c @@ -55,11 +55,6 @@ */ void hal_lld_init(void) { - // XXX: LED at PIN0.20 was initialized at __early_init - - NRF_GPIO->PIN_CNF[18] = 1; - NRF_GPIO->PIN_CNF[19] = 1; - NRF_GPIO->OUTSET = ((uint32_t) 1 << 18) | ((uint32_t) 1 << 19); } /** -- cgit v1.2.3 From 57f582abae3e240498c91d3ccf398880bb78d3a2 Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Fri, 15 May 2015 20:45:02 -0300 Subject: Add some GPIO pin definitions --- os/hal/boards/WVSHARE_BLE400/board.h | 17 +++++++++++------ 1 file changed, 11 insertions(+), 6 deletions(-) (limited to 'os') diff --git a/os/hal/boards/WVSHARE_BLE400/board.h b/os/hal/boards/WVSHARE_BLE400/board.h index 4755609..957fe7e 100644 --- a/os/hal/boards/WVSHARE_BLE400/board.h +++ b/os/hal/boards/WVSHARE_BLE400/board.h @@ -17,17 +17,22 @@ #ifndef _BOARD_H_ #define _BOARD_H_ -/* - * Board identifier. - */ +/* Board identifier. */ #define BOARD_WVSHARE_BLE400 #define BOARD_NAME "WvShare BLE400" -/* - * Board oscillators-related settings. - */ +/* Board oscillators-related settings. */ #define XTAL_VALUE 16000000 +/* GPIO pins. */ +#define LED0 18 +#define LED1 19 +#define LED2 20 +#define LED3 21 +#define LED4 22 +#define UART_TX 9 +#define UART_RX 11 + #if !defined(_FROM_ASM_) #ifdef __cplusplus extern "C" { -- cgit v1.2.3 From 69d70de9b746094768de835e14d2f3686d15e072 Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Fri, 15 May 2015 21:04:52 -0300 Subject: Add PAL configuration --- os/hal/boards/WVSHARE_BLE400/board.c | 55 ++++++++++++++++++++++++++++++++---- 1 file changed, 49 insertions(+), 6 deletions(-) (limited to 'os') diff --git a/os/hal/boards/WVSHARE_BLE400/board.c b/os/hal/boards/WVSHARE_BLE400/board.c index 3c33e5d..bee9490 100644 --- a/os/hal/boards/WVSHARE_BLE400/board.c +++ b/os/hal/boards/WVSHARE_BLE400/board.c @@ -16,6 +16,51 @@ #include "hal.h" +#if HAL_USE_PAL || defined(__DOXYGEN__) +/** + * @brief PAL setup. + * @details Digital I/O ports static configuration as defined in @p board.h. + * This variable is used by the HAL when initializing the PAL driver. + */ +const PALConfig pal_default_config = +{ + .pads = { + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_OUTPUT_PUSHPULL, // UART_TX + PAL_MODE_INPUT, + PAL_MODE_INPUT, // UART_RX + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_OUTPUT_PUSHPULL, // LED0 + PAL_MODE_OUTPUT_PUSHPULL, // LED1 + PAL_MODE_OUTPUT_PUSHPULL, // LED2 + PAL_MODE_OUTPUT_PUSHPULL, // LED3 + PAL_MODE_OUTPUT_PUSHPULL, // LED4 + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + PAL_MODE_INPUT, + }, +}; +#endif + /** * @brief Early initialization code. * @details This initialization is performed just after reset before BSS and @@ -23,8 +68,6 @@ */ void __early_init(void) { - NRF_GPIO->PIN_CNF[20] = 1; - NRF_GPIO->OUTSET = (uint32_t) 1 << 20; } /** @@ -35,8 +78,8 @@ void __early_init(void) void boardInit(void) { //FIXME: not really needed yet - NRF_CLOCK->XTALFREQ = 0xff; - NRF_CLOCK->EVENTS_HFCLKSTARTED = 0; - NRF_CLOCK->TASKS_HFCLKSTART = 1; - while (!NRF_CLOCK->EVENTS_HFCLKSTARTED) {} + //NRF_CLOCK->XTALFREQ = 0xff; + //NRF_CLOCK->EVENTS_HFCLKSTARTED = 0; + //NRF_CLOCK->TASKS_HFCLKSTART = 1; + //while (!NRF_CLOCK->EVENTS_HFCLKSTARTED) {} } -- cgit v1.2.3 From 343042d9d25a80a47d6ba10026d66987a7db3256 Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Fri, 15 May 2015 21:08:53 -0300 Subject: Add tx/rx pin configuration to SerialConfig --- os/hal/ports/NRF51/NRF51822/serial_lld.c | 22 ++++++++++++++-------- os/hal/ports/NRF51/NRF51822/serial_lld.h | 2 ++ 2 files changed, 16 insertions(+), 8 deletions(-) (limited to 'os') diff --git a/os/hal/ports/NRF51/NRF51822/serial_lld.c b/os/hal/ports/NRF51/NRF51822/serial_lld.c index ea687c8..1783b92 100644 --- a/os/hal/ports/NRF51/NRF51822/serial_lld.c +++ b/os/hal/ports/NRF51/NRF51822/serial_lld.c @@ -33,6 +33,7 @@ /*===========================================================================*/ #define INVALID_BAUDRATE 0xFFFFFFFF +#define INVALID_PIN 0xFF /*===========================================================================*/ /* Driver exported variables. */ @@ -51,7 +52,9 @@ SerialDriver SD1; * @brief Driver default configuration. */ static const SerialConfig default_config = { - 38400 + .speed = 38400, + .tx_pin = INVALID_PIN, + .rx_pin = INVALID_PIN, }; /*===========================================================================*/ @@ -131,8 +134,7 @@ OSAL_IRQ_HANDLER(Vector48) { osalSysUnlockFromISR(); } - //TODO - //NRF_UART0->EVENTS_ERROR = 0; + /* TODO: Error handling for EVENTS_ERROR */ OSAL_IRQ_EPILOGUE(); } @@ -176,15 +178,19 @@ void sd_lld_start(SerialDriver *sdp, const SerialConfig *config) { if (sdp == &SD1) { uint32_t regval; - /* FIXME: some board specific, some hardcodeds! */ + /* TODO: Add support for CTS/RTS! */ /* Configure PINs */ NRF_UART0->PSELRTS = ~0; NRF_UART0->PSELCTS = ~0; - - NRF_GPIO->PIN_CNF[9] = 1; - NRF_UART0->PSELTXD = 9; - NRF_UART0->PSELRXD = 11; + if (config->tx_pin != INVALID_PIN) { + palSetPadMode(IOPORT1, config->tx_pin, PAL_MODE_OUTPUT_PUSHPULL); + NRF_UART0->PSELTXD = config->tx_pin; + } + if (config->rx_pin != INVALID_PIN) { + palSetPadMode(IOPORT1, config->rx_pin, PAL_MODE_INPUT); + NRF_UART0->PSELRXD = config->rx_pin; + } regval = regval_from_baudrate(config->speed); osalDbgAssert(regval != INVALID_BAUDRATE, "invalid baudrate speed"); diff --git a/os/hal/ports/NRF51/NRF51822/serial_lld.h b/os/hal/ports/NRF51/NRF51822/serial_lld.h index b7b1beb..62f1302 100644 --- a/os/hal/ports/NRF51/NRF51822/serial_lld.h +++ b/os/hal/ports/NRF51/NRF51822/serial_lld.h @@ -71,6 +71,8 @@ typedef struct { */ uint32_t speed; /* End of the mandatory fields.*/ + uint8_t tx_pin; + uint8_t rx_pin; } SerialConfig; /** -- cgit v1.2.3 From 2ba20d691dd398b3ef46d41d62edf20bcd97188b Mon Sep 17 00:00:00 2001 From: Fabio Utzig Date: Fri, 15 May 2015 21:25:46 -0300 Subject: Remove ChibiOS mentions from copyright --- os/common/ports/ARMCMx/devices/NRF51822/cmparams.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'os') diff --git a/os/common/ports/ARMCMx/devices/NRF51822/cmparams.h b/os/common/ports/ARMCMx/devices/NRF51822/cmparams.h index 0cb4ee4..126acf6 100644 --- a/os/common/ports/ARMCMx/devices/NRF51822/cmparams.h +++ b/os/common/ports/ARMCMx/devices/NRF51822/cmparams.h @@ -1,5 +1,5 @@ /* - ChibiOS - Copyright (C) 2015 Fabio Utzig + Copyright (C) 2015 Fabio Utzig This file is part of ChibiOS. -- cgit v1.2.3