You are viewing a plain text version of this content. The canonical link for it is here.
Posted to commits@nuttx.apache.org by gn...@apache.org on 2020/01/12 17:00:48 UTC

[incubator-nuttx] branch master updated: boards/arm/stm32/stm32f4discovery/: Add board support to external LoRa NiceRF module

This is an automated email from the ASF dual-hosted git repository.

gnutt pushed a commit to branch master
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git


The following commit(s) were added to refs/heads/master by this push:
     new 29f480f  boards/arm/stm32/stm32f4discovery/:  Add board support to external LoRa NiceRF module
29f480f is described below

commit 29f480f57f32dc55bbbeb403744b529ff91badf1
Author: Alan Carvalho de Assis <ac...@gmail.com>
AuthorDate: Sun Jan 12 10:59:30 2020 -0600

    boards/arm/stm32/stm32f4discovery/:  Add board support to external LoRa NiceRF module
---
 boards/arm/stm32/stm32f4discovery/README.txt       |  10 +
 boards/arm/stm32/stm32f4discovery/src/Makefile     |  16 +-
 .../arm/stm32/stm32f4discovery/src/stm32_bringup.c |   8 +
 boards/arm/stm32/stm32f4discovery/src/stm32_spi.c  |  21 +-
 .../arm/stm32/stm32f4discovery/src/stm32_sx127x.c  | 216 +++++++++++++++++++++
 .../stm32/stm32f4discovery/src/stm32f4discovery.h  |  21 ++
 drivers/wireless/lpwan/sx127x/sx127x.c             |   2 +-
 7 files changed, 286 insertions(+), 8 deletions(-)

diff --git a/boards/arm/stm32/stm32f4discovery/README.txt b/boards/arm/stm32/stm32f4discovery/README.txt
index 235e9a1..7a73c2e 100644
--- a/boards/arm/stm32/stm32f4discovery/README.txt
+++ b/boards/arm/stm32/stm32f4discovery/README.txt
@@ -41,6 +41,7 @@ Contents
   - RTC DS1307
   - SSD1289
   - UG-2864AMBAG01 / UG-2864HSWEG01
+  - NiceRF LoRa (2AD66-LoRa V2)
   - HCI UART
   - STM32F4Discovery-specific Configuration Options
   - BASIC
@@ -642,6 +643,15 @@ Darcy Gong recently added support for the UG-2864HSWEG01 OLED which is also
 an option with this configuration.  I have little technical information about
 the UG-2864HSWEG01 interface (see boards/arm/stm32/stm32f4discovery/src/up_ug2864hsweg01.c).
 
+NiceRF LoRa (2AD66-LoRa V2)
+===========================
+
+It is possible to wire an external LoRa module to STM32F4Discovery board.
+
+First connect the GND and VCC (to 3.3V) and then connect the SCK label to PA5,
+connnect the MISO to PA6, connect the MOSI to PA7, connect the NSS to PD8,
+connect DIO0 to PD0 and finally connect NRESET to PD4.
+
 HCI UART
 ========
 
diff --git a/boards/arm/stm32/stm32f4discovery/src/Makefile b/boards/arm/stm32/stm32f4discovery/src/Makefile
index 08caf71..d242420 100644
--- a/boards/arm/stm32/stm32f4discovery/src/Makefile
+++ b/boards/arm/stm32/stm32f4discovery/src/Makefile
@@ -74,15 +74,19 @@ CSRCS += stm32_bmp180.c
 endif
 
 ifeq ($(CONFIG_SENSORS_MLX90614),y)
-  CSRCS += stm32_mlx90614.c
+CSRCS += stm32_mlx90614.c
 endif
 
 ifeq ($(CONFIG_LCD_ST7567),y)
-  CSRCS += stm32_st7567.c
+CSRCS += stm32_st7567.c
+endif
+
+ifeq ($(CONFIG_LPWAN_SX127X),y)
+CSRCS += stm32_sx127x.c
 endif
 
 ifeq ($(CONFIG_INPUT_NUNCHUCK),y)
-  CSRCS += stm32_nunchuck.c
+CSRCS += stm32_nunchuck.c
 endif
 
 ifeq ($(CONFIG_SENSORS_MAX31855),y)
@@ -98,11 +102,11 @@ CSRCS += stm32_max6675.c
 endif
 
 ifeq ($(CONFIG_LCD_MAX7219),y)
