diff --git a/README.md b/README.md index ad1f611..00446e6 100644 --- a/README.md +++ b/README.md @@ -9,6 +9,21 @@ targeted to RPi and Dragino LoRA/GPS HAT. The goal was to keep the LMIC 1.6 sourcecode untouched, and just provide a Hardware Abstraction Layer (HAL) for Raspberry Pi and Dragino LoRa/GPS HAT. +## Installation + +### WiringPi +To control the RPi's GPI ports, the WiringPi GPIO interface library has to +be installed. On some operating systems WiringPi is already installed per +default. For instructions on manual installation please refer to the +following site: +http://wiringpi.com/download-and-install/ + +### Enable SPI interface +Per default, the SPI ports on the Raspberry Pi are disabled. You need to +manually enable them using raspi-config. +Follow the instructions given here: +https://www.raspberrypi.org/documentation/hardware/raspberrypi/spi/README.md + ## Note on LMIC 1.6 license Text copied from https://www.research.ibm.com/labs/zurich/ics/lrsc/lmic.html @@ -16,4 +31,15 @@ IBM "LoRa WAN in C" is the LoRa WAN implementation of choice, and a perfect match to the IBM LRSC on the end device. It is provided as open source under the BSD License. +## Example "hello" +Directory: /examples/hello +Modifications neccessary: None + +This example does not use radio, it just periodically logs a counter value. +Can be used to checked if the timer implemenation on RPi works as expected. + + cd examples/hello + make clean + make + sudo ./build/hello.out diff --git a/examples/hello/build/aes.o b/examples/hello/build/aes.o new file mode 100644 index 0000000..b1a2eda Binary files /dev/null and b/examples/hello/build/aes.o differ diff --git a/examples/hello/build/debug.o b/examples/hello/build/debug.o new file mode 100644 index 0000000..fd91ff2 Binary files /dev/null and b/examples/hello/build/debug.o differ diff --git a/examples/hello/build/gpio.o b/examples/hello/build/gpio.o new file mode 100644 index 0000000..c81cbf8 Binary files /dev/null and b/examples/hello/build/gpio.o differ diff --git a/examples/hello/build/hal.o b/examples/hello/build/hal.o new file mode 100644 index 0000000..657dc44 Binary files /dev/null and b/examples/hello/build/hal.o differ diff --git a/examples/hello/build/hello.out b/examples/hello/build/hello.out new file mode 100755 index 0000000..0607208 Binary files /dev/null and b/examples/hello/build/hello.out differ diff --git a/examples/hello/build/lmic.o b/examples/hello/build/lmic.o new file mode 100644 index 0000000..2844d18 Binary files /dev/null and b/examples/hello/build/lmic.o differ diff --git a/examples/hello/build/main.o b/examples/hello/build/main.o new file mode 100644 index 0000000..d345b10 Binary files /dev/null and b/examples/hello/build/main.o differ diff --git a/examples/hello/build/oslmic.o b/examples/hello/build/oslmic.o new file mode 100644 index 0000000..952c670 Binary files /dev/null and b/examples/hello/build/oslmic.o differ diff --git a/examples/hello/build/radio.o b/examples/hello/build/radio.o new file mode 100644 index 0000000..f11893c Binary files /dev/null and b/examples/hello/build/radio.o differ diff --git a/examples/projects.gmk b/examples/projects.gmk index 56288ef..8fecfb9 100644 --- a/examples/projects.gmk +++ b/examples/projects.gmk @@ -1,89 +1,25 @@ -# SELECT TOOLCHAIN GNU/IAR/KEIL -TOOLCHAIN = keil - -# EDIT CONFIGURATIONS BELOW TO REFLECT COMPILER INSTALL DIR AND CMSIS INCLUDE DIR - -# IAR TOOLCHAIN -ifeq (${TOOLCHAIN}, iar) -IAR = C:/PROGRA~2/IARSYS~1/EMBEDD~1.5_2/arm -INC = ${IAR}/CMSIS/Include -CC = ${IAR}/bin/iccarm -AS = ${IAR}/bin/iasmarm -LN = ${IAR}/bin/ilinkarm -HEX = ${IAR}/bin/ielftool --ihex -BIN = ${IAR}/bin/ielftool --bin - -CCOPTS = --cpu=Cortex-M3 --endian=little --diag_suppress Pa050,Pa089,Pe066 -ASOPTS = --cpu Cortex-M3 -LNOPTS = --semihosting --config ${IAR}/config/linker/ST/STM32L152xB.icf -endif - -# KEIL TOOLCHAIN -ifeq (${TOOLCHAIN}, keil) -KEIL = C:/Keil_v5 -INC = ${KEIL}/ARM/Pack/ARM/CMSIS/4.1.0/CMSIS/Include -CC = ${KEIL}/ARM/ARMCC/bin/armcc.exe -AS = ${KEIL}/ARM/ARMCC/bin/armasm.exe -LN = ${KEIL}/ARM/ARMCC/bin/armlink.exe -HEX = ${KEIL}/ARM/ARMCC/bin/fromelf.exe --i32 -BIN = ${KEIL}/ARM/ARMCC/bin/fromelf.exe --bin - -CCOPTS = --cpu=Cortex-M3 -c --c99 -D__MICROLIB --apcs=interwork --split_sections -ASOPTS = --cpu Cortex-M3 --pd "__MICROLIB SETA 1" -LNOPTS = --library_type=microlib --ro-base 0x08000000 --entry 0x08000000 --rw-base 0x20000000 --entry Reset_Handler --first __Vectors --strict --summary_stderr --info summarysizes -HEXOPTS = --output -endif - -# GNU TOOLCHAIN -ifeq (${TOOLCHAIN}, gnu) -GNU = /opt/arm-gnu-toolchain-4.9.3.475/arm-none-eabi -CC = ${GNU}/bin/arm-none-eabi-gcc -AS = ${GNU}/bin/arm-none-eabi-as -LN = ${GNU}/bin/arm-none-eabi-gcc -HEX = ${GNU}/bin/arm-none-eabi-objcopy -O ihex -BIN = ${GNU}/bin/arm-none-eabi-objcopy -O binary - -# OpenOCD -OPENOCD := /opt/openocd-0.9.0/bin/openocd - -CMSIS_INC = ../../stm32/CMSIS/Include -define CMSIS_MSG -ERROR: CMSIS Library missing: $(CMSIS_INC) -## CMSIS: Cortex Microcontroller Software Interface Standard -## CMSIS Library can be obtained from the STM32L1xx standard peripherals library -## Download URL: www.st.com/web/catalog/tools/FM147/CL1794/SC961/SS1743/PF257913 -endef -ifeq (,$(wildcard $(CMSIS_INC))) -$(error $(CMSIS_MSG)) -endif - -LINKER_SCRIPT = ../../stm32/STM32L152VB_FLASH.ld -define LNK_SCRIPT_MSG -ERROR: Linker Script missing: $(LINKER_SCRIPT) -## Linker Script can be obtained from the STM32L1xx standard peripherals library -## Download URL: www.st.com/web/catalog/tools/FM147/CL1794/SC961/SS1743/PF257913 -endef -ifeq (,$(wildcard $(LINKER_SCRIPT))) -$(error $(LNK_SCRIPT_MSG)) -endif - -INC = $(CMSIS_INC) - -CPU = -mcpu=cortex-m3 -mthumb -CCOPTS = $(CPU) -c -std=gnu99 -CCOPTS += -fno-common -fmessage-length=0 -fno-builtin -fno-exceptions -ffunction-sections -fdata-sections -fomit-frame-pointer -MMD -MP -ASOPTS = $(CPU) -LNOPTS = $(CPU) -Wl,--gc-sections -T$(LINKER_SCRIPT) -endif +# +# 2017-04-12 Wolfgang Klenk +# +# Adapted for use on Raspberry Pi and Dragino LoRa/GPS HAT +# working in EU868 MHz Band # LMIC CONFIG -LMICCFG += -DSTM32L1XX_MD -DCFG_DEBUG -DCFG_eu868 -DCFG_wimod_board -DCFG_sx1272_radio -DCFG_lmic_clib +LMICCFG += -DCFG_DEBUG -DCFG_eu868 -DCFG_sx1276_radio -DDEBUG_LMIC -DDEBUG_HAL + +CCOPTS = -c -std=gnu99 + +LNOPTS = -lwiringPi +INC = . +CC = gcc +LN = gcc LMICDIR = ../../lmic -HALDIR = ../../stm32 +HALDIR = ../../lora_gps_hat TOOLSDIR = ../../tools BUILDDIR = build + # RULES SRCS = $(notdir $(wildcard ${LMICDIR}/*.c ${HALDIR}/*.c ${HALDIR}/*_${TOOLCHAIN}.s *.c)) OBJS = $(patsubst %, ${BUILDDIR}/%.o, $(basename ${SRCS})) @@ -99,20 +35,13 @@ ${BUILDDIR}/%.o: %.s | ${BUILDDIR} ${BUILDDIR}/%.out: ${OBJS} ${LN} ${LNOPTS} -o $@ $^ -${BUILDDIR}/%.hex: ${BUILDDIR}/%.out - ${HEX} $< ${HEXOPTS} $@ -${BUILDDIR}/%.bin: ${BUILDDIR}/%.out - ${BIN} $< ${HEXOPTS} $@ - -all: ${BUILDDIR}/$(notdir ${CURDIR}).bin ${BUILDDIR}/$(notdir ${CURDIR}).hex +#all: ${BUILDDIR}/$(notdir ${CURDIR}).out ${BUILDDIR}/$(notdir ${CURDIR}).bin ${BUILDDIR}/$(notdir ${CURDIR}).hex +all: ${BUILDDIR}/$(notdir ${CURDIR}).out clean: rm -rf ${BUILDDIR} Debug RTE settings *.dep *.bak *.sfr *.map *.uvguix.* -load: ${BUILDDIR}/$(notdir ${CURDIR}).bin - $(OPENOCD) -f $(TOOLSDIR)/openocd/wimod.cfg -f $(TOOLSDIR)/openocd/flash.cfg -c "flash_binary $<" - ${BUILDDIR}: mkdir $@ diff --git a/examples/projects.gmk.lmic_1.6_original b/examples/projects.gmk.lmic_1.6_original new file mode 100644 index 0000000..56288ef --- /dev/null +++ b/examples/projects.gmk.lmic_1.6_original @@ -0,0 +1,121 @@ +# SELECT TOOLCHAIN GNU/IAR/KEIL +TOOLCHAIN = keil + +# EDIT CONFIGURATIONS BELOW TO REFLECT COMPILER INSTALL DIR AND CMSIS INCLUDE DIR + +# IAR TOOLCHAIN +ifeq (${TOOLCHAIN}, iar) +IAR = C:/PROGRA~2/IARSYS~1/EMBEDD~1.5_2/arm +INC = ${IAR}/CMSIS/Include +CC = ${IAR}/bin/iccarm +AS = ${IAR}/bin/iasmarm +LN = ${IAR}/bin/ilinkarm +HEX = ${IAR}/bin/ielftool --ihex +BIN = ${IAR}/bin/ielftool --bin + +CCOPTS = --cpu=Cortex-M3 --endian=little --diag_suppress Pa050,Pa089,Pe066 +ASOPTS = --cpu Cortex-M3 +LNOPTS = --semihosting --config ${IAR}/config/linker/ST/STM32L152xB.icf +endif + +# KEIL TOOLCHAIN +ifeq (${TOOLCHAIN}, keil) +KEIL = C:/Keil_v5 +INC = ${KEIL}/ARM/Pack/ARM/CMSIS/4.1.0/CMSIS/Include +CC = ${KEIL}/ARM/ARMCC/bin/armcc.exe +AS = ${KEIL}/ARM/ARMCC/bin/armasm.exe +LN = ${KEIL}/ARM/ARMCC/bin/armlink.exe +HEX = ${KEIL}/ARM/ARMCC/bin/fromelf.exe --i32 +BIN = ${KEIL}/ARM/ARMCC/bin/fromelf.exe --bin + +CCOPTS = --cpu=Cortex-M3 -c --c99 -D__MICROLIB --apcs=interwork --split_sections +ASOPTS = --cpu Cortex-M3 --pd "__MICROLIB SETA 1" +LNOPTS = --library_type=microlib --ro-base 0x08000000 --entry 0x08000000 --rw-base 0x20000000 --entry Reset_Handler --first __Vectors --strict --summary_stderr --info summarysizes +HEXOPTS = --output +endif + +# GNU TOOLCHAIN +ifeq (${TOOLCHAIN}, gnu) +GNU = /opt/arm-gnu-toolchain-4.9.3.475/arm-none-eabi +CC = ${GNU}/bin/arm-none-eabi-gcc +AS = ${GNU}/bin/arm-none-eabi-as +LN = ${GNU}/bin/arm-none-eabi-gcc +HEX = ${GNU}/bin/arm-none-eabi-objcopy -O ihex +BIN = ${GNU}/bin/arm-none-eabi-objcopy -O binary + +# OpenOCD +OPENOCD := /opt/openocd-0.9.0/bin/openocd + +CMSIS_INC = ../../stm32/CMSIS/Include +define CMSIS_MSG +ERROR: CMSIS Library missing: $(CMSIS_INC) +## CMSIS: Cortex Microcontroller Software Interface Standard +## CMSIS Library can be obtained from the STM32L1xx standard peripherals library +## Download URL: www.st.com/web/catalog/tools/FM147/CL1794/SC961/SS1743/PF257913 +endef +ifeq (,$(wildcard $(CMSIS_INC))) +$(error $(CMSIS_MSG)) +endif + +LINKER_SCRIPT = ../../stm32/STM32L152VB_FLASH.ld +define LNK_SCRIPT_MSG +ERROR: Linker Script missing: $(LINKER_SCRIPT) +## Linker Script can be obtained from the STM32L1xx standard peripherals library +## Download URL: www.st.com/web/catalog/tools/FM147/CL1794/SC961/SS1743/PF257913 +endef +ifeq (,$(wildcard $(LINKER_SCRIPT))) +$(error $(LNK_SCRIPT_MSG)) +endif + +INC = $(CMSIS_INC) + +CPU = -mcpu=cortex-m3 -mthumb +CCOPTS = $(CPU) -c -std=gnu99 +CCOPTS += -fno-common -fmessage-length=0 -fno-builtin -fno-exceptions -ffunction-sections -fdata-sections -fomit-frame-pointer -MMD -MP +ASOPTS = $(CPU) +LNOPTS = $(CPU) -Wl,--gc-sections -T$(LINKER_SCRIPT) +endif + +# LMIC CONFIG +LMICCFG += -DSTM32L1XX_MD -DCFG_DEBUG -DCFG_eu868 -DCFG_wimod_board -DCFG_sx1272_radio -DCFG_lmic_clib + +LMICDIR = ../../lmic +HALDIR = ../../stm32 +TOOLSDIR = ../../tools +BUILDDIR = build + +# RULES +SRCS = $(notdir $(wildcard ${LMICDIR}/*.c ${HALDIR}/*.c ${HALDIR}/*_${TOOLCHAIN}.s *.c)) +OBJS = $(patsubst %, ${BUILDDIR}/%.o, $(basename ${SRCS})) + +VPATH = ${LMICDIR} ${HALDIR} . + +${BUILDDIR}/%.o: %.c | ${BUILDDIR} + ${CC} ${CCOPTS} ${LMICCFG} -I${INC} -I${LMICDIR} -I${HALDIR} $< -o$@ + +${BUILDDIR}/%.o: %.s | ${BUILDDIR} + ${AS} ${ASOPTS} -I${INC} $< -o $@ + +${BUILDDIR}/%.out: ${OBJS} + ${LN} ${LNOPTS} -o $@ $^ + +${BUILDDIR}/%.hex: ${BUILDDIR}/%.out + ${HEX} $< ${HEXOPTS} $@ + +${BUILDDIR}/%.bin: ${BUILDDIR}/%.out + ${BIN} $< ${HEXOPTS} $@ + +all: ${BUILDDIR}/$(notdir ${CURDIR}).bin ${BUILDDIR}/$(notdir ${CURDIR}).hex + +clean: + rm -rf ${BUILDDIR} Debug RTE settings *.dep *.bak *.sfr *.map *.uvguix.* + +load: ${BUILDDIR}/$(notdir ${CURDIR}).bin + $(OPENOCD) -f $(TOOLSDIR)/openocd/wimod.cfg -f $(TOOLSDIR)/openocd/flash.cfg -c "flash_binary $<" + +${BUILDDIR}: + mkdir $@ + +.PHONY: all clean + +.SECONDARY: diff --git a/lora_gps_hat/debug.c b/lora_gps_hat/debug.c new file mode 100644 index 0000000..ac220c4 --- /dev/null +++ b/lora_gps_hat/debug.c @@ -0,0 +1,82 @@ +// +// BSD 3-Clause License +// +// Hardware Abstraction Layer (HAL) targeted to Raspberry Pi and +// Dragino LoRa/GPS HAT +// +// Copyright (c) 2017, Wolfgang Klenk +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, this +// list of conditions and the following disclaimer. +// +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * Neither the name of the copyright holder nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +#include +#include + +#include "lmic.h" +#include "debug.h" + +void debug_init () { + fprintf(stdout, "%09d Debug: Initializing\n", osticks2ms(hal_ticks())); +} + +void debug_str (const char* str) { + fprintf(stdout, "%09d Debug: %s\n", osticks2ms(hal_ticks()), str); +} + +void debug_val (const char* label, u4_t val) { + fprintf(stdout, "%09d Debug: Label '%s' value 0x%x\n", osticks2ms(hal_ticks()), label, val); +} + +void debug_led (int val) { + // fprintf(stdout, "Debug: Set LED to 0x%02x\n", val); +} + +void debug_event (int ev) { + static const char* evnames[] = { + [EV_SCAN_TIMEOUT] = "SCAN_TIMEOUT", + [EV_BEACON_FOUND] = "BEACON_FOUND", + [EV_BEACON_MISSED] = "BEACON_MISSED", + [EV_BEACON_TRACKED] = "BEACON_TRACKED", + [EV_JOINING] = "JOINING", + [EV_JOINED] = "JOINED", + [EV_RFU1] = "RFU1", + [EV_JOIN_FAILED] = "JOIN_FAILED", + [EV_REJOIN_FAILED] = "REJOIN_FAILED", + [EV_TXCOMPLETE] = "TXCOMPLETE", + [EV_LOST_TSYNC] = "LOST_TSYNC", + [EV_RESET] = "RESET", + [EV_RXCOMPLETE] = "RXCOMPLETE", + [EV_LINK_DEAD] = "LINK_DEAD", + [EV_LINK_ALIVE] = "LINK_ALIVE", + [EV_SCAN_FOUND] = "SCAN_FOUND", + [EV_TXSTART] = "EV_TXSTART", + }; + debug_str((ev < sizeof(evnames)/sizeof(evnames[0])) ? evnames[ev] : "EV_UNKNOWN" ); +} + +void debug_buf (const u1_t* buf, int len) { + fprintf(stdout, "%09d Debug: Buffer received. length=%d\n", osticks2ms(hal_ticks()), len); +} diff --git a/lora_gps_hat/debug.h b/lora_gps_hat/debug.h new file mode 100644 index 0000000..e495be6 --- /dev/null +++ b/lora_gps_hat/debug.h @@ -0,0 +1,63 @@ +/* + * Copyright (c) 2014-2016 IBM Corporation. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the 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 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. + */ + +// intialize debug library +void debug_init (void); + +// set LED state +void debug_led (int val); + +// write character to USART +void debug_char (char c); + +// write byte as two hex digits to USART +void debug_hex (u1_t b); + +// write buffer as hex dump to USART +void debug_buf (const u1_t* buf, int len); + +// write 32-bit integer as eight hex digits to USART +void debug_uint (u4_t v); + +// write 32-bit integer as signed decimal digits to USART +void debug_int (s4_t v); + +// write nul-terminated string to USART +void debug_str (const char* str); + +// write LMiC event name to USART +void debug_event (int ev); + +// write label and 32-bit value as hex to USART +void debug_val (const char* label, u4_t val); + +// write label and 32-bit value as signed decimal to USART +void debug_valdec (const char* label, s4_t val); + +// convert integer 'val' to ASCII string (bin/oct/dec/hex/base36) +// store string at 'buf', return number of characters written +int debug_fmt (char* buf, int max, s4_t val, int base, int width, char pad); diff --git a/lora_gps_hat/gpio.c b/lora_gps_hat/gpio.c new file mode 100644 index 0000000..5685531 --- /dev/null +++ b/lora_gps_hat/gpio.c @@ -0,0 +1,200 @@ +// +// BSD 3-Clause License +// +// Hardware Abstraction Layer (HAL) targeted to Raspberry Pi and +// Dragino LoRa/GPS HAT +// +// Copyright (c) 2017, Wolfgang Klenk +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, this +// list of conditions and the following disclaimer. +// +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * Neither the name of the copyright holder nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "gpio.h" + +/** + * Ask the kernel to export control of a GPIO to userspace by writing its number to file + * /sys/class/gpio/export. + */ +void gpioExportPin(int pin) { + static const char* fn = "/sys/class/gpio/export"; + int fd = open(fn, O_WRONLY); + if(fd < 0) { + perror(fn); + exit(1); + } + + char str_pin[16]; + snprintf(str_pin, 16, "%d", pin); + + size_t rc = write(fd, str_pin, strlen(str_pin)); + if(rc != strlen(str_pin)) { + perror("exportPin"); + exit(1); + } + + close(fd); +} + +/** + * Reverses the effect of exporting a GPIO to userspace by writing its number to file + * /sys/class/gpio/unexport. + */ +void gpioUnexportPin(int pin) { + static const char* fn = "/sys/class/gpio/unexport"; + int fd = open(fn, O_WRONLY); + if(fd < 0) { + perror(fn); + exit(1); + } + + char str_pin[16]; + snprintf(str_pin, 16, "%d", pin); + + size_t rc = write(fd, str_pin, strlen(str_pin)); + if(rc != strlen(str_pin)) { + // perror("gpioUnexportPin"); + // exit(1); + } + + close(fd); +} + +/** + * Sets the direction of a GPIO pin. + * Reads as either "in" or "out". This value may normally be written. + * Writing as "out" defaults to initializing the value as low. + * To ensure glitch free operation, values "low" and "high" may be written to + * configure the GPIO as an output with that initial value. + */ +void gpioSetPinDirection(int pin, const char* direction) { + + const int BUFSIZE = 64; + char fn[BUFSIZE]; + snprintf(fn, BUFSIZE, "/sys/class/gpio/gpio%d/direction", pin); + int fd = open(fn, O_WRONLY); + if(fd < 0) { + perror(fn); + exit(1); + } + + size_t rc = write(fd, direction, strlen(direction)); + if(rc != strlen(direction)) { + perror("gpioSetPinDirection"); + exit(1); + } + + close(fd); +} + +/** + * Sets the signal edge(s) that will make poll(2) on the "value" file return. + * Reads as either "none", "rising", "falling", or "both". + * This file exists only if the pin can be configured as an interrupt generating input pin. + */ +void gpioSetPinEdge(int pin, void* edge) { + + const int BUFSIZE = 64; + char fn[BUFSIZE]; + snprintf(fn, BUFSIZE, "/sys/class/gpio/gpio%d/edge", pin); + int fd = open(fn, O_WRONLY); + if(fd < 0) { + perror(fn); + exit(EXIT_FAILURE); + } + + size_t rc = write(fd, edge, strlen(edge)); + if(rc != strlen(edge)) { + perror("setPinEdge"); + exit(EXIT_FAILURE); + } + + + close(fd); +} + +int gpioWaitForInterrupt(const int *pins, size_t npins, int timeout_ms) { + + struct pollfd pl[npins]; + + const int BUFSIZE = 64; + char fn[BUFSIZE]; + + for (int i=0 ; i 0) { + rc |= (1< +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "lmic.h" +#include "gpio.h" + +// Note: WiringPi Pin Numbering Schema +const int WIRING_PI_PIN_NSS = 6; +const int WIRING_PI_PIN_RST = 0; +const int WIRING_PI_PIN_DIO[3] = { 7, 4, 5 }; + +// Note: BCM Pin Numbering Schema +const int BCM_PIN_DIO[3] = { 4, 23, 24 }; + +// Local function prototypes +void hal_time_init(); +void timespec_diff(struct timespec *start, struct timespec *stop, struct timespec *result); + +// Used to store the current time +static struct timespec ts_start; + +static s4_t sleep_interval_ms = 0; + +void hal_init () { + hal_time_init(); + +#ifdef DEBUG_HAL + fprintf(stdout, "%09d HAL: Initializing ...\n", osticks2ms(hal_ticks())); +#endif + + wiringPiSetup(); + + // Pin Direction + pinMode(WIRING_PI_PIN_NSS, OUTPUT); + pinMode(WIRING_PI_PIN_RST, INPUT); + + // WiringPi is missing a feature to _blocking_ wait for pins change + // their values using the OS system call "poll". For this reason, we + // needed to implement it on our own. + for (int i=0 ; i<3 ; i++) { + gpioUnexportPin(BCM_PIN_DIO[i]); + } + + for (int i=0 ; i<3 ; i++) { + gpioExportPin(BCM_PIN_DIO[i]); + gpioSetPinDirection(BCM_PIN_DIO[i], GPIO_DIRECTION_IN); + gpioSetPinEdge(BCM_PIN_DIO[i], GPIO_EDGE_RISING); + } + + int rc = wiringPiSPISetup(0, 10000000); + if (rc < 0) { + fprintf(stderr, "HAL: Initialization of SPI failed: %s\n", strerror(errno)); + hal_failed(); + } + +} + +void hal_failed () { + fprintf(stderr, "%09d HAL: Failed. Aborting.\n", osticks2ms(hal_ticks())); + for (int i=0 ; i<3 ; i++) { + gpioUnexportPin(BCM_PIN_DIO[i]); + } + exit(EXIT_FAILURE); +} + +// set radio NSS pin to given value +void hal_pin_nss (u1_t val) { + digitalWrite(WIRING_PI_PIN_NSS, val==0 ? LOW : HIGH); +} + +// switch between radio RX/TX +void hal_pin_rxtx (u1_t val) { +#ifdef DEBUG_HAL + val > 0 ? fprintf(stdout, "%09d HAL: Sending ...\n", osticks2ms(hal_ticks()), val) : fprintf(stdout, "%09d HAL: Receiving ...\n", osticks2ms(hal_ticks()), val); +#endif + + // Nothing to do. There is no such pin in the Lora/GPS HAT module. +} + +// set radio RST pin to given value (or keep floating!) +void hal_pin_rst (u1_t val) { +#ifdef DEBUG_HAL + fprintf(stdout, "%09d HAL: Set radio RST pin to 0x%02x\n", osticks2ms(hal_ticks()), val); +#endif + + if(val == 0 || val == 1) { // drive pin + pinMode(WIRING_PI_PIN_RST, OUTPUT); + digitalWrite(WIRING_PI_PIN_RST, val==0 ? LOW : HIGH); + } else { // keep pin floating + pinMode(WIRING_PI_PIN_RST, INPUT); + } +} + +// perform 8-bit SPI transaction. +// write given byte outval to radio, read byte from radio and return value. +u1_t hal_spi (u1_t out) { + static u1_t isAddress = 0x01; + static u1_t address = 0x00; + u1_t value = out; + + if (isAddress) { + address = out; + } + + u1_t rc = wiringPiSPIDataRW(0, &out, 1); + if (rc < 0) { + fprintf(stderr, "HAL: Cannot send data on SPI: %s\n", strerror(errno)); + hal_failed(); + } + +/* + if (!isAddress && (address != 0x2c)) { + if (address & 0x80) { + fprintf(stdout, "%09d HAL: SPI write to address 0x%02x value 0x%02x\n", osticks2ms(hal_ticks()), address & 0x7F, value); + fprintf(stdout, " writeReg(0x%02x, 0x%02x);\n", address & 0x7F, value); + } else { + fprintf(stdout, "%09d HAL: SPI read from address 0x%02x value 0x%02x\n", osticks2ms(hal_ticks()), address, out); + } + } +*/ + + isAddress = !isAddress; + + return out; +} + +void hal_disableIRQs () { +} + +void hal_enableIRQs () { +} + +// store current timer value of the system. +void hal_time_init() { + int rc = clock_gettime(CLOCK_MONOTONIC_RAW, &ts_start); + if (rc < 0) { + fprintf(stderr, "HAL: Cannot initialize timer: %s\n", strerror(errno)); + hal_failed(); + } +} + +// return 32 bit system time in ticks. +// OSTICKS_PER_SEC has to be defined, else the default 32768 is used. +// OSTICKS_PER_SEC must be in range [10000:64516]. One tick must be 15.5us .. 100us long. +u4_t hal_ticks () { + + struct timespec ts; + int rc = clock_gettime(CLOCK_MONOTONIC_RAW, &ts); + if (rc < 0) { + fprintf(stderr, "HAL: Cannot get current time: %s\n", strerror(errno)); + hal_failed(); + } + + struct timespec ts_diff; + timespec_diff(&ts_start, &ts, &ts_diff); + + ostime_t ticks_sec = sec2osticks(ts_diff.tv_sec); + ostime_t ticks_nsec = us2osticks(ts_diff.tv_nsec / 1000); + + u4_t ticks = ticks_sec + ticks_nsec; + + return ticks; +} + +// busy wait until timestamp (in ticks) is reached +void hal_waitUntil (u4_t target_ticks) { +#ifdef DEBUG_HAL + fprintf(stdout, "%09d HAL: Wait until %09d ms\n", osticks2ms(hal_ticks()), osticks2ms(target_ticks)); +#endif + + // TODO: Deal with tick counter overflow + + u4_t current_ticks = hal_ticks(); + s4_t diff_ticks = target_ticks - current_ticks; + + if (diff_ticks > 0) { + s4_t diff_us = osticks2us(diff_ticks); + usleep(diff_us); + } +} + +void timespec_diff(struct timespec *start, struct timespec *stop, struct timespec *result) +{ + if ((stop->tv_nsec - start->tv_nsec) < 0) { + result->tv_sec = stop->tv_sec - start->tv_sec - 1; + result->tv_nsec = stop->tv_nsec - start->tv_nsec + 1000000000; + } else { + result->tv_sec = stop->tv_sec - start->tv_sec; + result->tv_nsec = stop->tv_nsec - start->tv_nsec; + } +} + +// Used for scheduled jobs: +// If target time is reached, then 1 is returned and the scheduled job is executed. +// If 0 is returned, then control goes back into the LMIC main loop. +u1_t hal_checkTimer (u4_t target_ticks) { + + u4_t current_ticks = hal_ticks(); + s4_t diff_ticks = target_ticks - current_ticks; + s4_t diff_ms = osticks2ms(diff_ticks); + + if (diff_ticks <= 0) { // Reached target ticks + return 1; // Execute scheduled job + } else if (diff_ms < 21) { + // We have not reached the target ticks, but we also don't + // want to execute the scheduled job now. By returning 0 the code + // will continue looping in the LMIC main loop. + sleep_interval_ms = 0; + return 0; + } else { + sleep_interval_ms = diff_ms - 20; + assert(sleep_interval_ms > 0); + + // Use (diff_ms - 20) as timeout, to reduce the risk that the linux OS + // causes the timeout longer as desired. + // Let the code actively loop in the LMIC main loop until the final target time is reached. + + return 0; // Will cause a "sleep" in the LMIC main loop + } +} + +void hal_sleep () { + if (sleep_interval_ms > 0) { + int rc = gpioWaitForInterrupt(BCM_PIN_DIO, 3, sleep_interval_ms); + if(rc < 0) { + fprintf(stderr, "HAL: Cannot poll: %s\n", strerror(errno)); + hal_failed(); + } + + sleep_interval_ms = 0; + + if (rc > 0) { + if (rc & 0x01) radio_irq_handler(0); + if (rc & 0x02) radio_irq_handler(1); + if (rc & 0x04) radio_irq_handler(2); + } + } else { + // We need to check if one of the DIO ports where set to HIGH + // to signal an interrupt condition. + for (int i=0 ; i<3 ; i++) { + if (HIGH == digitalRead(WIRING_PI_PIN_DIO[i])) { + radio_irq_handler(i); + } + } + } +} +