nrf52: add support for SPI

nrf52: add support for GPIO interrupts

nrf52: add macros to decode GPIO PIN and GPIO PORT

nrf52: various cosmetic changes

nrf52: fix GPIO P1 memory address

boards/nrf52840-dk: add support for SPI

boards/nrf52840-dk: add support for LSM6DSL sensor

boards/nrf52840-dk: add support for SX127X radio
This commit is contained in:
raiden00pl 2020-01-08 15:48:20 +01:00 committed by Gregory Nutt
parent d76ba14d58
commit f51e478ad8
29 changed files with 2335 additions and 141 deletions

View File

@ -118,6 +118,18 @@ config NRF52_SPI3_MASTER
select NRF52_SPI_MASTER
depends on NRF52_HAVE_SPI3_MASTER
if NRF52_SPI_MASTER
config NRF52_SPI_MASTER_INTERRUPTS
bool "SPI Master interrupts support"
default n
endif
config NRF52_GPIOTE
bool "GPIOTE (GPIO interrupts)"
default n
config NRF52_UART0
bool "UART0"
default n
@ -220,8 +232,4 @@ config NRF52_PROGMEM
menu "GPIO Interrupt Configuration"
config NRF52_GPIOIRQ
bool "Support GPIO Interrupts"
default n
endmenu # GPIO Interrupt Configuration

View File

@ -101,6 +101,10 @@ ifneq ($(CONFIG_ARCH_IDLE_CUSTOM),y)
CHIP_CSRCS += nrf52_idle.c
endif
ifeq ($(CONFIG_NRF52_GPIOTE),y)
CHIP_CSRCS += nrf52_gpiote.c
endif
ifeq ($(CONFIG_NRF52_UART),y)
CHIP_CSRCS += nrf52_serial.c
endif
@ -117,3 +121,11 @@ ifeq ($(CONFIG_NRF52_RNG),y)
CHIP_CSRCS += nrf52_rng.c
endif
ifeq ($(CONFIG_NRF52_SPI_MASTER),y)
CHIP_CSRCS += nrf52_spi.c
endif
ifeq ($(CONFIG_NRF52_I2C_MASTER),y)
CHIP_CSRCS += nrf52_i2c.c
endif

View File

@ -48,8 +48,14 @@
* Pre-processor Definitions
************************************************************************************/
#define NRF52_GPIO_PORT0 0
#define NRF52_GPIO_NPORTS 1
#ifdef CONFIG_ARCH_CHIP_NRF52840
# define NRF52_GPIO_NPORTS 2
# define NRF52_GPIO_PORT0 0
# define NRF52_GPIO_PORT1 1
#else
# define NRF52_GPIO_PORT0 0
# define NRF52_GPIO_NPORTS 1
#endif
/* Register offsets *****************************************************************/

View File

@ -71,6 +71,10 @@
/* Register offsets for GPIOTE *********************************************/
/* EVENT_IN Register */
#define GPIOTE_EVENT_IN_EVENT (1 << 0) /* Bit 0: Event generated from pin */
/* INTENSET/INTENCLR Register */
#define GPIOTE_INT_IN_SHIFT 0 /* Bits 0-7: Enable interrupt for event IN[i] */
@ -83,8 +87,8 @@
#define GPIOTE_CONFIG_MODE_SHIFT 0 /* Bits 0-1: Mode */
#define GPIOTE_CONFIG_MODE_MASK (0x3 << GPIOTE_CONFIG_MODE_SHIFT)
# define GPIOTE_CONFIG_MODE_DIS (0x0 << GPIOTE_CONFIG_MODE_SHIFT) /* 0: Disabled */
# define GPIOTE_CONFIG_MODE_EV (0x0 << GPIOTE_CONFIG_MODE_SHIFT) /* 1: Event */
# define GPIOTE_CONFIG_MODE_TS (0x0 << GPIOTE_CONFIG_MODE_SHIFT) /* 2: Task */
# define GPIOTE_CONFIG_MODE_EV (0x1 << GPIOTE_CONFIG_MODE_SHIFT) /* 1: Event */
# define GPIOTE_CONFIG_MODE_TS (0x3 << GPIOTE_CONFIG_MODE_SHIFT) /* 2: Task */
#define GPIOTE_CONFIG_PSEL_SHIFT (8) /* Bits 8-12: GPIO number */
#define GPIOTE_CONFIG_PSEL_MASK (0x1f << GPIOTE_CONFIG_PSEL_SHIFT)
#define GPIOTE_CONFIG_PORT_SHIFT (13) /* Bit 13: GPIO port */

View File

@ -139,7 +139,7 @@
#define NRF52_GPIO_P0_BASE 0x50000000
#ifdef CONFIG_ARCH_CHIP_NRF52840
# define NRF52_GPIO_P1_BASE 0x50003000
# define NRF52_GPIO_P1_BASE 0x50000300
#endif
#ifdef CONFIG_ARCH_CHIP_NRF52840

View File

@ -171,7 +171,7 @@
/* PSELSCK Register */
#define SPIM_PSELSCK_PIN_SHIFT (0) /* Bits 0-4: SCK pin number */
#define SPIM_PSELSCK_PIN_MASK (0xf << SPIM_PSELSCK_PIN_SHIFT)
#define SPIM_PSELSCK_PIN_MASK (0x1f << SPIM_PSELSCK_PIN_SHIFT)
#define SPIM_PSELSCK_PORT_SHIFT (5) /* Bit 5: SCK port number */
#define SPIM_PSELSCK_PORT_MASK (0x1 << SPIM_PSELSCK_PORT_SHIFT)
#define SPIM_PSELSCK_CONNECTED (1 << 31) /* Bit 31: Connection */
@ -180,7 +180,7 @@
/* PSELMOSI Register */
#define SPIM_PSELMOSI_PIN_SHIFT (0) /* Bits 0-4: MOSI pin number */
#define SPIM_PSELMOSI_PIN_MASK (0xf << SPIM_PSELMOSI_PIN_SHIFT)
#define SPIM_PSELMOSI_PIN_MASK (0x1f << SPIM_PSELMOSI_PIN_SHIFT)
#define SPIM_PSELMOSI_PORT_SHIFT (5) /* Bit 5: MOSI port number */
#define SPIM_PSELMOSI_PORT_MASK (0x1 << SPIM_PSELMOSI_PORT_SHIFT)
#define SPIM_PSELMOSI_CONNECTED (1 << 31) /* Bit 31: Connection */
@ -189,7 +189,7 @@
/* PSELMISO Register */
#define SPIM_PSELMISO_PIN_SHIFT (0) /* Bits 0-4: MISO pin number */
#define SPIM_PSELMISO_PIN_MASK (0xf << SPIM_PSELMISO_PIN_SHIFT)
#define SPIM_PSELMISO_PIN_MASK (0x1f << SPIM_PSELMISO_PIN_SHIFT)
#define SPIM_PSELMISO_PORT_SHIFT (5) /* Bit 5: MISO port number */
#define SPIM_PSELMISO_PORT_MASK (0x1 << SPIM_PSELMISO_PORT_SHIFT)
#define SPIM_PSELMISO_CONNECTED (1 << 31) /* Bit 31: Connection */
@ -198,7 +198,7 @@
/* PSELCSN Register */
#define SPIM_PSELCSN_PIN_SHIFT (0) /* Bits 0-4: CSN pin number */
#define SPIM_PSELCSN_PIN_MASK (0xf << SPIM_PSELCSN_PIN_SHIFT)
#define SPIM_PSELCSN_PIN_MASK (0x1f << SPIM_PSELCSN_PIN_SHIFT)
#define SPIM_PSELCSN_PORT_SHIFT (5) /* Bit 5: CSN port number */
#define SPIM_PSELCSN_PORT_MASK (0x1 << SPIM_PSELCSN_PORT_SHIFT)
#define SPIM_PSELCSN_CONNECTED (1 << 31) /* Bit 31: Connection */
@ -245,7 +245,7 @@
/* PSELDCX Register */
#define SPIM_PSELDCX_PIN_SHIFT (0) /* Bits 0-4: DCX pin number */
#define SPIM_PSELDCX_PIN_MASK (0xf << SPIM_PSELDCX_PIN_SHIFT)
#define SPIM_PSELDCX_PIN_MASK (0x1f << SPIM_PSELDCX_PIN_SHIFT)
#define SPIM_PSELDCX_PORT_SHIFT (5) /* Bit 5: SCK port number */
#define SPIM_PSELDCX_PORT_MASK (0x1 << SPIM_PSELDCX_PORT_SHIFT)
#define SPIM_PSELDCX_CONNECTED (1 << 31) /* Bit 31: Connection */