-  CSRCS += stm32_max7219.c
+CSRCS += stm32_max7219.c
 endif
 
 ifeq ($(CONFIG_LCD_ST7032),y)
-  CSRCS += stm32_st7032.c
+CSRCS += stm32_st7032.c
 endif
 
 ifeq ($(CONFIG_PCA9635PW),y)
@@ -118,7 +122,7 @@ CSRCS += stm32_ethernet.c
 endif
 
 ifeq ($(CONFIG_LEDS_MAX7219),y)
-  CSRCS += stm32_max7219_leds.c
+CSRCS += stm32_max7219_leds.c
 endif
 
 ifeq ($(CONFIG_RGBLED),y)
diff --git a/boards/arm/stm32/stm32f4discovery/src/stm32_bringup.c b/boards/arm/stm32/stm32f4discovery/src/stm32_bringup.c
index edb885f..5cdcce7 100644
--- a/boards/arm/stm32/stm32f4discovery/src/stm32_bringup.c
+++ b/boards/arm/stm32/stm32f4discovery/src/stm32_bringup.c
@@ -466,5 +466,13 @@ int stm32_bringup(void)
     }
 #endif
 
+#ifdef CONFIG_LPWAN_SX127X
+  ret = stm32_lpwaninitialize();
+  if (ret < 0)
+    {
+      syslog(LOG_ERR, "ERROR: Failed to initialize wireless driver: %d\n", ret);
+    }
+#endif  /* CONFIG_LPWAN_SX127X */
+
   return ret;
 }
diff --git a/boards/arm/stm32/stm32f4discovery/src/stm32_spi.c b/boards/arm/stm32/stm32f4discovery/src/stm32_spi.c
index ffd092f..cbdf86a 100644
--- a/boards/arm/stm32/stm32f4discovery/src/stm32_spi.c
+++ b/boards/arm/stm32/stm32f4discovery/src/stm32_spi.c
@@ -78,6 +78,10 @@ void weak_function stm32_spidev_initialize(void)
 #if defined(CONFIG_LCD_MAX7219) || defined(CONFIG_LEDS_MAX7219)
   stm32_configgpio(GPIO_MAX7219_CS);  /* MAX7219 chip select */
 #endif
+#ifdef CONFIG_LPWAN_SX127X
+  stm32_configgpio(GPIO_SX127X_CS);   /* SX127x chip select*/
+#endif
+
 #if defined(CONFIG_LCD_ST7567)
   stm32_configgpio(STM32_LCD_CS);     /* ST7567 chip select */
 #endif
