Skip to content

Commit

Permalink
Merge pull request #571 from mcci-catena/issue568
Browse files Browse the repository at this point in the history
The primary purpose of this PR is to fix #524, allowing the LMIC to run without disabling interrupts at all, and without requiring any changes to underlying BSPs. When configured for interrupts, interrupts simply cause the current time stamp to be captured. The secondary ISR is run as part of os_runloop_once(). This should also fix #503, and address #528, #558, #548, and others.

In addition, since we're updating the radio driver, I addressed #524.

In testing, I discovered a subtle bug with one of our applications that uses LMIC_sendAlive() -- there was a path when sending piggybacked MAC data with a poll that would result in trying to take the port 0 path instead. This caused problems with ChirpStack and TTN, at least. (This is #570.)

Finally, updated to use Arduino IDE 1.8.12 in test.

Version of library changes to v3.1.0.20.
  • Loading branch information
terrillmoore authored May 12, 2020
2 parents 59df2fa + c2e1f64 commit 0e67c4e
Show file tree
Hide file tree
Showing 9 changed files with 175 additions and 63 deletions.
2 changes: 1 addition & 1 deletion .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ sudo: true

env:
global:
- IDE_VERSION=1.8.10
- IDE_VERSION=1.8.12
matrix:
- TARGET=samd
- TARGET=stm32l0
Expand Down
47 changes: 35 additions & 12 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,9 @@ requires C99 mode to be enabled by default.
- [LoRa Nexus by Ideetron](#lora-nexus-by-ideetron)
- [Example Sketches](#example-sketches)
- [Timing](#timing)
- [Controlling protocol timing](#controlling-protocol-timing)
- [`LMIC_setClockError()`](#lmic_setclockerror)
- [Interrupts and Arduino system timing](#interrupts-and-arduino-system-timing)
- [Downlink data rate](#downlink-data-rate)
- [Encoding Utilities](#encoding-utilities)
- [sflt16](#sflt16)
Expand Down Expand Up @@ -290,7 +292,7 @@ Configures the library for use with an sx1276 transceiver.

`#define LMIC_USE_INTERRUPTS`

If defined, configures the library to use interrupts for detecting events from the transceiver. If left undefined, the library will poll for events from the transceiver. See [Timing](#timing) for more info.
If defined, configures the library to use interrupts for detecting events from the transceiver. If left undefined, the library will poll for events from the transceiver. See [Timing](#timing) for more info. Be aware that interrupts are not tested or supported on many platforms.

### Disabling PING

Expand Down Expand Up @@ -812,32 +814,36 @@ This library provides several examples.
The library is
responsible for keeping track of time of certain network events, and scheduling
other events relative to those events. In particular, the library must note
other events relative to those events. For Class A uplink transmissions, the library must note
when a packet finishes transmitting, so it can open up the RX1 and RX2
receive windows at a fixed time after the end of transmission. The library does this
by watching for rising edges on the DIO0 output of the SX127x, and noting the time.
The library observes and processes rising edges on the pins as part of `os_runloop()` processing.
This can be configured in one of two ways (see
[Controlling use of interrupts](#controlling-use-of-interrupts)).
[Controlling use of interrupts](#controlling-use-of-interrupts)). See [Interrupts and Arduino system timing](#interrupts-and-arduino-system-timing) for implementation details.
By default, the routine `hal_io_check()`
By default, the library
polls the enabled pins to determine whether an event has occurred. This approach
allows use of any CPU pin to sense the DIOs, and makes no assumptions about
interrupts. However, it means that the end-of-transmit event is not observed
(and time-stamped) until `os_runloop()` is called.
(and time-stamped) until `os_runloop_once()` is called.
Optionally, you can configure the LMIC library to use interrupts. The
interrupt handlers capture the time of
the event. Actual processing is done the next time that `os_runloop()`
the event. Actual processing is done the next time that `os_runloop_once()`
is called, using the captured time. However, this requires that the
DIO pins be wired to Arduino pins that support rising-edge interrupts.
DIO pins be wired to Arduino pins that support rising-edge interrupts,
and it may require custom initialization code on your platform to
hook up the interrupts.
Fortunately, LoRa is a fairly slow protocol and the timing of the
receive windows is not super critical. To synchronize transmitter and
receiver, a preamble is first transmitted. Using LoRaWAN, this preamble
consists of 8 symbols, of which the receiver needs to see 4 symbols to
lock on. The current implementation tries to enable the receiver for 6
### Controlling protocol timing
The timing of end-of-transmit interrupts is used to determine when to open the downlink receive window. Because of the considerations above, some inaccuracy in the time stamp for the end-of-transmit interrupt is inevitable.
Fortunately, the timing of the receive windows at the device need not be extremely accurate; the LMIC has to turn on the receiver early enough to capture a downlink
from the gateway and must leave the receiver on long enough to compensate for timing
errors due to various inaccuracies. To make it easier for the device to catch downlinks, the gateway first transmits a preamble consisting of 8 symbols. The SX127x receiver needs to see at least 4 symbols to detect a message. The Arduino LMIC tries to enable the receiver for 6
symbol times slightly before the start of the receive window.
The HAL bases all timing on the Arduino `micros()` timer, which has a platform-specific
Expand Down Expand Up @@ -886,6 +892,20 @@ For a variety of reasons, the LMIC normally ignores clock errors greater than 40
This clock error is not reset by `LMIC_reset()`.
### Interrupts and Arduino system timing
The IBM LMIC used as the basis for this code disables interrupts while the radio driver is active, to prevent reentrancy via `radio_irq_handler()` at unexpected moments. It uses `os_getTime()`, and assumes that `os_getTime()` still works when interrupts were disabled. This causes problems on Arduino platforms. Most board support packages use interrupts to advance `millis()` and `micros()`, and with these BSPs, `millis()` and `micros()` return incorrect values while interrupts are disabled. Although some BSPs (like the ones provided by MCCI) provide real time correctly while interrupts are disabled, this is not portable. It's not practical to make such changes in every BSP.
To avoid this, the LMIC processes events in several steps; these steps ensure that `radio_irq_handler_v2()` is only called at predictable times.
1. If interrupts are enabled via `LMIC_USE_INTERRUPTS`, hardware interrupts catch the time of the interrupt and record that the interrupt occurred. These routines rely on hardware edge-sensitive interrupts. If your hardware interrupts are level-sensitive, you must mask the interrupt somehow at the ISR. You can't use SPI routines to talk to the radio, because this may leave the SPI system and the radio in undefined states. In this configuration, `hal_io_pollIRQs()` exists but is a no-op.
2. If interrupts are not enabled via `LMIC_USE_INTERRUPTS`, the digital I/O lines are polled every so often by calling the routine `hal_io_pollIRQs()`. This routine watches for edges on the relevant digital I/O lines, and records the time of transition.
3. The LMIC `os_runloop_once()` routine calls `hal_processPendingIRQs()`. This routine uses the timestamps captured by the hardware ISRs and `hal_io_pollIRQs()` to invoke `radio_irq_hander_v2()` with the appropriate information. `hal_processPendingIRQs()` in turn calls `hal_io_pollIRQs()` (in case interrupts are not configured).
4. For compatibility with older versions of the Arduino LMIC, `hal_enableIRQs()` also calls `hal_io_pollIRQs()` when enabling interrupts. However, it does not dispatch the interrupts to `radio_irq_handler_v2()`; this must be done by a subsequent call to `hal_processPendingIRQs()`.
## Downlink data rate
Note that the data rate used for downlink packets in the RX2 window varies by region. Consult your network's manual for any divergences from the LoRaWAN Regional Parameters. This library assumes that the network follows the regional default.
Expand Down Expand Up @@ -1195,6 +1215,9 @@ function uflt12f(rawUflt12)

- HEAD has the following changes:

- [#570](https://github.com/mcci-catena/arduino-lmic/issue/570) corrects handling of piggy-back MAC responses when sending an `LMIC_sendAlive()` (`OPMODE_POLL`) message.
- [#524](https://github.com/mcci-catena/arduino-lmic/issue/524) corrects handling of interrupt disable, and slightly refactors the low-level interrupt handling wrappers for clarity. With this change, `radio_irq_handler_v2()` is never called except from the run loop, and so the radio driver need not (and does not) disable interrupts. Version is v3.1.0.20.
- [#568](https://github.com/mcci-catena/arduino-lmic/issue/568) improves documentation for the radio driver.
- [#537](https://github.com/mcci-catena/arduino-lmic/pull/537) fixes a compile error in SX1272 support. (Thanks @ricaun.) Version is v3.1.0.10.

- v3.1.0 officially adopts the changes from v3.0.99. There were dozens of changes; check the GitHub issue logs and change logs. This was a breaking release (due to changes in data layout in the LMIC structure; the structure is accessed by apps).
Expand Down
68 changes: 49 additions & 19 deletions src/hal/hal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,75 +81,101 @@ s1_t hal_getRssiCal (void) {
return plmic_pins->rssi_cal;
}

//--------------------
// Interrupt handling
//--------------------
static constexpr unsigned NUM_DIO_INTERRUPT = 3;
static_assert(NUM_DIO_INTERRUPT <= NUM_DIO, "Number of interrupt-sensitive lines must be less than number of GPIOs");
static ostime_t interrupt_time[NUM_DIO_INTERRUPT] = {0};

#if !defined(LMIC_USE_INTERRUPTS)
static void hal_interrupt_init() {
pinMode(plmic_pins->dio[0], INPUT);
if (plmic_pins->dio[1] != LMIC_UNUSED_PIN)
pinMode(plmic_pins->dio[1], INPUT);
if (plmic_pins->dio[2] != LMIC_UNUSED_PIN)
pinMode(plmic_pins->dio[2], INPUT);
static_assert(NUM_DIO_INTERRUPT == 3, "Number of interrupt lines must be set to 3");
}

static bool dio_states[NUM_DIO] = {0};
static void hal_io_check() {
static bool dio_states[NUM_DIO_INTERRUPT] = {0};
void hal_pollPendingIRQs_helper() {
uint8_t i;
for (i = 0; i < NUM_DIO; ++i) {
for (i = 0; i < NUM_DIO_INTERRUPT; ++i) {
if (plmic_pins->dio[i] == LMIC_UNUSED_PIN)
continue;

if (dio_states[i] != digitalRead(plmic_pins->dio[i])) {
dio_states[i] = !dio_states[i];
if (dio_states[i])
radio_irq_handler(i);
if (dio_states[i] && interrupt_time[i] == 0) {
ostime_t const now = os_getTime();
interrupt_time[i] = now ? now : 1;
}
}
}
}

#else
// Interrupt handlers
static ostime_t interrupt_time[NUM_DIO] = {0};

static void hal_isrPin0() {
ostime_t now = os_getTime();
interrupt_time[0] = now ? now : 1;
if (interrupt_time[0] == 0) {
ostime_t now = os_getTime();
interrupt_time[0] = now ? now : 1;
}
}
static void hal_isrPin1() {
ostime_t now = os_getTime();
interrupt_time[1] = now ? now : 1;
if (interrupt_time[1] == 0) {
ostime_t now = os_getTime();
interrupt_time[1] = now ? now : 1;
}
}
static void hal_isrPin2() {
ostime_t now = os_getTime();
interrupt_time[2] = now ? now : 1;
if (interrupt_time[2] == 0) {
ostime_t now = os_getTime();
interrupt_time[2] = now ? now : 1;
}
}

typedef void (*isr_t)();
static isr_t interrupt_fns[NUM_DIO] = {hal_isrPin0, hal_isrPin1, hal_isrPin2};
static const isr_t interrupt_fns[NUM_DIO_INTERRUPT] = {hal_isrPin0, hal_isrPin1, hal_isrPin2};
static_assert(NUM_DIO_INTERRUPT == 3, "number of interrupts must be 3 for initializing interrupt_fns[]");

static void hal_interrupt_init() {
for (uint8_t i = 0; i < NUM_DIO; ++i) {
for (uint8_t i = 0; i < NUM_DIO_INTERRUPT; ++i) {
if (plmic_pins->dio[i] == LMIC_UNUSED_PIN)
continue;

pinMode(plmic_pins->dio[i], INPUT);
attachInterrupt(digitalPinToInterrupt(plmic_pins->dio[i]), interrupt_fns[i], RISING);
}
}
#endif // LMIC_USE_INTERRUPTS

static void hal_io_check() {
void hal_processPendingIRQs() {
uint8_t i;
for (i = 0; i < NUM_DIO; ++i) {
for (i = 0; i < NUM_DIO_INTERRUPT; ++i) {
ostime_t iTime;
if (plmic_pins->dio[i] == LMIC_UNUSED_PIN)
continue;

// NOTE(tmm@mcci.com): if using interrupts, this next step
// assumes uniprocessor and fairly strict memory ordering
// semantics relative to ISRs. It would be better to use
// interlocked-exchange, but that's really far beyond
// Arduino semantics. Because our ISRs use "first time
// stamp" semantics, we don't have a value-race. But if
// we were to disable ints here, we might observe a second
// edge that we'll otherwise miss. Not a problem in this
// use case, as the radio won't release IRQs until we
// explicitly clear them.
iTime = interrupt_time[i];
if (iTime) {
interrupt_time[i] = 0;
radio_irq_handler_v2(i, iTime);
}
}
}
#endif // LMIC_USE_INTERRUPTS

// -----------------------------------------------------------------------------
// SPI
Expand Down Expand Up @@ -319,15 +345,19 @@ void hal_enableIRQs () {
if(--irqlevel == 0) {
interrupts();

#if !defined(LMIC_USE_INTERRUPTS)
// Instead of using proper interrupts (which are a bit tricky
// and/or not available on all pins on AVR), just poll the pin
// values. Since os_runloop disables and re-enables interrupts,
// putting this here makes sure we check at least once every
// loop.
//
// As an additional bonus, this prevents the can of worms that
// we would otherwise get for running SPI transfers inside ISRs
hal_io_check();
// we would otherwise get for running SPI transfers inside ISRs.
// We merely collect the edges and timestamps here; we wait for
// a call to hal_processPendingIRQs() before dispatching.
hal_pollPendingIRQs_helper();
#endif /* !defined(LMIC_USE_INTERRUPTS) */
}
}

Expand Down
11 changes: 11 additions & 0 deletions src/lmic/hal.h
Original file line number Diff line number Diff line change
Expand Up @@ -169,6 +169,17 @@ uint8_t hal_getTxPowerPolicy(
u4_t freq
);

void hal_pollPendingIRQs_helper();
void hal_processPendingIRQs(void);

/// \brief check for any pending interrupts: stub if interrupts are enabled.
static void inline hal_pollPendingIRQs(void)
{
#if !defined(LMIC_USE_INTERRUPTS)
hal_pollPendingIRQs_helper();
#endif /* !defined(LMIC_USE_INTERRUPTS) */
}

#ifdef __cplusplus
} // extern "C"
#endif
Expand Down
16 changes: 13 additions & 3 deletions src/lmic/lmic.c
Original file line number Diff line number Diff line change
Expand Up @@ -889,10 +889,14 @@ scan_mac_cmds(
uint8_t cmd;

LMIC.pendMacLen = 0;
if (port == 0)
if (port == 0) {
// port zero: mac data is in the normal payload, and there can't be
// piggyback mac data.
LMIC.pendMacPiggyback = 0;
else
} else {
// port is either -1 (no port) or non-zero (piggyback): treat as piggyback.
LMIC.pendMacPiggyback = 1;
}

while( oidx < olen ) {
bit_t response_fit;
Expand Down Expand Up @@ -1861,7 +1865,8 @@ static bit_t buildDataFrame (void) {
// highest importance are the ones in the pendMac buffer.
int end = OFF_DAT_OPTS;

if (LMIC.pendTxPort != 0 && LMIC.pendMacPiggyback && LMIC.pendMacLen != 0) {
// Send piggyback data if: !txdata or txport != 0
if ((! txdata || LMIC.pendTxPort != 0) && LMIC.pendMacPiggyback && LMIC.pendMacLen != 0) {
os_copyMem(LMIC.frame + end, LMIC.pendMacData, LMIC.pendMacLen);
end += LMIC.pendMacLen;
}
Expand Down Expand Up @@ -2786,6 +2791,11 @@ void LMIC_reset (void) {
LMIC.adrEnabled = FCT_ADREN;
resetJoinParams();
LMIC.rxDelay = DELAY_DNW1;
// LMIC.pendMacLen = 0;
// LMIC.pendMacPiggyback = 0;
// LMIC.dn2Ans = 0;
// LMIC.macDlChannelAns = 0;
// LMIC.macRxTimingSetupAns = 0;
#if !defined(DISABLE_PING)
LMIC.ping.freq = FREQ_PING; // defaults for ping
LMIC.ping.dr = DR_PING; // ditto
Expand Down
4 changes: 2 additions & 2 deletions src/lmic/lmic.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* Copyright (c) 2016 Matthijs Kooijman.
* Copyright (c) 2016-2019 MCCI Corporation.
* Copyright (c) 2016-2020 MCCI Corporation.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
Expand Down Expand Up @@ -105,7 +105,7 @@ extern "C"{
#define ARDUINO_LMIC_VERSION_CALC(major, minor, patch, local) \
((((major)*UINT32_C(1)) << 24) | (((minor)*UINT32_C(1)) << 16) | (((patch)*UINT32_C(1)) << 8) | (((local)*UINT32_C(1)) << 0))

#define ARDUINO_LMIC_VERSION ARDUINO_LMIC_VERSION_CALC(3, 1, 0, 10) /* v3.1.0.10 */
#define ARDUINO_LMIC_VERSION ARDUINO_LMIC_VERSION_CALC(3, 1, 0, 20) /* v3.1.0.20 */

#define ARDUINO_LMIC_VERSION_GET_MAJOR(v) \
((((v)*UINT32_C(1)) >> 24u) & 0xFFu)
Expand Down
2 changes: 1 addition & 1 deletion src/lmic/lmic_compliance.c
Original file line number Diff line number Diff line change
Expand Up @@ -727,7 +727,7 @@ static void acSendUplink(void) {
__func__,
eSend,
(unsigned) downlink & 0xFFFF,
LMIC.client.txMessageCb
(unsigned) sizeof(payload)
);
LMIC_Compliance.eventflags |= LMIC_COMPLIANCE_EVENT_UPLINK_COMPLETE;
fsmEval();
Expand Down
2 changes: 2 additions & 0 deletions src/lmic/oslmic.c
Original file line number Diff line number Diff line change
Expand Up @@ -139,6 +139,8 @@ void os_runloop () {

void os_runloop_once() {
osjob_t* j = NULL;
hal_processPendingIRQs();

hal_disableIRQs();
// check for runnable jobs
if(OS.runnablejobs) {
Expand Down
Loading

0 comments on commit 0e67c4e

Please sign in to comment.