From d7e579a093fba09140acf936b2d91fe6c48a3e14 Mon Sep 17 00:00:00 2001 From: Manivannan Sadhasivam Date: Sun, 21 Jul 2019 01:39:22 +0530 Subject: [PATCH 01/10] include: Add initial LoRa API Add initial LoRa API for P2P mode. Signed-off-by: Manivannan Sadhasivam --- include/drivers/lora.h | 140 +++++++++++++++++++++++++++++++++++++++++ 1 file changed, 140 insertions(+) create mode 100644 include/drivers/lora.h diff --git a/include/drivers/lora.h b/include/drivers/lora.h new file mode 100644 index 00000000000000..62e92f7745fa6e --- /dev/null +++ b/include/drivers/lora.h @@ -0,0 +1,140 @@ +/* + * Copyright (c) 2019 Manivannan Sadhasivam + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#ifndef ZEPHYR_INCLUDE_DRIVERS_LORA_H_ +#define ZEPHYR_INCLUDE_DRIVERS_LORA_H_ + +/** + * @file + * @brief Public LoRa APIs + */ + +#include +#include + +enum lora_signal_bandwidth { + BW_125_KHZ = 0, + BW_250_KHZ, + BW_500_KHZ, +}; + +enum lora_datarate { + SF_6 = 6, + SF_7, + SF_8, + SF_9, + SF_10, + SF_11, + SF_12, +}; + +enum lora_coding_rate { + CR_4_5 = 1, + CR_4_6 = 2, + CR_4_7 = 3, + CR_4_8 = 4, +}; + +struct lora_modem_config { + u32_t frequency; + enum lora_signal_bandwidth bandwidth; + enum lora_datarate datarate; + enum lora_coding_rate coding_rate; + u16_t preamble_len; + s8_t tx_power; + bool tx; +}; + +/** + * @typedef lora_api_config() + * @brief Callback API for configuring the LoRa module + * + * @see lora_config() for argument descriptions. + */ +typedef int (*lora_api_config)(struct device *dev, + struct lora_modem_config *config); + +/** + * @typedef lora_api_send() + * @brief Callback API for sending data over LoRa + * + * @see lora_send() for argument descriptions. + */ +typedef int (*lora_api_send)(struct device *dev, + u8_t *data, u32_t data_len); + +/** + * @typedef lora_api_recv() + * @brief Callback API for receiving data over LoRa + * + * @see lora_recv() for argument descriptions. + */ +typedef int (*lora_api_recv)(struct device *dev, u8_t *data, u8_t size, + s32_t timeout); + +struct lora_driver_api { + lora_api_config config; + lora_api_send send; + lora_api_recv recv; +}; + +/** + * @brief Configure the LoRa modem + * + * @param dev LoRa device + * @param config Data structure containing the intended configuration for the + modem + * @return 0 on success, negative on error + */ +static inline int lora_config(struct device *dev, + struct lora_modem_config *config) +{ + const struct lora_driver_api *api = dev->driver_api; + + return api->config(dev, config); +} + +/** + * @brief Send data over LoRa + * + * @note This is a non-blocking call. + * + * @param dev LoRa device + * @param data Data to be sent + * @param data_len Length of the data to be sent + * @return 0 on success, negative on error + */ +static inline int lora_send(struct device *dev, + u8_t *data, u32_t data_len) +{ + const struct lora_driver_api *api = dev->driver_api; + + return api->send(dev, data, data_len); +} + +/** + * @brief Receive data over LoRa + * + * @note This is a blocking call. + * + * @param dev LoRa device + * @param data Buffer to hold received data + * @param size Size of the buffer to hold the received data. Max size + allowed is 255. + * @param timeout Timeout value in milliseconds. API also accepts, K_NO_WAIT + for no wait time and K_FOREVER for blocking until + data arrives. + * @return Length of the data received on success, negative on error + */ +static inline int lora_recv(struct device *dev, u8_t *data, u8_t size, + s32_t timeout) +{ + const struct lora_driver_api *api = dev->driver_api; + + return api->recv(dev, data, size, timeout); +} + +#endif /* ZEPHYR_INCLUDE_DRIVERS_LORA_H_ */ From 16804686d4fe9967fd317c7ed334f465e370b58b Mon Sep 17 00:00:00 2001 From: Manivannan Sadhasivam Date: Sat, 31 Aug 2019 22:14:44 +0530 Subject: [PATCH 02/10] drivers: Add basic LoRa driver support Add basic driver support for LoRa. Signed-off-by: Manivannan Sadhasivam --- drivers/CMakeLists.txt | 1 + drivers/Kconfig | 2 ++ drivers/lora/CMakeLists.txt | 1 + drivers/lora/Kconfig | 26 ++++++++++++++++++++++++++ 4 files changed, 30 insertions(+) create mode 100644 drivers/lora/CMakeLists.txt create mode 100644 drivers/lora/Kconfig diff --git a/drivers/CMakeLists.txt b/drivers/CMakeLists.txt index 89c4d6a719ab31..68ac3b1fd9f0ea 100644 --- a/drivers/CMakeLists.txt +++ b/drivers/CMakeLists.txt @@ -37,6 +37,7 @@ add_subdirectory_if_kconfig(ps2) add_subdirectory_if_kconfig(kscan) add_subdirectory_if_kconfig(video) add_subdirectory_if_kconfig(eeprom) +add_subdirectory_if_kconfig(lora) add_subdirectory_ifdef(CONFIG_FLASH_HAS_DRIVER_ENABLED flash) add_subdirectory_ifdef(CONFIG_SERIAL_HAS_DRIVER serial) diff --git a/drivers/Kconfig b/drivers/Kconfig index d8c53bda07d517..e606c7b37e9263 100644 --- a/drivers/Kconfig +++ b/drivers/Kconfig @@ -9,6 +9,8 @@ source "drivers/bluetooth/Kconfig" source "drivers/ieee802154/Kconfig" +source "drivers/lora/Kconfig" + source "drivers/console/Kconfig" source "drivers/ethernet/Kconfig" diff --git a/drivers/lora/CMakeLists.txt b/drivers/lora/CMakeLists.txt new file mode 100644 index 00000000000000..e9be9ab9d307c1 --- /dev/null +++ b/drivers/lora/CMakeLists.txt @@ -0,0 +1 @@ +#nothing diff --git a/drivers/lora/Kconfig b/drivers/lora/Kconfig new file mode 100644 index 00000000000000..03178600084063 --- /dev/null +++ b/drivers/lora/Kconfig @@ -0,0 +1,26 @@ +# +# Copyright (c) 2019 Manivannan Sadhasivam +# +# SPDX-License-Identifier: Apache-2.0 +# + +# Top-level configuration file for LORA drivers. + +menuconfig LORA + bool "LoRa drivers" + help + Include LoRa drivers in the system configuration. + +if LORA + +module = LORA +module-str = lora +source "subsys/logging/Kconfig.template.log_config" + +config LORA_INIT_PRIORITY + int "LoRa initialization priority" + default 90 + help + System initialization priority for LoRa drivers. + +endif # LORA From ab6b2327c8039923b3094775cf576c03401414c1 Mon Sep 17 00:00:00 2001 From: Manivannan Sadhasivam Date: Sun, 21 Jul 2019 01:48:03 +0530 Subject: [PATCH 03/10] drivers: lora: Add SX1276 LoRa Modem support Add support for Semtech SX1276 LoRa Modem. Signed-off-by: Manivannan Sadhasivam --- drivers/lora/CMakeLists.txt | 6 +- drivers/lora/Kconfig | 4 +- drivers/lora/Kconfig.sx1276 | 37 ++ drivers/lora/sx1276.c | 501 ++++++++++++++++++++++++++ dts/bindings/lora/semtech,sx1276.yaml | 21 ++ 5 files changed, 567 insertions(+), 2 deletions(-) create mode 100644 drivers/lora/Kconfig.sx1276 create mode 100644 drivers/lora/sx1276.c create mode 100644 dts/bindings/lora/semtech,sx1276.yaml diff --git a/drivers/lora/CMakeLists.txt b/drivers/lora/CMakeLists.txt index e9be9ab9d307c1..4686147fa24975 100644 --- a/drivers/lora/CMakeLists.txt +++ b/drivers/lora/CMakeLists.txt @@ -1 +1,5 @@ -#nothing +# SPDX-License-Identifier: Apache-2.0 + +zephyr_library_named(loramac-node) + +zephyr_library_sources_ifdef(CONFIG_LORA_SX1276 sx1276.c) diff --git a/drivers/lora/Kconfig b/drivers/lora/Kconfig index 03178600084063..69957946cba486 100644 --- a/drivers/lora/Kconfig +++ b/drivers/lora/Kconfig @@ -7,7 +7,7 @@ # Top-level configuration file for LORA drivers. menuconfig LORA - bool "LoRa drivers" + bool "LoRa support" help Include LoRa drivers in the system configuration. @@ -23,4 +23,6 @@ config LORA_INIT_PRIORITY help System initialization priority for LoRa drivers. +source "drivers/lora/Kconfig.sx1276" + endif # LORA diff --git a/drivers/lora/Kconfig.sx1276 b/drivers/lora/Kconfig.sx1276 new file mode 100644 index 00000000000000..eed99be8b245ae --- /dev/null +++ b/drivers/lora/Kconfig.sx1276 @@ -0,0 +1,37 @@ +# +# Copyright (c) 2019 Manivannan Sadhasivam +# +# SPDX-License-Identifier: Apache-2.0 +# + +menuconfig LORA_SX1276 + bool "Semtech SX1276 driver" + select HAS_SEMTECH_RADIO_DRIVERS + select HAS_SEMTECH_LORAMAC + select HAS_SEMTECH_SX1276 + depends on SPI + depends on COUNTER + help + Enable LoRa driver for Semtech SX1276. + +if LORA_SX1276 + +choice + prompt "SX1276 PA Output pin" + default PA_BOOST_PIN + help + Antenna connection type. + +config PA_RFO_PIN + bool "PA_RFO_PIN" + help + Antenna connected to PA_RFO pin. + +config PA_BOOST_PIN + bool "PA_BOOST_PIN" + help + Antenna connected to PA_BOOST pin. + +endchoice + +endif # LORA_SX1276 diff --git a/drivers/lora/sx1276.c b/drivers/lora/sx1276.c new file mode 100644 index 00000000000000..1ef72e94174a8c --- /dev/null +++ b/drivers/lora/sx1276.c @@ -0,0 +1,501 @@ +/* + * Copyright (c) 2019 Manivannan Sadhasivam + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include +#include +#include +#include +#include + +#include + +#define LOG_LEVEL CONFIG_LORA_LOG_LEVEL +#include +LOG_MODULE_REGISTER(sx1276); + +#define SX1276_MAX_DIO 5 + +#define GPIO_RESET_PIN DT_INST_0_SEMTECH_SX1276_RESET_GPIOS_PIN +#define GPIO_CS_PIN DT_INST_0_SEMTECH_SX1276_CS_GPIOS_PIN + +#define SX1276_REG_PA_CONFIG 0x09 +#define SX1276_REG_PA_DAC 0x4d +#define SX1276_REG_VERSION 0x42 + +extern DioIrqHandler *DioIrq[]; + +int sx1276_dio_pins[SX1276_MAX_DIO] = { + DT_INST_0_SEMTECH_SX1276_DIO_GPIOS_PIN_0, + DT_INST_0_SEMTECH_SX1276_DIO_GPIOS_PIN_1, + DT_INST_0_SEMTECH_SX1276_DIO_GPIOS_PIN_2, + DT_INST_0_SEMTECH_SX1276_DIO_GPIOS_PIN_3, + DT_INST_0_SEMTECH_SX1276_DIO_GPIOS_PIN_4, +}; + +static char sx1276_dio_ports[SX1276_MAX_DIO][6] = { + DT_INST_0_SEMTECH_SX1276_DIO_GPIOS_CONTROLLER_0, + DT_INST_0_SEMTECH_SX1276_DIO_GPIOS_CONTROLLER_1, + DT_INST_0_SEMTECH_SX1276_DIO_GPIOS_CONTROLLER_2, + DT_INST_0_SEMTECH_SX1276_DIO_GPIOS_CONTROLLER_3, + DT_INST_0_SEMTECH_SX1276_DIO_GPIOS_CONTROLLER_4, +}; + +struct sx1276_data { + struct device *counter; + struct device *reset; + struct device *spi; + struct spi_config spi_cfg; + struct device *dio_dev[SX1276_MAX_DIO]; + struct k_sem data_sem; + RadioEvents_t sx1276_event; + u8_t *rx_buf; + u8_t rx_len; +} dev_data; + +bool SX1276CheckRfFrequency(uint32_t frequency) +{ + /* TODO */ + return true; +} + +void RtcStopAlarm(void) +{ + counter_stop(dev_data.counter); +} + +void SX1276SetAntSwLowPower(bool status) +{ + /* TODO */ +} + +void SX1276SetBoardTcxo(u8_t state) +{ + /* TODO */ +} + +void SX1276SetAntSw(u8_t opMode) +{ + /* TODO */ +} + +void SX1276Reset(void) +{ + gpio_pin_configure(dev_data.reset, GPIO_RESET_PIN, + GPIO_DIR_OUT | GPIO_PUD_NORMAL); + gpio_pin_write(dev_data.reset, GPIO_RESET_PIN, 0); + + k_sleep(1); + + gpio_pin_configure(dev_data.reset, GPIO_RESET_PIN, + GPIO_DIR_IN | GPIO_PUD_NORMAL); + k_sleep(6); +} + +void BoardCriticalSectionBegin(uint32_t *mask) +{ + *mask = irq_lock(); +} + +void BoardCriticalSectionEnd(uint32_t *mask) +{ + irq_unlock(*mask); +} + +uint32_t RtcGetTimerElapsedTime(void) +{ + return counter_read(dev_data.counter); +} + +u32_t RtcGetMinimumTimeout(void) +{ + /* TODO: Get this value from counter driver */ + return 3; +} + +void RtcSetAlarm(uint32_t timeout) +{ + struct counter_alarm_cfg alarm_cfg; + + alarm_cfg.flags = 0; + alarm_cfg.ticks = timeout; + + counter_set_channel_alarm(dev_data.counter, 0, &alarm_cfg); +} + +uint32_t RtcSetTimerContext(void) +{ + return 0; +} + +uint32_t RtcMs2Tick(uint32_t milliseconds) +{ + return counter_us_to_ticks(dev_data.counter, (milliseconds / 1000)); +} + +void DelayMsMcu(uint32_t ms) +{ + k_sleep(ms); +} + +static void sx1276_irq_callback(struct device *dev, + struct gpio_callback *cb, u32_t pins) +{ + unsigned int i, pin; + + pin = find_lsb_set(pins) - 1; + + for (i = 0; i < SX1276_MAX_DIO; i++) { + if (pin == sx1276_dio_pins[i]) { + (*DioIrq[i])(NULL); + } + } +} + +void SX1276IoIrqInit(DioIrqHandler **irqHandlers) +{ + unsigned int i; + static struct gpio_callback callbacks[SX1276_MAX_DIO]; + + /* Setup DIO gpios */ + for (i = 0; i < SX1276_MAX_DIO; i++) { + dev_data.dio_dev[i] = device_get_binding(sx1276_dio_ports[i]); + if (dev_data.dio_dev[i] == NULL) { + LOG_ERR("Cannot get pointer to %s device", + sx1276_dio_ports[i]); + return; + } + + gpio_pin_configure(dev_data.dio_dev[i], sx1276_dio_pins[i], + GPIO_DIR_IN | GPIO_INT | GPIO_INT_EDGE | + GPIO_INT_DEBOUNCE | GPIO_INT_ACTIVE_HIGH); + + gpio_init_callback(&callbacks[i], + sx1276_irq_callback, + BIT(sx1276_dio_pins[i])); + + if (gpio_add_callback(dev_data.dio_dev[i], &callbacks[i]) < 0) { + LOG_ERR("Could not set gpio callback."); + return; + } + gpio_pin_enable_callback(dev_data.dio_dev[i], + sx1276_dio_pins[i]); + } + +} + +static int sx1276_transceive(u8_t reg, bool write, void *data, size_t length) +{ + const struct spi_buf buf[2] = { + { + .buf = ®, + .len = sizeof(reg) + }, + { + .buf = data, + .len = length + } + }; + struct spi_buf_set tx = { + .buffers = buf, + .count = ARRAY_SIZE(buf), + }; + + if (!write) { + const struct spi_buf_set rx = { + .buffers = buf, + .count = ARRAY_SIZE(buf) + }; + + return spi_transceive(dev_data.spi, &dev_data.spi_cfg, + &tx, &rx); + } + + return spi_write(dev_data.spi, &dev_data.spi_cfg, &tx); +} + +int sx1276_read(u8_t reg_addr, u8_t *data, u8_t len) +{ + return sx1276_transceive(reg_addr, false, data, len); +} + +int sx1276_write(u8_t reg_addr, u8_t *data, u8_t len) +{ + return sx1276_transceive(reg_addr | BIT(7), true, data, len); +} + +void SX1276WriteBuffer(u16_t addr, u8_t *buffer, u8_t size) +{ + int ret; + + ret = sx1276_write(addr, buffer, size); + if (ret < 0) { + LOG_ERR("Unable to write address: 0x%x", addr); + } +} + +void SX1276ReadBuffer(u16_t addr, u8_t *buffer, u8_t size) +{ + int ret; + + ret = sx1276_read(addr, buffer, size); + if (ret < 0) { + LOG_ERR("Unable to read address: 0x%x", addr); + } +} + +void SX1276SetRfTxPower(int8_t power) +{ + int ret; + u8_t pa_config = 0; + u8_t pa_dac = 0; + + ret = sx1276_read(SX1276_REG_PA_CONFIG, &pa_config, 1); + if (ret < 0) { + LOG_ERR("Unable to read PA config"); + return; + } + + ret = sx1276_read(SX1276_REG_PA_DAC, &pa_dac, 1); + if (ret < 0) { + LOG_ERR("Unable to read PA dac"); + return; + } + + pa_config = (pa_config & RF_PACONFIG_MAX_POWER_MASK) | 0x70; + pa_config &= RF_PACONFIG_PASELECT_MASK; + +#if defined CONFIG_PA_BOOST_PIN + pa_config |= RF_PACONFIG_PASELECT_PABOOST; + + if (power > 17) { + pa_dac = (pa_dac & RF_PADAC_20DBM_MASK) | RF_PADAC_20DBM_ON; + } else { + pa_dac = (pa_dac & RF_PADAC_20DBM_MASK) | RF_PADAC_20DBM_OFF; + } + + if ((pa_dac & RF_PADAC_20DBM_ON) == RF_PADAC_20DBM_ON) { + if (power < 5) { + power = 5; + } else if (power > 20) { + power = 20; + } + + pa_config = (pa_config & RF_PACONFIG_OUTPUTPOWER_MASK) | + ((power - 5) & 0x0F); + } else { + if (power < 2) { + power = 2; + } else if (power > 17) { + power = 17; + } + + pa_config = (pa_config & RF_PACONFIG_OUTPUTPOWER_MASK) | + ((power - 2) & 0x0F); + } +#elif CONFIG_PA_RFO_PIN + if (power < -1) { + power = -1; + } else if (power > 14) { + power = 14; + } + + pa_config = (pa_config & RF_PACONFIG_OUTPUTPOWER_MASK) | + ((power + 1) & 0x0F); +#endif + ret = sx1276_write(SX1276_REG_PA_CONFIG, &pa_config, 1); + if (ret < 0) { + LOG_ERR("Unable to write PA config"); + return; + } + + ret = sx1276_write(SX1276_REG_PA_DAC, &pa_dac, 1); + if (ret < 0) { + LOG_ERR("Unable to write PA dac"); + return; + } +} + +static int sx1276_lora_send(struct device *dev, u8_t *data, u32_t data_len) +{ + Radio.SetMaxPayloadLength(MODEM_LORA, data_len); + + Radio.Send(data, data_len); + + return 0; +} + +static void sx1276_tx_done(void) +{ + Radio.Sleep(); +} + +static void sx1276_rx_done(u8_t *payload, u16_t size, int16_t rssi, int8_t snr) +{ + Radio.Sleep(); + + dev_data.rx_buf = payload; + dev_data.rx_len = size; + + k_sem_give(&dev_data.data_sem); +} + +static int sx1276_lora_recv(struct device *dev, u8_t *data, u8_t size, + s32_t timeout) +{ + int ret; + + Radio.SetMaxPayloadLength(MODEM_LORA, 255); + Radio.Rx(0); + + /* + * As per the API requirement, timeout value can be in ms/K_FOREVER/ + * K_NO_WAIT. So, let's handle all cases. + */ + ret = k_sem_take(&dev_data.data_sem, timeout == K_FOREVER ? K_FOREVER : + timeout == K_NO_WAIT ? K_NO_WAIT : K_MSEC(timeout)); + if (ret < 0) { + LOG_ERR("Receive timeout!"); + return ret; + } + + /* Only copy the bytes that can fit the buffer, drop the rest */ + if (dev_data.rx_len > size) + dev_data.rx_len = size; + + /* + * FIXME: We are copying the global buffer here, so it might get + * overwritten inbetween when a new packet comes in. Use some + * wise method to fix this! + */ + memcpy(data, dev_data.rx_buf, dev_data.rx_len); + + return dev_data.rx_len; +} + +static int sx1276_lora_config(struct device *dev, + struct lora_modem_config *config) +{ + + Radio.SetChannel(config->frequency); + + if (config->tx) { + Radio.SetTxConfig(MODEM_LORA, config->tx_power, 0, + config->bandwidth, config->datarate, + config->coding_rate, config->preamble_len, + false, true, 0, 0, false, 4000); + } else { + /* TODO: Get symbol timeout value from config parameters */ + Radio.SetRxConfig(MODEM_LORA, config->bandwidth, + config->datarate, config->coding_rate, + 0, config->preamble_len, 10, false, 0, + false, 0, 0, false, true); + } + + return 0; +} + +/* Initialize Radio driver callbacks */ +const struct Radio_s Radio = { + .Init = SX1276Init, + .GetStatus = SX1276GetStatus, + .SetModem = SX1276SetModem, + .SetChannel = SX1276SetChannel, + .IsChannelFree = SX1276IsChannelFree, + .Random = SX1276Random, + .SetRxConfig = SX1276SetRxConfig, + .SetTxConfig = SX1276SetTxConfig, + .Send = SX1276Send, + .Sleep = SX1276SetSleep, + .Standby = SX1276SetStby, + .Rx = SX1276SetRx, + .Write = SX1276Write, + .Read = SX1276Read, + .WriteBuffer = SX1276WriteBuffer, + .ReadBuffer = SX1276ReadBuffer, + .SetMaxPayloadLength = SX1276SetMaxPayloadLength, + .IrqProcess = NULL, + .RxBoosted = NULL, + .SetRxDutyCycle = NULL, +}; + +static int sx1276_lora_init(struct device *dev) +{ + static struct spi_cs_control spi_cs; + int ret; + u8_t regval; + + dev_data.spi = device_get_binding(DT_INST_0_SEMTECH_SX1276_BUS_NAME); + if (!dev_data.spi) { + LOG_ERR("Cannot get pointer to %s device", + DT_INST_0_SEMTECH_SX1276_BUS_NAME); + return -EINVAL; + } + + dev_data.spi_cfg.operation = SPI_WORD_SET(8) | SPI_TRANSFER_MSB; + dev_data.spi_cfg.frequency = DT_INST_0_SEMTECH_SX1276_SPI_MAX_FREQUENCY; + dev_data.spi_cfg.slave = DT_INST_0_SEMTECH_SX1276_BASE_ADDRESS; + + spi_cs.gpio_pin = GPIO_CS_PIN, + spi_cs.gpio_dev = device_get_binding( + DT_INST_0_SEMTECH_SX1276_CS_GPIOS_CONTROLLER); + if (!spi_cs.gpio_dev) { + LOG_ERR("Cannot get pointer to %s device", + DT_INST_0_SEMTECH_SX1276_CS_GPIOS_CONTROLLER); + return -EIO; + } + + dev_data.spi_cfg.cs = &spi_cs; + + /* Setup Reset gpio */ + dev_data.reset = device_get_binding( + DT_INST_0_SEMTECH_SX1276_RESET_GPIOS_CONTROLLER); + if (!dev_data.reset) { + LOG_ERR("Cannot get pointer to %s device", + DT_INST_0_SEMTECH_SX1276_RESET_GPIOS_CONTROLLER); + return -EIO; + } + + ret = gpio_pin_configure(dev_data.reset, GPIO_RESET_PIN, GPIO_DIR_OUT); + + /* Perform soft reset */ + gpio_pin_write(dev_data.reset, GPIO_RESET_PIN, 0); + k_sleep(100); + gpio_pin_write(dev_data.reset, GPIO_RESET_PIN, 1); + k_sleep(100); + + ret = sx1276_read(SX1276_REG_VERSION, ®val, 1); + if (ret < 0) { + LOG_ERR("Unable to read version info"); + return -EIO; + } + + dev_data.counter = device_get_binding(DT_RTC_0_NAME); + if (!dev_data.counter) { + LOG_ERR("Cannot get pointer to %s device", DT_RTC_0_NAME); + return -EIO; + } + + k_sem_init(&dev_data.data_sem, 0, UINT_MAX); + + dev_data.sx1276_event.TxDone = sx1276_tx_done; + dev_data.sx1276_event.RxDone = sx1276_rx_done; + Radio.Init(&dev_data.sx1276_event); + + LOG_INF("SX1276 Version:%02x found", regval); + + return 0; +} + +static const struct lora_driver_api sx1276_lora_api = { + .config = sx1276_lora_config, + .send = sx1276_lora_send, + .recv = sx1276_lora_recv, +}; + +DEVICE_AND_API_INIT(sx1276_lora, DT_INST_0_SEMTECH_SX1276_LABEL, + &sx1276_lora_init, NULL, + NULL, POST_KERNEL, CONFIG_LORA_INIT_PRIORITY, + &sx1276_lora_api); diff --git a/dts/bindings/lora/semtech,sx1276.yaml b/dts/bindings/lora/semtech,sx1276.yaml new file mode 100644 index 00000000000000..ed3a70ad131ae3 --- /dev/null +++ b/dts/bindings/lora/semtech,sx1276.yaml @@ -0,0 +1,21 @@ +# +# Copyright (c) 2019, Manivannan Sadhasivam +# +# SPDX-License-Identifier: Apache-2.0 +# + +description: Semtech SX1276 LoRa Modem + +compatible: "semtech,sx1276" + +include: spi-device.yaml + +properties: + reset-gpios: + type: phandle-array + required: true + + dio-gpios: + type: phandle-array + required: true +... From 16a94b1aeab06810f4a796b6f89cd254895eaa5d Mon Sep 17 00:00:00 2001 From: Manivannan Sadhasivam Date: Sun, 21 Jul 2019 01:48:29 +0530 Subject: [PATCH 04/10] boards: arm: 96b_wistrio: Add on-board SX1276 LoRa Modem suppport Add support for Semtech SX1276 LoRa Modem found within the RAK811 module on the board. Signed-off-by: Manivannan Sadhasivam --- boards/arm/96b_wistrio/96b_wistrio.dts | 11 ++++++ boards/arm/96b_wistrio/pinmux.c | 48 +++++++++++++++++++++++--- 2 files changed, 55 insertions(+), 4 deletions(-) diff --git a/boards/arm/96b_wistrio/96b_wistrio.dts b/boards/arm/96b_wistrio/96b_wistrio.dts index f7a807753274ad..d050f72c3a77f5 100644 --- a/boards/arm/96b_wistrio/96b_wistrio.dts +++ b/boards/arm/96b_wistrio/96b_wistrio.dts @@ -59,6 +59,17 @@ &spi1 { status = "okay"; + cs-gpios = <&gpiob 0 0>; + + sx1276@0 { + compatible = "semtech,sx1276"; + reg = <0>; + label = "sx1276"; + reset-gpios = <&gpiob 13 0>; + dio-gpios = <&gpioa 11 0 &gpiob 1 0 &gpioa 3 0 + &gpioh 0 0 &gpioc 13 0>; + spi-max-frequency = <1000000>; + }; }; &rtc { diff --git a/boards/arm/96b_wistrio/pinmux.c b/boards/arm/96b_wistrio/pinmux.c index a649e785ffe4ec..3281178a99df55 100644 --- a/boards/arm/96b_wistrio/pinmux.c +++ b/boards/arm/96b_wistrio/pinmux.c @@ -4,10 +4,11 @@ * SPDX-License-Identifier: Apache-2.0 */ -#include #include +#include #include -#include +#include +#include #include #include @@ -25,16 +26,55 @@ static const struct pin_config pinconf[] = { {STM32_PIN_PB8, STM32L1X_PINMUX_FUNC_PB8_I2C1_SCL}, {STM32_PIN_PB9, STM32L1X_PINMUX_FUNC_PB9_I2C1_SDA}, #endif /* CONFIG_I2C_1 */ +#ifdef CONFIG_SPI_1 + {STM32_PIN_PA5, STM32L1X_PINMUX_FUNC_PA5_SPI1_SCK}, + {STM32_PIN_PA6, STM32L1X_PINMUX_FUNC_PA6_SPI1_MISO}, + {STM32_PIN_PA7, STM32L1X_PINMUX_FUNC_PA7_SPI1_MOSI}, +#endif /* CONFIG_SPI_1 */ + /* RF_CTX_PA */ + {STM32_PIN_PA4, STM32_PUSHPULL_PULLUP}, + /* RF_CRX_RX */ + {STM32_PIN_PB6, STM32_PUSHPULL_PULLUP}, + /* RF_CBT_HF */ + {STM32_PIN_PB7, STM32_PUSHPULL_PULLUP}, }; static int pinmux_stm32_init(struct device *port) { ARG_UNUSED(port); + struct device *gpioa, *gpiob, *gpioh; stm32_setup_pins(pinconf, ARRAY_SIZE(pinconf)); + gpioa = device_get_binding(DT_ST_STM32_GPIO_40020000_LABEL); + if (!gpioa) { + return -ENODEV; + } + + gpiob = device_get_binding(DT_ST_STM32_GPIO_40020400_LABEL); + if (!gpiob) { + return -ENODEV; + } + + gpioh = device_get_binding(DT_ST_STM32_GPIO_40021400_LABEL); + if (!gpioh) { + return -ENODEV; + } + + gpio_pin_configure(gpioa, 4, GPIO_DIR_OUT); + gpio_pin_write(gpioa, 4, 1); + + gpio_pin_configure(gpiob, 6, GPIO_DIR_OUT); + gpio_pin_write(gpiob, 6, 1); + + gpio_pin_configure(gpiob, 7, GPIO_DIR_OUT); + gpio_pin_write(gpiob, 7, 0); + + gpio_pin_configure(gpioh, 1, GPIO_DIR_OUT); + gpio_pin_write(gpioh, 1, 1); + return 0; } -SYS_INIT(pinmux_stm32_init, PRE_KERNEL_1, - CONFIG_PINMUX_STM32_DEVICE_INITIALIZATION_PRIORITY); +/* Need to be initialised after GPIO driver */ +SYS_INIT(pinmux_stm32_init, POST_KERNEL, CONFIG_KERNEL_INIT_PRIORITY_DEVICE); From 0b0298334090073ec586737cb920dd2adc346f75 Mon Sep 17 00:00:00 2001 From: Manivannan Sadhasivam Date: Sun, 21 Jul 2019 01:50:09 +0530 Subject: [PATCH 05/10] samples: drivers: Add LoRa sender sample Add sample application for sending data packets over LoRa. Signed-off-by: Manivannan Sadhasivam --- samples/drivers/lora/send/CMakeLists.txt | 9 +++ .../drivers/lora/send/boards/96b_wistrio.conf | 1 + samples/drivers/lora/send/prj.conf | 7 +++ samples/drivers/lora/send/sample.yaml | 8 +++ samples/drivers/lora/send/src/main.c | 59 +++++++++++++++++++ 5 files changed, 84 insertions(+) create mode 100644 samples/drivers/lora/send/CMakeLists.txt create mode 100644 samples/drivers/lora/send/boards/96b_wistrio.conf create mode 100644 samples/drivers/lora/send/prj.conf create mode 100644 samples/drivers/lora/send/sample.yaml create mode 100644 samples/drivers/lora/send/src/main.c diff --git a/samples/drivers/lora/send/CMakeLists.txt b/samples/drivers/lora/send/CMakeLists.txt new file mode 100644 index 00000000000000..ce4b633d9731b6 --- /dev/null +++ b/samples/drivers/lora/send/CMakeLists.txt @@ -0,0 +1,9 @@ +# SPDX-License-Identifier: Apache-2.0 + +cmake_minimum_required(VERSION 3.13.1) + +include($ENV{ZEPHYR_BASE}/cmake/app/boilerplate.cmake NO_POLICY_SCOPE) +project(lora_send) + +FILE(GLOB app_sources src/*.c) +target_sources(app PRIVATE ${app_sources}) diff --git a/samples/drivers/lora/send/boards/96b_wistrio.conf b/samples/drivers/lora/send/boards/96b_wistrio.conf new file mode 100644 index 00000000000000..be022a25e699d3 --- /dev/null +++ b/samples/drivers/lora/send/boards/96b_wistrio.conf @@ -0,0 +1 @@ +CONFIG_SPI_1=y diff --git a/samples/drivers/lora/send/prj.conf b/samples/drivers/lora/send/prj.conf new file mode 100644 index 00000000000000..89c2cef5c484b8 --- /dev/null +++ b/samples/drivers/lora/send/prj.conf @@ -0,0 +1,7 @@ +CONFIG_LOG=y +CONFIG_SPI=y +CONFIG_GPIO=y +CONFIG_LORA=y +CONFIG_LORA_SX1276=y +CONFIG_PRINTK=y +CONFIG_COUNTER=y diff --git a/samples/drivers/lora/send/sample.yaml b/samples/drivers/lora/send/sample.yaml new file mode 100644 index 00000000000000..9b6d7dd07d6572 --- /dev/null +++ b/samples/drivers/lora/send/sample.yaml @@ -0,0 +1,8 @@ +common: + tags: lora +sample: + description: Demonstration of LoRa Send functionality + name: LoRa Send Sample +tests: + sample.driver.lora.send: + platform_whitelist: 96b_wistrio diff --git a/samples/drivers/lora/send/src/main.c b/samples/drivers/lora/send/src/main.c new file mode 100644 index 00000000000000..d548520b7deb1e --- /dev/null +++ b/samples/drivers/lora/send/src/main.c @@ -0,0 +1,59 @@ +/* + * Copyright (c) 2019 Manivannan Sadhasivam + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include +#include +#include +#include +#include + +#define MAX_DATA_LEN 10 + +#define LOG_LEVEL CONFIG_LOG_DEFAULT_LEVEL +#include +LOG_MODULE_REGISTER(lora_send); + +char data[MAX_DATA_LEN] = {'h', 'e', 'l', 'l', 'o', 'w', 'o', 'r', 'l', 'd'}; + +void main(void) +{ + struct device *lora_dev; + struct lora_modem_config config; + int ret; + + lora_dev = device_get_binding(DT_INST_0_SEMTECH_SX1276_LABEL); + if (!lora_dev) { + LOG_ERR("%s Device not found", DT_INST_0_SEMTECH_SX1276_LABEL); + return; + } + + config.frequency = 865100000; + config.bandwidth = BW_125_KHZ; + config.datarate = SF_10; + config.preamble_len = 8; + config.coding_rate = CR_4_5; + config.tx_power = 4; + config.tx = true; + + ret = lora_config(lora_dev, &config); + if (ret < 0) { + LOG_ERR("LoRa config failed"); + return; + } + + while (1) { + ret = lora_send(lora_dev, data, MAX_DATA_LEN); + if (ret < 0) { + LOG_ERR("LoRa send failed"); + return; + } + + LOG_INF("Data sent!"); + + /* Send data at 1s interval */ + k_sleep(1000); + } +} From dfa39943aa4855246800114ecb736e37e4b3340b Mon Sep 17 00:00:00 2001 From: Manivannan Sadhasivam Date: Sun, 21 Jul 2019 01:50:59 +0530 Subject: [PATCH 06/10] samples: drivers: Add LoRa receiver sample Add sample application for receiving data packets over LoRa. Signed-off-by: Manivannan Sadhasivam --- samples/drivers/lora/receive/CMakeLists.txt | 9 +++ .../lora/receive/boards/96b_wistrio.conf | 1 + samples/drivers/lora/receive/prj.conf | 7 +++ samples/drivers/lora/receive/sample.yaml | 8 +++ samples/drivers/lora/receive/src/main.c | 56 +++++++++++++++++++ 5 files changed, 81 insertions(+) create mode 100644 samples/drivers/lora/receive/CMakeLists.txt create mode 100644 samples/drivers/lora/receive/boards/96b_wistrio.conf create mode 100644 samples/drivers/lora/receive/prj.conf create mode 100644 samples/drivers/lora/receive/sample.yaml create mode 100644 samples/drivers/lora/receive/src/main.c diff --git a/samples/drivers/lora/receive/CMakeLists.txt b/samples/drivers/lora/receive/CMakeLists.txt new file mode 100644 index 00000000000000..fa2e994c23d727 --- /dev/null +++ b/samples/drivers/lora/receive/CMakeLists.txt @@ -0,0 +1,9 @@ +# SPDX-License-Identifier: Apache-2.0 + +cmake_minimum_required(VERSION 3.13.1) + +include($ENV{ZEPHYR_BASE}/cmake/app/boilerplate.cmake NO_POLICY_SCOPE) +project(lora_receive) + +FILE(GLOB app_sources src/*.c) +target_sources(app PRIVATE ${app_sources}) diff --git a/samples/drivers/lora/receive/boards/96b_wistrio.conf b/samples/drivers/lora/receive/boards/96b_wistrio.conf new file mode 100644 index 00000000000000..be022a25e699d3 --- /dev/null +++ b/samples/drivers/lora/receive/boards/96b_wistrio.conf @@ -0,0 +1 @@ +CONFIG_SPI_1=y diff --git a/samples/drivers/lora/receive/prj.conf b/samples/drivers/lora/receive/prj.conf new file mode 100644 index 00000000000000..89c2cef5c484b8 --- /dev/null +++ b/samples/drivers/lora/receive/prj.conf @@ -0,0 +1,7 @@ +CONFIG_LOG=y +CONFIG_SPI=y +CONFIG_GPIO=y +CONFIG_LORA=y +CONFIG_LORA_SX1276=y +CONFIG_PRINTK=y +CONFIG_COUNTER=y diff --git a/samples/drivers/lora/receive/sample.yaml b/samples/drivers/lora/receive/sample.yaml new file mode 100644 index 00000000000000..06233e6de1cf37 --- /dev/null +++ b/samples/drivers/lora/receive/sample.yaml @@ -0,0 +1,8 @@ +common: + tags: lora +sample: + description: Demonstration of LoRa Receive functionality + name: LoRa Receive Sample +tests: + sample.driver.lora.receive: + platform_whitelist: 96b_wistrio diff --git a/samples/drivers/lora/receive/src/main.c b/samples/drivers/lora/receive/src/main.c new file mode 100644 index 00000000000000..45256b2931f0c0 --- /dev/null +++ b/samples/drivers/lora/receive/src/main.c @@ -0,0 +1,56 @@ +/* + * Copyright (c) 2019 Manivannan Sadhasivam + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include +#include +#include +#include +#include + +#define MAX_DATA_LEN 255 + +#define LOG_LEVEL CONFIG_LOG_DEFAULT_LEVEL +#include +LOG_MODULE_REGISTER(lora_receive); + +void main(void) +{ + struct device *lora_dev; + struct lora_modem_config config; + int ret, len; + u8_t data[MAX_DATA_LEN] = {0}; + + lora_dev = device_get_binding(DT_INST_0_SEMTECH_SX1276_LABEL); + if (!lora_dev) { + LOG_ERR("%s Device not found", DT_INST_0_SEMTECH_SX1276_LABEL); + return; + } + + config.frequency = 865100000; + config.bandwidth = BW_125_KHZ; + config.datarate = SF_10; + config.preamble_len = 8; + config.coding_rate = CR_4_5; + config.tx_power = 14; + config.tx = false; + + ret = lora_config(lora_dev, &config); + if (ret < 0) { + LOG_ERR("LoRa config failed"); + return; + } + + while (1) { + /* Block until data arrives */ + len = lora_recv(lora_dev, data, MAX_DATA_LEN, K_FOREVER); + if (len < 0) { + LOG_ERR("LoRa receive failed"); + return; + } + + LOG_INF("Received data: %s", log_strdup(data)); + } +} From 4dac3aba72cae9d2e5af0a14ded5be23608f18ff Mon Sep 17 00:00:00 2001 From: Manivannan Sadhasivam Date: Mon, 22 Jul 2019 20:42:47 +0530 Subject: [PATCH 07/10] CODEOWNERS: Add entry for LoRa support Add CODEOWNERS entry for LoRa API, drivers and samples. Signed-off-by: Manivannan Sadhasivam --- CODEOWNERS | 3 +++ 1 file changed, 3 insertions(+) diff --git a/CODEOWNERS b/CODEOWNERS index a54bbc7ecff9be..431b87a22f63b5 100644 --- a/CODEOWNERS +++ b/CODEOWNERS @@ -147,6 +147,7 @@ /drivers/ipm/ipm_stm32_ipcc.c @arnopo /drivers/led/ @Mani-Sadhasivam /drivers/led_strip/ @mbolivar +/drivers/lora/ @Mani-Sadhasivam /drivers/modem/ @mike-scott /drivers/pcie/ @andrewboie /drivers/pinmux/stm32/ @rsalveti @idlethread @@ -241,6 +242,7 @@ /include/drivers/led_strip.h @mbolivar /include/drivers/sensor.h @MaureenHelm /include/drivers/spi.h @tbursztyka +/include/drivers/lora.h @Mani-Sadhasivam /include/app_memory/ @andrewboie /include/arch/arc/ @vonhust @ruuddw /include/arch/arc/arch.h @andrewboie @@ -305,6 +307,7 @@ /samples/display/ @vanwinkeljan /samples/drivers/CAN/ @alexanderwachter /samples/drivers/ht16k33/ @henrikbrixandersen +/samples/drivers/lora/ @Mani-Sadhasivam /samples/gui/ @vanwinkeljan /samples/net/ @jukkar @tbursztyka @pfalcon /samples/net/dns_resolve/ @jukkar @tbursztyka @pfalcon From 53ed26bb695fb27df5093921a38a7fa52c823352 Mon Sep 17 00:00:00 2001 From: Manivannan Sadhasivam Date: Sat, 7 Sep 2019 14:57:59 +0530 Subject: [PATCH 08/10] modules: Add LoRaMac Stack and drivers Add LoRaMac module support for building the LoRaWAN stack and LoRa drivers provided by Semtech. Signed-off-by: Manivannan Sadhasivam --- modules/Kconfig.loramac-node | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) create mode 100644 modules/Kconfig.loramac-node diff --git a/modules/Kconfig.loramac-node b/modules/Kconfig.loramac-node new file mode 100644 index 00000000000000..9d54080d62a532 --- /dev/null +++ b/modules/Kconfig.loramac-node @@ -0,0 +1,21 @@ +# +# Copyright (c) 2019 Manivannan Sadhasivam +# +# SPDX-License-Identifier: Apache-2.0 +# + +config HAS_SEMTECH_LORAMAC + bool "Semtech LoRaMac Stack" + help + This option enables the use of Semtech's LoRaMac stack + +config HAS_SEMTECH_RADIO_DRIVERS + bool "Semtech LoRa Radio Drivers" + help + This option enables the use of Semtech's Radio drivers + +if HAS_SEMTECH_RADIO_DRIVERS + +config HAS_SEMTECH_SX1276 + bool +endif From 27824f1e3df71f5d69d09c440042a3ac9560b312 Mon Sep 17 00:00:00 2001 From: Manivannan Sadhasivam Date: Sat, 7 Sep 2019 14:57:39 +0530 Subject: [PATCH 09/10] west: Add LoRaMac-node module Add LoRaMac-node module support to make use of Semtech LoRaWAN stack and LoRa drivers. Signed-off-by: Manivannan Sadhasivam --- west.yml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/west.yml b/west.yml index b638ab79446e25..7ff03a0b51b4ba 100644 --- a/west.yml +++ b/west.yml @@ -91,6 +91,9 @@ manifest: - name: open-amp revision: 9b591b289e1f37339bd038b5a1f0e6c8ad39c63a path: modules/lib/open-amp + - name: loramac-node + revision: 29e516ec585b1a909af2b5f1c60d83e7d4d563e3 + path: modules/lib/loramac-node - name: openthread revision: 05aaccc6e0db0fe17ac4beed2a2aacc9a9af167c path: modules/lib/openthread From 3092d57995b0d3a752de6532b103cb313068cdcf Mon Sep 17 00:00:00 2001 From: Manivannan Sadhasivam Date: Wed, 6 Nov 2019 20:53:08 +0530 Subject: [PATCH 10/10] boards: arm: 96b_wistrio: Use STM32_OSPEEDR_VERY_HIGH_SPEED for SPI1_SCK Add Add STM32_OSPEEDR_VERY_HIGH_SPEED flag for SPI1_SCK to function properly. This is needed for the proper communication with the LoRa modem. Without this flag, the received data is mangled when burst read is performed. Signed-off-by: Manivannan Sadhasivam --- boards/arm/96b_wistrio/pinmux.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/boards/arm/96b_wistrio/pinmux.c b/boards/arm/96b_wistrio/pinmux.c index 3281178a99df55..de8c34cb07ce42 100644 --- a/boards/arm/96b_wistrio/pinmux.c +++ b/boards/arm/96b_wistrio/pinmux.c @@ -27,7 +27,8 @@ static const struct pin_config pinconf[] = { {STM32_PIN_PB9, STM32L1X_PINMUX_FUNC_PB9_I2C1_SDA}, #endif /* CONFIG_I2C_1 */ #ifdef CONFIG_SPI_1 - {STM32_PIN_PA5, STM32L1X_PINMUX_FUNC_PA5_SPI1_SCK}, + {STM32_PIN_PA5, STM32L1X_PINMUX_FUNC_PA5_SPI1_SCK | + STM32_OSPEEDR_VERY_HIGH_SPEED}, {STM32_PIN_PA6, STM32L1X_PINMUX_FUNC_PA6_SPI1_MISO}, {STM32_PIN_PA7, STM32L1X_PINMUX_FUNC_PA7_SPI1_MOSI}, #endif /* CONFIG_SPI_1 */