From e29477fa7e6a294d7bc088c3c66c4097b47c03a9 Mon Sep 17 00:00:00 2001
From: Manuel Bl <10954524+manuelbl@users.noreply.github.com>
Date: Wed, 1 Jan 2020 17:00:47 +0100
Subject: [PATCH] Update to latest LMIC version (3.0.99.10)

---
 Kconfig                                       |   4 +-
 src/esp_idf_lmic_config.h                     |   5 +-
 src/hal/hal_esp32.cpp                         |  10 +-
 src/hal/hal_esp32.h                           |   2 +-
 src/lmic/config.h                             |   8 +
 src/lmic/hal.h                                |   5 +-
 src/lmic/lmic.c                               | 231 +++++++++++-------
 src/lmic/lmic.h                               |  76 +++++-
 src/lmic/{lmic_au921.c => lmic_au915.c}       |  58 ++---
 src/lmic/lmic_bandplan.h                      |   7 +-
 ...bandplan_au921.h => lmic_bandplan_au915.h} |  40 +--
 src/lmic/lmic_config_preconditions.h          |  24 +-
 src/lmic/lmic_eu_like.c                       |   9 +-
 src/lmic/lmic_us_like.c                       |   2 +-
 src/lmic/lorabase.h                           |  49 ++--
 .../{lorabase_au921.h => lorabase_au915.h}    |  68 +++---
 src/lmic/oslmic.h                             |  18 +-
 src/lmic/radio.c                              | 118 +++++++--
 18 files changed, 485 insertions(+), 249 deletions(-)
 rename src/lmic/{lmic_au921.c => lmic_au915.c} (86%)
 rename src/lmic/{lmic_bandplan_au921.h => lmic_bandplan_au915.h} (68%)
 rename src/lmic/{lorabase_au921.h => lorabase_au915.h} (63%)

diff --git a/Kconfig b/Kconfig
index 1bd33af..06ce10b 100644
--- a/Kconfig
+++ b/Kconfig
@@ -16,8 +16,8 @@ config TTN_LORA_FREQ_EU_868
 config TTN_LORA_FREQ_US_915
     bool "North and South America (915 MHz)"
 
-config TTN_LORA_FREQ_AU_921
-    bool "Australia (921 MHz)"
+config TTN_LORA_FREQ_AU_915
+    bool "Australia (915 MHz)"
 
 config TTN_LORA_FREQ_AS_923
     bool "Asia (923 MHz)"
diff --git a/src/esp_idf_lmic_config.h b/src/esp_idf_lmic_config.h
index 7b08a13..d21a5fb 100755
--- a/src/esp_idf_lmic_config.h
+++ b/src/esp_idf_lmic_config.h
@@ -17,7 +17,10 @@
 #elif defined(CONFIG_TTN_LORA_FREQ_US_915)
 #define CFG_us915 1
 #elif defined(CONFIG_TTN_LORA_FREQ_AU_921)
-#define CFG_au921 1
+#   warning "CONFIG_TTN_LORA_FREQ_AU_921 was deprecated in favour of CONFIG_TTN_LORA_FREQ_AU_921. Support for CONFIG_TTN_LORA_FREQ_AU_921 will be removed in the future."
+#define CFG_au915 1
+#elif defined(CONFIG_TTN_LORA_FREQ_AU_915)
+#define CFG_au915 1
 #elif defined(CONFIG_TTN_LORA_FREQ_AS_923)
 #define CFG_as923 1
 #elif defined(CONFIG_TTN_LORA_FREQ_AS_923_JP)
diff --git a/src/hal/hal_esp32.cpp b/src/hal/hal_esp32.cpp
index 646bfbe..14f674c 100755
--- a/src/hal/hal_esp32.cpp
+++ b/src/hal/hal_esp32.cpp
@@ -342,18 +342,22 @@ u4_t hal_ticks()
 // Wait until the specified time.
 // Called if the LMIC code needs to wait for a precise time.
 // All other events are ignored and will be served later.
-void hal_waitUntil(u4_t time)
+u4_t hal_waitUntil(u4_t time)
 {
-    ttn_hal.waitUntil(time);
+    return ttn_hal.waitUntil(time);
 }
 
-void HAL_ESP32::waitUntil(uint32_t osTime)
+uint32_t HAL_ESP32::waitUntil(uint32_t osTime)
 {
     int64_t espNow = esp_timer_get_time();
     int64_t espTime = osTimeToEspTime(espNow, osTime);
     setNextAlarm(espTime);
     armTimer(espNow);
     wait(WAIT_FOR_TIMER);
+
+    u4_t osNow = hal_ticks();
+    u4_t diff = osNow - osTime;
+    return diff < 0x80000000U ? diff : 0;
 }
 
 // Called by client code to wake up LMIC to do something,
diff --git a/src/hal/hal_esp32.h b/src/hal/hal_esp32.h
index 955e1a2..2db6140 100644
--- a/src/hal/hal_esp32.h
+++ b/src/hal/hal_esp32.h
@@ -50,7 +50,7 @@ public:
     uint8_t checkTimer(uint32_t osTime);
     void sleep();
     
-    void waitUntil(uint32_t osTime);
+    uint32_t waitUntil(uint32_t osTime);
 
     spi_host_device_t spiHost;
     gpio_num_t pinNSS;
diff --git a/src/lmic/config.h b/src/lmic/config.h
index c50ad36..8673b46 100644
--- a/src/lmic/config.h
+++ b/src/lmic/config.h
@@ -204,4 +204,12 @@
 # define LMIC_LORAWAN_SPEC_VERSION	LMIC_LORAWAN_SPEC_VERSION_1_0_3
 #endif
 
+// LMIC_ENABLE_arbitrary_clock_error
+// We normally don't want to allow users to set wide clock errors, because
+// we assume reasonably-disciplined os_getTime() values. But... there might
+// be platforms that require wider errors.
+#if !defined(LMIC_ENABLE_arbitrary_clock_error)
+# define LMIC_ENABLE_arbitrary_clock_error 0	/* PARAM */
+#endif
+
 #endif // _lmic_config_h_
diff --git a/src/lmic/hal.h b/src/lmic/hal.h
index 00a6e58..ac09089 100644
--- a/src/lmic/hal.h
+++ b/src/lmic/hal.h
@@ -110,9 +110,10 @@ void hal_sleep (void);
 u4_t hal_ticks (void);
 
 /*
- * busy-wait until specified timestamp (in ticks) is reached.
+ * busy-wait until specified timestamp (in ticks) is reached. If on-time, return 0,
+ * otherwise return the number of ticks we were late.
  */
-void hal_waitUntil (u4_t time);
+u4_t hal_waitUntil (u4_t time);
 
 /*
  * check and rewind timer for target time.
diff --git a/src/lmic/lmic.c b/src/lmic/lmic.c
index 7a1beec..19fdb09 100644
--- a/src/lmic/lmic.c
+++ b/src/lmic/lmic.c
@@ -294,6 +294,16 @@ ostime_t calcAirTime (rps_t rps, u1_t plen) {
 //      500kHz   |  0   1   2   3   4   5
 //
 
+static void setRxsyms (ostime_t rxsyms) {
+    if (rxsyms >= (1u << 10u)) {
+        LMIC.rxsyms = (1u << 10u) - 1;
+    } else if (rxsyms < 0) {
+        LMIC.rxsyms = 0;
+    } else {
+        LMIC.rxsyms = rxsyms;
+    }
+}
+
 #if !defined(DISABLE_BEACONS)
 static ostime_t calcRxWindow (u1_t secs, dr_t dr) {
     ostime_t rxoff, err;
@@ -306,9 +316,9 @@ static ostime_t calcRxWindow (u1_t secs, dr_t dr) {
         rxoff = (LMIC.drift * (ostime_t)secs) >> BCN_INTV_exp;
         err = (LMIC.lastDriftDiff * (ostime_t)secs) >> BCN_INTV_exp;
     }
-    u1_t rxsyms = LMICbandplan_MINRX_SYMS_LoRa_ClassB;
+    rxsyms_t rxsyms = LMICbandplan_MINRX_SYMS_LoRa_ClassB;
     err += (ostime_t)LMIC.maxDriftDiff * LMIC.missedBcns;
-    LMIC.rxsyms = LMICbandplan_MINRX_SYMS_LoRa_ClassB + (err / dr2hsym(dr));
+    setRxsyms(LMICbandplan_MINRX_SYMS_LoRa_ClassB + (err / dr2hsym(dr)));
 
     return (rxsyms-LMICbandplan_PAMBL_SYMS) * dr2hsym(dr) + rxoff;
 }
@@ -616,7 +626,9 @@ static void stateJustJoined (void) {
 #if !defined(DISABLE_BEACONS)
 // Decode beacon  - do not overwrite bcninfo unless we have a match!
 static lmic_beacon_error_t decodeBeacon (void) {
-    ASSERT(LMIC.dataLen == LEN_BCN); // implicit header RX guarantees this
+    if (LMIC.dataLen != LEN_BCN) { // implicit header RX guarantees this
+        return LMIC_BEACON_ERROR_INVALID;
+    }
     xref2u1_t d = LMIC.frame;
     if(! LMICbandplan_isValidBeacon1(d))
         return LMIC_BEACON_ERROR_INVALID;   // first (common) part fails CRC check
@@ -711,7 +723,7 @@ static CONST_TABLE(u1_t, macCmdSize)[] = {
 static u1_t getMacCmdSize(u1_t macCmd) {
     if (macCmd < 2)
         return 0;
-    if (macCmd >= LENOF_TABLE(macCmdSize) - 2)
+    if ((macCmd - 2) >= LENOF_TABLE(macCmdSize))
         return 0;
     return TABLE_GET_U1(macCmdSize, macCmd - 2);
 }
@@ -747,7 +759,7 @@ applyAdrRequests(
             u1_t chpage = p4 & MCMD_LinkADRReq_Redundancy_ChMaskCntl_MASK;     // channel page
 
             map_ok = LMICbandplan_mapChannels(chpage, chmap);
-            LMICOS_logEventUint32("applyAdrRequests: mapChannels", (chpage << 16)|(chmap << 0));
+            LMICOS_logEventUint32("applyAdrRequests: mapChannels", ((u4_t)chpage << 16)|(chmap << 0));
         }
     }
 
@@ -789,7 +801,7 @@ applyAdrRequests(
             changes = 1;
         }
 
-        LMICOS_logEventUint32("applyAdrRequests: setDrTxPow", (adrAns << 16)|(dr << 8)|(p1 << 0));
+        LMICOS_logEventUint32("applyAdrRequests: setDrTxPow", ((u4_t)adrAns << 16)|(dr << 8)|(p1 << 0));
 
         // handle power changes here, too.
         changes |= setDrTxpow(DRCHG_NWKCMD, dr, pow2dBm(p1));
@@ -836,7 +848,7 @@ scan_mac_cmds_link_adr(
 
         if( !LMICbandplan_canMapChannels(chpage, chmap) ) {
             adrAns &= ~MCMD_LinkADRAns_ChannelACK;
-            LMICOS_logEventUint32("scan_mac_cmds_link_adr: failed canMapChannels", (chpage << UINT32_C(16))|(chmap << UINT32_C(0)));
+            LMICOS_logEventUint32("scan_mac_cmds_link_adr: failed canMapChannels", ((u4_t)chpage << 16)|((u4_t)chmap << 0));
         }
 
         if( !validDR(dr) ) {
@@ -883,8 +895,9 @@ scan_mac_cmds(
         cmd = opts[oidx];
 
         /* compute length, and exit for illegal commands */