View File

@ -150,7 +150,7 @@
/* PSELSCL Register */
#define TWIM_PSELSCL_PIN_SHIFT (0) /* Bits 0-4: SCL pin number */
#define TWIM_PSELSCL_PIN_MASK (0xf << TWIM_PSELSCL_PIN_SHIFT)
#define TWIM_PSELSCL_PIN_MASK (0x1f << TWIM_PSELSCL_PIN_SHIFT)
#define TWIM_PSELSCL_PORT_SHIFT (5) /* Bit 5: SCL port number */
#define TWIM_PSELSCL_PORT_MASK (0x1 << TWIM_PSELSCL_PORT_SHIFT)
#define TWIM_PSELSCL_CONNECTED (1 << 31) /* Bit 31: Connection */
@ -159,7 +159,7 @@
/* PSELSDA Register */
#define TWIM_PSELSDA_PIN_SHIFT (0) /* Bits 0-4: SDA pin number */
#define TWIM_PSELSDA_PIN_MASK (0xf << TWIM_PSELSDA_PIN_SHIFT)
#define TWIM_PSELSDA_PIN_MASK (0x1f << TWIM_PSELSDA_PIN_SHIFT)
#define TWIM_PSELSDA_PORT_SHIFT (5) /* Bit 5: SDA port number */
#define TWIM_PSELSDA_PORT_MASK (0x1 << TWIM_PSELSDA_PORT_SHIFT)
#define TWIM_PSELSDA_CONNECTED (1 << 31) /* Bit 31: Connection */

View File

@ -238,7 +238,7 @@
/* PSELRTS Register */
#define UART_PSELRTS_PIN_SHIFT (0) /* Bits 0-4: Pin number*/
#define UART_PSELRTS_PIN_MASK (0xf << UART_PSELRTS_PIN_SHIFT)
#define UART_PSELRTS_PIN_MASK (0x1f << UART_PSELRTS_PIN_SHIFT)
#define UART_PSELRTS_PORT_SHIFT (5) /* Bit 5: Port number */
#define UART_PSELRTS_PORT_MASK (0x1 << UART_PSELRTS_PORT_SHIFT)
#define UART_PSELRTS_CONNECT (1 << 31) /* Bit 31: Connection */
@ -247,7 +247,7 @@
/* PSELTXD Register */
#define UART_PSELTXD_PIN_SHIFT (0) /* Bits 0-4: Pin number*/
#define UART_PSELTXD_PIN_MASK (0xf << UART_PSELTXD_PIN_SHIFT)
#define UART_PSELTXD_PIN_MASK (0x1f << UART_PSELTXD_PIN_SHIFT)
#define UART_PSELTXD_PORT_SHIFT (5) /* Bit 5: Port number */
#define UART_PSELTXD_PORT_MASK (0x1 << UART_PSELTXD_PORT_SHIFT)
#define UART_PSELTXD_CONNECT (1 << 31) /* Bit 31: Connection */
@ -256,7 +256,7 @@
/* PSELCTS Register */
#define UART_PSELCTS_PIN_SHIFT (0) /* Bits 0-4: Pin number*/
#define UART_PSELCTS_PIN_MASK (0xf << UART_PSELCTS_PIN_SHIFT)
#define UART_PSELCTS_PIN_MASK (0x1f << UART_PSELCTS_PIN_SHIFT)
#define UART_PSELCTS_PORT_SHIFT (5) /* Bit 5: Port number */
#define UART_PSELCTS_PORT_MASK (0x1 << UART_PSELCTS_PORT_SHIFT)
#define UART_PSELCTS_CONNECT (1 << 31) /* Bit 31: Connection */
@ -265,7 +265,7 @@
/* PSELRXD Register */
#define UART_PSELRXD_PIN_SHIFT (0) /* Bits 0-4: Pin number*/
#define UART_PSELRXD_PIN_MASK (0xf << UART_PSELRXD_PIN_SHIFT)
#define UART_PSELRXD_PIN_MASK (0x1f << UART_PSELRXD_PIN_SHIFT)
#define UART_PSELRXD_PORT_SHIFT (5) /* Bit 5: Port number */
#define UART_PSELRXD_PORT_MASK (0x1 << UART_PSELRXD_PORT_SHIFT)
#define UART_PSELRXD_CONNECT (1 << 31) /* Bit 31: Connection */

View File