@@ -126,6 +130,12 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
 {
   spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
 
+#ifdef CONFIG_LPWAN_SX127X
+  if (devid == SPIDEV_LPWAN(0))
+    {
+      stm32_gpiowrite(GPIO_SX127X_CS, !selected);
+    }
+#endif
 #ifdef CONFIG_LCD_ST7567
   if (devid == SPIDEV_DISPLAY(0))
     {
@@ -153,7 +163,16 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
 
 uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid)
 {
-  return 0;
+  uint8_t status = 0;
+
+#ifdef CONFIG_LPWAN_SX127X
+  if (devid == SPIDEV_LPWAN(0))
+    {
+      status |= SPI_STATUS_PRESENT;
+    }
+#endif
+
+  return status;
 }
 #endif
 
diff --git a/boards/arm/stm32/stm32f4discovery/src/stm32_sx127x.c b/boards/arm/stm32/stm32f4discovery/src/stm32_sx127x.c
new file mode 100644
index 0000000..1bc850d
--- /dev/null
+++ b/boards/arm/stm32/stm32f4discovery/src/stm32_sx127x.c
@@ -0,0 +1,216 @@
+/****************************************************************************
+ * boards/arm/stm32/stm32f4discovery/src/stm32_boot.c
+ *
+ *   Copyright (C) 2019 Gregory Nutt. All rights reserved.
+ *   Authors: Mateusz Szafoni <ra...@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 "stm32_gpio.h"
+#include "stm32_exti.h"
+#include "stm32_spi.h"
+
+#include "stm32f4discovery.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* SX127X on SPI1 bus */
+
+#define SX127X_SPI 1
+
+/****************************************************************************
+ * 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      = false
+};
+
+static bool g_high_power_output = false;
+
+/****************************************************************************
+ * 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 */
+
+  stm32_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 */
+
+  stm32_configgpio(GPIO_SX127X_RESET);
+
+  /* Set pin to zero */
+
+  stm32_gpiowrite(GPIO_SX127X_RESET, false);
+
+  /* Wait 1 ms */
+
+  nxsig_usleep(1000);
+
+  /* Configure reset as input */
+
+  stm32_configgpio(GPIO_SX127X_RESET | GPIO_INPUT | GPIO_FLOAT);
+
+  /* Wait 10 ms */
+
+  nxsig_usleep(10000);
+}
+
+/****************************************************************************
+ * Name: sx127x_opmode_change
+ ****************************************************************************/
+
+static int sx127x_opmode_change(int opmode)
+{
+  /* Nothing to do */
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: sx127x_freq_select
+ ****************************************************************************/
+
+static int sx127x_freq_select(uint32_t freq)
+{
+  int ret = OK;
+
+  /* Only HF supported (BAND3 - 860-930 MHz) */
+
+  if (freq < SX127X_HFBAND_THR)
+    {
+      ret = -EINVAL;
+      wlerr("LF band not supported\n");
+    }
+
+  return ret;
+}
+
+/****************************************************************************
+ * Name: sx127x_pa_select
+ ****************************************************************************/
+
+static int sx127x_pa_select(bool enable)
+{
+  g_high_power_output = enable;
+  return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+int stm32_lpwaninitialize(void)
+{
+  FAR struct spi_dev_s *spidev;
+  int ret = OK;
+
+  wlinfo("Register the sx127x module\n");
+
+  /* Setup DIO0 */
+
+  stm32_configgpio(GPIO_SX127X_DIO0);
+
+  /* Init SPI bus */
+
+  spidev = stm32_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;
+}
diff --git a/boards/arm/stm32/stm32f4discovery/src/stm32f4discovery.h b/boards/arm/stm32/stm32f4discovery/src/stm32f4discovery.h
index 48c553c..0d34a67 100644
--- a/boards/arm/stm32/stm32f4discovery/src/stm32f4discovery.h
+++ b/boards/arm/stm32/stm32f4discovery/src/stm32f4discovery.h
@@ -242,6 +242,13 @@
 
 #define GPIO_CS43L22_RESET  (GPIO_OUTPUT|GPIO_SPEED_50MHz|GPIO_PORTD|GPIO_PIN4)
 
+/* LoRa SX127x */
+
+#define GPIO_SX127X_DIO0    (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN0)
+
+#define GPIO_SX127X_RESET   (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_OUTPUT_CLEAR|\
+		             GPIO_SPEED_50MHz|GPIO_PORTD|GPIO_PIN4)
+
 /* PWM
  *
  * The STM32F4 Discovery has no real on-board PWM devices, but the board can be
@@ -262,6 +269,9 @@
 #define GPIO_MAX6675_CS   (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
                            GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN8)
 
+#define GPIO_SX127X_CS    (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+                           GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN8)
+
 #define GPIO_MAX7219_CS   (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
                            GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN3)
 
@@ -477,6 +487,17 @@ int stm32_bmp180initialize(FAR const char *devpath);
 int stm32_lis3dshinitialize(FAR const char *devpath);
 #endif
 
+/*****************************************************************************
+ * Name: stm32_lpwaninitialize
+ *
+ * Description:
+ *   Initialize SX127X LPWAN interaface.
+ ****************************************************************************/
+
+#ifdef CONFIG_LPWAN_SX127X
+int stm32_lpwaninitialize(void);
+#endif
+
 /****************************************************************************
  * Name: stm32_mmcsdinitialize
  *
diff --git a/drivers/wireless/lpwan/sx127x/sx127x.c b/drivers/wireless/lpwan/sx127x/sx127x.c
index 6fa0cae..c41bd6c 100644
--- a/drivers/wireless/lpwan/sx127x/sx127x.c
+++ b/drivers/wireless/lpwan/sx127x/sx127x.c
@@ -58,7 +58,7 @@
 #include "sx127x.h"
 
 /* TODO:
- *   - OOK communication (RX+TX) deosnt work yet
+ *   - OOK communication (RX+TX) doesn't work yet
  *   - Channel Activity Detection (CAD) for LORA
  *   - frequency hopping for LORA and FSK/OOK
  *   - modulation shaping for FSK/OOK