+        // cmdlen == 0 for error, or > 0 length of command.
         int const cmdlen = getMacCmdSize(cmd);
-        if (cmdlen > olen - oidx) {
+        if (cmdlen <= 0 || cmdlen > olen - oidx) {
             // "the first unknown command terminates processing"
             olen = oidx;
             break;
@@ -993,7 +1006,7 @@ scan_mac_cmds(
 
             if( ans == (MCMD_NewChannelAns_DataRateACK|MCMD_NewChannelAns_ChannelACK)) {
                 if ( ! LMIC_setupChannel(chidx, freq, DR_RANGE_MAP(MinDR, MaxDR), -1) ) {
-                    LMICOS_logEventUint32("NewChannelReq: setupChannel failed", (MaxDR << 24u) | (MinDR << 16u) | (raw_f_not_zero << 8) | (chidx << 0));
+                    LMICOS_logEventUint32("NewChannelReq: setupChannel failed", ((u4_t)MaxDR << 24u) | ((u4_t)MinDR << 16u) | (raw_f_not_zero << 8) | (chidx << 0));
                     ans &= ~MCMD_NewChannelAns_ChannelACK;
                 }
             }
@@ -1059,13 +1072,12 @@ scan_mac_cmds(
 
 #if defined(ENABLE_MCMD_BeaconTimingAns) && !defined(DISABLE_BEACONS)
         case MCMD_BeaconTimingAns: {
-            // Ignore if tracking already enabled
-            if( (LMIC.opmode & OP_TRACK) == 0 ) {
+            // Ignore if tracking already enabled or bcninfoTries == 0
+            if( (LMIC.opmode & OP_TRACK) == 0 && LMIC.bcninfoTries != 0) {
                 LMIC.bcnChnl = opts[oidx+3];
                 // Enable tracking - bcninfoTries
                 LMIC.opmode |= OP_TRACK;
-                // Cleared later in txComplete handling - triggers EV_BEACON_FOUND
-                ASSERT(LMIC.bcninfoTries!=0);
+                // LMIC.bcninfoTries is cleared later in txComplete handling - triggers EV_BEACON_FOUND
                 // Setup RX parameters
                 LMIC.bcninfo.txtime = (LMIC.rxtime
                                        + ms2osticks(os_rlsbf2(&opts[oidx+1]) * MCMD_BeaconTimingAns_TUNIT)
@@ -1204,7 +1216,7 @@ static bit_t decodeFrame (void) {
         goto norx;
     }
     if( poff > pend ) {
-        LMICOS_logEventUint32("decodeFrame: corrupted frame", (dlen << 16) | (fct << 8) | (poff - pend));
+        LMICOS_logEventUint32("decodeFrame: corrupted frame", ((u4_t)dlen << 16) | (fct << 8) | (poff - pend));
         EV(specCond, ERR, (e_.reason = EV::specCond_t::CORRUPTED_FRAME,
                            e_.eui    = MAIN::CDEV->getEui(),
                            e_.info   = 0x1000000 + (poff-pend) + (fct<<8) + (dlen<<16)));
@@ -1245,7 +1257,7 @@ static bit_t decodeFrame (void) {
                                 e_.eui    = MAIN::CDEV->getEui(),
                                 e_.info   = LMIC.seqnoDn,
                                 e_.info2  = seqno));
-            LMICOS_logEventUint32("decodeFrame: rollover discarded", (seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
+            LMICOS_logEventUint32("decodeFrame: rollover discarded", ((u4_t)seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
             goto norx;
         }
         if( seqno != LMIC.seqnoDn-1 || !LMIC.lastDnConf || ftype != HDR_FTYPE_DCDN ) {
@@ -1253,19 +1265,19 @@ static bit_t decodeFrame (void) {
                                 e_.eui    = MAIN::CDEV->getEui(),
                                 e_.info   = LMIC.seqnoDn,
                                 e_.info2  = seqno));
-            LMICOS_logEventUint32("decodeFrame: Retransmit confimed discarded", (seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
+            LMICOS_logEventUint32("decodeFrame: Retransmit confimed discarded", ((u4_t)seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
             goto norx;
         }
         // Replay of previous sequence number allowed only if
         // previous frame and repeated both requested confirmation
         // but set a flag, so we don't actually process the message.
-        LMICOS_logEventUint32("decodeFrame: Retransmit confimed accepted", (seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
+        LMICOS_logEventUint32("decodeFrame: Retransmit confimed accepted", ((u4_t)seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
         replayConf = 1;
         LMIC.dnConf = FCT_ACK;
     }
     else {
         if( seqnoDiff > LMICbandplan_MAX_FCNT_GAP) {
-            LMICOS_logEventUint32("decodeFrame: gap too big", (seqnoDiff << 16) | (seqno & 0xFFFFu));
+            LMICOS_logEventUint32("decodeFrame: gap too big", ((u4_t)seqnoDiff << 16) | (seqno & 0xFFFFu));
             goto norx;
         }
         if( seqno > LMIC.seqnoDn ) {
@@ -1279,7 +1291,7 @@ static bit_t decodeFrame (void) {
         // DN frame requested confirmation - provide ACK once with next UP frame
         LMIC.dnConf = LMIC.lastDnConf = (ftype == HDR_FTYPE_DCDN ? FCT_ACK : 0);
         if (LMIC.dnConf)
-            LMICOS_logEventUint32("decodeFrame: Confirmed downlink", (seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
+            LMICOS_logEventUint32("decodeFrame: Confirmed downlink", ((u4_t)seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
     }
 
     if (port == 0 && olen != 0 && pend > poff) {
@@ -1364,7 +1376,7 @@ static bit_t decodeFrame (void) {
                             e_.info   = Base::lsbf4(&d[pend]),
                             e_.info2  = seqno));
         // discard the data
-        LMICOS_logEventUint32("decodeFrame: discarding replay", (seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
+        LMICOS_logEventUint32("decodeFrame: discarding replay", ((u4_t)seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
         goto norx;
     }
 
@@ -1420,59 +1432,84 @@ static void setupRx2 (void) {
     radioRx();
 }
 
-ostime_t LMICcore_adjustForDrift (ostime_t delay, ostime_t hsym) {
-    if (LMIC.client.clockError != 0) {
-        // Calculate how much the clock will drift maximally after delay has
-        // passed. This indicates the amount of time we can be early
-        // _or_ late.
-        ostime_t drift = (int64_t)delay * LMIC.client.clockError / MAX_CLOCK_ERROR;
-
-        // Increase the receive window by twice the maximum drift (to
-        // compensate for a slow or a fast clock).
-        delay -= drift;
-
-        // adjust rxsyms (the size of the window in syms) according to our
-        // uncertainty. do this in a strange order to avoid a divide if we can.
-        // rely on hsym = Tsym / 2
-        if ((255 - LMIC.rxsyms) * hsym < drift) {
-            LMIC.rxsyms = 255;
-        } else {
-            LMIC.rxsyms = (u1_t) (LMIC.rxsyms + drift / hsym);
-        }
-    }
-    return delay;
-}
-
-ostime_t LMICcore_RxWindowOffset (ostime_t hsym, u1_t rxsyms_in) {
-    ostime_t const Tsym = 2 * hsym;
-    ostime_t rxsyms;
+//! \brief Adjust the delay (in ticks) of the target window-open time from nominal.
+//! \param hsym the duration of one-half symbol in osticks.
+//! \param rxsyms_in the nominal window length -- minimum length of time to delay.
+//! \return Effective delay to use (positive for later, negative for earlier).
+//! \post LMIC.rxsyms is set to the number of rxsymbols to be used for preamble timeout.
+//! \bug For FSK, the radio driver ignores LMIC.rxsysms, and uses a fixed value of 4080 bits
+//! (81 ms)
+//!
+//! \details The calculation of the RX Window opening time has to balance several things.
+//! The system clock might be inaccurate. Generally, the LMIC assumes that the timebase
+//! is accurage to 100 ppm, or 0.01%.  0.01% of a 6 second window is 600 microseconds.
+//! For LoRa, the fastest data rates of interest is SF7 (1024 us/symbol); with an 8-byte
+//! preamble, the shortest preamble is 8.092ms long. If using FSK, the symbol rate is
+//! 20 microseconds, but the preamble is 8*5 bits long, so the preamble is 800 microseconds.
+//! Unless LMIC_ENABLE_arbitrary_clock_error is true, we fold clock errors of > 0.4% back
+//! to 0.4%.
+ostime_t LMICcore_adjustForDrift (ostime_t delay, ostime_t hsym, rxsyms_t rxsyms_in) {
     ostime_t rxoffset;
 
-    rxsyms = ((2 * (int)rxsyms_in - 8) * Tsym + LMICbandplan_RX_ERROR_ABS_osticks * 2 + Tsym - 1) / Tsym;
-    if (rxsyms < rxsyms_in) {
-        rxsyms = rxsyms_in;
-    }
-    LMIC.rxsyms = (u1_t) rxsyms;
+    // decide if we want to move left or right of the reference time.
+    rxoffset = -LMICbandplan_RX_EXTRA_MARGIN_osticks;
 
-    rxoffset = (8 - rxsyms) * hsym - LMICbandplan_RX_EXTRA_MARGIN_osticks;
+    u2_t clockerr = LMIC.client.clockError;
 
-    return rxoffset;
+    // Most crystal oscillators are 100 ppm. If things are that tight, there's
+    // no point in specifying a drift, as 6 seconds at 100ppm is +/- 600 microseconds.
+    // We position the windows at the front, and there's some extra margin, so...
+    // don't bother setting values <= 100 ppm.
+    if (clockerr != 0)
+        {
+        // client has set clock error. Limit this to 0.1% unless there's
+        // a compile-time configuration. (In other words, assume that millis()
+        // clock is accurate to 0.1%.) You should never use clockerror to
+        // compensate for system-late problems.
+        u2_t const maxError = LMIC_kMaxClockError_ppm * MAX_CLOCK_ERROR / (1000 * 1000);
+        if (! LMIC_ENABLE_arbitrary_clock_error && clockerr > maxError)
+            {
+            clockerr = maxError;
+            }
+        }
+
+    // If the clock is slow, the window needs to open earlier in our time
+    // in order to open at or before the specified time (in real world),.
+    // Don't bother to round, as this is very fine-grained.
+    ostime_t drift = (ostime_t)(((int64_t)delay * clockerr) / MAX_CLOCK_ERROR);
+
+    // calculate the additional rxsyms needed to hit the window nominally.
+    ostime_t const tsym = 2 * hsym;
+    ostime_t driftwin;
+    driftwin = 2 * drift;
+    if (rxoffset < 0)
+        driftwin += -rxoffset;
+    // else we'll hit the window nominally.
+
+    rxsyms_in += (driftwin + tsym - 1) / tsym;
+
+    // reduce the rxoffset by the drift; this compensates for a slow clock;
+    // but it makes the rxtime too early by approximately `drift` if clock
+    // is fast.
+    rxoffset -= drift;
+
+    setRxsyms(rxsyms_in);
+
+    return delay + rxoffset;
 }
 
 static void schedRx12 (ostime_t delay, osjobcb_t func, u1_t dr) {
     ostime_t hsym = dr2hsym(dr);
 
-    // Center the receive window on the center of the expected preamble and timeout.
-    // (again note that hsym is half a sumbol time, so no /2 needed)
-    // we leave RX_RAMPUP unadjusted for the clock drift.  The IBM LMIC generates delays
-    // that are too long for SF12, and too short for other SFs, so we follow the
-    // Semtech reference code.
+    // Schedule the start of the receive window. os_getRadioRxRampup() is used to make sure we
+    // exit "sleep" well enough in advance of the receive window to be able to
+    // time things accurately.
     //
-    // This also sets LMIC.rxsyms.
-    LMIC.rxtime = LMIC.txend + LMICcore_adjustForDrift(delay + LMICcore_RxWindowOffset(hsym, LMICbandplan_MINRX_SYMS_LoRa_ClassA), hsym);
+    // This also sets LMIC.rxsyms. This is NOT normally used for FSK; see LMICbandplan_txDoneFSK()
+    LMIC.rxtime = LMIC.txend + LMICcore_adjustForDrift(delay, hsym, LMICbandplan_MINRX_SYMS_LoRa_ClassA);
 
-    LMIC_X_DEBUG_PRINTF("%"LMIC_PRId_ostime_t": sched Rx12 %"LMIC_PRId_ostime_t"\n", os_getTime(), LMIC.rxtime - RX_RAMPUP);
-    os_setTimedCallback(&LMIC.osjob, LMIC.rxtime - RX_RAMPUP, func);
+    LMIC_X_DEBUG_PRINTF("%"LMIC_PRId_ostime_t": sched Rx12 %"LMIC_PRId_ostime_t"\n", os_getTime(), LMIC.rxtime - os_getRadioRxRampup());
+    os_setTimedCallback(&LMIC.osjob, LMIC.rxtime - os_getRadioRxRampup(), func);
 }
 
 static void setupRx1 (osjobcb_t func) {
@@ -1498,9 +1535,8 @@ static void txDone (ostime_t delay, osjobcb_t func) {
     // change params and rps (US only) before we increment txChnl
     LMICbandplan_setRx1Params();
 
-    // LMIC.rxsyms carries the TX datarate (can be != LMIC.datarate [confirm retries etc.])
-    // Setup receive - LMIC.rxtime is preloaded with 1.5 symbols offset to tune
-    // into the middle of the 8 symbols preamble.
+    // LMIC.dndr carries the TX datarate (can be != LMIC.datarate [confirm retries etc.])
+    // Setup receive -- either schedule FSK or schedule rx1 or rx2 window.
     if( LMICbandplan_isFSK() ) {
         LMICbandplan_txDoneFSK(delay, func);
     }
@@ -1527,12 +1563,22 @@ static bit_t processJoinAccept (void) {
     if ((LMIC.txrxFlags & TXRX_DNW1) != 0 && LMIC.dataLen == 0)
         return 0;
 
-    ASSERT((LMIC.opmode & OP_TXRXPEND)!=0);
+    // formerly we asserted.
+    if ((LMIC.opmode & OP_TXRXPEND) == 0)
+        // nothing we can do.
+        return 1;
+
+    // formerly we asserted.
+    if ((LMIC.opmode & (OP_JOINING|OP_REJOIN)) == 0) {
+        // we shouldn't be here. just drop the frame, but clean up txrxpend.
+        return processJoinAccept_badframe();
+    }
 
     if( LMIC.dataLen == 0 ) {
         // we didn't get any data and we're in slot 2. So... there's no join frame.
         return processJoinAccept_nojoinframe();
     }
+
     u1_t hdr  = LMIC.frame[0];
     u1_t dlen = LMIC.dataLen;
     u4_t mic  = os_rlsbf4(&LMIC.frame[dlen-4]); // safe before modified by encrypt!
@@ -1594,7 +1640,6 @@ static bit_t processJoinAccept (void) {
                                       ? EV::joininfo_t::REJOIN_ACCEPT
                                       : EV::joininfo_t::ACCEPT)));
 
-    ASSERT((LMIC.opmode & (OP_JOINING|OP_REJOIN))!=0);
     //
     // XXX(tmm@mcci.com) OP_REJOIN confuses me, and I'm not sure why we're
     // adjusting DRs here. We've just received a join accept, and the
@@ -1646,7 +1691,12 @@ static bit_t processJoinAccept_nojoinframe(void) {
         // the rejoin-sent count. Internal callers will turn on rejoin
         // occasionally.
         if( (LMIC.opmode & OP_JOINING) == 0) {
-            ASSERT((LMIC.opmode & OP_REJOIN) != 0);
+            // formerly, we asserted ((LMIC.opmode & OP_REJOIN) != 0);
+            // but now we just return 1 if it's not asserted.
+            if ( (LMIC.opmode & OP_REJOIN) == 0) {
+                LMIC.opmode &= ~OP_TXRXPEND;
+                return 1;
+            }
             LMIC.opmode &= ~(OP_REJOIN|OP_TXRXPEND);
             if( LMIC.rejoinCnt < 10 )
                 LMIC.rejoinCnt++;
@@ -1882,7 +1932,7 @@ static bit_t buildDataFrame (void) {
     u1_t maxFlen = LMICbandplan_maxFrameLen(LMIC.datarate);
 
     if (flen > maxFlen) {
-        LMICOS_logEventUint32("frame too long for this bandplan", (dlen << 16) | (flen << 8) | maxFlen);
+        LMICOS_logEventUint32("frame too long for this bandplan", ((u4_t)dlen << 16) | (flen << 8) | maxFlen);
         return 0;
     }
 
@@ -1896,7 +1946,7 @@ static bit_t buildDataFrame (void) {
         LMIC.seqnoUp += 1;
         DO_DEVDB(LMIC.seqnoUp,seqnoUp);
     } else {
-        LMICOS_logEventUint32("retransmit", (LMIC.frame[OFF_DAT_FCT] << 24u) | (LMIC.txCnt << 16u) | (LMIC.upRepeatCount << 8u) | (LMIC.upRepeat<<0u));
+        LMICOS_logEventUint32("retransmit", ((u4_t)LMIC.frame[OFF_DAT_FCT] << 24u) | ((u4_t)LMIC.txCnt << 16u) | (LMIC.upRepeatCount << 8u) | (LMIC.upRepeat<<0u));
         EV(devCond, INFO, (e_.reason = EV::devCond_t::RE_TX,
                            e_.eui    = MAIN::CDEV->getEui(),
                            e_.info   = LMIC.seqnoUp-1,
@@ -1981,7 +2031,9 @@ static void onBcnRx (xref2osjob_t osjob) {
 // Implicitely cancels any pending TX/RX transaction.
 // Also cancels an onpoing joining procedure.
 static void startScan (void) {
-    ASSERT(LMIC.devaddr!=0 && (LMIC.opmode & OP_JOINING)==0);
+    // formerly, we asserted.
+    if (LMIC.devaddr == 0 || (LMIC.opmode & OP_JOINING) != 0)
+        return;
     if( (LMIC.opmode & OP_SHUTDOWN) != 0 )
         return;
     // Cancel onging TX/RX transaction
@@ -2170,7 +2222,10 @@ static bit_t processDnData_norx(void);
 static bit_t processDnData_txcomplete(void);
 
 static bit_t processDnData (void) {
-    ASSERT((LMIC.opmode & OP_TXRXPEND)!=0);
+    // if no TXRXPEND, we shouldn't be here and can do nothign.
+    // formerly we asserted.
+    if ((LMIC.opmode & OP_TXRXPEND) == 0)
+        return 1;
 
     if( LMIC.dataLen == 0 ) {
         // if this is an RX1 window, shouldn't we return 0 to schedule
@@ -2416,7 +2471,7 @@ static void processBeacon (xref2osjob_t osjob) {
                          e_.eui    = MAIN::CDEV->getEui(),
                          e_.info   = drift,
                          e_.info2  = /*occasion BEACON*/0));
-        ASSERT((LMIC.bcninfo.flags & (BCN_PARTIAL|BCN_FULL)) != 0);
+        // formerly we'd assert on BCN_PARTIAL|BCN_FULL, but we can't get here if so
     } else {
         ev = EV_BEACON_MISSED;
         LMIC.bcninfo.txtime += BCN_INTV_osticks - LMIC.drift;
@@ -2424,9 +2479,9 @@ static void processBeacon (xref2osjob_t osjob) {
         LMIC.missedBcns++;
         // Delay any possible TX after surmised beacon - it's there although we missed it
         txDelay(LMIC.bcninfo.txtime + BCN_RESERVE_osticks, 4);
-        if( LMIC.missedBcns > MAX_MISSED_BCNS )
-            LMIC.opmode |= OP_REJOIN;  // try if we can roam to another network
-        if( LMIC.bcnRxsyms > MAX_RXSYMS ) {
+        // if too many missed beacons or we lose sync, drop back to Class A.
+        if( LMIC.missedBcns > MAX_MISSED_BCNS ||
+            LMIC.bcnRxsyms > MAX_RXSYMS ) {
             LMIC.opmode &= ~(OP_TRACK|OP_PINGABLE|OP_PINGINI|OP_REJOIN);
             reportEventAndUpdate(EV_LOST_TSYNC);
             return;
@@ -2495,8 +2550,14 @@ static void engineUpdate_inner (void) {
 
     if( (LMIC.opmode & OP_TRACK) != 0 ) {
         // We are tracking a beacon
-        ASSERT( now + RX_RAMPUP - LMIC.bcnRxtime <= 0 );
-        rxtime = LMIC.bcnRxtime - RX_RAMPUP;
+        // formerly asserted ( now - (LMIC.bcnRxtime - os_getRadioRxRampup()) <= 0 );
+        rxtime = LMIC.bcnRxtime - os_getRadioRxRampup();
+        if (now - rxtime < 0) {
+            // too late: drop out of Class B.
+            LMIC.opmode &= ~(OP_TRACK|OP_PINGABLE|OP_PINGINI|OP_REJOIN);
+            reportEventNoUpdate(EV_LOST_TSYNC);
+            return;
+        }
     }
 #endif // !DISABLE_BEACONS
 
@@ -2609,7 +2670,7 @@ static void engineUpdate_inner (void) {
 #if !defined(DISABLE_PING)
     if( (LMIC.opmode & OP_PINGINI) != 0 ) {
         // One more RX slot in this beacon period?
-        if( rxschedNext(&LMIC.ping, now+RX_RAMPUP) ) {
+        if( rxschedNext(&LMIC.ping, now+os_getRadioRxRampup()) ) {
             if( txbeg != 0  &&  (txbeg - LMIC.ping.rxtime) < 0 )
                 goto txdelay;
             LMIC.rxsyms  = LMIC.ping.rxsyms;
@@ -2617,8 +2678,14 @@ static void engineUpdate_inner (void) {
             LMIC.freq    = LMIC.ping.freq;
             LMIC.rps     = dndr2rps(LMIC.ping.dr);
             LMIC.dataLen = 0;
-            ASSERT(LMIC.rxtime - now+RX_RAMPUP >= 0 );
-            os_setTimedCallback(&LMIC.osjob, LMIC.rxtime - RX_RAMPUP, FUNC_ADDR(startRxPing));
+            ostime_t rxtime_ping = LMIC.rxtime - os_getRadioRxRampup();
+            // did we miss the time?
+            if (now - rxtime_ping > 0) {
+                LMIC.opmode &= ~(OP_TRACK|OP_PINGABLE|OP_PINGINI|OP_REJOIN);
+                reportEventNoUpdate(EV_LOST_TSYNC);
+            } else {
+                os_setTimedCallback(&LMIC.osjob, rxtime_ping, FUNC_ADDR(startRxPing));
+            }
             return;
         }
         // no - just wait for the beacon
@@ -2819,7 +2886,7 @@ void LMIC_setTxData (void) {
 }
 
 void LMIC_setTxData_strict (void) {
-    LMICOS_logEventUint32(__func__, (LMIC.pendTxPort << 24u) | (LMIC.pendTxConf << 16u) | (LMIC.pendTxLen << 0u));
+    LMICOS_logEventUint32(__func__, ((u4_t)LMIC.pendTxPort << 24u) | ((u4_t)LMIC.pendTxConf << 16u) | (LMIC.pendTxLen << 0u));
     LMIC.opmode |= OP_TXDATA;
     if( (LMIC.opmode & OP_JOINING) == 0 ) {
         LMIC.txCnt = 0;             // reset the confirmed uplink FSM
diff --git a/src/lmic/lmic.h b/src/lmic/lmic.h
index d05d2c0..fe92003 100644
--- a/src/lmic/lmic.h
+++ b/src/lmic/lmic.h
@@ -103,18 +103,18 @@ extern "C"{
 
 // Arduino LMIC version
 #define ARDUINO_LMIC_VERSION_CALC(major, minor, patch, local)	\
-	(((major) << 24ul) | ((minor) << 16ul) | ((patch) << 8ul) | ((local) << 0ul))
+	((((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, 0, 99, 5)	/* v3.0.99.5 */
+#define	ARDUINO_LMIC_VERSION	ARDUINO_LMIC_VERSION_CALC(3, 0, 99, 10)	/* v3.0.99.10 */
 
 #define	ARDUINO_LMIC_VERSION_GET_MAJOR(v)	\
-	(((v) >> 24u) & 0xFFu)
+	((((v)*UINT32_C(1)) >> 24u) & 0xFFu)
 
 #define	ARDUINO_LMIC_VERSION_GET_MINOR(v)	\
-	(((v) >> 16u) & 0xFFu)
+	((((v)*UINT32_C(1)) >> 16u) & 0xFFu)
 
 #define	ARDUINO_LMIC_VERSION_GET_PATCH(v)	\
-	(((v) >> 8u) & 0xFFu)
+	((((v)*UINT32_C(1)) >> 8u) & 0xFFu)
 
 #define	ARDUINO_LMIC_VERSION_GET_LOCAL(v)	\
 	((v) & 0xFFu)
@@ -127,8 +127,15 @@ extern "C"{
 enum { MAX_FRAME_LEN      =  MAX_LEN_FRAME };   //!< Library cap on max frame length
 
 enum { TXCONF_ATTEMPTS    =   8 };   //!< Transmit attempts for confirmed frames
-enum { MAX_MISSED_BCNS    =  20 };   // threshold for triggering rejoin requests
-enum { MAX_RXSYMS         = 100 };   // stop tracking beacon beyond this
+enum { MAX_MISSED_BCNS    =  (2 * 60 * 60 + 127) / 128 };   //!< threshold for dropping out of class B, triggering rejoin requests
+                                     // note that we need 100 ppm timing accuracy for
+                                     // this, to keep the timing error to +/- 700ms.
+enum { MAX_RXSYMS         = 350 };   // Stop tracking beacon if sync error grows beyond this. A 0.4% clock error
+                                     // at SF9.125k means 512 ms; one sybol is 4.096 ms,
+                                     // so this needs to be at least 125 for an STM32L0.
+                                     // And for 100ppm clocks and 2 hours of beacon misses,
+                                     // this needs to accomodate 1.4 seconds of error at
+                                     // 4.096 ms/sym or at least 342 symbols.
 
 enum { LINK_CHECK_CONT    =  0  ,    // continue with this after reported dead link
        LINK_CHECK_DEAD    =  32 ,    // after this UP frames and no response to ack from NWK assume link is dead (ADR_ACK_DELAY)
@@ -185,10 +192,10 @@ enum { KEEP_TXPOW = -128 };
 #if !defined(DISABLE_PING)
 //! \internal
 struct rxsched_t {
-    u1_t     dr;
+    dr_t     dr;
     u1_t     intvExp;   // 0..7
     u1_t     slot;      // runs from 0 to 128
-    u1_t     rxsyms;
+    rxsyms_t rxsyms;
     ostime_t rxbase;
     ostime_t rxtime;    // start of next spot
     u4_t     freq;
@@ -219,7 +226,7 @@ struct bcninfo_t {
 #endif // !DISABLE_BEACONS
 
 // purpose of receive window - lmic_t.rxState
-enum { RADIO_RST=0, RADIO_TX=1, RADIO_RX=2, RADIO_RXON=3 };
+enum { RADIO_RST=0, RADIO_TX=1, RADIO_RX=2, RADIO_RXON=3, RADIO_TX_AT=4, };
 // Netid values /  lmic_t.netid
 enum { NETID_NONE=(int)~0U, NETID_MASK=(int)0xFFFFFF };
 // MAC operation modes (lmic_t.opmode).
@@ -320,9 +327,25 @@ static inline bit_t LMIC_BEACON_SUCCESSFUL(lmic_beacon_error_t e) {
     return e < 0;
 }
 
+// LMIC_CFG_max_clock_error_ppm
+#if !defined(LMIC_CFG_max_clock_error_ppm)
+# define LMIC_CFG_max_clock_error_ppm	2000	/* max clock error: 0.2% (2000 ppm) */
+#endif
+
+
 enum {
         // This value represents 100% error in LMIC.clockError
         MAX_CLOCK_ERROR = 65536,
+        //! \brief maximum clock error that users can specify: 2000 ppm (0.2%).
+        //! \details This is the limit for clock error, unless LMIC_ENABLE_arbitrary_clock_error is set.
+        //! The default is 4,000 ppm, which is .004, or 0.4%; this is what you get on an
+        //! STM32L0 running with the HSI oscillator after cal. If your clock error is bigger,
+        //! usually you want to calibrate it so that millis() and micros() are reasonably
+        //! accurate. Important: do not use clock error to compensate for late serving
+        //! of the LMIC. If you see that LMIC.radio.rxlate_count is increasing, you need
+        //! to adjust your application logic so the LMIC gets serviced promptly when a
+        //! Class A downlink (or beacon) is pending.
+        LMIC_kMaxClockError_ppm = 4000,
 };
 
 // callbacks for client alerts.
@@ -417,6 +440,32 @@ struct lmic_client_data_s {
 
 /*
 
+Structure:  lmic_radio_data_t
+
+Function:
+    Holds LMIC radio driver.
+
+Description:
+    Eventually this will be used for all portable things for the radio driver,
+    but for now it's where we can start to add things.
+
+*/
+
+typedef struct lmic_radio_data_s lmic_radio_data_t;
+
+struct lmic_radio_data_s {
+    // total os ticks of accumulated delay error. Can overflow!
+    ostime_t    rxlate_ticks;
+    // number of rx late launches.
+    unsigned    rxlate_count;
+    // total os ticks of accumulated tx delay error. Can overflow!
+    ostime_t    txlate_ticks;
+    // number of tx late launches.
+    unsigned    txlate_count;
+};
+
+/*
+
 Structure:  lmic_t
 
 Function:
@@ -439,6 +488,9 @@ struct lmic_t {
     rxsched_t   ping;         // pingable setup
 #endif
 
+    // the radio driver portable context
+    lmic_radio_data_t   radio;
+
     /* (u)int32_t things */
 
     // Radio settings TX/RX (also accessed by HAL)
@@ -498,13 +550,14 @@ struct lmic_t {
     s2_t        drift;          // last measured drift
     s2_t        lastDriftDiff;
     s2_t        maxDriftDiff;
+    rxsyms_t    bcnRxsyms;      //
 #endif
 
     /* (u)int8_t things */
     lmic_engine_update_state_t engineUpdateState;   // state of the engineUpdate() evaluator.
     s1_t        rssi;
     s1_t        snr;            // LMIC.snr is SNR times 4
-    u1_t        rxsyms;
+    rxsyms_t    rxsyms;         // symbols for receive timeout.
     u1_t        dndr;
     s1_t        txpow;          // transmit dBm (administrative)
     s1_t        radio_txpow;    // the radio driver's copy of txpow, in dB limited by adrTxPow, and
@@ -586,7 +639,6 @@ struct lmic_t {
 
 #if !defined(DISABLE_BEACONS)
     u1_t        bcnChnl;
-    u1_t        bcnRxsyms;    //
 #endif
 
     u1_t        noRXIQinversion;
diff --git a/src/lmic/lmic_au921.c b/src/lmic/lmic_au915.c
similarity index 86%
rename from src/lmic/lmic_au921.c
rename to src/lmic/lmic_au915.c
index e12ad8a..08df1ad 100644
--- a/src/lmic/lmic_au921.c
+++ b/src/lmic/lmic_au915.c
@@ -30,10 +30,10 @@
 
 #include "lmic_bandplan.h"
 
-#if defined(CFG_au921)
+#if defined(CFG_au915)
 // ================================================================================
 //
-// BEG: AU921 related stuff
+// BEG: AU915 related stuff
 //
 
 CONST_TABLE(u1_t, _DR2RPS_CRC)[] = {
@@ -64,16 +64,16 @@ static CONST_TABLE(u1_t, maxFrameLens_dwell1)[] = {
         61+5, 137+5, 250+5, 250+5, 250+5, 250+5 };
 
 static bit_t
-LMICau921_getUplinkDwellBit() {
+LMICau915_getUplinkDwellBit() {
         // if uninitialized, return default.
         if (LMIC.txParam == 0xFF) {
-                return AU921_INITIAL_TxParam_UplinkDwellTime;
+                return AU915_INITIAL_TxParam_UplinkDwellTime;
         }
         return (LMIC.txParam & MCMD_TxParam_TxDWELL_MASK) != 0;
 }
 
-uint8_t LMICau921_maxFrameLen(uint8_t dr) {
-        if (LMICau921_getUplinkDwellBit()) {
+uint8_t LMICau915_maxFrameLen(uint8_t dr) {
+        if (LMICau915_getUplinkDwellBit()) {
                 if (dr < LENOF_TABLE(maxFrameLens_dwell0))
                         return TABLE_GET_U1(maxFrameLens_dwell0, dr);
                 else
@@ -91,10 +91,10 @@ static CONST_TABLE(s1_t, TXMAXEIRP)[16] = {
 	8, 10, 12, 13, 14, 16, 18, 20, 21, 24, 26, 27, 29, 30, 33, 36
 };
 
-static int8_t LMICau921_getMaxEIRP(uint8_t mcmd_txparam) {
+static int8_t LMICau915_getMaxEIRP(uint8_t mcmd_txparam) {
         // if uninitialized, return default.
 	if (mcmd_txparam == 0xFF)
-		return AU921_TX_EIRP_MAX_DBM;
+		return AU915_TX_EIRP_MAX_DBM;
 	else
 		return TABLE_GET_S1(
 			TXMAXEIRP,
@@ -103,11 +103,11 @@ static int8_t LMICau921_getMaxEIRP(uint8_t mcmd_txparam) {
 			);
 }
 
-int8_t LMICau921_pow2dbm(uint8_t mcmd_ladr_p1) {
+int8_t LMICau915_pow2dbm(uint8_t mcmd_ladr_p1) {
         if ((mcmd_ladr_p1 & MCMD_LinkADRReq_POW_MASK) == MCMD_LinkADRReq_POW_MASK)
                 return -128;
         else    {
-                return ((s1_t)(LMICau921_getMaxEIRP(LMIC.txParam) - (((mcmd_ladr_p1)&MCMD_LinkADRReq_POW_MASK)<<1)));
+                return ((s1_t)(LMICau915_getMaxEIRP(LMIC.txParam) - (((mcmd_ladr_p1)&MCMD_LinkADRReq_POW_MASK)<<1)));
         }
 }
 
@@ -131,20 +131,20 @@ static CONST_TABLE(ostime_t, DR2HSYM_osticks)[] = {
 // get ostime for symbols based on datarate. This is not like us915,
 // becuase the times don't match between the upper half and lower half
 // of the table.
-ostime_t LMICau921_dr2hsym(uint8_t dr) {
+ostime_t LMICau915_dr2hsym(uint8_t dr) {
         return TABLE_GET_OSTIME(DR2HSYM_osticks, dr);
 }
 
 
 
-u4_t LMICau921_convFreq(xref2cu1_t ptr) {
+u4_t LMICau915_convFreq(xref2cu1_t ptr) {
         u4_t freq = (os_rlsbf4(ptr - 1) >> 8) * 100;
-        if (freq < AU921_FREQ_MIN || freq > AU921_FREQ_MAX)
+        if (freq < AU915_FREQ_MIN || freq > AU915_FREQ_MAX)
                 freq = 0;
         return freq;
 }
 
-// au921: no support for xchannels.
+// au915: no support for xchannels.
 bit_t LMIC_setupChannel(u1_t chidx, u4_t freq, u2_t drmap, s1_t band) {
         LMIC_API_PARAMETER(chidx);
         LMIC_API_PARAMETER(freq);
@@ -229,14 +229,14 @@ bit_t LMIC_selectSubBand(u1_t band) {
         return result;
 }
 
-void LMICau921_updateTx(ostime_t txbeg) {
+void LMICau915_updateTx(ostime_t txbeg) {
         u1_t chnl = LMIC.txChnl;
-        LMIC.txpow = LMICau921_getMaxEIRP(LMIC.txParam);
+        LMIC.txpow = LMICau915_getMaxEIRP(LMIC.txParam);
         if (chnl < 64) {
-                LMIC.freq = AU921_125kHz_UPFBASE + chnl*AU921_125kHz_UPFSTEP;
+                LMIC.freq = AU915_125kHz_UPFBASE + chnl*AU915_125kHz_UPFSTEP;
         } else {
                 ASSERT(chnl < 64 + 8);
-                LMIC.freq = AU921_500kHz_UPFBASE + (chnl - 64)*AU921_500kHz_UPFSTEP;
+                LMIC.freq = AU915_500kHz_UPFBASE + (chnl - 64)*AU915_500kHz_UPFSTEP;
         }
 
         // Update global duty cycle stat and deal with dwell time.
@@ -248,8 +248,8 @@ void LMICau921_updateTx(ostime_t txbeg) {
                 ostime_t airtime = calcAirTime(LMIC.rps, LMIC.dataLen);
                 globalDutyDelay = txbeg + (airtime << LMIC.globalDutyRate);
         }
-        if (LMICau921_getUplinkDwellBit(LMIC.txParam)) {
-                dwellDelay = AU921_UPLINK_DWELL_TIME_osticks;
+        if (LMICau915_getUplinkDwellBit(LMIC.txParam)) {
+                dwellDelay = AU915_UPLINK_DWELL_TIME_osticks;
         }
         if (dwellDelay > globalDutyDelay) {
                 globalDutyDelay = dwellDelay;
@@ -260,22 +260,22 @@ void LMICau921_updateTx(ostime_t txbeg) {
 }
 
 #if !defined(DISABLE_BEACONS)
-void LMICau921_setBcnRxParams(void) {
+void LMICau915_setBcnRxParams(void) {
         LMIC.dataLen = 0;
-        LMIC.freq = AU921_500kHz_DNFBASE + LMIC.bcnChnl * AU921_500kHz_DNFSTEP;
+        LMIC.freq = AU915_500kHz_DNFBASE + LMIC.bcnChnl * AU915_500kHz_DNFSTEP;
         LMIC.rps = setIh(setNocrc(dndr2rps((dr_t)DR_BCN), 1), LEN_BCN);
 }
 #endif // !DISABLE_BEACONS
 
 // set the Rx1 dndr, rps.
-void LMICau921_setRx1Params(void) {
+void LMICau915_setRx1Params(void) {
         u1_t const txdr = LMIC.dndr;
         u1_t candidateDr;
-        LMIC.freq = AU921_500kHz_DNFBASE + (LMIC.txChnl & 0x7) * AU921_500kHz_DNFSTEP;
-        if ( /* TX datarate */txdr < AU921_DR_SF8C)
+        LMIC.freq = AU915_500kHz_DNFBASE + (LMIC.txChnl & 0x7) * AU915_500kHz_DNFSTEP;
+        if ( /* TX datarate */txdr < AU915_DR_SF8C)
                 candidateDr = txdr + 8 - LMIC.rx1DrOffset;
         else
-                candidateDr = AU921_DR_SF7CR;
+                candidateDr = AU915_DR_SF7CR;
 
         if (candidateDr < LORAWAN_DR8)
                 candidateDr = LORAWAN_DR8;
@@ -286,17 +286,17 @@ void LMICau921_setRx1Params(void) {
         LMIC.rps = dndr2rps(LMIC.dndr);
 }
 
-void LMICau921_initJoinLoop(void) {
+void LMICau915_initJoinLoop(void) {
         // LMIC.txParam is set to 0xFF by the central code at init time.
         LMICuslike_initJoinLoop();
 
         // initialize the adrTxPower.
-        LMIC.adrTxPow = LMICau921_getMaxEIRP(LMIC.txParam); // dBm
+        LMIC.adrTxPow = LMICau915_getMaxEIRP(LMIC.txParam); // dBm
 
 }
 
 //
-// END: AU921 related stuff
+// END: AU915 related stuff
 //
 // ================================================================================
 #endif
diff --git a/src/lmic/lmic_bandplan.h b/src/lmic/lmic_bandplan.h
index 74efc61..db5863d 100644
--- a/src/lmic/lmic_bandplan.h
+++ b/src/lmic/lmic_bandplan.h
@@ -37,8 +37,8 @@
 # include "lmic_bandplan_eu868.h"
 #elif defined(CFG_us915)
 # include "lmic_bandplan_us915.h"
-#elif defined(CFG_au921)
-# include "lmic_bandplan_au921.h"
+#elif defined(CFG_au915)
+# include "lmic_bandplan_au915.h"
 #elif defined(CFG_as923)
 # include "lmic_bandplan_as923.h"
 #elif defined(CFG_kr920)
@@ -226,7 +226,6 @@
 // internal APIs
 ostime_t LMICcore_rndDelay(u1_t secSpan);
 void LMICcore_setDrJoin(u1_t reason, u1_t dr);
-ostime_t LMICcore_adjustForDrift(ostime_t delay, ostime_t hsym);
-ostime_t LMICcore_RxWindowOffset(ostime_t hsym, u1_t rxsyms_in);
+ostime_t LMICcore_adjustForDrift(ostime_t delay, ostime_t hsym, rxsyms_t rxsyms_in);
 
 #endif // _lmic_bandplan_h_
diff --git a/src/lmic/lmic_bandplan_au921.h b/src/lmic/lmic_bandplan_au915.h
similarity index 68%
rename from src/lmic/lmic_bandplan_au921.h
rename to src/lmic/lmic_bandplan_au915.h
index 16d7c88..f17194b 100644
--- a/src/lmic/lmic_bandplan_au921.h
+++ b/src/lmic/lmic_bandplan_au915.h
@@ -26,8 +26,8 @@
 * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 */
 
-#ifndef _lmic_bandplan_au921_h_
-# define _lmic_bandplan_au921_h_
+#ifndef _lmic_bandplan_au915_h_
+# define _lmic_bandplan_au915_h_
 
 // preconditions for lmic_us_like.h
 #define LMICuslike_getFirst500kHzDR()   (LORAWAN_DR6)
@@ -37,33 +37,33 @@
 # include "lmic_us_like.h"
 #endif
 
-// return maximum frame length (including PHY header) for this data rate (au921); 0 --> not valid dr.
-uint8_t LMICau921_maxFrameLen(uint8_t dr);
+// return maximum frame length (including PHY header) for this data rate (au915); 0 --> not valid dr.
+uint8_t LMICau915_maxFrameLen(uint8_t dr);
 // return maximum frame length (including PHY header) for this data rate; 0 --> not valid dr.
-#define LMICbandplan_maxFrameLen(dr) LMICau921_maxFrameLen(dr)
+#define LMICbandplan_maxFrameLen(dr) LMICau915_maxFrameLen(dr)
 
-int8_t LMICau921_pow2dbm(uint8_t mcmd_ladr_p1);
-#define pow2dBm(mcmd_ladr_p1) LMICau921_pow2dbm(mcmd_ladr_p1)
+int8_t LMICau915_pow2dbm(uint8_t mcmd_ladr_p1);
+#define pow2dBm(mcmd_ladr_p1) LMICau915_pow2dbm(mcmd_ladr_p1)
 
-ostime_t LMICau921_dr2hsym(uint8_t dr);
-#define dr2hsym(dr) LMICau921_dr2hsym(dr)
+ostime_t LMICau915_dr2hsym(uint8_t dr);
+#define dr2hsym(dr) LMICau915_dr2hsym(dr)
 
 
 #define LMICbandplan_getInitialDrJoin() (LORAWAN_DR2)
 
-void LMICau921_initJoinLoop(void);
-#define LMICbandplan_initJoinLoop()     LMICau921_initJoinLoop()
+void LMICau915_initJoinLoop(void);
+#define LMICbandplan_initJoinLoop()     LMICau915_initJoinLoop()
 
-void LMICau921_setBcnRxParams(void);
-#define LMICbandplan_setBcnRxParams() LMICau921_setBcnRxParams()
+void LMICau915_setBcnRxParams(void);
+#define LMICbandplan_setBcnRxParams() LMICau915_setBcnRxParams()
 
-u4_t LMICau921_convFreq(xref2cu1_t ptr);
-#define LMICbandplan_convFreq(ptr)      LMICau921_convFreq(ptr)
+u4_t LMICau915_convFreq(xref2cu1_t ptr);
+#define LMICbandplan_convFreq(ptr)      LMICau915_convFreq(ptr)
 
-void LMICau921_setRx1Params(void);
-#define LMICbandplan_setRx1Params()     LMICau921_setRx1Params()
+void LMICau915_setRx1Params(void);
+#define LMICbandplan_setRx1Params()     LMICau915_setRx1Params()
 
-void LMICau921_updateTx(ostime_t txbeg);
-#define LMICbandplan_updateTx(txbeg)    LMICau921_updateTx(txbeg)
+void LMICau915_updateTx(ostime_t txbeg);
+#define LMICbandplan_updateTx(txbeg)    LMICau915_updateTx(txbeg)
 
-#endif // _lmic_bandplan_au921_h_
+#endif // _lmic_bandplan_au915_h_
diff --git a/src/lmic/lmic_config_preconditions.h b/src/lmic/lmic_config_preconditions.h
index 4cfca25..4eca675 100644
--- a/src/lmic/lmic_config_preconditions.h
+++ b/src/lmic/lmic_config_preconditions.h
@@ -67,7 +67,7 @@ Revision history:
 #define LMIC_REGION_us915    2
 #define LMIC_REGION_cn783    3
 #define LMIC_REGION_eu433    4
-#define LMIC_REGION_au921    5
+#define LMIC_REGION_au915    5
 #define LMIC_REGION_cn490    6
 #define LMIC_REGION_as923    7
 #define LMIC_REGION_kr920    8
@@ -93,6 +93,16 @@ Revision history:
 # include CFG_TEXT_1(ARDUINO_LMIC_PROJECT_CONFIG_H)
 #endif /* ARDUINO_LMIC_PROJECT_CONFIG_H_SUPPRESS */
 
+#if defined(CFG_au921) && !defined(CFG_au915)
+#   warning "CFG_au921 was deprecated in favour of CFG_au915. Support for CFG_au921 might be removed in the future."
+#   define CFG_au915
+#endif
+
+// for backwards compatibility to legacy code, define CFG_au921 if we see CFG_au915.
+#if defined(CFG_au915) && !defined(CFG_au921)
+#   define CFG_au921
+#endif
+
 // a mask of the supported regions
 // TODO(tmm@mcci.com) consider moving this block to a central file as it's not
 // user-editable.
@@ -101,7 +111,7 @@ Revision history:
                                 (1 << LMIC_REGION_us915) |      \
                              /* (1 << LMIC_REGION_cn783) | */   \
                              /* (1 << LMIC_REGION_eu433) | */   \
-                                (1 << LMIC_REGION_au921) |      \
+                                (1 << LMIC_REGION_au915) |      \
                              /* (1 << LMIC_REGION_cn490) | */   \
                                 (1 << LMIC_REGION_as923) |      \
                                 (1 << LMIC_REGION_kr920) |      \
@@ -125,7 +135,7 @@ Revision history:
                          (defined(CFG_us915) << LMIC_REGION_us915) | \
                          (defined(CFG_cn783) << LMIC_REGION_cn783) | \
                          (defined(CFG_eu433) << LMIC_REGION_eu433) | \
-                         (defined(CFG_au921) << LMIC_REGION_au921) | \
+                         (defined(CFG_au915) << LMIC_REGION_au915) | \
                          (defined(CFG_cn490) << LMIC_REGION_cn490) | \
                          (defined(CFG_as923) << LMIC_REGION_as923) | \
                          (defined(CFG_kr920) << LMIC_REGION_kr920) | \
@@ -143,8 +153,8 @@ Revision history:
 # define CFG_region     LMIC_REGION_cn783
 #elif defined(CFG_eu433)
 # define CFG_region     LMIC_REGION_eu433
-#elif defined(CFG_au921)
-# define CFG_region     LMIC_REGION_au921
+#elif defined(CFG_au915)
+# define CFG_region     LMIC_REGION_au915
 #elif defined(CFG_cn490)
 # define CFG_region     LMIC_REGION_cn490
 #elif defined(CFG_as923jp)
@@ -171,7 +181,7 @@ Revision history:
                              /* (1 << LMIC_REGION_us915) | */   \
                                 (1 << LMIC_REGION_cn783) |      \
                                 (1 << LMIC_REGION_eu433) |      \
-                             /* (1 << LMIC_REGION_au921) | */   \
+                             /* (1 << LMIC_REGION_au915) | */   \
                              /* (1 << LMIC_REGION_cn490) | */   \
                                 (1 << LMIC_REGION_as923) |      \
                                 (1 << LMIC_REGION_kr920) |      \
@@ -189,7 +199,7 @@ Revision history:
                                 (1 << LMIC_REGION_us915) |      \
                              /* (1 << LMIC_REGION_cn783) | */   \
                              /* (1 << LMIC_REGION_eu433) | */   \
-                                (1 << LMIC_REGION_au921) |      \
+                                (1 << LMIC_REGION_au915) |      \
                              /* (1 << LMIC_REGION_cn490) | */   \
                              /* (1 << LMIC_REGION_as923) | */   \
                              /* (1 << LMIC_REGION_kr920) | */   \
diff --git a/src/lmic/lmic_eu_like.c b/src/lmic/lmic_eu_like.c
index 982ae49..46694e3 100644
--- a/src/lmic/lmic_eu_like.c
+++ b/src/lmic/lmic_eu_like.c
@@ -255,14 +255,15 @@ void LMICeulike_setRx1Freq(void) {
 // Class A txDone handling for FSK.
 void
 LMICeulike_txDoneFSK(ostime_t delay, osjobcb_t func) {
-        ostime_t const hsym = us2osticksRound(80);
+        // one symbol == one bit at 50kHz == 20us.
+        ostime_t const hsym = us2osticksRound(10);
 
-        // start a little earlier.
+        // start a little earlier.  PRERX_FSK is in bytes; one byte at 50 kHz == 160us
         delay -= LMICbandplan_PRERX_FSK * us2osticksRound(160);
 
         // set LMIC.rxtime and LMIC.rxsyms:
-        LMIC.rxtime = LMIC.txend + LMICcore_adjustForDrift(delay + LMICcore_RxWindowOffset(hsym, LMICbandplan_RXLEN_FSK), hsym);
-        os_setTimedCallback(&LMIC.osjob, LMIC.rxtime - RX_RAMPUP, func);
+        LMIC.rxtime = LMIC.txend + LMICcore_adjustForDrift(delay, hsym, 8 * LMICbandplan_RXLEN_FSK);
+        os_setTimedCallback(&LMIC.osjob, LMIC.rxtime - os_getRadioRxRampup(), func);
 }
 
 #endif // CFG_LMIC_EU_like
diff --git a/src/lmic/lmic_us_like.c b/src/lmic/lmic_us_like.c
index c6b075f..d1383bd 100644
--- a/src/lmic/lmic_us_like.c
+++ b/src/lmic/lmic_us_like.c
@@ -186,7 +186,7 @@ bit_t LMICuslike_mapChannels(u1_t chpage, u2_t chmap) {
                 }
         }
 
-        LMICOS_logEventUint32("LMICuslike_mapChannels", (LMIC.activeChannels125khz << 16u)|(LMIC.activeChannels500khz << 0u));
+        LMICOS_logEventUint32("LMICuslike_mapChannels", ((u4_t)LMIC.activeChannels125khz << 16u)|(LMIC.activeChannels500khz << 0u));
 	return (LMIC.activeChannels125khz > 0) || (LMIC.activeChannels500khz > 0);
 }
 
diff --git a/src/lmic/lorabase.h b/src/lmic/lorabase.h
index 873658b..93034c0 100644
--- a/src/lmic/lorabase.h
+++ b/src/lmic/lorabase.h
@@ -44,6 +44,7 @@ typedef u1_t cr_t;
 typedef u1_t sf_t;
 typedef u1_t bw_t;
 typedef u1_t dr_t;
+typedef u2_t rxsyms_t;
 
 // Radio parameter set (encodes SF/BW/CR/IH/NOCRC)
 // 2..0:    Spreading factor
@@ -226,28 +227,28 @@ enum _dr_configured_t {
 };
 # endif // LMIC_DR_LEGACY
 
-#elif defined(CFG_au921)  // =========================================
+#elif defined(CFG_au915)  // =========================================
 
-#include "lorabase_au921.h"
+#include "lorabase_au915.h"
 
 // per 2.5.3: must be implemented
 #define LMIC_ENABLE_TxParamSetupReq	1
 
-enum { DR_DFLTMIN       = AU921_DR_SF7 };  // DR5
+enum { DR_DFLTMIN       = AU915_DR_SF7 };  // DR5
 
                                 // DR_PAGE is a debugging parameter; it must be defined but it has no use in arduino-lmic
-enum { DR_PAGE          = DR_PAGE_AU921 };
+enum { DR_PAGE          = DR_PAGE_AU915 };
 
 //enum { CHNL_PING        = 0 }; // used only for default init of state (follows beacon - rotating)
-enum { FREQ_PING        = AU921_500kHz_DNFBASE + 0*AU921_500kHz_DNFSTEP };  // default ping freq
-enum { DR_PING          = AU921_DR_SF10CR };       // default ping DR
+enum { FREQ_PING        = AU915_500kHz_DNFBASE + 0*AU915_500kHz_DNFSTEP };  // default ping freq
+enum { DR_PING          = AU915_DR_SF10CR };       // default ping DR
 //enum { CHNL_DNW2        = 0 };
-enum { FREQ_DNW2        = AU921_500kHz_DNFBASE + 0*AU921_500kHz_DNFSTEP };
-enum { DR_DNW2          = AU921_DR_SF12CR };                  // DR8
+enum { FREQ_DNW2        = AU915_500kHz_DNFBASE + 0*AU915_500kHz_DNFSTEP };
+enum { DR_DNW2          = AU915_DR_SF12CR };                  // DR8
 enum { CHNL_BCN         = 0 }; // used only for default init of state (rotating beacon scheme)
-enum { DR_BCN           = AU921_DR_SF10CR };
+enum { DR_BCN           = AU915_DR_SF10CR };
 enum { AIRTIME_BCN      = 72192 };  // micros ... TODO(tmm@mcci.com) check.
-enum { LMIC_REGION_EIRP = AU921_LMIC_REGION_EIRP };         // region uses EIRP
+enum { LMIC_REGION_EIRP = AU915_LMIC_REGION_EIRP };         // region uses EIRP
 
 enum {
         // Beacon frame format AU DR10/SF10 500kHz
@@ -264,20 +265,20 @@ enum {
 
 # if LMIC_DR_LEGACY
 enum _dr_configured_t {
-        DR_SF12    = AU921_DR_SF12,
-        DR_SF11    = AU921_DR_SF11,
-        DR_SF10    = AU921_DR_SF10,
-        DR_SF9     = AU921_DR_SF9,
-        DR_SF8     = AU921_DR_SF8,
-        DR_SF7     = AU921_DR_SF7,
-        DR_SF8C    = AU921_DR_SF8C,
-        DR_NONE    = AU921_DR_NONE,
-        DR_SF12CR  = AU921_DR_SF12CR,
-        DR_SF11CR  = AU921_DR_SF11CR,
-        DR_SF10CR  = AU921_DR_SF10CR,
-        DR_SF9CR   = AU921_DR_SF9CR,
-        DR_SF8CR   = AU921_DR_SF8CR,
-        DR_SF7CR   = AU921_DR_SF7CR
+        DR_SF12    = AU915_DR_SF12,
+        DR_SF11    = AU915_DR_SF11,
+        DR_SF10    = AU915_DR_SF10,
+        DR_SF9     = AU915_DR_SF9,
+        DR_SF8     = AU915_DR_SF8,
+        DR_SF7     = AU915_DR_SF7,
+        DR_SF8C    = AU915_DR_SF8C,
+        DR_NONE    = AU915_DR_NONE,
+        DR_SF12CR  = AU915_DR_SF12CR,
+        DR_SF11CR  = AU915_DR_SF11CR,
+        DR_SF10CR  = AU915_DR_SF10CR,
+        DR_SF9CR   = AU915_DR_SF9CR,
+        DR_SF8CR   = AU915_DR_SF8CR,
+        DR_SF7CR   = AU915_DR_SF7CR
 };
 # endif // LMIC_DR_LEGACY
 
diff --git a/src/lmic/lorabase_au921.h b/src/lmic/lorabase_au915.h
similarity index 63%
rename from src/lmic/lorabase_au921.h
rename to src/lmic/lorabase_au915.h
index 7d8a198..7bac54e 100644
--- a/src/lmic/lorabase_au921.h
+++ b/src/lmic/lorabase_au915.h
@@ -28,8 +28,8 @@
 * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 */
 
-#ifndef _lorabase_au921_h_
-#define _lorabase_au921_h_
+#ifndef _lorabase_au915_h_
+#define _lorabase_au915_h_
 
 #ifndef _LMIC_CONFIG_PRECONDITIONS_H_
 # include "lmic_config_preconditions.h"
@@ -37,53 +37,53 @@
 
 /****************************************************************************\
 |
-| Basic definitions for AS921 (always in scope)
+| Basic definitions for AU 915 (always in scope)
 |
 \****************************************************************************/
 
-// Frequency plan for AU 921 MHz
-enum _dr_as921_t {
-        AU921_DR_SF12 = 0,
-        AU921_DR_SF11,
-        AU921_DR_SF10,
-        AU921_DR_SF9,
-        AU921_DR_SF8,
-        AU921_DR_SF7,
-        AU921_DR_SF8C,
-        AU921_DR_NONE,
+// Frequency plan for AU 915 MHz
+enum _dr_au915_t {
+        AU915_DR_SF12 = 0,
+        AU915_DR_SF11,
+        AU915_DR_SF10,
+        AU915_DR_SF9,
+        AU915_DR_SF8,
+        AU915_DR_SF7,
+        AU915_DR_SF8C,
+        AU915_DR_NONE,
         // Devices behind a router:
-        AU921_DR_SF12CR = 8,
-        AU921_DR_SF11CR,
-        AU921_DR_SF10CR,
-        AU921_DR_SF9CR,
-        AU921_DR_SF8CR,
-        AU921_DR_SF7CR
+        AU915_DR_SF12CR = 8,
+        AU915_DR_SF11CR,
+        AU915_DR_SF10CR,
+        AU915_DR_SF9CR,
+        AU915_DR_SF8CR,
+        AU915_DR_SF7CR
 };
 
-// Default frequency plan for AU 921MHz
+// Default frequency plan for AU 915MHz
 enum {
-        AU921_125kHz_UPFBASE = 915200000,
-        AU921_125kHz_UPFSTEP = 200000,
-        AU921_500kHz_UPFBASE = 915900000,
-        AU921_500kHz_UPFSTEP = 1600000,
-        AU921_500kHz_DNFBASE = 923300000,
-        AU921_500kHz_DNFSTEP = 600000
+        AU915_125kHz_UPFBASE = 915200000,
+        AU915_125kHz_UPFSTEP = 200000,
+        AU915_500kHz_UPFBASE = 915900000,
+        AU915_500kHz_UPFSTEP = 1600000,
+        AU915_500kHz_DNFBASE = 923300000,
+        AU915_500kHz_DNFSTEP = 600000
 };
 enum {
-        AU921_FREQ_MIN = 915000000,
-        AU921_FREQ_MAX = 928000000
+        AU915_FREQ_MIN = 915000000,
+        AU915_FREQ_MAX = 928000000
 };
 enum {
-        AU921_TX_EIRP_MAX_DBM = 30      // 30 dBm
+        AU915_TX_EIRP_MAX_DBM = 30      // 30 dBm
 };
 enum {
         // initial value of UplinkDwellTime before TxParamSetupReq received.
-        AU921_INITIAL_TxParam_UplinkDwellTime = 1,
-        AU921_UPLINK_DWELL_TIME_osticks = sec2osticks(20),
+        AU915_INITIAL_TxParam_UplinkDwellTime = 1,
+        AU915_UPLINK_DWELL_TIME_osticks = sec2osticks(20),
 };
 
-enum { DR_PAGE_AU921 = 0x10 * (LMIC_REGION_au921 - 1) };
+enum { DR_PAGE_AU915 = 0x10 * (LMIC_REGION_au915 - 1) };
 
-enum { AU921_LMIC_REGION_EIRP = 1 };         // region uses EIRP
+enum { AU915_LMIC_REGION_EIRP = 1 };         // region uses EIRP
 
-#endif /* _lorabase_au921_h_ */
\ No newline at end of file
+#endif /* _lorabase_au915_h_ */
\ No newline at end of file
diff --git a/src/lmic/oslmic.h b/src/lmic/oslmic.h
index f6edae0..448b029 100644
--- a/src/lmic/oslmic.h
+++ b/src/lmic/oslmic.h
@@ -119,12 +119,13 @@ void radio_monitor_rssi(ostime_t n, oslmic_radio_rssi_t *pRssi);
 
 //================================================================================
 
-#ifndef RX_RAMPUP
-// RX_RAMPUP specifies the extra time we must allow to set up an RX event due
-// to platform issues. It's specified in units of ostime_t. It must reflect
-// platform jitter and latency, as well as the speed of the LMIC when running
-// on this plaform.
-#define RX_RAMPUP  (us2osticks(2000))
+#ifndef RX_RAMPUP_DEFAULT
+//! \brief RX_RAMPUP_DEFAULT specifies the extra time we must allow to set up an RX event due
+//! to platform issues. It's specified in units of ostime_t. It must reflect
+//! platform jitter and latency, as well as the speed of the LMIC when running
+//! on this plaform. It's not used directly; clients call os_getRadioRxRampup(),
+//! which might adaptively vary this based on observed timeouts.
+#define RX_RAMPUP_DEFAULT  (us2osticks(10000))
 #endif
 
 #ifndef TX_RAMPUP
@@ -132,7 +133,7 @@ void radio_monitor_rssi(ostime_t n, oslmic_radio_rssi_t *pRssi);
 // to platform issues. It's specified in units of ostime_t. It must reflect
 // platform jitter and latency, as well as the speed of the LMIC when running
 // on this plaform.
-#define TX_RAMPUP  (us2osticks(2000))
+#define TX_RAMPUP  (us2osticks(10000))
 #endif
 
 #ifndef OSTICKS_PER_SEC
@@ -196,6 +197,9 @@ void os_setTimedCallback (xref2osjob_t job, ostime_t time, osjobcb_t cb);
 #ifndef os_clearCallback
 void os_clearCallback (xref2osjob_t job);
 #endif
+#ifndef os_getRadioRxRampup
+ostime_t os_getRadioRxRampup (void);
+#endif
 #ifndef os_getTime
 ostime_t os_getTime (void);
 #endif
diff --git a/src/lmic/radio.c b/src/lmic/radio.c
index c97e3aa..fdbbf19 100644
--- a/src/lmic/radio.c
+++ b/src/lmic/radio.c
@@ -249,6 +249,14 @@
 #define SX1276_RSSI_ADJUST_LF   -164            // add to rssi value to get dB (LF)
 #define SX1276_RSSI_ADJUST_HF   -157            // add to rssi value to get dB (HF)
 
+#ifdef CFG_sx1276_radio
+# define SX127X_RSSI_ADJUST_LF  SX1276_RSSI_ADJUST_LF
+# define SX127X_RSSI_ADJUST_HF  SX1276_RSSI_ADJUST_HF
+#else
+# define SX127X_RSSI_ADJUST_LF  SX1272_RSSI_ADJUST
+# define SX127X_RSSI_ADJUST_HF  SX1272_RSSI_ADJUST
+#endif
+
 // per datasheet 2.5.2 (but note that we ought to ask Semtech to confirm, because
 // datasheet is unclear).
 #define SX127X_RX_POWER_UP      us2osticks(500) // delay this long to let the receiver power up.
@@ -459,10 +467,15 @@ static void configLoraModem () {
         // set ModemConfig1
         writeReg(LORARegModemConfig1, mc1);
 
-        mc2 = (SX1272_MC2_SF7 + ((sf-1)<<4));
+        mc2 = (SX1272_MC2_SF7 + ((sf-1)<<4) + ((LMIC.rxsyms >> 8) & 0x3) );
         if (getNocrc(LMIC.rps) == 0) {
             mc2 |= SX1276_MC2_RX_PAYLOAD_CRCON;
         }
+#if CFG_TxContinuousMode
+        // Only for testing
+        // set ModemConfig2 (sf, TxContinuousMode=1, AgcAutoOn=1 SymbTimeoutHi=00)
+        mc2 |= 0x8;
+#endif
         writeReg(LORARegModemConfig2, mc2);
 
         mc3 = SX1276_MC3_AGCAUTO;
@@ -519,15 +532,18 @@ static void configLoraModem () {
         // set ModemConfig1
         writeReg(LORARegModemConfig1, mc1);
 
-        // set ModemConfig2 (sf, AgcAutoOn=1 SymbTimeoutHi=00)
-        writeReg(LORARegModemConfig2, (SX1272_MC2_SF7 + ((sf-1)<<4)) | 0x04);
+        // set ModemConfig2 (sf, AgcAutoOn=1 SymbTimeoutHi)
+        u1_t mc2;
+        mc2 = (SX1272_MC2_SF7 + ((sf-1)<<4)) | 0x04 | ((LMIC.rxsyms >> 8) & 0x3));
 
 #if CFG_TxContinuousMode
         // Only for testing
         // set ModemConfig2 (sf, TxContinuousMode=1, AgcAutoOn=1 SymbTimeoutHi=00)
-        writeReg(LORARegModemConfig2, (SX1272_MC2_SF7 + ((sf-1)<<4)) | 0x06);
+        mc2 |= 0x8;
 #endif
 
+        writeReg(LORARegModemConfig2, mc2);
+
 #else
 #error Missing CFG_sx1272_radio/CFG_sx1276_radio
 #endif /* CFG_sx1272_radio */
@@ -765,6 +781,14 @@ static void txfsk () {
     hal_pin_rxtx(1);
 
     // now we actually start the transmission
+    if (LMIC.txend) {
+        u4_t nLate = hal_waitUntil(LMIC.txend); // busy wait until exact tx time
+        if (nLate > 0) {
+            LMIC.radio.txlate_ticks += nLate;
+            ++LMIC.radio.txlate_count;
+        }
+    }
+    LMICOS_logEventUint32("+Tx FSK", LMIC.dataLen);
     opmode(OPMODE_TX);
 }
 
@@ -809,6 +833,14 @@ static void txlora () {
     hal_pin_rxtx(1);
 
     // now we actually start the transmission
+    if (LMIC.txend) {
+        u4_t nLate = hal_waitUntil(LMIC.txend); // busy wait until exact tx time
+        if (nLate) {
+            LMIC.radio.txlate_ticks += nLate;
+            ++LMIC.radio.txlate_count;
+        }
+    }
+    LMICOS_logEventUint32("+Tx LoRa", LMIC.dataLen);
     opmode(OPMODE_TX);
 
 #if LMIC_DEBUG_LEVEL > 0
@@ -870,6 +902,18 @@ static CONST_TABLE(u1_t, rxlorairqmask)[] = {
     [RXMODE_RSSI]   = 0x00,
 };
 
+//! \brief handle late RX events.
+//! \param nLate is the number of `ostime_t` ticks that the event was late.
+//! \details If nLate is non-zero, increment the count of events, totalize
+//! the number of ticks late, and (if implemented) adjust the estimate of
+//! what would be best to return from `os_getRadioRxRampup()`.
+static void rxlate (u4_t nLate) {
+    if (nLate) {
+            LMIC.radio.rxlate_ticks += nLate;
+            ++LMIC.radio.rxlate_count;
+    }
+}
+
 // start LoRa receiver (time=LMIC.rxtime, timeout=LMIC.rxsyms, result=LMIC.frame[LMIC.dataLen])
 static void rxlora (u1_t rxmode) {
     // select LoRa modem (from sleep mode)
@@ -914,7 +958,7 @@ static void rxlora (u1_t rxmode) {
     }
 
     // set symbol timeout (for single rx)
-    writeReg(LORARegSymbTimeoutLsb, LMIC.rxsyms);
+    writeReg(LORARegSymbTimeoutLsb, (uint8_t) LMIC.rxsyms);
     // set sync word
     writeReg(LORARegSyncWord, LORA_MAC_PREAMBLE);
 
@@ -933,13 +977,16 @@ static void rxlora (u1_t rxmode) {
 
     // now instruct the radio to receive
     if (rxmode == RXMODE_SINGLE) { // single rx
-        hal_waitUntil(LMIC.rxtime); // busy wait until exact rx time
+        u4_t nLate = hal_waitUntil(LMIC.rxtime); // busy wait until exact rx time
         opmode(OPMODE_RX_SINGLE);
+        LMICOS_logEventUint32("+Rx LoRa Single", nLate);
+        rxlate(nLate);
 #if LMIC_DEBUG_LEVEL > 0
         ostime_t now = os_getTime();
         LMIC_DEBUG_PRINTF("start single rx: now-rxtime: %"LMIC_PRId_ostime_t"\n", now - LMIC.rxtime);
 #endif
     } else { // continous rx (scan or rssi)
+        LMICOS_logEventUint32("+Rx LoRa Continuous", rxmode);
         opmode(OPMODE_RX);
     }
 
@@ -963,8 +1010,14 @@ static void rxlora (u1_t rxmode) {
 }
 
 static void rxfsk (u1_t rxmode) {
-    // only single rx (no continuous scanning, no noise sampling)
-    ASSERT( rxmode == RXMODE_SINGLE );
+    // only single or continuous rx (no noise sampling)
+    if (rxmode == RXMODE_SCAN) {
+        // indicate no bytes received.
+        LMIC.dataLen = 0;
+        // complete the request by scheduling the job.
+        os_setCallback(&LMIC.osjob, LMIC.osjob.func);
+    }
+
     // select FSK modem (from sleep mode)
     //writeReg(RegOpMode, 0x00); // (not LoRa)
     opmodeFSK();
@@ -995,8 +1048,15 @@ static void rxfsk (u1_t rxmode) {
     hal_pin_rxtx(0);
 
     // now instruct the radio to receive
-    hal_waitUntil(LMIC.rxtime); // busy wait until exact rx time
-    opmode(OPMODE_RX); // no single rx mode available in FSK
+    if (rxmode == RXMODE_SINGLE) {
+        u4_t nLate = hal_waitUntil(LMIC.rxtime); // busy wait until exact rx time
+        opmode(OPMODE_RX); // no single rx mode available in FSK
+        LMICOS_logEventUint32("+Rx FSK", nLate);
+        rxlate(nLate);
+    } else {
+        LMICOS_logEvent("+Rx FSK Continuous");
+        opmode(OPMODE_RX);
+    }
 }
 
 static void startrx (u1_t rxmode) {
@@ -1210,6 +1270,7 @@ void radio_irq_handler_v2 (u1_t dio, ostime_t now) {
     writeReg(LORARegFifoAddrPtr, 0x00);
     u1_t s = readReg(RegOpMode);
     u1_t c = readReg(LORARegModemConfig2);
+    LMICOS_logEventUint32("+Tx LoRa Continuous", (r << 8) + c);
     opmode(OPMODE_TX);
     return;
 #else /* ! CFG_TxContinuousMode */
@@ -1240,9 +1301,22 @@ void radio_irq_handler_v2 (u1_t dio, ostime_t now) {
             readBuf(RegFifo, LMIC.frame, LMIC.dataLen);
             // read rx quality parameters
             LMIC.snr  = readReg(LORARegPktSnrValue); // SNR [dB] * 4
-            LMIC.rssi = readReg(LORARegPktRssiValue);
-            LMIC_X_DEBUG_PRINTF("RX snr=%u rssi=%d\n", LMIC.snr/4, SX127X_RSSI_ADJUST_HF + LMIC.rssi);
-            LMIC.rssi = LMIC.rssi - 125 + 64; // RSSI [dBm] (-196...+63)
+            u1_t const rRssi = readReg(LORARegPktRssiValue);
+            s2_t rssi = rRssi;
+            if (LMIC.freq > SX127X_FREQ_LF_MAX)
+                rssi += SX127X_RSSI_ADJUST_HF;
+            else
+                rssi += SX127X_RSSI_ADJUST_LF;
+            if (LMIC.snr < 0)
+                rssi = rssi - (-LMIC.snr >> 2);
+            else if (rssi > -100) {
+                // correct nonlinearity -- this is the same as multiplying rRssi * 16/15 initially.
+                rssi += (rRssi / 15);
+            }
+
+            LMIC_X_DEBUG_PRINTF("RX snr=%u rssi=%d\n", LMIC.snr/4, rssi);
+            // ugh compatibility requires a biased range. RSSI
+            LMIC.rssi = (s1_t) (RSSI_OFF + (rssi < -196 ? -196 : rssi > 63 ? 63 : rssi)); // RSSI [dBm] (-196...+63)
         } else if( flags & IRQ_LORA_RXTOUT_MASK ) {
             // indicate timeout
             LMIC.dataLen = 0;
@@ -1260,7 +1334,7 @@ void radio_irq_handler_v2 (u1_t dio, ostime_t now) {
         u1_t flags1 = readReg(FSKRegIrqFlags1);
         u1_t flags2 = readReg(FSKRegIrqFlags2);
 
-        LMICOS_logEventUint32("radio_irq_handler_v2: FSK", (flags2 << UINT32_C(8)) | flags1);
+        LMICOS_logEventUint32("*radio_irq_handler_v2: FSK", ((u2_t)flags2 << 8) | flags1);
 
         if( flags2 & IRQ_FSK2_PACKETSENT_MASK ) {
             // save exact tx time
@@ -1273,8 +1347,9 @@ void radio_irq_handler_v2 (u1_t dio, ostime_t now) {
             // now read the FIFO
             readBuf(RegFifo, LMIC.frame, LMIC.dataLen);
             // read rx quality parameters
-            LMIC.snr  = 0; // determine snr
-            LMIC.rssi = 0; // determine rssi
+            LMIC.snr  = 0;              // SX127x doesn't give SNR for FSK.
+            LMIC.rssi = -64 + RSSI_OFF; // SX127x doesn't give packet RSSI for FSK,
+                                        // so substitute a dummy value.
         } else if( flags1 & IRQ_FSK1_TIMEOUT_MASK ) {
             // indicate timeout
             LMIC.dataLen = 0;
@@ -1304,9 +1379,16 @@ void os_radio (u1_t mode) {
 
       case RADIO_TX:
         // transmit frame now
+        LMIC.txend = 0;
         starttx(); // buf=LMIC.frame, len=LMIC.dataLen
         break;
 
+      case RADIO_TX_AT:
+        if (LMIC.txend == 0)
+            LMIC.txend = 1;
+        starttx();
+        break;
+
       case RADIO_RX:
         // receive frame now (exactly at rxtime)
         startrx(RXMODE_SINGLE); // buf=LMIC.frame, time=LMIC.rxtime, timeout=LMIC.rxsyms
@@ -1319,3 +1401,7 @@ void os_radio (u1_t mode) {
     }
     hal_enableIRQs();
 }
+
+ostime_t os_getRadioRxRampup (void) {
+    return RX_RAMPUP_DEFAULT;
+}