@ -186,7 +186,7 @@ int nrf52_gpio_config(nrf52_pinset_t cfgset)
* that pin.
*/
pin = (cfgset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
pin = GPIO_PIN_DECODE(cfgset);
/* First, configure the port as a generic input so that we have a
* known starting point and consistent behavior during the re-
@ -206,16 +206,6 @@ int nrf52_gpio_config(nrf52_pinset_t cfgset)
case GPIO_INPUT: /* GPIO input pin */
break; /* Already configured */
#ifdef CONFIG_NRF52_GPIOIRQ
case GPIO_INTFE: /* GPIO interrupt falling edge */
case GPIO_INTRE: /* GPIO interrupt rising edge */
case GPIO_INTBOTH: /* GPIO interrupt both edges */
case GPIO_INTLOW: /* GPIO interrupt low level */
case GPIO_INTHIGH: /* GPIO interrupt high level */
nrf52_gpio_interrupt(cfgset);
break;
#endif
case GPIO_OUTPUT: /* GPIO outpout pin */
nrf52_gpio_output(cfgset, port, pin);
break;
@ -244,8 +234,8 @@ int nrf52_gpio_unconfig(nrf52_pinset_t cfgset)
/* Get port and pin number */
port = (cfgset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pin = (cfgset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
pin = GPIO_PIN_DECODE(cfgset);
port = GPIO_PORT_DECODE(cfgset);
/* Get address offset */
@ -274,8 +264,8 @@ void nrf52_gpio_write(nrf52_pinset_t pinset, bool value)
/* Get port and pin number */
pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pin = GPIO_PIN_DECODE(pinset);
port = GPIO_PORT_DECODE(pinset);
/* Get register address */
@ -310,8 +300,8 @@ bool nrf52_gpio_read(nrf52_pinset_t pinset)
/* Get port and pin number */
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
pin = GPIO_PIN_DECODE(pinset);
port = GPIO_PORT_DECODE(pinset);
/* Get register address */

View File

@ -176,6 +176,11 @@
# define GPIO_PIN31 (31 << GPIO_PIN_SHIFT)
# define GPIO_PIN(n) ((n) << GPIO_PIN_SHIFT)
/* Helper macros */
#define GPIO_PIN_DECODE(p) (((p) & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT)
#define GPIO_PORT_DECODE(p) (((p) & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT)
/************************************************************************************
* Public Types
************************************************************************************/
@ -200,21 +205,6 @@ extern "C"
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: nrf52_gpio_irqinitialize
*
* Description:
* Initialize logic to support interrupting GPIO pins. This function is called by
* the OS inialization logic and is not a user interface.
*
************************************************************************************/
#ifdef CONFIG_NRF52_GPIOIRQ
void nrf52_gpio_irqinitialize(void);
#else
# define nrf52_gpio_irqinitialize()
#endif
/************************************************************************************
* Name: nrf52_gpio_config
*
@ -235,47 +225,6 @@ int nrf52_gpio_config(nrf52_pinset_t cfgset);
int nrf52_gpio_unconfig(nrf52_pinset_t cfgset);
/************************************************************************************
* Name: nrf52_gpio_interrupt
*
* Description:
* Configure a GPIO interrupt pin based on bit-encoded description of the pin.
* This function is called by nrf52_gpio_config to setup interrupting pins. It is
* not a user interface.
*
************************************************************************************/
#ifdef CONFIG_NRF52_GPIOIRQ
int nrf52_gpio_interrupt(nrf52_pinset_t pinset);
#endif
/************************************************************************************
* Name: nrf52_gpio_irqno
*
* Description:
* Returns the IRQ number that was associated with an interrupt pin after it was
* configured.
*
************************************************************************************/
#ifdef CONFIG_NRF52_GPIOIRQ
int nrf52_gpio_irqno(nrf52_pinset_t pinset);
#endif
/************************************************************************************
* Name: nrf52_gpio_ackedge
*
* Description:
* Acknowledge edge interrupts by clearing the associated bits in the rising and
* falling registers. This acknowledgemment is, of course, not needed for level
* interupts.
*
************************************************************************************/
#ifdef CONFIG_NRF52_GPIOIRQ
int nrf52_gpio_ackedge(int irq);
#endif
/************************************************************************************
* Name: rnf52_gpio_write
*

View File

@ -0,0 +1,287 @@
/****************************************************************************
* arch/arm/src/nrf52/nrf52_gpiote.c
*
* Copyright (C) 2019 Gregory Nutt. All rights reserved.
* Author: Mateusz Szafoni <raiden00@railab.me>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
* 3. Neither the name NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <errno.h>
#include <debug.h>
#include <string.h>
#include <arch/irq.h>
#include <nuttx/arch.h>
#include "up_arch.h"
#include "nrf52_gpio.h"
#include "nrf52_gpiote.h"
#include "hardware/nrf52_gpiote.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define GPIOTE_CHANNELS 8
/****************************************************************************
* Private Types
****************************************************************************/
struct nrf52_gpiote_callback_s
{
xcpt_t callback;
FAR void *arg;
};
/****************************************************************************
* Private Data
****************************************************************************/
/* Interrupt handlers attached to each GPIOTE */
static struct nrf52_gpiote_callback_s g_gpiote_callbacks[GPIOTE_CHANNELS];
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: nrf52_gpiote_putreg
*
* Description:
* Put a 32-bit register value by offset
*
****************************************************************************/
static inline void nrf52_gpiote_putreg(uint32_t offset, uint32_t value)
{
putreg32(value, NRF52_GPIOTE_BASE + offset);
}
/****************************************************************************
* Name: nrf52_gpiote_getreg
*
* Description:
* Get a 32-bit register value by offset
*
****************************************************************************/
static inline uint32_t nrf52_gpiote_getreg(uint32_t offset)
{
return getreg32(NRF52_GPIOTE_BASE + offset);
}
/****************************************************************************
* Name: nrf52_gpiote_isr
*
* Description:
* Common GPIOTE interrupt handler
*
****************************************************************************/
static int nrf52_gpiote_isr(int irq, FAR void *context, FAR void *arg)
{
uint32_t regval = 0;
int ret = OK;
int i = 0;
/* Scan all GPIOTE channels */
for (i = 0; i < GPIOTE_CHANNELS; i += 1)
{
/* Only if callback is registered */
if (g_gpiote_callbacks[i].callback != NULL)
{
/* Get input event register */
regval = nrf52_gpiote_getreg(NRF52_GPIOTE_EVENTS_IN_OFFSET(i));
if (regval == GPIOTE_EVENT_IN_EVENT)
{
/* Execute callback */
xcpt_t callback = g_gpiote_callbacks[i].callback;
FAR void *cbarg = g_gpiote_callbacks[i].arg;
ret = callback(irq, context, cbarg);
/* Clear event */
nrf52_gpiote_putreg(NRF52_GPIOTE_EVENTS_IN_OFFSET(i), 0);
}
}
}
return ret;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: nrf52_gpiosetevent
*
* Description:
* Sets/clears GPIO based event and interrupt triggers.
*
* Input Parameters:
* - pinset: GPIO pin configuration
* - risingedge: Enables interrupt on rising edges
* - fallingedge: Enables interrupt on falling edges
* - event: Generate event when set
* - func: When non-NULL, generate interrupt
* - arg: Argument passed to the interrupt callback
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure indicating the
* nature of the failure.
*
****************************************************************************/
int nrf52_gpiosetevent(uint32_t pinset, bool risingedge, bool fallingedge,
bool event, xcpt_t func, FAR void *arg)
{
int ret = OK;
int i = 0;
int pin = 0;
int port = 0;
uint32_t regval = 0;
bool found = false;
irqstate_t flags;
/* Find available GPIOTE channel */
flags = enter_critical_section();
for (i = 0; i < GPIOTE_CHANNELS; i += 1)
{
if (g_gpiote_callbacks[i].callback == NULL)
{
found = true;
break;
}
}
leave_critical_section(flags);
/* Return error if there is no free channel */
if (found == false)
{
ret = -ENODEV;
goto errout;
}
/* NOTE: GPIOTE module has priority over GPIO module
* so GPIO configuration will be ignored
*/
/* Select GPIOTE pin */
pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
regval = (pin << GPIOTE_CONFIG_PSEL_SHIFT);
regval |= (port << GPIOTE_CONFIG_PORT_SHIFT);
/* Select EVENT mode */
if (event || func)
{
regval |= GPIOTE_CONFIG_MODE_EV;
}
/* Select polarity */
if (risingedge == true && fallingedge == true)
{
regval |= GPIOTE_CONFIG_POL_TG;
}
else if (risingedge == true)
{
regval |= GPIOTE_CONFIG_POL_LTH;
}
else if (fallingedge == true)
{
regval |= GPIOTE_CONFIG_POL_HTL;
}
/* Write CONFIG register */
nrf52_gpiote_putreg(NRF52_GPIOTE_CONFIG_OFFSET(i), regval);
/* Enable interrupt for given event */
nrf52_gpiote_putreg(NRF52_GPIOTE_INTENSET_OFFSET, GPIOTE_INT_IN(i));
/* Connect callback */
g_gpiote_callbacks[i].callback = func;
g_gpiote_callbacks[i].arg = arg;
errout:
return ret;
}
/****************************************************************************
* Name: nrf52_gpiote_init
*
* Description:
* Initialize GPIOTE
*
****************************************************************************/
int nrf52_gpiote_init(void)
{
/* Reset GPIOTE data */
memset(&g_gpiote_callbacks,
0,
sizeof(struct nrf52_gpiote_callback_s)*GPIOTE_CHANNELS);
/* Attach GPIOTE interrupt handler */
irq_attach(NRF52_IRQ_GPIOTE, nrf52_gpiote_isr, NULL);
up_enable_irq(NRF52_IRQ_GPIOTE);
return OK;
}

View File

@ -0,0 +1,89 @@
/****************************************************************************
* arch/arm/src/nrf52/nrf52_gpiote.h
*
* Copyright (C) 2019 Gregory Nutt. All rights reserved.
* Author: Mateusz Szafoni <raiden00@railab.me>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
* 3. Neither the name NuttX 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 OWNER 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.
*
****************************************************************************/
#ifndef __ARCH_ARM_SRC_NRF52_NRF52_GPIOTE_H
#define __ARCH_ARM_SRC_NRF52_NRF52_GPIOTE_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/irq.h>
#include "chip.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: nrf52_gpiosetevent
*
* Description:
* Sets/clears GPIO based event and interrupt triggers.
*
* Input Parameters:
* - pinset: gpio pin configuration
* - rising/falling edge: enables
* - event: generate event when set
* - func: when non-NULL, generate interrupt
* - arg: Argument passed to the interrupt callback
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure indicating the
* nature of the failure.
*
****************************************************************************/
int nrf52_gpiosetevent(uint32_t pinset, bool risingedge, bool fallingedge,
bool event, xcpt_t func, FAR void *arg);
/****************************************************************************
* Name: nrf52_gpiote_init
*
* Description:
* Initialize GPIOTE
*
****************************************************************************/
int nrf52_gpiote_init(void);
#endif /* __ARCH_ARM_SRC_NRF52_NRF52_GPIOTE_H */

View File

@ -310,6 +310,10 @@ static int nrf52_i2c_transfer(FAR struct i2c_master_s *dev,
#ifdef CONFIG_I2C_POLLED
while (nrf52_i2c_getreg(priv,
NRF52_TWIM_EVENTS_LASTTX_OFFSET) != 1);
/* Clear event */
nrf52_i2c_putreg(priv, NRF52_TWIM_EVENTS_LASTTX_OFFSET, 0);
#endif
/* TWIM stop */
@ -321,6 +325,10 @@ static int nrf52_i2c_transfer(FAR struct i2c_master_s *dev,
#ifdef CONFIG_I2C_POLLED
while (nrf52_i2c_getreg(priv,
NRF52_TWIM_EVENTS_STOPPED_OFFSET) != 1);
/* Clear event */
nrf52_i2c_putreg(priv, NRF52_TWIM_EVENTS_STOPPED_OFFSET, 0);
#endif
}
else
@ -425,8 +433,8 @@ static int nrf52_i2c_init(FAR struct nrf52_i2c_priv_s *priv)
/* Select SCL pin */
pin = (priv->scl_pin & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
port = (priv->scl_pin & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pin = GPIO_PIN_DECODE(priv->scl_pin);
port = GPIO_PORT_DECODE(priv->scl_pin);
regval = (pin << TWIM_PSELSCL_PIN_SHIFT);
regval |= (port << TWIM_PSELSCL_PORT_SHIFT);
@ -434,8 +442,8 @@ static int nrf52_i2c_init(FAR struct nrf52_i2c_priv_s *priv)
/* Select SDA pin */
pin = (priv->sda_pin & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
port = (priv->sda_pin & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pin = GPIO_PIN_DECODE(priv->sda_pin);
port = GPIO_PORT_DECODE(priv->sda_pin);
regval = (pin << TWIM_PSELSDA_PIN_SHIFT);
regval |= (port << TWIM_PSELSDA_PORT_SHIFT);

View File

@ -53,8 +53,10 @@
#include "up_arch.h"
#include "up_internal.h"
#include "nrf52_gpio.h"
#include "nrf52_irq.h"
#ifdef CONFIG_NRF52_GPIOTE
# include "nrf52_gpiote.h"
#endif
/****************************************************************************
* Pre-processor Definitions
@ -114,9 +116,12 @@ static void nrf52_dumpnvic(const char *msg, int irq)
irqinfo(" INTCTRL: %08x VECTAB: %08x\n",
getreg32(NVIC_INTCTRL), getreg32(NVIC_VECTAB));
#if 0
irqinfo(" SYSH ENABLE MEMFAULT: %08x BUSFAULT: %08x USGFAULT: %08x SYSTICK: %08x\n",
getreg32(NVIC_SYSHCON_MEMFAULTENA), getreg32(NVIC_SYSHCON_BUSFAULTENA),
getreg32(NVIC_SYSHCON_USGFAULTENA), getreg32(NVIC_SYSTICK_CTRL_ENABLE));
irqinfo(" SYSH ENABLE MEMFAULT: %08x BUSFAULT: %08x \n",
getreg32(NVIC_SYSHCON_MEMFAULTENA),
getreg32(NVIC_SYSHCON_BUSFAULTENA));
irqinfo(" USGFAULT: %08x SYSTICK: %08x\n",
getreg32(NVIC_SYSHCON_USGFAULTENA),
getreg32(NVIC_SYSTICK_CTRL_ENABLE));
#endif
irqinfo(" IRQ ENABLE: %08x %08x\n",
getreg32(NVIC_IRQ0_31_ENABLE), getreg32(NVIC_IRQ32_63_ENABLE));
@ -370,7 +375,9 @@ void up_irqinitialize(void)
/* Set the priority of the SVCall interrupt */
#ifdef CONFIG_ARCH_IRQPRIO
/* up_prioritize_irq(NRF52_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN); */
# if 0
up_prioritize_irq(NRF52_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN);
# endif
#endif
#ifdef CONFIG_ARMV7M_USEBASEPRI
@ -413,10 +420,10 @@ void up_irqinitialize(void)
putreg32(regval, NVIC_DEMCR);
#endif
#ifdef CONFIG_NRF52_GPIOIRQ
/* Initialize GPIO interrupts */
#ifdef CONFIG_NRF52_GPIOTE
/* Initialize GPIOTE */
nrf52_gpio_irqinitialize();
nrf52_gpiote_init();
#endif
#ifndef CONFIG_SUPPRESS_INTERRUPTS

View File

@ -114,8 +114,7 @@ static const struct uart_config_s g_console_config =
****************************************************************************/
#ifdef HAVE_UART_DEVICE
static void nrf52_setbaud(uintptr_t base,
FAR const struct uart_config_s *config)
static void nrf52_setbaud(uintptr_t base, const struct uart_config_s *config)
{
uint32_t br = 0;
@ -164,8 +163,7 @@ void nrf52_lowsetup(void)
****************************************************************************/
#ifdef HAVE_UART_DEVICE
void nrf52_usart_configure(uintptr_t base,
FAR const struct uart_config_s *config)
void nrf52_usart_configure(uintptr_t base, const struct uart_config_s *config)
{
uint32_t pin = 0;
uint32_t port = 0;
@ -186,8 +184,8 @@ void nrf52_usart_configure(uintptr_t base,
/* Setect TX pins for UART */
pin = (config->txpin & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
port = (config->txpin & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pin = GPIO_PIN_DECODE(config->txpin);
port = GPIO_PORT_DECODE(config->txpin);
regval = (pin << UART_PSELTXD_PIN_SHIFT);
regval |= (port << UART_PSELTXD_PORT_SHIFT);
@ -195,8 +193,8 @@ void nrf52_usart_configure(uintptr_t base,
/* Setect RX pins for UART */
pin = (config->rxpin & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
port = (config->rxpin & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pin = GPIO_PIN_DECODE(config->rxpin);
port = GPIO_PORT_DECODE(config->rxpin);
regval = (pin << UART_PSELRXD_PIN_SHIFT);
regval |= (port << UART_PSELRXD_PORT_SHIFT);
@ -218,8 +216,7 @@ void nrf52_usart_configure(uintptr_t base,
****************************************************************************/
#ifdef HAVE_UART_DEVICE
void nrf52_usart_disable(uintptr_t base,
FAR const struct uart_config_s *config)
void nrf52_usart_disable(uintptr_t base, const struct uart_config_s *config)
{
/* Disable interrupts */

View File

@ -1,4 +1,4 @@
/************************************************************************************
/****************************************************************************
* arch/arm/src/nrf52/nrf52_lowputc.h
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
@ -31,14 +31,14 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
****************************************************************************/
#ifndef __ARCH_ARM_SRC_NRF52_NRF52_LOWPUTC_H
#define __ARCH_ARM_SRC_NRF52_NRF52_LOWPUTC_H
/************************************************************************************
/****************************************************************************
* Included Files
************************************************************************************/
****************************************************************************/
#include <nuttx/config.h>
@ -46,9 +46,9 @@
#include <stdbool.h>
#include <nrf52_gpio.h>
/************************************************************************************
/****************************************************************************
* Public Types
************************************************************************************/
****************************************************************************/
#ifdef HAVE_UART_DEVICE
/* This structure describes the configuration of an UART */
@ -58,56 +58,56 @@ struct uart_config_s
uint32_t baud; /* Configured baud */
uint8_t parity; /* 0=none, 1=odd, 2=even */
uint8_t bits; /* Number of bits (5-9) */
bool stopbits2; /* true: Configure with 2 stop bits instead of 1 */
bool stopbits2; /* Configure with 2 stop bits instead of 1 */
#ifdef CONFIG_SERIAL_IFLOWCONTROL
bool iflow; /* true: Input flow control supported */
bool iflow; /* Input flow control supported */
#endif
#ifdef CONFIG_SERIAL_OFLOWCONTROL
bool oflow; /* true: Output flow control supported. */
bool oflow; /* Output flow control supported. */
#endif
nrf52_pinset_t txpin; /* TX pin */
nrf52_pinset_t rxpin; /* RX pin */
};
#endif
/************************************************************************************
/****************************************************************************
* Public Functions
************************************************************************************/
****************************************************************************/
/************************************************************************************
/****************************************************************************
* Name: nrf52_lowsetup
*
* Description:
* Called at the very beginning of _start. Performs low level initialization
* including setup of the console UART. This UART initialization is done
* early so that the serial console is available for debugging very early in
* the boot sequence.
* Called at the very beginning of _start. Performs low level
* initialization including setup of the console UART. This UART
* initialization is done early so that the serial console is available
* for debugging very early in the boot sequence.
*
************************************************************************************/
****************************************************************************/
void nrf52_lowsetup(void);
/************************************************************************************
/****************************************************************************
* Name: nrf52_usart_configure
*
* Description:
* Configure a UART for non-interrupt driven operation
*
************************************************************************************/
****************************************************************************/
#ifdef HAVE_UART_DEVICE
void nrf52_usart_configure(uintptr_t base,
FAR const struct uart_config_s *config);
#endif
/************************************************************************************
/****************************************************************************
* Name: nrf52_usart_disable
*
* Description:
* Disable a UART. it will be necessary to again call
* nrf52_usart_configure() in order to use this UART channel again.
*
************************************************************************************/
****************************************************************************/
#ifdef HAVE_UART_DEVICE
void nrf52_usart_disable(uintptr_t base,

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,130 @@
/****************************************************************************
* arch/arm/src/nrf52/nrf52_spi.h
*
* Copyright (C) 2019 Gregory Nutt. All rights reserved.
* Author: Mateusz Szafoni <raiden00@railab.me>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
* 3. Neither the name NuttX 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 OWNER 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.
*
****************************************************************************/
#ifndef __ARCH_ARM_SRC_NRF52_NRF52_SPI_H
#define __ARCH_ARM_SRC_NRF52_NRF52_SPI_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/spi/spi.h>
#include "chip.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: nrf52_spibus_initialize
*
* Description:
* Initialize the selected SPI port.
*
* Input Parameters:
* Port number (for hardware that has multiple SPI interfaces)
*
* Returned Value:
* Valid SPI device structure reference on success; a NULL on failure
*
****************************************************************************/
FAR struct spi_dev_s *nrf52_spibus_initialize(int port);
/****************************************************************************
* Name: nrf52_spi0/1/...select and nrf52_spi0/1/...status
*
* Description:
* The external functions, nrf52_spi0/1/...select, nrf52_spi0/1/...status,
* and nrf52_spi0/1/...cmddata must be provided by board-specific logic.
* These are implementations of the select, status, and cmddata methods of
* the SPI interface defined by struct spi_ops_s (include/nuttx/spi/spi.h).
* All other methods (including nrf52_spibus_initialize()) are provided by
* common NRF52 logic. To use this common SPI logic on your board:
*
* 1. Provide logic in nrf52_boardinitialize() to configure SPI chip select
* pins.
* 2. Provide nrf52_spi0/1/...select() and nrf52_spi0/1/...status()
* functions in your board-specific logic. These functions will perform
* chip selection and status operations using GPIOs in the way your board
* is configured.
* 3. If CONFIG_SPI_CMDDATA is defined in your NuttX configuration file,
* then provide nrf52_spi0/1/...cmddata() functions in your
* board-specific logic. These functions will perform cmd/data selection
* operations using GPIOs in the way your board is configured.
* 4. Add a calls to nrf52_spibus_initialize() in your low level application
* initialization logic
* 5. The handle returned by nrf52_spibus_initialize() may then be used to
* bind the SPI driver to higher level logic (e.g., calling
* mmcsd_spislotinitialize(), for example, will bind the SPI driver to
* the SPI MMC/SD driver).
*
****************************************************************************/
#ifdef CONFIG_NRF52_SPI0_MASTER
void nrf52_spi0select(FAR struct spi_dev_s *dev, uint32_t devid,
bool selected);
uint8_t nrf52_spi0status(FAR struct spi_dev_s *dev, uint32_t devid);
int nrf52_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd);
#endif
#ifdef CONFIG_NRF52_SPI1_MASTER
void nrf52_spi1select(FAR struct spi_dev_s *dev, uint32_t devid,
bool selected);
uint8_t nrf52_spi1status(FAR struct spi_dev_s *dev, uint32_t devid);
int nrf52_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd);
#endif
#ifdef CONFIG_NRF52_SPI2_MASTER
void nrf52_spi2select(FAR struct spi_dev_s *dev, uint32_t devid,
bool selected);
uint8_t nrf52_spi2status(FAR struct spi_dev_s *dev, uint32_t devid);
int nrf52_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd);
#endif
#ifdef CONFIG_NRF52_SPI3_MASTER
void nrf52_spi3select(FAR struct spi_dev_s *dev, uint32_t devid,
bool selected);
uint8_t nrf52_spi3status(FAR struct spi_dev_s *dev, uint32_t devid);
int nrf52_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd);
#endif
#endif /* __ARCH_ARM_SRC_NRF52_NRF52_SPI_H */

View File

@ -43,7 +43,7 @@
#include <nuttx/config.h>
#include <stdbool.h>
#if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_NRF52_GPIO_IRQ)
#if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_NRF52_GPIOTE)
# include <nuttx/irq.h>
#endif

View File

@ -43,7 +43,7 @@
#include <nuttx/config.h>
#include <stdbool.h>
#if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_NRF52_GPIO_IRQ)
#if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_NRF52_GPIOTE)
# include <nuttx/irq.h>
#endif

View File

@ -43,7 +43,7 @@
#include <nuttx/config.h>
#include <stdbool.h>
#if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_NRF52_GPIO_IRQ)
#if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_NRF52_GPIOTE)
# include <nuttx/irq.h>
#endif
@ -130,4 +130,26 @@
#define BOARD_UART1_RX_PIN (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN(1))
#define BOARD_UART1_TX_PIN (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT1 | GPIO_PIN(2))
/* SPI Pins *****************************************************************/
/* SPI0 - Arduino PINs
* SPI0_SCK - P1.15 (P13)
* SPI0_MOSI - P1.13 (D11)
* SPI0_MISO - P1.14 (D12)
*/
#define BOARD_SPI0_SCK_PIN (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT1 | GPIO_PIN(15))
#define BOARD_SPI0_MOSI_PIN (GPIO_OUTPUT | GPIO_PORT1 | GPIO_PIN(13))
#define BOARD_SPI0_MISO_PIN (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN(14))
/* I2C Pins *****************************************************************/
/* I2C0 (TWI0) - Arduino PINs
* I2C0_SCL - P0.27
* I2C0_SDA - P0.26
*/
#define BOARD_I2C0_SCL_PIN (GPIO_OUTPUT | GPIO_PORT0 | GPIO_PIN(27))
#define BOARD_I2C0_SDA_PIN (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN(26))
#endif /* __BOARDS_ARM_NRF52_NRF52840_DK_INCLUDE_BOARD_H */

View File

@ -52,4 +52,16 @@ ifeq ($(CONFIG_ARCH_BUTTONS),y)
CSRCS += nrf52_buttons.c
endif
ifeq ($(CONFIG_NRF52_SPI_MASTER),y)
CSRCS += nrf52_spi.c
endif
ifeq ($(CONFIG_SENSORS_LSM6DSL),y)
CSRCS += nrf52_lsm6dsl.c
endif
ifeq ($(CONFIG_LPWAN_SX127X),y)
CSRCS += nrf52_sx127x.c
endif
include $(TOPDIR)/boards/Board.mk

View File

@ -67,6 +67,16 @@
#define GPIO_BUTTON3 (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN(24))
#define GPIO_BUTTON4 (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN(25))
/* Dragino LORA shield (v1.4) - RF98 module (based on SX127X)
* RESET - P1.11 (D9)
* CS - P1.12 (D10)
* DIO0 - P1.03 (D2)
*/
#define GPIO_SX127X_RESET (GPIO_PORT1 | GPIO_PIN(11))
#define GPIO_SX127X_CS (GPIO_OUTPUT | GPIO_PORT1 | GPIO_PIN(12))
#define GPIO_SX127X_DIO0 (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN(3))
/****************************************************************************
* Public Types
****************************************************************************/
@ -97,5 +107,41 @@
int nrf52_bringup(void);
/****************************************************************************
* Name: nrf52_spidev_initialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the
* nrf52840-dk board.
*
****************************************************************************/
#ifdef CONFIG_NRF52_SPI_MASTER
void nrf52_spidev_initialize(void);
#endif
/*****************************************************************************
* Name: nrf52_lsm6dsl_initialize
*
* Description:
* Initialize I2C-based LSM6DSL.
*
****************************************************************************/
#ifdef CONFIG_SENSORS_LSM303AGR
int nrf52_lsm6dsl_initialize(char *devpath);
#endif
/*****************************************************************************
* Name: nrf52_lpwaninitialize
*
* Description:
* Initialize SX127X LPWAN interaface.
****************************************************************************/
#ifdef CONFIG_LPWAN_SX127X
int nrf52_lpwaninitialize(void);
#endif
#endif /* __ASSEMBLY__ */
#endif /* __BOARDS_ARM_NRF52_NRF52840_DK_SRC_NRF52840_DK_H */

View File

@ -71,6 +71,12 @@ void nrf52_board_initialize(void)
#ifdef CONFIG_ARCH_LEDS
board_autoled_initialize();
#endif
#ifdef CONFIG_NRF52_SPI_MASTER
/* Configure SPI chip selects */
nrf52_spidev_initialize();
#endif
}
/****************************************************************************

View File

@ -46,10 +46,64 @@
# include <nuttx/leds/userled.h>
#endif
#include "nrf52840-dk.h"
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: nrf52_i2c_register
*
* Description:
* Register one I2C drivers for the I2C tool.
*
****************************************************************************/
#if defined(CONFIG_I2C) && defined(CONFIG_SYSTEM_I2CTOOL)
static void nrf52_i2c_register(int bus)
{
struct i2c_master_s *i2c;
int ret;
i2c = nrf52_i2cbus_initialize(bus);
if (i2c == NULL)
{
syslog(LOG_ERR, "ERROR: Failed to get I2C%d interface\n", bus);
}
else
{
ret = i2c_register(i2c, bus);
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: Failed to register I2C%d driver: %d\n",
bus, ret);
nrf52_i2cbus_uninitialize(i2c);
}
}
}
#endif
/****************************************************************************
* Name: nrf52_i2ctool
*
* Description:
* Register I2C drivers for the I2C tool.
*
****************************************************************************/
#if defined(CONFIG_I2C) && defined(CONFIG_SYSTEM_I2CTOOL)
static void nrf52_i2ctool(void)
{
#ifdef CONFIG_NRF52_I2C0
nrf52_i2c_register(0);
#endif
#ifdef CONFIG_NRF52_I2C1
nrf52_i2c_register(1);
#endif
}
#endif
/****************************************************************************
* Name: nrf52_bringup
*
@ -74,10 +128,32 @@ int nrf52_bringup(void)
ret = userled_lower_initialize(CONFIG_EXAMPLES_LEDS_DEVPATH);
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: userled_lower_initialize() failed: %d\n", ret);
syslog(LOG_ERR,
"ERROR: userled_lower_initialize() failed: %d\n",
ret);
}
#endif
#ifdef CONFIG_SENSORS_LSM6DSL
ret = nrf52_lsm6dsl_initialize("/dev/lsm6dsl0");
if (ret < 0)
{
syslog(LOG_ERR,
"ERROR: Failed to initialize LSM6DSL driver: %d\n",
ret);
}
#endif /* CONFIG_SENSORS_LSM6DSL */
#ifdef CONFIG_LPWAN_SX127X
ret = nrf52_lpwaninitialize();
if (ret < 0)
{
syslog(LOG_ERR,
"ERROR: Failed to initialize wireless driver: %d\n",
ret);
}
#endif /* CONFIG_LPWAN_SX127X */
UNUSED(ret);
return OK;
}

View File

@ -0,0 +1,97 @@
/*****************************************************************************
* boards/arm/nrf52/nrf52840-dk/src/nrf52_lsm6dsl.c
*
* Copyright (C) 2019 Greg Nutt. All rights reserved.
* Author: Mateusz Szafoni <raiden00@railab.me>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
* 3. Neither the name NuttX 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 OWNER 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.
****************************************************************************/
/*****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/arch.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/board.h>
#include "nrf52_i2c.h"
#include "nrf52840-dk.h"
#include <nuttx/sensors/lsm6dsl.h>
/*****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#ifndef CONFIG_NRF52_I2C0_MASTER
# error "LSM6DSL driver requires CONFIG_NRF52_I2C0_MASTER to be enabled"
#endif
/*****************************************************************************
* Public Functions
****************************************************************************/
/*****************************************************************************
* Name: nrf52_lsm6dsl_initialize
*
* Description:
* Initialize I2C-based LSM6DSL.
****************************************************************************/
int nrf52_lsm6dsl_initialize(char *devpath)
{
FAR struct i2c_master_s *i2c;
int ret = OK;
sninfo("Initializing LMS6DSL!\n");
#ifdef CONFIG_NRF52_I2C0_MASTER
i2c = nrf52_i2cbus_initialize(0);
if (i2c == NULL)
{
return -ENODEV;
}
sninfo("INFO: Initializing LMS6DSL accelero-gyro sensor over I2C%d\n", ret);
ret = lsm6dsl_sensor_register(devpath, i2c, LSM6DSLACCEL_ADDR1);
if (ret < 0)
{
snerr("ERROR: Failed to initialize LMS6DSL accelero-gyro driver %s\n",
devpath);
return -ENODEV;
}
sninfo("INFO: LMS6DSL sensor has been initialized successfully\n");
#endif
return ret;
}

View File

@ -0,0 +1,206 @@
/****************************************************************************
* boards/arm/nrf52/nrf52840-dk/src/nrf52_spi.c
*
* Copyright (C) 2019 Greg Nutt. All rights reserved.
* Author: Mateusz Szafoni <raiden00@railab.me>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
* 3. Neither the name NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <stdbool.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/spi/spi.h>
#include "up_arch.h"
#include "chip.h"
#include "nrf52_gpio.h"
#include "nrf52_spi.h"
#include "nrf52840-dk.h"
#include <arch/board/board.h>
#ifdef CONFIG_NRF52_SPI_MASTER
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: nrf52_spidev_initialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the Nucleo-144 board.
*
****************************************************************************/
void nrf52_spidev_initialize(void)
{
#ifdef CONFIG_NRF52_SPI0_MASTER
# ifdef CONFIG_LPWAN_SX127X
/* Configure the SPI-based SX127X chip select GPIO */
spiinfo("Configure GPIO for SX127X SPI1/CS\n");
nrf52_gpio_config(GPIO_SX127X_CS);
nrf52_gpio_write(GPIO_SX127X_CS, true);
# endif
#endif
}
/****************************************************************************
* Name: nrf52_spi0/1/2/3/select and nrf52_spi0/1/2/3/status
*
* Description:
* The external functions, nrf52_spi0/1/2/3select and
* nrf52_spi0/1/2/3status must be provided by board-specific logic.
* They are implementations of the select and status methods of the SPI
* interface defined by struct spi_ops_s (see include/nuttx/spi/spi.h).
* All other methods (including nrf52_spibus_initialize()) are provided
* by common NRF52 logic. To use this common SPI logic on your board:
*
* 1. Provide logic in nrf52_boardinitialize() to configure SPI chip select
* pins.
* 2. Provide nrf52_spi0/1/2/3select() and nrf52_spi0/1/2/3status()
* functions in your board-specific logic. These functions will perform
* chip selection and status operations using GPIOs in the way your
* board is configured.
* 3. Add a calls to nrf52_spibus_initialize() in your low level application
* initialization logic
* 4. The handle returned by nrf52_spibus_initialize() may then be used to
* bind the SPI driver to higher level logic (e.g., calling
* mmcsd_spislotinitialize(), for example, will bind the SPI driver to
* the SPI MMC/SD driver).
*
****************************************************************************/
#ifdef CONFIG_NRF52_SPI0_MASTER
void nrf52_spi0select(FAR struct spi_dev_s *dev, uint32_t devid,
bool selected)
{
spiinfo("devid: %08lx CS: %s\n",
(unsigned long)devid, selected ? "assert" : "de-assert");
switch (devid)
{
#ifdef CONFIG_LPWAN_SX127X
case SPIDEV_LPWAN(0):
{
spiinfo("SX127X device %s\n",
selected ? "asserted" : "de-asserted");
/* Set the GPIO low to select and high to de-select */
nrf52_gpio_write(GPIO_SX127X_CS, !selected);
break;
}
#endif
default:
{
break;
}
}
}
uint8_t nrf52_spi0status(FAR struct spi_dev_s *dev, uint32_t devid)
{
uint8_t status = 0;
switch (devid)
{
#ifdef CONFIG_LPWAN_SX127X
case SPIDEV_LPWAN(0):
{
status |= SPI_STATUS_PRESENT;
break;
}
#endif
default:
{
break;
}
}
return status;
}
#endif
#ifdef CONFIG_NRF52_SPI1_MASTER
void nrf52_spi1select(FAR struct spi_dev_s *dev, uint32_t devid,
bool selected)
{
spiinfo("devid: %08lx CS: %s\n",
(unsigned long)devid, selected ? "assert" : "de-assert");
}
uint8_t nrf52_spi1status(FAR struct spi_dev_s *dev, uint32_t devid)
{
return 0;
}
#endif
#ifdef CONFIG_nrf52_SPI2_MASTER
void nrf52_spi2select(FAR struct spi_dev_s *dev, uint32_t devid,
bool selected)
{
spiinfo("devid: %08lx CS: %s\n",
(unsigned long)devid, selected ? "assert" : "de-assert");
}
uint8_t nrf52_spi2status(FAR struct spi_dev_s *dev, uint32_t devid)
{
return 0;
}
#endif
#ifdef CONFIG_NRF52_SPI3_MASTER
void nrf52_spi3select(FAR struct spi_dev_s *dev, uint32_t devid,
bool selected)
{
spiinfo("devid: %08lx CS: %s\n",
(unsigned long)devid, selected ? "assert" : "de-assert");
}
uint8_t nrf52_spi3status(FAR struct spi_dev_s *dev, uint32_t devid)
{
return 0;
}
#endif
#endif /* CONFIG_NRF52_SPI_MASTER */

View File

@ -0,0 +1,225 @@
/****************************************************************************
* boards/arm/nrf52/nrf52840-dk/src/nrf52_sx127x.c
* This logic is specific for the RFM98 modules (433MHz)
*
* Copyright (C) 2019 Gregory Nutt. All rights reserved.
* Author: Mateusz Szafoni <raiden00@railab.me>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
* 3. Neither the name NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdio.h>
#include <stdint.h>
#include <errno.h>
#include <assert.h>
#include <debug.h>
#include <nuttx/board.h>
#include <nuttx/signal.h>
#include <nuttx/wireless/lpwan/sx127x.h>
#include <arch/board/board.h>
#include "nrf52_gpio.h"
#include "nrf52_gpiote.h"
#include "nrf52_spi.h"
#include "nrf52840-dk.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* SX127X on SPI0 bus */
#define SX127X_SPI 0
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
static void sx127x_chip_reset(void);
static int sx127x_opmode_change(int opmode);
static int sx127x_freq_select(uint32_t freq);
static int sx127x_pa_select(bool enable);
static int sx127x_irq0_attach(xcpt_t isr, FAR void *arg);
/****************************************************************************
* Private Data
****************************************************************************/
struct sx127x_lower_s lower =
{
.irq0attach = sx127x_irq0_attach,
.reset = sx127x_chip_reset,
.opmode_change = sx127x_opmode_change,
.freq_select = sx127x_freq_select,
.pa_select = sx127x_pa_select,
.pa_force = true
};
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: sx127x_irq0_attach
****************************************************************************/
static int sx127x_irq0_attach(xcpt_t isr, FAR void *arg)
{
wlinfo("Attach DIO0 IRQ\n");
/* IRQ on rising edge */
nrf52_gpiosetevent(GPIO_SX127X_DIO0, true, false, false, isr, arg);
return OK;
}
/****************************************************************************
* Name: sx127x_chip_reset
****************************************************************************/
static void sx127x_chip_reset(void)
{
wlinfo("SX127X RESET\n");
/* Configure reset as output */
nrf52_gpio_config(GPIO_SX127X_RESET | GPIO_OUTPUT | GPIO_VALUE_ZERO);
/* Set pin to zero */
nrf52_gpio_write(GPIO_SX127X_RESET, false);
/* Wait 1 ms */
nxsig_usleep(1000);
/* Configure reset as input */
nrf52_gpio_config(GPIO_SX127X_RESET | GPIO_INPUT | GPIO_FLOAT);
/* Wait 10 ms */
nxsig_usleep(10000);
}
/****************************************************************************
* Name: sx127x_opmode_change
****************************************************************************/
static int sx127x_opmode_change(int opmode)
{
/* Do nothing */
return OK;
}
/****************************************************************************
* Name: sx127x_freq_select
****************************************************************************/
static int sx127x_freq_select(uint32_t freq)
{
int ret = OK;
/* NOTE: this depends on your module version */
if (freq > SX127X_HFBAND_THR)
{
ret = -EINVAL;
wlerr("HF band not supported\n");
}
return ret;
}
/****************************************************************************
* Name: sx127x_pa_select
****************************************************************************/
static int sx127x_pa_select(bool enable)
{
int ret = OK;
/* Only PA_BOOST output connected to antenna */
if (enable == false)
{
ret = -EINVAL;
wlerr("Module supports only PA_BOOST pin,"
" so PA_SELECT must be enabled!\n");
}
return ret;
}
/****************************************************************************
* Public Functions
****************************************************************************/
int nrf52_lpwaninitialize(void)
{
FAR struct spi_dev_s *spidev;
int ret = OK;
wlinfo("Register the sx127x module\n");
/* Setup DIO0 */
nrf52_gpio_config(GPIO_SX127X_DIO0);
/* Init SPI bus */
spidev = nrf52_spibus_initialize(SX127X_SPI);
if (!spidev)
{
wlerr("ERROR: Failed to initialize SPI %d bus\n", SX127X_SPI);
ret = -ENODEV;
goto errout;
}
/* Initialize SX127X */
ret = sx127x_register(spidev, &lower);
if (ret < 0)
{
wlerr("ERROR: Failed to register sx127x\n");
goto errout;
}
errout:
return ret;
}

View File

@ -43,7 +43,7 @@
#include <nuttx/config.h>
#include <stdbool.h>
#if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_NRF52_GPIO_IRQ)
#if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_NRF52_GPIOTE)
# include <nuttx/irq.h>
#endif