Upgrade to LMIC version 3.2.0
This commit is contained in:
parent
e29477fa7e
commit
513ac44268
|
@ -155,6 +155,7 @@ uint8_t hal_getTxPowerPolicy(u1_t inputPolicy, s1_t requestedPower, u4_t frequen
|
|||
}
|
||||
|
||||
|
||||
|
||||
// -----------------------------------------------------------------------------
|
||||
// SPI
|
||||
|
||||
|
@ -210,6 +211,7 @@ void HAL_ESP32::spiRead(uint8_t cmd, uint8_t *buf, size_t len)
|
|||
ESP_ERROR_CHECK(err);
|
||||
}
|
||||
|
||||
|
||||
// -----------------------------------------------------------------------------
|
||||
// TIME
|
||||
|
||||
|
@ -420,6 +422,12 @@ void hal_enableIRQs()
|
|||
// and don't access any shared data structures
|
||||
}
|
||||
|
||||
void hal_processPendingIRQs()
|
||||
{
|
||||
// nothing to do as interrupt handlers post message to queue
|
||||
// and don't access any shared data structures
|
||||
}
|
||||
|
||||
|
||||
// -----------------------------------------------------------------------------
|
||||
// Synchronization between application code and background task
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -295,7 +295,7 @@ ostime_t calcAirTime (rps_t rps, u1_t plen) {
|
|||
//
|
||||
|
||||
static void setRxsyms (ostime_t rxsyms) {
|
||||
if (rxsyms >= (1u << 10u)) {
|
||||
if (rxsyms >= (((ostime_t)1) << 10u)) {
|
||||
LMIC.rxsyms = (1u << 10u) - 1;
|
||||
} else if (rxsyms < 0) {
|
||||
LMIC.rxsyms = 0;
|
||||
|
@ -721,11 +721,17 @@ static CONST_TABLE(u1_t, macCmdSize)[] = {
|
|||
};
|
||||
|
||||
static u1_t getMacCmdSize(u1_t macCmd) {
|
||||
if (macCmd < 2)
|
||||
return 0;
|
||||
if ((macCmd - 2) >= LENOF_TABLE(macCmdSize))
|
||||
return 0;
|
||||
return TABLE_GET_U1(macCmdSize, macCmd - 2);
|
||||
if (macCmd >= 2) {
|
||||
const unsigned macCmdMinus2 = macCmd - 2u;
|
||||
if (macCmdMinus2 < LENOF_TABLE(macCmdSize)) {
|
||||
// macCmd in table, fetch it's size.
|
||||
return TABLE_GET_U1(macCmdSize, macCmdMinus2);
|
||||
}
|
||||
}
|
||||
// macCmd too small or too large: return zero. Zero is
|
||||
// never a legal command size, so it signals an error
|
||||
// to the caller.
|
||||
return 0;
|
||||
}
|
||||
|
||||
static bit_t
|
||||
|
@ -883,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;
|
||||
|
@ -1855,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;
|
||||
}
|
||||
|
@ -2780,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
|
||||
|
@ -3080,6 +3096,8 @@ int LMIC_getNetworkTimeReference(lmic_time_reference_t *pReference) {
|
|||
pReference->tNetwork = LMIC.netDeviceTime;
|
||||
return 1;
|
||||
}
|
||||
#else
|
||||
LMIC_API_PARAMETER(pReference);
|
||||
#endif // LMIC_ENABLE_DeviceTimeReq
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -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
|
||||
|
@ -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, 0, 99, 10) /* v3.0.99.10 */
|
||||
#define ARDUINO_LMIC_VERSION ARDUINO_LMIC_VERSION_CALC(3, 2, 0, 0) /* v3.2.0 */
|
||||
|
||||
#define ARDUINO_LMIC_VERSION_GET_MAJOR(v) \
|
||||
((((v)*UINT32_C(1)) >> 24u) & 0xFFu)
|
||||
|
@ -730,4 +730,7 @@ DECL_ON_LMIC_EVENT;
|
|||
} // extern "C"
|
||||
#endif
|
||||
|
||||
// names for backward compatibility
|
||||
#include "lmic_compat.h"
|
||||
|
||||
#endif // _lmic_h_
|
||||
|
|
|
@ -0,0 +1,72 @@
|
|||
/*
|
||||
|
||||
Module: lmic_compat.h
|
||||
|
||||
Function:
|
||||
Symbols that are defined for backward compatibility
|
||||
|
||||
Copyright notice and license info:
|
||||
See LICENSE file accompanying this project.
|
||||
|
||||
Author:
|
||||
Terry Moore, MCCI Corporation January 2020
|
||||
|
||||
Description:
|
||||
This include file centralizes backwards compatibility
|
||||
definitions. The idea is to centralize the decision,
|
||||
so it's clear as to what's deprecated.
|
||||
|
||||
*/
|
||||
|
||||
#ifndef _lmic_compat_h_ /* prevent multiple includes */
|
||||
#define _lmic_compat_h_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"{
|
||||
#endif
|
||||
|
||||
#ifndef ARDUINO_LMIC_VERSION
|
||||
# error "This file is normally included from lmic.h, not stand alone"
|
||||
#endif
|
||||
|
||||
#define LMIC_DEPRECATE(m) _Pragma(#m)
|
||||
|
||||
#if ! defined(LMIC_REGION_au921) && ARDUINO_LMIC_VERSION < ARDUINO_LMIC_VERSION_CALC(5,0,0,0)
|
||||
# define LMIC_REGION_au921 LMIC_DEPRECATE(GCC warning "LMIC_REGION_au921 is deprecated, EOL at V5, use LMIC_REGION_au915") \
|
||||
LMIC_REGION_au915
|
||||
|
||||
// Frequency plan symbols
|
||||
# define AU921_DR_SF12 LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF12
|
||||
# define AU921_DR_SF11 LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF11
|
||||
# define AU921_DR_SF10 LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF10
|
||||
# define AU921_DR_SF9 LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF9
|
||||
# define AU921_DR_SF8 LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF8
|
||||
# define AU921_DR_SF7 LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF7
|
||||
# define AU921_DR_SF8C LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF8C
|
||||
# define AU921_DR_NONE LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_NONE
|
||||
# define AU921_DR_SF12CR LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF12CR
|
||||
# define AU921_DR_SF11CR LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF11CR
|
||||
# define AU921_DR_SF10CR LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF10CR
|
||||
# define AU921_DR_SF9CR LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF9CR
|
||||
# define AU921_DR_SF8CR LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF8CR
|
||||
# define AU921_DR_SF7CR LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF7CR
|
||||
# define AU921_125kHz_UPFBASE LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_125kHz_UPFBASE
|
||||
# define AU921_125kHz_UPFSTEP LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_125kHz_UPFSTEP
|
||||
# define AU921_500kHz_UPFBASE LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_500kHz_UPFBASE
|
||||
# define AU921_500kHz_UPFSTEP LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_500kHz_UPFSTEP
|
||||
# define AU921_500kHz_DNFBASE LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_500kHz_DNFBASE
|
||||
# define AU921_500kHz_DNFSTEP LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_500kHz_DNFSTEP
|
||||
# define AU921_FREQ_MIN LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_FREQ_MIN
|
||||
# define AU921_FREQ_MAX LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_FREQ_MAX
|
||||
# define AU921_TX_EIRP_MAX_DBM LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_TX_EIRP_MAX_DBM
|
||||
# define AU921_INITIAL_TxParam_UplinkDwellTime LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_INITIAL_TxParam_UplinkDwellTime
|
||||
# define AU921_UPLINK_DWELL_TIME_osticks LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_UPLINK_DWELL_TIME_osticks
|
||||
# define DR_PAGE_AU921 LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") DR_PAGE_AU915
|
||||
# define AU921_LMIC_REGION_EIRP LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_LMIC_REGION_EIRP
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* _lmic_compat_h_ */
|
|
@ -659,6 +659,7 @@ void acSetTimer(ostime_t delay) {
|
|||
}
|
||||
|
||||
static void timerExpiredCb(osjob_t *j) {
|
||||
LMIC_API_PARAMETER(j);
|
||||
LMIC_Compliance.eventflags |= LMIC_COMPLIANCE_EVENT_TIMER_EXPIRED;
|
||||
fsmEval();
|
||||
}
|
||||
|
@ -726,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();
|
||||
|
@ -734,6 +735,8 @@ static void acSendUplink(void) {
|
|||
}
|
||||
|
||||
static void sendUplinkCompleteCb(void *pUserData, int fSuccess) {
|
||||
LMIC_API_PARAMETER(pUserData);
|
||||
LMIC_API_PARAMETER(fSuccess);
|
||||
LMIC_Compliance.eventflags |= LMIC_COMPLIANCE_EVENT_UPLINK_COMPLETE;
|
||||
LMIC_COMPLIANCE_PRINTF("%s(%s)\n", __func__, LMICcompliance_txSuccessToString(fSuccess));
|
||||
fsmEvalDeferred();
|
||||
|
|
|
@ -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) {
|
||||
|
|
|
@ -26,6 +26,8 @@
|
|||
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
//! \file
|
||||
|
||||
#define LMIC_DR_LEGACY 0
|
||||
|
||||
#include "lmic.h"
|
||||
|
@ -534,7 +536,7 @@ static void configLoraModem () {
|
|||
|
||||
// set ModemConfig2 (sf, AgcAutoOn=1 SymbTimeoutHi)
|
||||
u1_t mc2;
|
||||
mc2 = (SX1272_MC2_SF7 + ((sf-1)<<4)) | 0x04 | ((LMIC.rxsyms >> 8) & 0x3));
|
||||
mc2 = (SX1272_MC2_SF7 + ((sf-1)<<4)) | 0x04 | ((LMIC.rxsyms >> 8) & 0x3);
|
||||
|
||||
#if CFG_TxContinuousMode
|
||||
// Only for testing
|
||||
|
@ -1070,10 +1072,26 @@ static void startrx (u1_t rxmode) {
|
|||
// or timed out, and the corresponding IRQ will inform us about completion.
|
||||
}
|
||||
|
||||
// get random seed from wideband noise rssi
|
||||
//! \brief Initialize radio at system startup.
|
||||
//!
|
||||
//! \details This procedure is called during initialization by the `os_init()`
|
||||
//! routine. It does a hardware reset of the radio, checks the version and confirms
|
||||
//! that we're operating a suitable chip, and gets a random seed from wideband
|
||||
//! noise rssi. It then puts the radio to sleep.
|
||||
//!
|
||||
//! \result True if successful, false if it doesn't look like the right radio is attached.
|
||||
//!
|
||||
//! \pre
|
||||
//! Preconditions must be observed, or you'll get hangs during initialization.
|
||||
//!
|
||||
//! - The `hal_pin_..()` functions must be ready for use.
|
||||
//! - The `hal_waitUntl()` function must be ready for use. This may mean that interrupts
|
||||
//! are enabled.
|
||||
//! - The `hal_spi_..()` functions must be ready for use.
|
||||
//!
|
||||
//! Generally, all these are satisfied by a call to `hal_init_with_pinmap()`.
|
||||
//!
|
||||
int radio_init () {
|
||||
hal_disableIRQs();
|
||||
|
||||
requestModuleActive(1);
|
||||
|
||||
// manually reset radio
|
||||
|
@ -1136,7 +1154,6 @@ int radio_init () {
|
|||
|
||||
opmode(OPMODE_SLEEP);
|
||||
|
||||
hal_enableIRQs();
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
@ -1155,19 +1172,23 @@ u1_t radio_rand1 () {
|
|||
}
|
||||
|
||||
u1_t radio_rssi () {
|
||||
hal_disableIRQs();
|
||||
u1_t r = readReg(LORARegRssiValue);
|
||||
hal_enableIRQs();
|
||||
return r;
|
||||
}
|
||||
|
||||
// monitor rssi for specified number of ostime_t ticks, and return statistics
|
||||
// This puts the radio into RX continuous mode, waits long enough for the
|
||||
// oscillators to start and the PLL to lock, and then measures for the specified
|
||||
// period of time. The radio is then returned to idle.
|
||||
//
|
||||
// RSSI returned is expressed in units of dB, and is offset according to the
|
||||
// current radio setting per section 5.5.5 of Semtech 1276 datasheet.
|
||||
/// \brief get the current RSSI on the current channel.
|
||||
///
|
||||
/// monitor rssi for specified number of ostime_t ticks, and return statistics
|
||||
/// This puts the radio into RX continuous mode, waits long enough for the
|
||||
/// oscillators to start and the PLL to lock, and then measures for the specified
|
||||
/// period of time. The radio is then returned to idle.
|
||||
///
|
||||
/// RSSI returned is expressed in units of dB, and is offset according to the
|
||||
/// current radio setting per section 5.5.5 of Semtech 1276 datasheet.
|
||||
///
|
||||
/// \param nTicks How long to monitor
|
||||
/// \param pRssi pointer to structure to fill in with RSSI data.
|
||||
///
|
||||
void radio_monitor_rssi(ostime_t nTicks, oslmic_radio_rssi_t *pRssi) {
|
||||
uint8_t rssiMax, rssiMin;
|
||||
uint16_t rssiSum;
|
||||
|
@ -1205,13 +1226,8 @@ void radio_monitor_rssi(ostime_t nTicks, oslmic_radio_rssi_t *pRssi) {
|
|||
tBegin = os_getTime();
|
||||
rssiMax = 0;
|
||||
|
||||
/* XXX(tanupoo)
|
||||
* In this loop, micros() in os_getTime() returns a past time sometimes.
|
||||
* At least, it happens on Dragino LoRa Mini.
|
||||
* the return value of micros() looks not to be stable in IRQ disabled.
|
||||
* Once it happens, this loop never exit infinitely.
|
||||
* In order to prevent it, it enables IRQ before calling os_getTime(),
|
||||
* disable IRQ again after that.
|
||||
/* Per bug report from tanupoo, it's critical that interrupts be enabled
|
||||
* in the loop below so that `os_getTime()` always advances.
|
||||
*/
|
||||
do {
|
||||
ostime_t now;
|
||||
|
@ -1224,10 +1240,7 @@ void radio_monitor_rssi(ostime_t nTicks, oslmic_radio_rssi_t *pRssi) {
|
|||
rssiMin = rssiNow;
|
||||
rssiSum += rssiNow;
|
||||
++rssiN;
|
||||
// TODO(tmm@mcci.com) move this to os_getTime().
|
||||
hal_enableIRQs();
|
||||
now = os_getTime();
|
||||
hal_disableIRQs();
|
||||
notDone = now - (tBegin + nTicks) < 0;
|
||||
} while (notDone);
|
||||
|
||||
|
@ -1369,8 +1382,32 @@ void radio_irq_handler_v2 (u1_t dio, ostime_t now) {
|
|||
#endif /* ! CFG_TxContinuousMode */
|
||||
}
|
||||
|
||||
/*!
|
||||
|
||||
\brief Initiate a radio operation.
|
||||
|
||||
\param mode Selects the operation to be performed.
|
||||
|
||||
The requested radio operation is initiated. Some operations complete
|
||||
immediately; others require hardware to do work, and don't complete until
|
||||
an interrupt occurs. In that case, `LMIC.osjob` is scheduled. Because the
|
||||
interrupt may occur right away, it's important that the caller initialize
|
||||
`LMIC.osjob` before calling this routine.
|
||||
|
||||
- `RADIO_RST` causes the radio to be put to sleep. No interrupt follows;
|
||||
when control returns, the radio is ready for the next operation.
|
||||
|
||||
- `RADIO_TX` and `RADIO_TX_AT` launch the transmission of a frame. An interrupt will
|
||||
occur, which will cause `LMIC.osjob` to be scheduled with its current
|
||||
function.
|
||||
|
||||
- `RADIO_RX` and `RADIO_RX_ON` launch either single or continuous receives.
|
||||
An interrupt will occur when a packet is recieved or the receive times out,
|
||||
which will cause `LMIC.osjob` to be scheduled with its current function.
|
||||
|
||||
*/
|
||||
|
||||
void os_radio (u1_t mode) {
|
||||
hal_disableIRQs();
|
||||
switch (mode) {
|
||||
case RADIO_RST:
|
||||
// put radio to sleep
|
||||
|
@ -1399,7 +1436,6 @@ void os_radio (u1_t mode) {
|
|||
startrx(RXMODE_SCAN); // buf=LMIC.frame
|
||||
break;
|
||||
}
|
||||
hal_enableIRQs();
|
||||
}
|
||||
|
||||
ostime_t os_getRadioRxRampup (void) {
|
||||
|
|
Loading…
Reference in New Issue