Integrate development version of 3.0.99
This commit is contained in:
parent
cf94bba4af
commit
1e1cadf400
|
@ -448,3 +448,7 @@ void hal_failed(const char *file, u2_t line)
|
|||
ESP_LOGE(TAG, "%s:%d", file, line);
|
||||
ASSERT(0);
|
||||
}
|
||||
|
||||
uint8_t hal_getTxPowerPolicy(u1_t inputPolicy, s1_t requestedPower, u4_t frequency) {
|
||||
return LMICHAL_radio_tx_power_policy_paboost;
|
||||
}
|
||||
|
|
|
@ -116,22 +116,16 @@
|
|||
|
||||
// define these in lmic_project_config.h to disable the corresponding MAC commands.
|
||||
// Class A
|
||||
//#define DISABLE_MCMD_DCAP_REQ // duty cycle cap
|
||||
//#define DISABLE_MCMD_DN2P_SET // 2nd DN window param
|
||||
//#define DISABLE_MCMD_SNCH_REQ // set new channel
|
||||
//#define DISABLE_MCMD_DutyCycleReq // duty cycle cap
|
||||
//#define DISABLE_MCMD_RXParamSetupReq // 2nd DN window param
|
||||
//#define DISABLE_MCMD_NewChannelReq // set new channel
|
||||
//#define DISABLE_MCMD_DlChannelReq // set downlink channel for RX1 for given uplink channel.
|
||||
//#define DISABLE_MCMD_RXTimingSetupReq // delay between TX and RX
|
||||
// Class B
|
||||
//#define DISABLE_MCMD_PING_SET // set ping freq, automatically disabled by DISABLE_PING
|
||||
//#define DISABLE_MCMD_BCNI_ANS // next beacon start, automatically disabled by DISABLE_BEACON
|
||||
//#define DISABLE_MCMD_PingSlotChannelReq // set ping freq, automatically disabled by DISABLE_PING
|
||||
//#define ENABLE_MCMD_BeaconTimingAns // next beacon start, DEPRECATED, normally disabled by DISABLE_BEACON
|
||||
|
||||
// In LoRaWAN, a gateway applies I/Q inversion on TX, and nodes do the
|
||||
// same on RX. This ensures that gateways can talk to nodes and vice
|
||||
// versa, but gateways will not hear other gateways and nodes will not
|
||||
// hear other nodes. By defining this macro in lmic_project_config.h,
|
||||
// this inversion is disabled and this node can hear other nodes. If
|
||||
// two nodes both have this macro set, they can talk to each other
|
||||
// (but they can no longer hear gateways). This should probably only
|
||||
// be used when debugging and/or when talking to the radio directly
|
||||
// (e.g. like in the "raw" example).
|
||||
// DEPRECATED(tmm@mcci.com); replaced by LMIC.noRXIQinversion (dynamic). Don't define this.
|
||||
//#define DISABLE_INVERT_IQ_ON_RX
|
||||
|
||||
// This allows choosing between multiple included AES implementations.
|
||||
|
@ -178,4 +172,36 @@
|
|||
# define LMIC_ENABLE_DeviceTimeReq 0
|
||||
#endif
|
||||
|
||||
// LMIC_ENABLE_user_events
|
||||
// Enable/disable support for programmable callbacks for events, rx, and tx.
|
||||
// This is always defined, and non-zero to enable. Default is enabled.
|
||||
#if !defined(LMIC_ENABLE_user_events)
|
||||
# define LMIC_ENABLE_user_events 1
|
||||
#endif
|
||||
|
||||
// LMIC_ENABLE_onEvent
|
||||
// Enable/disable support for out-call to user-supplied `onEvent()` function.
|
||||
// This is always defined, and non-zero to enable. Default is enabled.
|
||||
#if !defined(LMIC_ENABLE_onEvent)
|
||||
# define LMIC_ENABLE_onEvent 1
|
||||
#endif
|
||||
|
||||
// LMIC_ENABLE_long_messages
|
||||
// LMIC certification requires that this be enabled.
|
||||
#if !defined(LMIC_ENABLE_long_messages)
|
||||
# define LMIC_ENABLE_long_messages 1 /* PARAM */
|
||||
#endif
|
||||
|
||||
// LMIC_ENABLE_event_logging
|
||||
// LMIC debugging for certification tests requires this, because debug prints affect
|
||||
// timing too dramatically. But normal operation doesn't need this.
|
||||
#if !defined(LMIC_ENABLE_event_logging)
|
||||
# define LMIC_ENABLE_event_logging 0 /* PARAM */
|
||||
#endif
|
||||
|
||||
// LMIC_LORAWAN_SPEC_VERSION
|
||||
#if !defined(LMIC_LORAWAN_SPEC_VERSION)
|
||||
# define LMIC_LORAWAN_SPEC_VERSION LMIC_LORAWAN_SPEC_VERSION_1_0_3
|
||||
#endif
|
||||
|
||||
#endif // _lmic_config_h_
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2016, 2018 MCCI Corporation.
|
||||
* Copyright (c) 2016, 2018-2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -33,10 +33,17 @@
|
|||
# include "oslmic_types.h"
|
||||
#endif
|
||||
|
||||
#ifndef _lmic_env_h_
|
||||
# include "lmic_env.h"
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"{
|
||||
#endif
|
||||
|
||||
// The type of an optional user-defined failure handler routine
|
||||
typedef void LMIC_ABI_STD hal_failure_handler_t(const char* const file, const uint16_t line);
|
||||
|
||||
/*
|
||||
* initialize hardware (IO, SPI, TIMER, IRQ).
|
||||
* This API is deprecated as it uses the const global lmic_pins,
|
||||
|
@ -87,6 +94,11 @@ void hal_disableIRQs (void);
|
|||
*/
|
||||
void hal_enableIRQs (void);
|
||||
|
||||
/*
|
||||
* return CPU interrupt nesting count
|
||||
*/
|
||||
uint8_t hal_getIrqLevel (void);
|
||||
|
||||
/*
|
||||
* put system and CPU in low-power mode, sleep until interrupt.
|
||||
*/
|
||||
|
@ -116,6 +128,12 @@ u1_t hal_checkTimer (u4_t targettime);
|
|||
*/
|
||||
void hal_failed (const char *file, u2_t line);
|
||||
|
||||
/*
|
||||
* set a custom hal failure handler routine. The default behaviour, defined in
|
||||
* hal_failed(), is to halt by looping infintely.
|
||||
*/
|
||||
void hal_set_failure_handler(const hal_failure_handler_t* const);
|
||||
|
||||
/*
|
||||
* get the calibration value for radio_rssi
|
||||
*/
|
||||
|
@ -129,8 +147,27 @@ s1_t hal_getRssiCal (void);
|
|||
*/
|
||||
ostime_t hal_setModuleActive (bit_t val);
|
||||
|
||||
/* find out if we're using Tcxo */
|
||||
bit_t hal_queryUsingTcxo(void);
|
||||
|
||||
/* represent the various radio TX power policy */
|
||||
enum {
|
||||
LMICHAL_radio_tx_power_policy_rfo = 0,
|
||||
LMICHAL_radio_tx_power_policy_paboost = 1,
|
||||
LMICHAL_radio_tx_power_policy_20dBm = 2,
|
||||
};
|
||||
|
||||
/*
|
||||
* query the configuration as to the Tx Power Policy
|
||||
* to be used on this board, given our desires and
|
||||
* requested power.
|
||||
*/
|
||||
uint8_t hal_getTxPowerPolicy(
|
||||
u1_t inputPolicy,
|
||||
s1_t requestedPower,
|
||||
u4_t freq
|
||||
);
|
||||
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
#endif
|
||||
|
|
1750
src/lmic/lmic.c
1750
src/lmic/lmic.c
File diff suppressed because it is too large
Load Diff
357
src/lmic/lmic.h
357
src/lmic/lmic.h
|
@ -103,9 +103,9 @@ extern "C"{
|
|||
|
||||
// Arduino LMIC version
|
||||
#define ARDUINO_LMIC_VERSION_CALC(major, minor, patch, local) \
|
||||
(((major) << 24u) | ((minor) << 16u) | ((patch) << 8u) | (local))
|
||||
(((major) << 24ul) | ((minor) << 16ul) | ((patch) << 8ul) | ((local) << 0ul))
|
||||
|
||||
#define ARDUINO_LMIC_VERSION ARDUINO_LMIC_VERSION_CALC(2, 3, 2, 0) /* v2.3.2 */
|
||||
#define ARDUINO_LMIC_VERSION ARDUINO_LMIC_VERSION_CALC(3, 0, 99, 5) /* v3.0.99.5 */
|
||||
|
||||
#define ARDUINO_LMIC_VERSION_GET_MAJOR(v) \
|
||||
(((v) >> 24u) & 0xFFu)
|
||||
|
@ -122,14 +122,19 @@ extern "C"{
|
|||
//! Only For Antenna Tuning Tests !
|
||||
//#define CFG_TxContinuousMode 1
|
||||
|
||||
enum { MAX_FRAME_LEN = 64 }; //!< Library cap on max frame length
|
||||
// since this was annouunced as the API variable, we keep it. But it's not used,
|
||||
// MAX_LEN_FRAME is what the code uses.
|
||||
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 { LINK_CHECK_CONT = 12 , // continue with this after reported dead link
|
||||
LINK_CHECK_DEAD = 24 , // after this UP frames and no response from NWK assume link is dead
|
||||
LINK_CHECK_INIT = -12 , // UP frame count until we inc datarate
|
||||
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)
|
||||
LINK_CHECK_UNJOIN_MIN = LINK_CHECK_DEAD + 4, // this is the minimum value of LINK_CHECK_UNJOIN if we parameterize
|
||||
LINK_CHECK_UNJOIN = LINK_CHECK_DEAD + (3 * 240), // after this many UP frames and no response, switch to join (by default)
|
||||
LINK_CHECK_INIT = -64 , // UP frame count until we ask for ack (ADR_ACK_LIMIT)
|
||||
LINK_CHECK_OFF =-128 }; // link check disabled
|
||||
|
||||
enum { TIME_RESYNC = 6*128 }; // secs
|
||||
|
@ -153,14 +158,27 @@ struct band_t {
|
|||
};
|
||||
TYPEDEF_xref2band_t; //!< \internal
|
||||
|
||||
struct lmic_saved_adr_state_s {
|
||||
u4_t channelFreq[MAX_CHANNELS];
|
||||
u2_t channelMap;
|
||||
};
|
||||
|
||||
#elif CFG_LMIC_US_like // US915 spectrum =================================================
|
||||
|
||||
enum { MAX_XCHANNELS = 2 }; // extra channels in RAM, channels 0-71 are immutable
|
||||
|
||||
struct lmic_saved_adr_state_s {
|
||||
u2_t channelMap[(72+MAX_XCHANNELS+15)/16]; // enabled bits
|
||||
u2_t activeChannels125khz;
|
||||
u2_t activeChannels500khz;
|
||||
};
|
||||
|
||||
#endif // ==========================================================================
|
||||
|
||||
typedef struct lmic_saved_adr_state_s lmic_saved_adr_state_t;
|
||||
|
||||
// Keep in sync with evdefs.hpp::drChange
|
||||
enum { DRCHG_SET, DRCHG_NOJACC, DRCHG_NOACK, DRCHG_NOADRACK, DRCHG_NWKCMD };
|
||||
enum { DRCHG_SET, DRCHG_NOJACC, DRCHG_NOACK, DRCHG_NOADRACK, DRCHG_NWKCMD, DRCHG_FRAMESIZE };
|
||||
enum { KEEP_TXPOW = -128 };
|
||||
|
||||
|
||||
|
@ -189,14 +207,14 @@ enum { BCN_NONE = 0x00, //!< No beacon received
|
|||
//! Information about the last and previous beacons.
|
||||
struct bcninfo_t {
|
||||
ostime_t txtime; //!< Time when the beacon was sent
|
||||
u4_t time; //!< GPS time in seconds of last beacon (received or surrogate)
|
||||
s4_t lat; //!< Lat field of last beacon (valid only if BCN_FULL set)
|
||||
s4_t lon; //!< Lon field of last beacon (valid only if BCN_FULL set)
|
||||
s1_t rssi; //!< Adjusted RSSI value of last received beacon
|
||||
s1_t snr; //!< Scaled SNR value of last received beacon
|
||||
u1_t flags; //!< Last beacon reception and tracking states. See BCN_* values.
|
||||
u4_t time; //!< GPS time in seconds of last beacon (received or surrogate)
|
||||
//
|
||||
u1_t info; //!< Info field of last beacon (valid only if BCN_FULL set)
|
||||
s4_t lat; //!< Lat field of last beacon (valid only if BCN_FULL set)
|
||||
s4_t lon; //!< Lon field of last beacon (valid only if BCN_FULL set)
|
||||
};
|
||||
#endif // !DISABLE_BEACONS
|
||||
|
||||
|
@ -220,29 +238,99 @@ enum { OP_NONE = 0x0000,
|
|||
OP_NEXTCHNL = 0x0800, // find a new channel
|
||||
OP_LINKDEAD = 0x1000, // link was reported as dead
|
||||
OP_TESTMODE = 0x2000, // developer test mode
|
||||
OP_UNJOIN = 0x4000, // unjoin and rejoin on next engineUpdate().
|
||||
};
|
||||
// TX-RX transaction flags - report back to user
|
||||
enum { TXRX_ACK = 0x80, // confirmed UP frame was acked
|
||||
TXRX_NACK = 0x40, // confirmed UP frame was not acked
|
||||
TXRX_NOPORT = 0x20, // set if a frame with a port was RXed, clr if no frame/no port
|
||||
TXRX_PORT = 0x10, // set if a frame with a port was RXed, LMIC.frame[LMIC.dataBeg-1] => port
|
||||
TXRX_DNW1 = 0x01, // received in 1st DN slot
|
||||
TXRX_LENERR = 0x08, // set if frame was discarded due to length error.
|
||||
TXRX_PING = 0x04, // received in a scheduled RX slot
|
||||
TXRX_DNW2 = 0x02, // received in 2dn DN slot
|
||||
TXRX_PING = 0x04 }; // received in a scheduled RX slot
|
||||
TXRX_DNW1 = 0x01, // received in 1st DN slot
|
||||
};
|
||||
|
||||
// Event types for event callback
|
||||
enum _ev_t { EV_SCAN_TIMEOUT=1, EV_BEACON_FOUND,
|
||||
EV_BEACON_MISSED, EV_BEACON_TRACKED, EV_JOINING,
|
||||
EV_JOINED, EV_RFU1, EV_JOIN_FAILED, EV_REJOIN_FAILED,
|
||||
EV_TXCOMPLETE, EV_LOST_TSYNC, EV_RESET,
|
||||
EV_RXCOMPLETE, EV_LINK_DEAD, EV_LINK_ALIVE, EV_SCAN_FOUND,
|
||||
EV_TXSTART };
|
||||
EV_TXSTART, EV_TXCANCELED, EV_RXSTART, EV_JOIN_TXCOMPLETE };
|
||||
typedef enum _ev_t ev_t;
|
||||
|
||||
// this macro can be used to initalize a normal table of event strings
|
||||
#define LMIC_EVENT_NAME_TABLE__INIT \
|
||||
"<<zero>>", \
|
||||
"EV_SCAN_TIMEOUT", "EV_BEACON_FOUND", \
|
||||
"EV_BEACON_MISSED", "EV_BEACON_TRACKED", "EV_JOINING", \
|
||||
"EV_JOINED", "EV_RFU1", "EV_JOIN_FAILED", "EV_REJOIN_FAILED", \
|
||||
"EV_TXCOMPLETE", "EV_LOST_TSYNC", "EV_RESET", \
|
||||
"EV_RXCOMPLETE", "EV_LINK_DEAD", "EV_LINK_ALIVE", "EV_SCAN_FOUND", \
|
||||
"EV_TXSTART", "EV_TXCANCELED", "EV_RXSTART", "EV_JOIN_TXCOMPLETE"
|
||||
|
||||
// if working on an AVR (or worried about it), you can use this multi-zero
|
||||
// string and put this in a single const F() string. Index through this
|
||||
// counting up from 0, until you get to the entry you want or to an
|
||||
// entry that begins with a \0.
|
||||
#define LMIC_EVENT_NAME_MULTISZ__INIT \
|
||||
"<<zero>>\0" \
|
||||
"EV_SCAN_TIMEOUT\0" "EV_BEACON_FOUND\0" \
|
||||
"EV_BEACON_MISSED\0" "EV_BEACON_TRACKED\0" "EV_JOINING\0" \
|
||||
"EV_JOINED\0" "EV_RFU1\0" "EV_JOIN_FAILED\0" "EV_REJOIN_FAILED\0" \
|
||||
"EV_TXCOMPLETE\0" "EV_LOST_TSYNC\0" "EV_RESET\0" \
|
||||
"EV_RXCOMPLETE\0" "EV_LINK_DEAD\0" "EV_LINK_ALIVE\0" "EV_SCAN_FOUND\0" \
|
||||
"EV_TXSTART\0" "EV_TXCANCELED\0" "EV_RXSTART\0" "EV_JOIN_TXCOMPLETE\0"
|
||||
|
||||
enum {
|
||||
LMIC_ERROR_SUCCESS = 0,
|
||||
LMIC_ERROR_TX_BUSY = -1,
|
||||
LMIC_ERROR_TX_TOO_LARGE = -2,
|
||||
LMIC_ERROR_TX_NOT_FEASIBLE = -3,
|
||||
LMIC_ERROR_TX_FAILED = -4,
|
||||
};
|
||||
|
||||
typedef int lmic_tx_error_t;
|
||||
|
||||
#define LMIC_ERROR_NAME__INIT \
|
||||
"LMIC_ERROR_SUCCESS", \
|
||||
"LMIC_ERROR_TX_BUSY", \
|
||||
"LMIC_ERROR_TX_TOO_LARGE", \
|
||||
"LMIC_ERROR_TX_NOT_FEASIBLE", \
|
||||
"LMIC_ERROR_TX_FAILED"
|
||||
|
||||
#define LMIC_ERROR_NAME_MULTISZ__INIT \
|
||||
"LMIC_ERROR_SUCCESS\0" \
|
||||
"LMIC_ERROR_TX_BUSY\0" \
|
||||
"LMIC_ERROR_TX_TOO_LARGE\0" \
|
||||
"LMIC_ERROR_TX_NOT_FEASIBLE\0" \
|
||||
"LMIC_ERROR_TX_FAILED"
|
||||
|
||||
enum {
|
||||
LMIC_BEACON_ERROR_INVALID = -2,
|
||||
LMIC_BEACON_ERROR_WRONG_NETWORK = -1,
|
||||
LMIC_BEACON_ERROR_SUCCESS_PARTIAL = 0,
|
||||
LMIC_BEACON_ERROR_SUCCESS_FULL = 1,
|
||||
};
|
||||
|
||||
typedef s1_t lmic_beacon_error_t;
|
||||
|
||||
static inline bit_t LMIC_BEACON_SUCCESSFUL(lmic_beacon_error_t e) {
|
||||
return e < 0;
|
||||
}
|
||||
|
||||
enum {
|
||||
// This value represents 100% error in LMIC.clockError
|
||||
MAX_CLOCK_ERROR = 65536,
|
||||
};
|
||||
|
||||
// callbacks for client alerts.
|
||||
// types and functions are always defined, to reduce #ifs in example code and libraries.
|
||||
typedef void LMIC_ABI_STD lmic_rxmessage_cb_t(void *pUserData, uint8_t port, const uint8_t *pMessage, size_t nMessage);
|
||||
typedef void LMIC_ABI_STD lmic_txmessage_cb_t(void *pUserData, int fSuccess);
|
||||
typedef void LMIC_ABI_STD lmic_event_cb_t(void *pUserData, ev_t e);
|
||||
|
||||
// network time request callback function
|
||||
// defined unconditionally, because APIs and types can't change based on config.
|
||||
// This is called when a time-request succeeds or when we get a downlink
|
||||
|
@ -272,29 +360,123 @@ enum lmic_request_time_state_e {
|
|||
|
||||
typedef u1_t lmic_request_time_state_t;
|
||||
|
||||
enum lmic_engine_update_state_e {
|
||||
lmic_EngineUpdateState_idle = 0, // engineUpdate is idle.
|
||||
lmic_EngineUpdateState_busy = 1, // engineUpdate is busy, but has not been reentered.
|
||||
lmic_EngineUpdateState_again = 2, // engineUpdate is busy, and has to be evaluated again.
|
||||
};
|
||||
|
||||
typedef u1_t lmic_engine_update_state_t;
|
||||
|
||||
/*
|
||||
|
||||
Structure: lmic_client_data_t
|
||||
|
||||
Function:
|
||||
Holds LMIC client data that must live through LMIC_reset().
|
||||
|
||||
Description:
|
||||
There are a variety of client registration linkage items that
|
||||
must live through LMIC_reset(), because LMIC_reset() is called
|
||||
at frame rollover time. We group them together into a structure
|
||||
to make copies easy.
|
||||
|
||||
*/
|
||||
|
||||
//! abstract type for collection of client data that survives LMIC_reset().
|
||||
typedef struct lmic_client_data_s lmic_client_data_t;
|
||||
|
||||
//! contents of lmic_client_data_t
|
||||
struct lmic_client_data_s {
|
||||
|
||||
/* pointer-width things come first */
|
||||
#if LMIC_ENABLE_DeviceTimeReq
|
||||
lmic_request_network_time_cb_t *pNetworkTimeCb; //! call-back routine for network time
|
||||
void *pNetworkTimeUserData; //! call-back data for network time.
|
||||
#endif
|
||||
|
||||
#if LMIC_ENABLE_user_events
|
||||
lmic_event_cb_t *eventCb; //! user-supplied callback function for events.
|
||||
void *eventUserData; //! data for eventCb
|
||||
lmic_rxmessage_cb_t *rxMessageCb; //! user-supplied message-received callback
|
||||
void *rxMessageUserData; //! data for rxMessageCb
|
||||
lmic_txmessage_cb_t *txMessageCb; //! transmit-complete message handler; reset on each tx complete.
|
||||
void *txMessageUserData; //! data for txMessageCb.
|
||||
#endif // LMIC_ENABLE_user_events
|
||||
|
||||
/* next we have things that are (u)int32_t */
|
||||
/* none at the moment */
|
||||
|
||||
/* next we have things that are (u)int16_t */
|
||||
|
||||
u2_t clockError; //! Inaccuracy in the clock. CLOCK_ERROR_MAX represents +/-100% error
|
||||
|
||||
/* finally, things that are (u)int8_t */
|
||||
/* none at the moment */
|
||||
};
|
||||
|
||||
/*
|
||||
|
||||
Structure: lmic_t
|
||||
|
||||
Function:
|
||||
Provides the instance data for the LMIC.
|
||||
|
||||
*/
|
||||
|
||||
struct lmic_t {
|
||||
// client setup data, survives LMIC_reset().
|
||||
lmic_client_data_t client;
|
||||
|
||||
// the OS job object. pointer alignment.
|
||||
osjob_t osjob;
|
||||
|
||||
#if !defined(DISABLE_BEACONS)
|
||||
bcninfo_t bcninfo; // Last received beacon info
|
||||
#endif
|
||||
|
||||
#if !defined(DISABLE_PING)
|
||||
rxsched_t ping; // pingable setup
|
||||
#endif
|
||||
|
||||
/* (u)int32_t things */
|
||||
|
||||
// Radio settings TX/RX (also accessed by HAL)
|
||||
ostime_t txend;
|
||||
ostime_t rxtime;
|
||||
|
||||
// LBT info
|
||||
ostime_t lbt_ticks; // ticks to listen
|
||||
s1_t lbt_dbmax; // max permissible dB on our channel (eg -80)
|
||||
|
||||
u4_t freq;
|
||||
s1_t rssi;
|
||||
s1_t snr; // LMIC.snr is SNR times 4
|
||||
rps_t rps;
|
||||
u1_t rxsyms;
|
||||
u1_t dndr;
|
||||
s1_t txpow; // dBm
|
||||
|
||||
osjob_t osjob;
|
||||
ostime_t globalDutyAvail; // time device can send again
|
||||
|
||||
// Channel scheduling
|
||||
u4_t netid; // current network id (~0 - none)
|
||||
devaddr_t devaddr;
|
||||
u4_t seqnoDn; // device level down stream seqno
|
||||
u4_t seqnoUp;
|
||||
u4_t dn2Freq;
|
||||
|
||||
#if !defined(DISABLE_BEACONS)
|
||||
ostime_t bcnRxtime;
|
||||
#endif
|
||||
|
||||
#if LMIC_ENABLE_DeviceTimeReq
|
||||
// put here for alignment, to reduce RAM use.
|
||||
ostime_t localDeviceTime; // the LMIC.txend value for last DeviceTimeAns
|
||||
lmic_gpstime_t netDeviceTime; // the netDeviceTime for lastDeviceTimeAns
|
||||
// zero ==> not valid.
|
||||
#endif // LMIC_ENABLE_DeviceTimeReq
|
||||
|
||||
// Channel scheduling -- very much private
|
||||
#if CFG_LMIC_EU_like
|
||||
band_t bands[MAX_BANDS];
|
||||
u4_t channelFreq[MAX_CHANNELS];
|
||||
#if !defined(DISABLE_MCMD_DlChannelReq)
|
||||
u4_t channelDlFreq[MAX_CHANNELS];
|
||||
#endif
|
||||
// bit map of enabled datarates for each channel
|
||||
u2_t channelDrMap[MAX_CHANNELS];
|
||||
u2_t channelMap;
|
||||
#elif CFG_LMIC_US_like
|
||||
|
@ -304,66 +486,70 @@ struct lmic_t {
|
|||
u2_t activeChannels125khz;
|
||||
u2_t activeChannels500khz;
|
||||
#endif
|
||||
|
||||
/* (u)int16_t things */
|
||||
rps_t rps; // radio parameter selections: SF, BW, CodingRate, NoCrc, implicit hdr
|
||||
u2_t opmode; // engineUpdate() operating mode flags
|
||||
u2_t devNonce; // last generated nonce
|
||||
|
||||
s2_t adrAckReq; // counter for link integrity tracking (LINK_CHECK_OFF=off)
|
||||
|
||||
#if !defined(DISABLE_BEACONS)
|
||||
s2_t drift; // last measured drift
|
||||
s2_t lastDriftDiff;
|
||||
s2_t maxDriftDiff;
|
||||
#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;
|
||||
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
|
||||
// also adjusted for EIRP/antenna gain considerations.
|
||||
// This is just the radio's idea of power. So if you are
|
||||
// controlling EIRP, and you have 3 dB antenna gain, this
|
||||
// needs to reduced by 3 dB.
|
||||
s1_t lbt_dbmax; // max permissible dB on our channel (eg -80)
|
||||
|
||||
u1_t txChnl; // channel for next TX
|
||||
u1_t globalDutyRate; // max rate: 1/2^k
|
||||
ostime_t globalDutyAvail; // time device can send again
|
||||
|
||||
u4_t netid; // current network id (~0 - none)
|
||||
u2_t opmode;
|
||||
u1_t upRepeat; // configured up repeat
|
||||
s1_t adrTxPow; // ADR adjusted TX power
|
||||
u1_t datarate; // current data rate
|
||||
u1_t errcr; // error coding rate (used for TX only)
|
||||
u1_t rejoinCnt; // adjustment for rejoin datarate
|
||||
#if !defined(DISABLE_BEACONS)
|
||||
s2_t drift; // last measured drift
|
||||
s2_t lastDriftDiff;
|
||||
s2_t maxDriftDiff;
|
||||
#endif
|
||||
|
||||
u2_t clockError; // Inaccuracy in the clock. CLOCK_ERROR_MAX
|
||||
// represents +/-100% error
|
||||
u1_t upRepeatCount; // current up-repeat
|
||||
bit_t initBandplanAfterReset; // cleared by LMIC_reset(), set by first join. See issue #244
|
||||
|
||||
u1_t pendTxPort;
|
||||
u1_t pendTxConf; // confirmed data
|
||||
u1_t pendTxLen; // +0x80 = confirmed
|
||||
u1_t pendTxLen; // count of bytes in pendTxData.
|
||||
u1_t pendTxData[MAX_LEN_PAYLOAD];
|
||||
|
||||
u2_t devNonce; // last generated nonce
|
||||
u1_t pendMacLen; // number of bytes of pending Mac response data
|
||||
bit_t pendMacPiggyback; // received on port 0 or piggyback?
|
||||
// response data if piggybacked
|
||||
u1_t pendMacData[LWAN_FCtrl_FOptsLen_MAX];
|
||||
|
||||
u1_t nwkKey[16]; // network session key
|
||||
u1_t artKey[16]; // application router session key
|
||||
devaddr_t devaddr;
|
||||
u4_t seqnoDn; // device level down stream seqno
|
||||
u4_t seqnoUp;
|
||||
#if LMIC_ENABLE_DeviceTimeReq
|
||||
// put here for alignment, to reduce RAM use.
|
||||
ostime_t localDeviceTime; // the LMIC.txend value for last DeviceTimeAns
|
||||
lmic_gpstime_t netDeviceTime; // the netDeviceTime for lastDeviceTimeAns
|
||||
// zero ==> not valid.
|
||||
lmic_request_network_time_cb_t *pNetworkTimeCb; // call-back routine
|
||||
void *pNetworkTimeUserData; // call-back data
|
||||
#endif // LMIC_ENABLE_DeviceTimeReq
|
||||
|
||||
u1_t dnConf; // dn frame confirm pending: LORA::FCT_ACK or 0
|
||||
s1_t adrAckReq; // counter until we reset data rate (0=off)
|
||||
u1_t lastDnConf; // downlink with seqnoDn-1 requested confirmation
|
||||
u1_t adrChanged;
|
||||
|
||||
u1_t rxDelay; // Rx delay after TX
|
||||
|
||||
u1_t margin;
|
||||
bit_t ladrAns; // link adr adapt answer pending
|
||||
bit_t devsAns; // device status answer pending
|
||||
s1_t devAnsMargin; // SNR value between -32 and 31 (inclusive) for the last successfully received DevStatusReq command
|
||||
u1_t adrEnabled;
|
||||
u1_t moreData; // NWK has more data pending
|
||||
#if !defined(DISABLE_MCMD_DCAP_REQ)
|
||||
bit_t dutyCapAns; // have to ACK duty cycle settings
|
||||
#endif
|
||||
#if !defined(DISABLE_MCMD_SNCH_REQ)
|
||||
u1_t snchAns; // answer set new channel
|
||||
#endif
|
||||
#if LMIC_ENABLE_TxParamSetupReq
|
||||
bit_t txParamSetupAns; // transmit setup answer pending.
|
||||
u1_t txParam; // the saved TX param byte.
|
||||
#endif
|
||||
#if LMIC_ENABLE_DeviceTimeReq
|
||||
|
@ -376,23 +562,21 @@ struct lmic_t {
|
|||
|
||||
// 2nd RX window (after up stream)
|
||||
u1_t dn2Dr;
|
||||
u4_t dn2Freq;
|
||||
#if !defined(DISABLE_MCMD_DN2P_SET)
|
||||
#if !defined(DISABLE_MCMD_RXParamSetupReq)
|
||||
u1_t dn2Ans; // 0=no answer pend, 0x80+ACKs
|
||||
#endif
|
||||
#if !defined(DISABLE_MCMD_DlChannelReq)
|
||||
u1_t macDlChannelAns; // 0 ==> no answer pending, 0x80+ACK bits
|
||||
#endif
|
||||
#if !defined(DISABLE_MCMD_RXTimingSetupReq)
|
||||
bit_t macRxTimingSetupAns; // 0 ==> no answer pend, non-zero inserts response.
|
||||
#endif
|
||||
|
||||
// Class B state
|
||||
#if !defined(DISABLE_BEACONS)
|
||||
u1_t missedBcns; // unable to track last N beacons
|
||||
u1_t bcninfoTries; // how often to try (scan mode only)
|
||||
#endif
|
||||
#if !defined(DISABLE_MCMD_PING_SET) && !defined(DISABLE_PING)
|
||||
u1_t pingSetAns; // answer set cmd and ACK bits
|
||||
#endif
|
||||
#if !defined(DISABLE_PING)
|
||||
rxsched_t ping; // pingable setup
|
||||
#endif
|
||||
|
||||
// Public part of MAC state
|
||||
u1_t txCnt;
|
||||
u1_t txrxFlags; // transaction flags (TX-RX combo)
|
||||
|
@ -403,11 +587,10 @@ struct lmic_t {
|
|||
#if !defined(DISABLE_BEACONS)
|
||||
u1_t bcnChnl;
|
||||
u1_t bcnRxsyms; //
|
||||
ostime_t bcnRxtime;
|
||||
bcninfo_t bcninfo; // Last received beacon info
|
||||
#endif
|
||||
|
||||
u1_t noRXIQinversion;
|
||||
u1_t saveIrqFlags; // last LoRa IRQ flags
|
||||
};
|
||||
|
||||
//! \var struct lmic_t LMIC
|
||||
|
@ -418,16 +601,20 @@ DECLARE_LMIC; //!< \internal
|
|||
#define DR_RANGE_MAP(drlo,drhi) (((u2_t)0xFFFF<<(drlo)) & ((u2_t)0xFFFF>>(15-(drhi))))
|
||||
bit_t LMIC_setupBand (u1_t bandidx, s1_t txpow, u2_t txcap);
|
||||
bit_t LMIC_setupChannel (u1_t channel, u4_t freq, u2_t drmap, s1_t band);
|
||||
void LMIC_disableChannel (u1_t channel);
|
||||
void LMIC_enableSubBand(u1_t band);
|
||||
void LMIC_enableChannel(u1_t channel);
|
||||
void LMIC_disableSubBand(u1_t band);
|
||||
void LMIC_selectSubBand(u1_t band);
|
||||
bit_t LMIC_disableChannel (u1_t channel);
|
||||
bit_t LMIC_enableSubBand(u1_t band);
|
||||
bit_t LMIC_enableChannel(u1_t channel);
|
||||
bit_t LMIC_disableSubBand(u1_t band);
|
||||
bit_t LMIC_selectSubBand(u1_t band);
|
||||
|
||||
void LMIC_setDrTxpow (dr_t dr, s1_t txpow); // set default/start DR/txpow
|
||||
void LMIC_setAdrMode (bit_t enabled); // set ADR mode (if mobile turn off)
|
||||
|
||||
#if !defined(DISABLE_JOIN)
|
||||
bit_t LMIC_startJoining (void);
|
||||
void LMIC_tryRejoin (void);
|
||||
void LMIC_unjoin (void);
|
||||
void LMIC_unjoinAndRejoin (void);
|
||||
#endif
|
||||
|
||||
void LMIC_shutdown (void);
|
||||
|
@ -435,7 +622,11 @@ void LMIC_init (void);
|
|||
void LMIC_reset (void);
|
||||
void LMIC_clrTxData (void);
|
||||
void LMIC_setTxData (void);
|
||||
int LMIC_setTxData2 (u1_t port, xref2u1_t data, u1_t dlen, u1_t confirmed);
|
||||
void LMIC_setTxData_strict(void);
|
||||
lmic_tx_error_t LMIC_setTxData2(u1_t port, xref2u1_t data, u1_t dlen, u1_t confirmed);
|
||||
lmic_tx_error_t LMIC_setTxData2_strict(u1_t port, xref2u1_t data, u1_t dlen, u1_t confirmed);
|
||||
lmic_tx_error_t LMIC_sendWithCallback(u1_t port, xref2u1_t data, u1_t dlen, u1_t confirmed, lmic_txmessage_cb_t *pCb, void *pUserData);
|
||||
lmic_tx_error_t LMIC_sendWithCallback_strict(u1_t port, xref2u1_t data, u1_t dlen, u1_t confirmed, lmic_txmessage_cb_t *pCb, void *pUserData);
|
||||
void LMIC_sendAlive (void);
|
||||
|
||||
#if !defined(DISABLE_BEACONS)
|
||||
|
@ -447,9 +638,6 @@ void LMIC_disableTracking (void);
|
|||
void LMIC_stopPingable (void);
|
||||
void LMIC_setPingable (u1_t intvExp);
|
||||
#endif
|
||||
#if !defined(DISABLE_JOIN)
|
||||
void LMIC_tryRejoin (void);
|
||||
#endif
|
||||
|
||||
void LMIC_setSession (u4_t netid, devaddr_t devaddr, xref2u1_t nwkKey, xref2u1_t artKey);
|
||||
void LMIC_setLinkCheckMode (bit_t enabled);
|
||||
|
@ -462,11 +650,26 @@ void LMIC_getSessionKeys (u4_t *netid, devaddr_t *devaddr, xref2u1_t nwkKey, xre
|
|||
void LMIC_requestNetworkTime(lmic_request_network_time_cb_t *pCallbackfn, void *pUserData);
|
||||
int LMIC_getNetworkTimeReference(lmic_time_reference_t *pReference);
|
||||
|
||||
int LMIC_registerRxMessageCb(lmic_rxmessage_cb_t *pRxMessageCb, void *pUserData);
|
||||
int LMIC_registerEventCb(lmic_event_cb_t *pEventCb, void *pUserData);
|
||||
|
||||
// APIs for client half of compliance.
|
||||
typedef u1_t lmic_compliance_rx_action_t;
|
||||
|
||||
enum lmic_compliance_rx_action_e {
|
||||
LMIC_COMPLIANCE_RX_ACTION_PROCESS = 0, // process this message normally
|
||||
LMIC_COMPLIANCE_RX_ACTION_START, // enter compliance mode, discard this message
|
||||
LMIC_COMPLIANCE_RX_ACTION_IGNORE, // continue in compliance mode, discard this message
|
||||
LMIC_COMPLIANCE_RX_ACTION_END // exit compliance mode, discard this message
|
||||
};
|
||||
|
||||
lmic_compliance_rx_action_t LMIC_complianceRxMessage(u1_t port, const u1_t *pMessage, size_t nMessage);
|
||||
|
||||
// Declare onEvent() function, to make sure any definition will have the
|
||||
// C conventions, even when in a C++ file.
|
||||
#if LMIC_ENABLE_onEvent
|
||||
DECL_ON_LMIC_EVENT;
|
||||
|
||||
|
||||
#endif /* LMIC_ENABLE_onEvent */
|
||||
|
||||
// Special APIs - for development or testing
|
||||
// !!!See implementation for caveats!!!
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017 MCCI Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -51,19 +51,19 @@ CONST_TABLE(u1_t, _DR2RPS_CRC)[] = {
|
|||
};
|
||||
|
||||
// see table in 2.7.6 -- this assumes UplinkDwellTime = 0.
|
||||
static CONST_TABLE(u1_t, maxFrameLens_dwell0)[] = {
|
||||
static CONST_TABLE(u1_t, maxFrameLens_dwell0)[] = {
|
||||
59+5, // [0]
|
||||
59+5, // [1]
|
||||
59+5, // [2]
|
||||
123+5, // [3]
|
||||
230+5, // [4]
|
||||
230+5, // [5]
|
||||
230+5, // [6]
|
||||
230+5 // [7]
|
||||
250+5, // [4]
|
||||
250+5, // [5]
|
||||
250+5, // [6]
|
||||
250+5 // [7]
|
||||
};
|
||||
|
||||
// see table in 2.7.6 -- this assumes UplinkDwellTime = 1.
|
||||
static CONST_TABLE(u1_t, maxFrameLens_dwell1)[] = {
|
||||
static CONST_TABLE(u1_t, maxFrameLens_dwell1)[] = {
|
||||
0, // [0]
|
||||
0, // [1]
|
||||
19+5, // [2]
|
||||
|
@ -74,18 +74,20 @@ static CONST_TABLE(u1_t, maxFrameLens_dwell1)[] = {
|
|||
250+5 // [7]
|
||||
};
|
||||
|
||||
static uint8_t
|
||||
static uint8_t
|
||||
LMICas923_getUplinkDwellBit(uint8_t mcmd_txparam) {
|
||||
LMIC_API_PARAMETER(mcmd_txparam);
|
||||
if (mcmd_txparam == 0xFF)
|
||||
return AS923_INITIAL_TxParam_UplinkDwellTime;
|
||||
|
||||
return (LMIC.txParam & MCMD_TxParam_TxDWELL_MASK) != 0;
|
||||
return (mcmd_txparam & MCMD_TxParam_TxDWELL_MASK) != 0;
|
||||
}
|
||||
|
||||
static uint8_t
|
||||
static uint8_t
|
||||
LMICas923_getDownlinkDwellBit(uint8_t mcmd_txparam) {
|
||||
LMIC_API_PARAMETER(mcmd_txparam);
|
||||
if (mcmd_txparam == 0xFF)
|
||||
return AS923_INITIAL_TxParam_DownlinkDwellTime;
|
||||
|
||||
return (LMIC.txParam & MCMD_TxParam_RxDWELL_MASK) != 0;
|
||||
return (mcmd_txparam & MCMD_TxParam_RxDWELL_MASK) != 0;
|
||||
}
|
||||
|
||||
uint8_t LMICas923_maxFrameLen(uint8_t dr) {
|
||||
|
@ -95,7 +97,7 @@ uint8_t LMICas923_maxFrameLen(uint8_t dr) {
|
|||
else
|
||||
return TABLE_GET_U1(maxFrameLens_dwell0, dr);
|
||||
} else {
|
||||
return 0xFF;
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -110,7 +112,6 @@ static CONST_TABLE(s1_t, TXPOWLEVELS)[] = {
|
|||
-10, // [5]: MaxEIRP - 10dB
|
||||
-12, // [6]: MaxEIRP - 12dB
|
||||
-14, // [7]: MaxEIRP - 14dB
|
||||
0, 0, 0, 0, 0, 0, 0, 0
|
||||
};
|
||||
|
||||
// from LoRaWAN 5.8: mapping from txParam to MaxEIRP
|
||||
|
@ -119,6 +120,7 @@ static CONST_TABLE(s1_t, TXMAXEIRP)[16] = {
|
|||
};
|
||||
|
||||
static int8_t LMICas923_getMaxEIRP(uint8_t mcmd_txparam) {
|
||||
// if uninitialized, return default.
|
||||
if (mcmd_txparam == 0xFF)
|
||||
return AS923_TX_EIRP_MAX_DBM;
|
||||
else
|
||||
|
@ -127,18 +129,23 @@ static int8_t LMICas923_getMaxEIRP(uint8_t mcmd_txparam) {
|
|||
(mcmd_txparam & MCMD_TxParam_MaxEIRP_MASK) >>
|
||||
MCMD_TxParam_MaxEIRP_SHIFT
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
// translate from an encoded power to an actual power using
|
||||
// the maxeirp setting.
|
||||
// translate from an encoded power to an actual power using
|
||||
// the maxeirp setting; return -128 if not legal.
|
||||
int8_t LMICas923_pow2dBm(uint8_t mcmd_ladr_p1) {
|
||||
s1_t const adj =
|
||||
TABLE_GET_S1(
|
||||
TXPOWLEVELS,
|
||||
(mcmd_ladr_p1&MCMD_LADR_POW_MASK)>>MCMD_LADR_POW_SHIFT
|
||||
);
|
||||
|
||||
return adj;
|
||||
uint8_t const pindex = (mcmd_ladr_p1&MCMD_LinkADRReq_POW_MASK)>>MCMD_LinkADRReq_POW_SHIFT;
|
||||
if (pindex < LENOF_TABLE(TXPOWLEVELS)) {
|
||||
s1_t const adj =
|
||||
TABLE_GET_S1(
|
||||
TXPOWLEVELS,
|
||||
pindex
|
||||
);
|
||||
|
||||
return LMICas923_getMaxEIRP(LMIC.txParam) + adj;
|
||||
} else {
|
||||
return -128;
|
||||
}
|
||||
}
|
||||
|
||||
// only used in this module, but used by variant macro dr2hsym().
|
||||
|
@ -162,7 +169,7 @@ ostime_t LMICas923_dr2hsym(uint8_t dr) {
|
|||
enum { NUM_DEFAULT_CHANNELS = 2 };
|
||||
static CONST_TABLE(u4_t, iniChannelFreq)[NUM_DEFAULT_CHANNELS] = {
|
||||
// Default operational frequencies
|
||||
AS923_F1 | BAND_CENTI,
|
||||
AS923_F1 | BAND_CENTI,
|
||||
AS923_F2 | BAND_CENTI,
|
||||
};
|
||||
|
||||
|
@ -171,6 +178,9 @@ void LMICas923_initDefaultChannels(bit_t join) {
|
|||
LMIC_API_PARAMETER(join);
|
||||
|
||||
os_clearMem(&LMIC.channelFreq, sizeof(LMIC.channelFreq));
|
||||
#if !defined(DISABLE_MCMD_DlChannelReq)
|
||||
os_clearMem(&LMIC.channelDlFreq, sizeof(LMIC.channelDlFreq));
|
||||
#endif // !DISABLE_MCMD_DlChannelReq
|
||||
os_clearMem(&LMIC.channelDrMap, sizeof(LMIC.channelDrMap));
|
||||
os_clearMem(&LMIC.bands, sizeof(LMIC.bands));
|
||||
|
||||
|
@ -217,6 +227,18 @@ bit_t LMIC_setupBand(u1_t bandidx, s1_t txpow, u2_t txcap) {
|
|||
}
|
||||
|
||||
bit_t LMIC_setupChannel(u1_t chidx, u4_t freq, u2_t drmap, s1_t band) {
|
||||
// zero the band bits in freq, just in case.
|
||||
freq &= ~3;
|
||||
|
||||
if (chidx < NUM_DEFAULT_CHANNELS) {
|
||||
// can't disable a default channel.
|
||||
if (freq == 0)
|
||||
return 0;
|
||||
// can't change a default channel.
|
||||
else if (freq != (LMIC.channelFreq[chidx] & ~3))
|
||||
return 0;
|
||||
}
|
||||
bit_t fEnable = (freq != 0);
|
||||
if (chidx >= MAX_CHANNELS)
|
||||
return 0;
|
||||
if (band == -1) {
|
||||
|
@ -226,10 +248,13 @@ bit_t LMIC_setupChannel(u1_t chidx, u4_t freq, u2_t drmap, s1_t band) {
|
|||
freq = (freq&~3) | band;
|
||||
}
|
||||
LMIC.channelFreq[chidx] = freq;
|
||||
LMIC.channelDrMap[chidx] =
|
||||
drmap == 0 ? DR_RANGE_MAP(AS923_DR_SF12, AS923_DR_SF7B)
|
||||
LMIC.channelDrMap[chidx] =
|
||||
drmap == 0 ? DR_RANGE_MAP(AS923_DR_SF12, AS923_DR_SF7B)
|
||||
: drmap;
|
||||
LMIC.channelMap |= 1 << chidx; // enabled right away
|
||||
if (fEnable)
|
||||
LMIC.channelMap |= 1 << chidx; // enabled right away
|
||||
else
|
||||
LMIC.channelMap &= ~(1 << chidx);
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
@ -259,7 +284,9 @@ void LMICas923_setRx1Params(void) {
|
|||
int const txdr = LMIC.dndr;
|
||||
int effective_rx1DrOffset;
|
||||
int candidateDr;
|
||||
|
||||
|
||||
LMICeulike_setRx1Freq();
|
||||
|
||||
effective_rx1DrOffset = LMIC.rx1DrOffset;
|
||||
// per section 2.7.7 of regional, lines 1101:1103:
|
||||
switch (effective_rx1DrOffset) {
|
||||
|
@ -267,22 +294,22 @@ void LMICas923_setRx1Params(void) {
|
|||
case 7: effective_rx1DrOffset = -2; break;
|
||||
default: /* no change */ break;
|
||||
}
|
||||
|
||||
|
||||
// per regional 2.2.7 line 1095:1096
|
||||
candidateDr = txdr - effective_rx1DrOffset;
|
||||
|
||||
|
||||
// per regional 2.2.7 lines 1097:1100
|
||||
if (LMICas923_getDownlinkDwellBit(LMIC.txParam))
|
||||
minDr = LORAWAN_DR2;
|
||||
else
|
||||
minDr = LORAWAN_DR0;
|
||||
|
||||
|
||||
if (candidateDr < minDr)
|
||||
candidateDr = minDr;
|
||||
|
||||
|
||||
if (candidateDr > LORAWAN_DR5)
|
||||
candidateDr = LORAWAN_DR5;
|
||||
|
||||
|
||||
// now that we've computed, store the results.
|
||||
LMIC.dndr = (uint8_t) candidateDr;
|
||||
LMIC.rps = dndr2rps(LMIC.dndr);
|
||||
|
@ -334,23 +361,18 @@ ostime_t LMICas923_nextJoinState(void) {
|
|||
}
|
||||
#endif // !DISABLE_JOIN
|
||||
|
||||
// txDone handling for FSK.
|
||||
void
|
||||
LMICas923_txDoneFSK(ostime_t delay, osjobcb_t func) {
|
||||
LMIC.rxtime = LMIC.txend + delay - PRERX_FSK*us2osticksRound(160);
|
||||
LMIC.rxsyms = RXLEN_FSK;
|
||||
os_setTimedCallback(&LMIC.osjob, LMIC.rxtime - RX_RAMPUP, func);
|
||||
}
|
||||
|
||||
void
|
||||
LMICas923_initJoinLoop(void) {
|
||||
LMIC.txParam = 0xFF;
|
||||
// LMIC.txParam is set to 0xFF by the central code at init time.
|
||||
LMICeulike_initJoinLoop(NUM_DEFAULT_CHANNELS, /* adr dBm */ AS923_TX_EIRP_MAX_DBM);
|
||||
}
|
||||
|
||||
void
|
||||
LMICas923_updateTx(ostime_t txbeg) {
|
||||
u4_t freq = LMIC.channelFreq[LMIC.txChnl];
|
||||
u4_t dwellDelay;
|
||||
u4_t globalDutyDelay;
|
||||
|
||||
// Update global/band specific duty cycle stats
|
||||
ostime_t airtime = calcAirTime(LMIC.rps, LMIC.dataLen);
|
||||
// Update channel/global duty cycle stats
|
||||
|
@ -358,8 +380,18 @@ LMICas923_updateTx(ostime_t txbeg) {
|
|||
LMIC.freq = freq & ~(u4_t)3;
|
||||
LMIC.txpow = LMICas923_getMaxEIRP(LMIC.txParam);
|
||||
band->avail = txbeg + airtime * band->txcap;
|
||||
if (LMIC.globalDutyRate != 0)
|
||||
LMIC.globalDutyAvail = txbeg + (airtime << LMIC.globalDutyRate);
|
||||
dwellDelay = globalDutyDelay = 0;
|
||||
if (LMIC.globalDutyRate != 0) {
|
||||
globalDutyDelay = (airtime << LMIC.globalDutyRate);
|
||||
}
|
||||
if (LMICas923_getUplinkDwellBit(LMIC.txParam)) {
|
||||
dwellDelay = AS923_UPLINK_DWELL_TIME_osticks;
|
||||
}
|
||||
if (dwellDelay > globalDutyDelay) {
|
||||
globalDutyDelay = dwellDelay;
|
||||
}
|
||||
if (globalDutyDelay != 0)
|
||||
LMIC.globalDutyAvail = txbeg + globalDutyDelay;
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017 MCCI Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -52,38 +52,83 @@ CONST_TABLE(u1_t, _DR2RPS_CRC)[] = {
|
|||
MAKERPS(SF9 , BW500, CR_4_5, 0, 0), // [11]
|
||||
MAKERPS(SF8 , BW500, CR_4_5, 0, 0), // [12]
|
||||
MAKERPS(SF7 , BW500, CR_4_5, 0, 0), // [13]
|
||||
ILLEGAL_RPS
|
||||
ILLEGAL_RPS
|
||||
};
|
||||
|
||||
static CONST_TABLE(u1_t, maxFrameLens)[] = {
|
||||
59+5, 59+5, 59+5, 123+5, 230+5, 230+5, 230+5, 255,
|
||||
41+5, 117+5, 230+5, 230+5, 230+5, 230+5 };
|
||||
static CONST_TABLE(u1_t, maxFrameLens_dwell0)[] = {
|
||||
59+5, 59+5, 59+5, 123+5, 250+5, 250+5, 250+5, 0,
|
||||
61+5, 137+5, 250+5, 250+5, 250+5, 250+5 };
|
||||
|
||||
static CONST_TABLE(u1_t, maxFrameLens_dwell1)[] = {
|
||||
0, 0, 19+5, 61+5, 133+5, 250+5, 250+5, 0,
|
||||
61+5, 137+5, 250+5, 250+5, 250+5, 250+5 };
|
||||
|
||||
static bit_t
|
||||
LMICau921_getUplinkDwellBit() {
|
||||
// if uninitialized, return default.
|
||||
if (LMIC.txParam == 0xFF) {
|
||||
return AU921_INITIAL_TxParam_UplinkDwellTime;
|
||||
}
|
||||
return (LMIC.txParam & MCMD_TxParam_TxDWELL_MASK) != 0;
|
||||
}
|
||||
|
||||
uint8_t LMICau921_maxFrameLen(uint8_t dr) {
|
||||
if (dr < LENOF_TABLE(maxFrameLens))
|
||||
return TABLE_GET_U1(maxFrameLens, dr);
|
||||
else
|
||||
return 0xFF;
|
||||
if (LMICau921_getUplinkDwellBit()) {
|
||||
if (dr < LENOF_TABLE(maxFrameLens_dwell0))
|
||||
return TABLE_GET_U1(maxFrameLens_dwell0, dr);
|
||||
else
|
||||
return 0;
|
||||
} else {
|
||||
if (dr < LENOF_TABLE(maxFrameLens_dwell1))
|
||||
return TABLE_GET_U1(maxFrameLens_dwell1, dr);
|
||||
else
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
// from LoRaWAN 5.8: mapping from txParam to MaxEIRP
|
||||
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) {
|
||||
// if uninitialized, return default.
|
||||
if (mcmd_txparam == 0xFF)
|
||||
return AU921_TX_EIRP_MAX_DBM;
|
||||
else
|
||||
return TABLE_GET_S1(
|
||||
TXMAXEIRP,
|
||||
(mcmd_txparam & MCMD_TxParam_MaxEIRP_MASK) >>
|
||||
MCMD_TxParam_MaxEIRP_SHIFT
|
||||
);
|
||||
}
|
||||
|
||||
int8_t LMICau921_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)));
|
||||
}
|
||||
}
|
||||
|
||||
static CONST_TABLE(ostime_t, DR2HSYM_osticks)[] = {
|
||||
us2osticksRound(128 << 7), // DR_SF12
|
||||
us2osticksRound(128 << 7), // DR_SF12
|
||||
us2osticksRound(128 << 6), // DR_SF11
|
||||
us2osticksRound(128 << 5), // DR_SF10
|
||||
us2osticksRound(128 << 4), // DR_SF9
|
||||
us2osticksRound(128 << 3), // DR_SF8
|
||||
us2osticksRound(128 << 2), // DR_SF7
|
||||
us2osticksRound(128 << 4), // DR_SF9
|
||||
us2osticksRound(128 << 3), // DR_SF8
|
||||
us2osticksRound(128 << 2), // DR_SF7
|
||||
us2osticksRound(128 << 1), // DR_SF8C
|
||||
us2osticksRound(128 << 0), // ------
|
||||
us2osticksRound(128 << 0), // ------
|
||||
us2osticksRound(128 << 5), // DR_SF12CR
|
||||
us2osticksRound(128 << 4), // DR_SF11CR
|
||||
us2osticksRound(128 << 3), // DR_SF10CR
|
||||
us2osticksRound(128 << 4), // DR_SF11CR
|
||||
us2osticksRound(128 << 3), // DR_SF10CR
|
||||
us2osticksRound(128 << 2), // DR_SF9CR
|
||||
us2osticksRound(128 << 1), // DR_SF8CR
|
||||
us2osticksRound(128 << 0), // DR_SF7CR
|
||||
};
|
||||
|
||||
// get ostime for symbols based on datarate. This is not like us915,
|
||||
// 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) {
|
||||
|
@ -109,9 +154,11 @@ bit_t LMIC_setupChannel(u1_t chidx, u4_t freq, u2_t drmap, s1_t band) {
|
|||
return 0; // all channels are hardwired.
|
||||
}
|
||||
|
||||
void LMIC_disableChannel(u1_t channel) {
|
||||
bit_t LMIC_disableChannel(u1_t channel) {
|
||||
bit_t result = 0;
|
||||
if (channel < 72) {
|
||||
if (ENABLED_CHANNEL(channel)) {
|
||||
result = 1;
|
||||
if (IS_CHANNEL_125khz(channel))
|
||||
LMIC.activeChannels125khz--;
|
||||
else if (IS_CHANNEL_500khz(channel))
|
||||
|
@ -119,11 +166,14 @@ void LMIC_disableChannel(u1_t channel) {
|
|||
}
|
||||
LMIC.channelMap[channel >> 4] &= ~(1 << (channel & 0xF));
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
void LMIC_enableChannel(u1_t channel) {
|
||||
bit_t LMIC_enableChannel(u1_t channel) {
|
||||
bit_t result = 0;
|
||||
if (channel < 72) {
|
||||
if (!ENABLED_CHANNEL(channel)) {
|
||||
result = 1;
|
||||
if (IS_CHANNEL_125khz(channel))
|
||||
LMIC.activeChannels125khz++;
|
||||
else if (IS_CHANNEL_500khz(channel))
|
||||
|
@ -131,47 +181,57 @@ void LMIC_enableChannel(u1_t channel) {
|
|||
}
|
||||
LMIC.channelMap[channel >> 4] |= (1 << (channel & 0xF));
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
void LMIC_enableSubBand(u1_t band) {
|
||||
bit_t LMIC_enableSubBand(u1_t band) {
|
||||
ASSERT(band < 8);
|
||||
u1_t start = band * 8;
|
||||
u1_t end = start + 8;
|
||||
bit_t result = 0;
|
||||
|
||||
// enable all eight 125 kHz channels in this subband
|
||||
for (int channel = start; channel < end; ++channel)
|
||||
LMIC_enableChannel(channel);
|
||||
result |= LMIC_enableChannel(channel);
|
||||
|
||||
// there's a single 500 kHz channel associated with
|
||||
// each group of 8 125 kHz channels. Enable it, too.
|
||||
LMIC_enableChannel(64 + band);
|
||||
result |= LMIC_enableChannel(64 + band);
|
||||
return result;
|
||||
}
|
||||
void LMIC_disableSubBand(u1_t band) {
|
||||
|
||||
bit_t LMIC_disableSubBand(u1_t band) {
|
||||
ASSERT(band < 8);
|
||||
u1_t start = band * 8;
|
||||
u1_t end = start + 8;
|
||||
bit_t result = 0;
|
||||
|
||||
// disable all eight 125 kHz channels in this subband
|
||||
for (int channel = start; channel < end; ++channel)
|
||||
LMIC_disableChannel(channel);
|
||||
result |= LMIC_disableChannel(channel);
|
||||
|
||||
// there's a single 500 kHz channel associated with
|
||||
// each group of 8 125 kHz channels. Disable it, too.
|
||||
LMIC_disableChannel(64 + band);
|
||||
result |= LMIC_disableChannel(64 + band);
|
||||
return result;
|
||||
}
|
||||
void LMIC_selectSubBand(u1_t band) {
|
||||
|
||||
bit_t LMIC_selectSubBand(u1_t band) {
|
||||
bit_t result = 0;
|
||||
|
||||
ASSERT(band < 8);
|
||||
for (int b = 0; b<8; ++b) {
|
||||
if (band == b)
|
||||
LMIC_enableSubBand(b);
|
||||
result |= LMIC_enableSubBand(b);
|
||||
else
|
||||
LMIC_disableSubBand(b);
|
||||
result |= LMIC_disableSubBand(b);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
void LMICau921_updateTx(ostime_t txbeg) {
|
||||
u1_t chnl = LMIC.txChnl;
|
||||
LMIC.txpow = AU921_TX_EIRP_MAX_DBM;
|
||||
LMIC.txpow = LMICau921_getMaxEIRP(LMIC.txParam);
|
||||
if (chnl < 64) {
|
||||
LMIC.freq = AU921_125kHz_UPFBASE + chnl*AU921_125kHz_UPFSTEP;
|
||||
} else {
|
||||
|
@ -179,10 +239,23 @@ void LMICau921_updateTx(ostime_t txbeg) {
|
|||
LMIC.freq = AU921_500kHz_UPFBASE + (chnl - 64)*AU921_500kHz_UPFSTEP;
|
||||
}
|
||||
|
||||
// Update global duty cycle stats
|
||||
// Update global duty cycle stat and deal with dwell time.
|
||||
u4_t dwellDelay;
|
||||
u4_t globalDutyDelay;
|
||||
dwellDelay = globalDutyDelay = 0;
|
||||
|
||||
if (LMIC.globalDutyRate != 0) {
|
||||
ostime_t airtime = calcAirTime(LMIC.rps, LMIC.dataLen);
|
||||
LMIC.globalDutyAvail = txbeg + (airtime << LMIC.globalDutyRate);
|
||||
globalDutyDelay = txbeg + (airtime << LMIC.globalDutyRate);
|
||||
}
|
||||
if (LMICau921_getUplinkDwellBit(LMIC.txParam)) {
|
||||
dwellDelay = AU921_UPLINK_DWELL_TIME_osticks;
|
||||
}
|
||||
if (dwellDelay > globalDutyDelay) {
|
||||
globalDutyDelay = dwellDelay;
|
||||
}
|
||||
if (globalDutyDelay != 0) {
|
||||
LMIC.globalDutyAvail = txbeg + globalDutyDelay;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -213,6 +286,14 @@ void LMICau921_setRx1Params(void) {
|
|||
LMIC.rps = dndr2rps(LMIC.dndr);
|
||||
}
|
||||
|
||||
void LMICau921_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
|
||||
|
||||
}
|
||||
|
||||
//
|
||||
// END: AU921 related stuff
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017 MCCI Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -41,6 +41,8 @@
|
|||
# include "lmic_bandplan_au921.h"
|
||||
#elif defined(CFG_as923)
|
||||
# include "lmic_bandplan_as923.h"
|
||||
#elif defined(CFG_kr920)
|
||||
# include "lmic_bandplan_kr920.h"
|
||||
#elif defined(CFG_in866)
|
||||
# include "lmic_bandplan_in866.h"
|
||||
#else
|
||||
|
@ -52,8 +54,8 @@
|
|||
# error "DNW2_SAFETY_ZONE not defined by bandplan"
|
||||
#endif
|
||||
|
||||
#ifndef maxFrameLen
|
||||
# error "maxFrameLen() not defined by bandplan"
|
||||
#ifndef LMICbandplan_maxFrameLen
|
||||
# error "LMICbandplan_maxFrameLen() not defined by bandplan"
|
||||
#endif
|
||||
|
||||
#ifndef pow2dBm
|
||||
|
@ -104,6 +106,10 @@
|
|||
# error "LMICbandplan_setBcnRxParams() not defined by bandplan"
|
||||
#endif
|
||||
|
||||
#if !defined(LMICbandplan_canMapChannels)
|
||||
# error "LMICbandplan_canMapChannels() not defined by bandplan"
|
||||
#endif
|
||||
|
||||
#if !defined(LMICbandplan_mapChannels)
|
||||
# error "LMICbandplan_mapChannels() not defined by bandplan"
|
||||
#endif
|
||||
|
@ -143,16 +149,65 @@
|
|||
#if !defined(LMICbandplan_init)
|
||||
# error "LMICbandplan_init() not defined by bandplan"
|
||||
#endif
|
||||
|
||||
#if !defined(LMICbandplan_saveAdrState)
|
||||
# error "LMICbandplan_saveAdrState() not defined by bandplan"
|
||||
#endif
|
||||
|
||||
#if !defined(LMICbandplan_compareAdrState)
|
||||
# error "LMICbandplan_compareAdrState() not defined by bandplan"
|
||||
#endif
|
||||
|
||||
#if !defined(LMICbandplan_restoreAdrState)
|
||||
# error "LMICbandplan_restoreAdrState() not defined by bandplan"
|
||||
#endif
|
||||
|
||||
#if !defined(LMICbandplan_isDataRateFeasible)
|
||||
# error "LMICbandplan_isDataRateFeasible() not defined by bandplan"
|
||||
#endif
|
||||
|
||||
//
|
||||
// Things common to lmic.c code
|
||||
//
|
||||
#define LMICbandplan_MINRX_SYMS_LoRa_ClassA 6
|
||||
#define LMICbandplan_RX_ERROR_ABS_osticks ms2osticks(10)
|
||||
|
||||
// Semtech inherently (by calculating in ms and taking ceilings)
|
||||
// rounds up to the next higher ms. It's a lot easier for us
|
||||
// to just add margin for things like hardware ramp-up time
|
||||
// and clock calibration when running from the LSE and HSI
|
||||
// clocks on an STM32.
|
||||
#define LMICbandplan_RX_EXTRA_MARGIN_osticks us2osticks(2000)
|
||||
|
||||
// probably this should be the same as the Class-A value, but
|
||||
// we have not the means to thoroughly test this. This is the
|
||||
// number of rxsyms used in the computations for ping and beacon
|
||||
// windows.
|
||||
#define LMICbandplan_MINRX_SYMS_LoRa_ClassB 5
|
||||
|
||||
#define LMICbandplan_PAMBL_SYMS 8
|
||||
#define LMICbandplan_PAMBL_FSK 5
|
||||
#define LMICbandplan_PRERX_FSK 1
|
||||
#define LMICbandplan_RXLEN_FSK (1+5+2)
|
||||
|
||||
// Legacy names
|
||||
#if !defined(MINRX_SYMS)
|
||||
#define MINRX_SYMS 5
|
||||
# define MINRX_SYMS LMICbandplan_MINRX_SYMS_LoRa_ClassB
|
||||
#endif // !defined(MINRX_SYMS)
|
||||
#define PAMBL_SYMS 8
|
||||
#define PAMBL_FSK 5
|
||||
#define PRERX_FSK 1
|
||||
#define RXLEN_FSK (1+5+2)
|
||||
#define PAMBL_SYMS LMICbandplan_PAMBL_SYMS
|
||||
#define PAMBL_FSK LMICbandplan_PAMBL_FSK
|
||||
#define PRERX_FSK LMICbandplan_PRERX_FSK
|
||||
#define RXLEN_FSK LMICbandplan_RXLEN_FSK
|
||||
|
||||
// this is regional, but so far all regions are the same
|
||||
#if !defined(LMICbandplan_MAX_FCNT_GAP)
|
||||
# define LMICbandplan_MAX_FCNT_GAP 16384
|
||||
#endif // !defined LWAN_MAX_FCNT_GAP
|
||||
|
||||
// this is probably regional, but for now default can be the same
|
||||
#if !defined(LMICbandplan_TX_RECOVERY_ms)
|
||||
# define LMICbandplan_TX_RECOVERY_ms 500
|
||||
#endif
|
||||
|
||||
#define BCN_INTV_osticks sec2osticks(BCN_INTV_sec)
|
||||
#define TXRX_GUARD_osticks ms2osticks(TXRX_GUARD_ms)
|
||||
|
@ -171,5 +226,7 @@
|
|||
// 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);
|
||||
|
||||
#endif // _lmic_bandplan_h_
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017 MCCI Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -26,15 +26,17 @@
|
|||
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#ifndef _lmic_as923_h_
|
||||
# define _lmic_as923_h_
|
||||
#ifndef _lmic_bandplan_as923_h_
|
||||
# define _lmic_bandplan_as923_h_
|
||||
|
||||
#ifndef _lmic_eu_like_h_
|
||||
# include "lmic_eu_like.h"
|
||||
#endif
|
||||
|
||||
// return maximum frame length (including PHY header) for this data rate (as923); 0 --> not valid dr.
|
||||
uint8_t LMICas923_maxFrameLen(uint8_t dr);
|
||||
#define maxFrameLen(dr) LMICas923_maxFrameLen(dr)
|
||||
// return maximum frame length (including PHY header) for this data rate; 0 --> not valid dr.
|
||||
#define LMICbandplan_maxFrameLen(dr) LMICas923_maxFrameLen(dr)
|
||||
|
||||
int8_t LMICas923_pow2dBm(uint8_t mcmd_ladr_p1);
|
||||
#define pow2dBm(mcmd_ladr_p1) LMICas923_pow2dBm(mcmd_ladr_p1)
|
||||
|
@ -70,13 +72,7 @@ void LMICas923_init(void);
|
|||
|
||||
// override default for LMICbandplan_isFSK()
|
||||
#undef LMICbandplan_isFSK
|
||||
#define LMICbandplan_isFSK() (/* TX datarate */LMIC.rxsyms == AS923_DR_FSK)
|
||||
|
||||
// txDone handling for FSK.
|
||||
void
|
||||
LMICas923_txDoneFSK(ostime_t delay, osjobcb_t func);
|
||||
|
||||
#define LMICbandplan_txDoneFsk(delay, func) LMICas923_txDoneFSK(delay, func)
|
||||
#define LMICbandplan_isFSK() (/* RX datarate */LMIC.dndr == AS923_DR_FSK)
|
||||
|
||||
#define LMICbandplan_getInitialDrJoin() (AS923_DR_SF10)
|
||||
|
||||
|
@ -112,4 +108,4 @@ void LMICas923_updateTx(ostime_t txbeg);
|
|||
ostime_t LMICas923_nextJoinTime(ostime_t now);
|
||||
#define LMICbandplan_nextJoinTime(now) LMICas923_nextJoinTime(now)
|
||||
|
||||
#endif // _lmic_as923_h_
|
||||
#endif // _lmic_bandplan_as923_h_
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017 MCCI Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -26,27 +26,33 @@
|
|||
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#ifndef _lmic_au921_h_
|
||||
# define _lmic_au921_h_
|
||||
#ifndef _lmic_bandplan_au921_h_
|
||||
# define _lmic_bandplan_au921_h_
|
||||
|
||||
// preconditions for lmic_us_like.h
|
||||
#define LMICuslike_getFirst500kHzDR() (AU921_DR_SF8C)
|
||||
|
||||
#define LMICuslike_getFirst500kHzDR() (LORAWAN_DR6)
|
||||
#define LMICuslike_getJoin125kHzDR() (LORAWAN_DR2)
|
||||
|
||||
#ifndef _lmic_us_like_h_
|
||||
# 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);
|
||||
#define maxFrameLen(dr) LMICau921_maxFrameLen(dr)
|
||||
// return maximum frame length (including PHY header) for this data rate; 0 --> not valid dr.
|
||||
#define LMICbandplan_maxFrameLen(dr) LMICau921_maxFrameLen(dr)
|
||||
|
||||
#define pow2dBm(mcmd_ladr_p1) ((s1_t)(30 - (((mcmd_ladr_p1)&MCMD_LADR_POW_MASK)<<1)))
|
||||
int8_t LMICau921_pow2dbm(uint8_t mcmd_ladr_p1);
|
||||
#define pow2dBm(mcmd_ladr_p1) LMICau921_pow2dbm(mcmd_ladr_p1)
|
||||
|
||||
ostime_t LMICau921_dr2hsym(uint8_t dr);
|
||||
#define dr2hsym(dr) LMICau921_dr2hsym(dr)
|
||||
|
||||
|
||||
#define LMICbandplan_getInitialDrJoin() (EU868_DR_SF7)
|
||||
#define LMICbandplan_getInitialDrJoin() (LORAWAN_DR2)
|
||||
|
||||
void LMICau921_initJoinLoop(void);
|
||||
#define LMICbandplan_initJoinLoop() LMICau921_initJoinLoop()
|
||||
|
||||
void LMICau921_setBcnRxParams(void);
|
||||
#define LMICbandplan_setBcnRxParams() LMICau921_setBcnRxParams()
|
||||
|
@ -60,4 +66,4 @@ void LMICau921_setRx1Params(void);
|
|||
void LMICau921_updateTx(ostime_t txbeg);
|
||||
#define LMICbandplan_updateTx(txbeg) LMICau921_updateTx(txbeg)
|
||||
|
||||
#endif // _lmic_au921_h_
|
||||
#endif // _lmic_bandplan_au921_h_
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017 MCCI Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -33,8 +33,10 @@
|
|||
# include "lmic_eu_like.h"
|
||||
#endif
|
||||
|
||||
// return maximum frame length (including PHY header) for this data rate (eu868); 0 --> not valid dr.
|
||||
uint8_t LMICeu868_maxFrameLen(uint8_t dr);
|
||||
#define maxFrameLen(dr) LMICeu868_maxFrameLen(dr)
|
||||
// return maximum frame length (including PHY header) for this data rate; 0 --> not valid dr.
|
||||
#define LMICbandplan_maxFrameLen(dr) LMICeu868_maxFrameLen(dr)
|
||||
|
||||
int8_t LMICeu868_pow2dBm(uint8_t mcmd_ladr_p1);
|
||||
#define pow2dBm(mcmd_ladr_p1) LMICeu868_pow2dBm(mcmd_ladr_p1)
|
||||
|
@ -57,13 +59,7 @@ LMICeu868_isValidBeacon1(const uint8_t *d) {
|
|||
|
||||
// override default for LMICbandplan_isFSK()
|
||||
#undef LMICbandplan_isFSK
|
||||
#define LMICbandplan_isFSK() (/* TX datarate */LMIC.rxsyms == EU868_DR_FSK)
|
||||
|
||||
// txDone handling for FSK.
|
||||
void
|
||||
LMICeu868_txDoneFSK(ostime_t delay, osjobcb_t func);
|
||||
|
||||
#define LMICbandplan_txDoneFsk(delay, func) LMICeu868_txDoneFSK(delay, func)
|
||||
#define LMICbandplan_isFSK() (/* RX datarate */LMIC.dndr == EU868_DR_FSK)
|
||||
|
||||
#define LMICbandplan_getInitialDrJoin() (EU868_DR_SF7)
|
||||
|
||||
|
@ -89,4 +85,7 @@ void LMICeu868_initDefaultChannels(bit_t join);
|
|||
ostime_t LMICeu868_nextJoinTime(ostime_t now);
|
||||
#define LMICbandplan_nextJoinTime(now) LMICeu868_nextJoinTime(now)
|
||||
|
||||
void LMICeu868_setRx1Params(void);
|
||||
#define LMICbandplan_setRx1Params() LMICeu868_setRx1Params()
|
||||
|
||||
#endif // _lmic_eu868_h_
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017 MCCI Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -26,15 +26,17 @@
|
|||
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#ifndef _lmic_in866_h_
|
||||
# define _lmic_in866_h_
|
||||
#ifndef _lmic_bandplan_in866_h_
|
||||
# define _lmic_bandplan_in866_h_
|
||||
|
||||
#ifndef _lmic_eu_like_h_
|
||||
# include "lmic_eu_like.h"
|
||||
#endif
|
||||
|
||||
// return maximum frame length (including PHY header) for this data rate (in866); 0 --> not valid dr.
|
||||
uint8_t LMICin866_maxFrameLen(uint8_t dr);
|
||||
#define maxFrameLen(dr) LMICin866_maxFrameLen(dr)
|
||||
// return maximum frame length (including PHY header) for this data rate; 0 --> not valid dr.
|
||||
#define LMICbandplan_maxFrameLen(dr) LMICin866_maxFrameLen(dr)
|
||||
|
||||
int8_t LMICin866_pow2dBm(uint8_t mcmd_ladr_p1);
|
||||
#define pow2dBm(mcmd_ladr_p1) LMICin866_pow2dBm(mcmd_ladr_p1)
|
||||
|
@ -54,13 +56,7 @@ LMICin866_isValidBeacon1(const uint8_t *d) {
|
|||
|
||||
// override default for LMICbandplan_isFSK()
|
||||
#undef LMICbandplan_isFSK
|
||||
#define LMICbandplan_isFSK() (/* TX datarate */LMIC.rxsyms == IN866_DR_FSK)
|
||||
|
||||
// txDone handling for FSK.
|
||||
void
|
||||
LMICin866_txDoneFSK(ostime_t delay, osjobcb_t func);
|
||||
|
||||
#define LMICbandplan_txDoneFsk(delay, func) LMICin866_txDoneFSK(delay, func)
|
||||
#define LMICbandplan_isFSK() (/* TX datarate */LMIC.dndr == IN866_DR_FSK)
|
||||
|
||||
#define LMICbandplan_getInitialDrJoin() (IN866_DR_SF7)
|
||||
|
||||
|
@ -82,4 +78,7 @@ ostime_t LMICin866_nextJoinState(void);
|
|||
void LMICin866_initDefaultChannels(bit_t join);
|
||||
#define LMICbandplan_initDefaultChannels(join) LMICin866_initDefaultChannels(join)
|
||||
|
||||
#endif // _lmic_in866_h_
|
||||
void LMICin866_setRx1Params(void);
|
||||
#define LMICbandplan_setRx1Params() LMICin866_setRx1Params()
|
||||
|
||||
#endif // _lmic_bandplan_in866_h_
|
||||
|
|
|
@ -0,0 +1,91 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
* * Neither the name of the <organization> nor the
|
||||
* names of its contributors may be used to endorse or promote products
|
||||
* derived from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
|
||||
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#ifndef _lmic_kr920_h_
|
||||
# define _lmic_kr920_h_
|
||||
|
||||
#ifndef _lmic_eu_like_h_
|
||||
# include "lmic_eu_like.h"
|
||||
#endif
|
||||
|
||||
// return maximum frame length (including PHY header) for this data rate (kr920); 0 --> not valid dr.
|
||||
uint8_t LMICkr920_maxFrameLen(uint8_t dr);
|
||||
// return maximum frame length (including PHY header) for this data rate; 0 --> not valid dr.
|
||||
#define LMICbandplan_maxFrameLen(dr) LMICkr920_maxFrameLen(dr)
|
||||
|
||||
int8_t LMICkr920_pow2dBm(uint8_t mcmd_ladr_p1);
|
||||
#define pow2dBm(mcmd_ladr_p1) LMICkr920_pow2dBm(mcmd_ladr_p1)
|
||||
|
||||
// Times for half symbol per DR
|
||||
// Per DR table to minimize rounding errors
|
||||
ostime_t LMICkr920_dr2hsym(uint8_t dr);
|
||||
#define dr2hsym(dr) LMICkr920_dr2hsym(dr)
|
||||
|
||||
|
||||
// TODO(tmm@mcci.com) this looks bogus compared to current 1.02 regional
|
||||
// spec. https://github.com/mcci-catena/arduino-lmic/issues/18
|
||||
static inline int
|
||||
LMICkr920_isValidBeacon1(const uint8_t *d) {
|
||||
return d[OFF_BCN_CRC1] != (u1_t)os_crc16(d, OFF_BCN_CRC1);
|
||||
}
|
||||
|
||||
#undef LMICbandplan_isValidBeacon1
|
||||
#define LMICbandplan_isValidBeacon1(pFrame) LMICkr920_isValidBeacon1(pFrame)
|
||||
|
||||
// override default for LMICbandplan_isFSK()
|
||||
#undef LMICbandplan_isFSK
|
||||
#define LMICbandplan_isFSK() (/* always false */ 0)
|
||||
|
||||
#define LMICbandplan_getInitialDrJoin() (KR920_DR_SF7)
|
||||
|
||||
void LMICkr920_setBcnRxParams(void);
|
||||
#define LMICbandplan_setBcnRxParams() LMICkr920_setBcnRxParams()
|
||||
|
||||
u4_t LMICkr920_convFreq(xref2cu1_t ptr);
|
||||
#define LMICbandplan_convFreq(ptr) LMICkr920_convFreq(ptr)
|
||||
|
||||
void LMICkr920_initJoinLoop(void);
|
||||
#define LMICbandplan_initJoinLoop() LMICkr920_initJoinLoop()
|
||||
|
||||
ostime_t LMICkr920_nextTx(ostime_t now);
|
||||
#define LMICbandplan_nextTx(now) LMICkr920_nextTx(now)
|
||||
|
||||
ostime_t LMICkr920_nextJoinState(void);
|
||||
#define LMICbandplan_nextJoinState() LMICkr920_nextJoinState()
|
||||
|
||||
void LMICkr920_initDefaultChannels(bit_t join);
|
||||
#define LMICbandplan_initDefaultChannels(join) LMICkr920_initDefaultChannels(join)
|
||||
|
||||
void LMICkr920_setRx1Params(void);
|
||||
#define LMICbandplan_setRx1Params() LMICkr920_setRx1Params()
|
||||
|
||||
#undef LMICbandplan_updateTx
|
||||
void LMICkr920_updateTx(ostime_t txbeg);
|
||||
#define LMICbandplan_updateTx(t) LMICkr920_updateTx(t)
|
||||
|
||||
#endif // _lmic_kr920_h_
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017 MCCI Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -26,26 +26,30 @@
|
|||
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#ifndef _lmic_us915_h_
|
||||
# define _lmic_us915_h_
|
||||
#ifndef _lmic_bandplan_us915_h_
|
||||
# define _lmic_bandplan_us915_h_
|
||||
|
||||
// preconditions for lmic_us_like.h
|
||||
#define LMICuslike_getFirst500kHzDR() (US915_DR_SF8C)
|
||||
#define LMICuslike_getFirst500kHzDR() (LORAWAN_DR4)
|
||||
#define LMICuslike_getJoin125kHzDR() (LORAWAN_DR0)
|
||||
|
||||
#ifndef _lmic_us_like_h_
|
||||
# include "lmic_us_like.h"
|
||||
#endif
|
||||
|
||||
// return maximum frame length (including PHY header) for this data rate (us915); 0 --> not valid dr.
|
||||
uint8_t LMICus915_maxFrameLen(uint8_t dr);
|
||||
#define maxFrameLen(dr) LMICus915_maxFrameLen(dr)
|
||||
// return maximum frame length (including PHY header) for this data rate; 0 --> not valid dr.
|
||||
#define LMICbandplan_maxFrameLen(dr) LMICus915_maxFrameLen(dr)
|
||||
|
||||
#define pow2dBm(mcmd_ladr_p1) ((s1_t)(US915_TX_MAX_DBM - (((mcmd_ladr_p1)&MCMD_LADR_POW_MASK)<<1)))
|
||||
int8_t LMICus915_pow2dbm(uint8_t mcmd_ladr_p1);
|
||||
#define pow2dBm(mcmd_ladr_p1) LMICus915_pow2dbm(mcmd_ladr_p1)
|
||||
|
||||
ostime_t LMICus915_dr2hsym(uint8_t dr);
|
||||
#define dr2hsym(dr) LMICus915_dr2hsym(dr)
|
||||
|
||||
|
||||
#define LMICbandplan_getInitialDrJoin() (US915_DR_SF7)
|
||||
#define LMICbandplan_getInitialDrJoin() (LORAWAN_DR0)
|
||||
|
||||
void LMICus915_setBcnRxParams(void);
|
||||
#define LMICbandplan_setBcnRxParams() LMICus915_setBcnRxParams()
|
||||
|
@ -53,10 +57,13 @@ void LMICus915_setBcnRxParams(void);
|
|||
u4_t LMICus915_convFreq(xref2cu1_t ptr);
|
||||
#define LMICbandplan_convFreq(ptr) LMICus915_convFreq(ptr)
|
||||
|
||||
void LMICus915_initJoinLoop(void);
|
||||
#define LMICbandplan_initJoinLoop() LMICus915_initJoinLoop()
|
||||
|
||||
void LMICus915_setRx1Params(void);
|
||||
#define LMICbandplan_setRx1Params() LMICus915_setRx1Params()
|
||||
|
||||
void LMICus915_updateTx(ostime_t txbeg);
|
||||
#define LMICbandplan_updateTx(txbeg) LMICus915_updateTx(txbeg)
|
||||
|
||||
#endif // _lmic_us915_h_
|
||||
#endif // _lmic_bandplan_us915_h_
|
||||
|
|
|
@ -0,0 +1,768 @@
|
|||
/*
|
||||
|
||||
Module: lmic_compliance.c
|
||||
|
||||
Function:
|
||||
Implementation of the compliance engine.
|
||||
|
||||
Copyright notice and license info:
|
||||
See LICENSE file accompanying this project.
|
||||
|
||||
Author:
|
||||
Terry Moore, MCCI Corporation March 2019
|
||||
|
||||
Description:
|
||||
See function descriptions.
|
||||
|
||||
*/
|
||||
|
||||
#include "lmic.h"
|
||||
#include "lmic_compliance.h"
|
||||
#include "lorawan_spec_compliance.h"
|
||||
#include <stdbool.h>
|
||||
#include <string.h>
|
||||
|
||||
#if defined(LMIC_PRINTF_TO)
|
||||
# include <stdio.h>
|
||||
# define LMIC_COMPLIANCE_PRINTF(f, ...) printf(f, ## __VA_ARGS__)
|
||||
#else
|
||||
# define LMIC_COMPLIANCE_PRINTF(f, ...) do { ; } while (0)
|
||||
#endif
|
||||
|
||||
/****************************************************************************\
|
||||
|
|
||||
| Manifest constants and local declarations.
|
||||
|
|
||||
\****************************************************************************/
|
||||
|
||||
static void acEnterActiveMode(void);
|
||||
static void acExitActiveMode(void);
|
||||
static void acSendUplink(void);
|
||||
static void acSetTimer(ostime_t);
|
||||
static void acSendUplinkBuffer(void);
|
||||
static void evActivate(void);
|
||||
static void evDeactivate(void);
|
||||
static void evJoinCommand(void);
|
||||
static void evMessage(const uint8_t *pMessage, size_t nMessage);
|
||||
static lmic_compliance_fsmstate_t fsmDispatch(lmic_compliance_fsmstate_t, bool);
|
||||
static void fsmEval(void);
|
||||
static void fsmEvalDeferred(void);
|
||||
static osjobcbfn_t fsmJobCb;
|
||||
static bool isActivateMessage(const uint8_t *pMessage, size_t nMessage);
|
||||
static void evEchoCommand(const uint8_t *pMessage, size_t nMessage);
|
||||
static lmic_event_cb_t lmicEventCb;
|
||||
static lmic_txmessage_cb_t sendUplinkCompleteCb;
|
||||
static osjobcbfn_t timerExpiredCb;
|
||||
|
||||
/* these are declared global so the optimizer can chuck them without warnings */
|
||||
const char *LMICcompliance_txSuccessToString(int fSuccess);
|
||||
const char * LMICcompliance_fsmstate_getName(lmic_compliance_fsmstate_t state);
|
||||
|
||||
/****************************************************************************\
|
||||
|
|
||||
| Read-only data.
|
||||
|
|
||||
\****************************************************************************/
|
||||
|
||||
/****************************************************************************\
|
||||
|
|
||||
| Variables.
|
||||
|
|
||||
\****************************************************************************/
|
||||
|
||||
lmic_compliance_t LMIC_Compliance;
|
||||
|
||||
/*
|
||||
|
||||
Name: LMIC_complianceRxMessage()
|
||||
|
||||
Function:
|
||||
Add compliance-awareness to LMIC applications by filtering messages.
|
||||
|
||||
Definition:
|
||||
lmic_compliance_rx_action_t LMIC_complianceRxMessage(
|
||||
u1_t port,
|
||||
const u1_t *pMessage,
|
||||
size_t nMessage
|
||||
);
|
||||
|
||||
Description:
|
||||
Clients who want to handle the LoRaWAN compliance protocol on
|
||||
port 224 should call this routine each time a downlink message is
|
||||
received. This function will update the internal compliance state,
|
||||
and return an appropriate action to the user.
|
||||
|
||||
If the result is `LMIC_COMPLIANCE_RX_ACTION_PROCESS`, then the client should
|
||||
process the message as usual. Otherwise, the client should discard the
|
||||
message. The other values further allow the client to track entry into,
|
||||
and exit from, compliance state. `LMIC_COMPLIANCE_RX_ACTION_START` signals
|
||||
entry into compliance state; `LMIC_COMPLIANCE_RX_ACTION_END` signals exit
|
||||
from compliance state; and `LMIC_COMPLIANCE_RX_ACTION_IGNORE` indicates
|
||||
a mesage that should be discarded while already in compliance
|
||||
state.
|
||||
|
||||
Returns:
|
||||
See description.
|
||||
|
||||
*/
|
||||
|
||||
lmic_compliance_rx_action_t
|
||||
LMIC_complianceRxMessage(
|
||||
uint8_t port,
|
||||
const uint8_t *pMessage,
|
||||
size_t nMessage
|
||||
) {
|
||||
lmic_compliance_state_t const complianceState = LMIC_Compliance.state;
|
||||
|
||||
// update the counter used by the status message.
|
||||
++LMIC_Compliance.downlinkCount;
|
||||
|
||||
// filter normal messages.
|
||||
if (port != LORAWAN_PORT_COMPLIANCE) {
|
||||
return lmic_compliance_state_IsActive(complianceState)
|
||||
? LMIC_COMPLIANCE_RX_ACTION_PROCESS
|
||||
: LMIC_COMPLIANCE_RX_ACTION_IGNORE
|
||||
;
|
||||
}
|
||||
|
||||
// it's a message to port 224.
|
||||
// if we're not active, ignore everything but activation messages
|
||||
if (! lmic_compliance_state_IsActive(complianceState)) {
|
||||
if (isActivateMessage(pMessage, nMessage)) {
|
||||
evActivate();
|
||||
} // else ignore.
|
||||
} else {
|
||||
evMessage(pMessage, nMessage);
|
||||
}
|
||||
if (lmic_compliance_state_IsActive(complianceState) == lmic_compliance_state_IsActive(LMIC_Compliance.state))
|
||||
return LMIC_COMPLIANCE_RX_ACTION_IGNORE;
|
||||
else if (! lmic_compliance_state_IsActive(complianceState))
|
||||
return LMIC_COMPLIANCE_RX_ACTION_START;
|
||||
else
|
||||
return LMIC_COMPLIANCE_RX_ACTION_END;
|
||||
}
|
||||
|
||||
/*
|
||||
|
||||
Name: isActivateMessage()
|
||||
|
||||
Function:
|
||||
See whether a message is a LoRaWAN activate test mode message.
|
||||
|
||||
Definition:
|
||||
static bool isActivateMessage(
|
||||
const uint8_t *pMessage,
|
||||
size_t nMessage
|
||||
);
|
||||
|
||||
Description:
|
||||
The message body is compared to an activate message (per the
|
||||
LoRa Alliance End Device Certification spec).
|
||||
|
||||
Returns:
|
||||
The result is `true` if the message is an activation message;
|
||||
it's `false` otherwise.
|
||||
|
||||
*/
|
||||
|
||||
static bool
|
||||
isActivateMessage(
|
||||
const uint8_t *pMessage,
|
||||
size_t nMessage
|
||||
) {
|
||||
const uint8_t body[LORAWAN_COMPLIANCE_CMD_ACTIVATE_LEN] = {
|
||||
LORAWAN_COMPLIANCE_CMD_ACTIVATE,
|
||||
LORAWAN_COMPLIANCE_CMD_ACTIVATE_MAGIC,
|
||||
LORAWAN_COMPLIANCE_CMD_ACTIVATE_MAGIC,
|
||||
LORAWAN_COMPLIANCE_CMD_ACTIVATE_MAGIC,
|
||||
};
|
||||
|
||||
if (nMessage != sizeof(body))
|
||||
return false;
|
||||
|
||||
if (memcmp(pMessage, body, sizeof(body)) == 0)
|
||||
return true;
|
||||
else
|
||||
return false;
|
||||
}
|
||||
|
||||
/*
|
||||
|
||||
Name: evActivate()
|
||||
|
||||
Function:
|
||||
Report an activation event to the finite state machine.
|
||||
|
||||
Definition:
|
||||
void evActivate(void);
|
||||
|
||||
Description:
|
||||
We report an activation event, and re-evaluate the FSM.
|
||||
|
||||
Returns:
|
||||
No explicit result.
|
||||
|
||||
*/
|
||||
|
||||
static void evActivate(void) {
|
||||
if (! lmic_compliance_state_IsActive(LMIC_Compliance.state)) {
|
||||
LMIC_Compliance.downlinkCount = 0;
|
||||
LMIC_Compliance.eventflags |= LMIC_COMPLIANCE_EVENT_ACTIVATE;
|
||||
LMIC_Compliance.state = LMIC_COMPLIANCE_STATE_ACTIVATING;
|
||||
|
||||
LMIC_Compliance.saveEvent.pEventCb = LMIC.client.eventCb;
|
||||
LMIC_Compliance.saveEvent.pUserData = LMIC.client.eventUserData;
|
||||
|
||||
#if CFG_LMIC_EU_like
|
||||
band_t *b = LMIC.bands;
|
||||
lmic_compliance_band_t *b_save = LMIC_Compliance.saveBands;
|
||||
|
||||
for (; b < &LMIC.bands[MAX_BANDS]; ++b, ++b_save) {
|
||||
b_save->txcap = b->txcap;
|
||||
b->txcap = 1;
|
||||
b->avail = os_getTime();
|
||||
}
|
||||
#endif // CFG_LMIC_EU_like
|
||||
|
||||
LMIC_registerEventCb(lmicEventCb, NULL);
|
||||
|
||||
fsmEvalDeferred();
|
||||
} else {
|
||||
LMIC_COMPLIANCE_PRINTF("Redundant ActivateTM message ignored.\n");
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
|
||||
Name: evMessage()
|
||||
|
||||
Function:
|
||||
Process an inbound message while active.
|
||||
|
||||
Definition:
|
||||
void evMessage(const uint8_t *pMessage, size_t nMessage);
|
||||
|
||||
Description:
|
||||
The event is parsed, and the appropriate event(s) are sent into
|
||||
the finite state machine. Note that because of the way the LMIC
|
||||
works, we can assume that no uplink event is pending; so it's safe
|
||||
to launch a send from here.
|
||||
|
||||
Returns:
|
||||
No explicit result.
|
||||
|
||||
*/
|
||||
|
||||
static void evMessage(
|
||||
const uint8_t *pMessage,
|
||||
size_t nMessage
|
||||
) {
|
||||
if (nMessage == 0)
|
||||
return;
|
||||
|
||||
const uint8_t cmd = pMessage[0];
|
||||
switch (cmd) {
|
||||
case LORAWAN_COMPLIANCE_CMD_DEACTIVATE: {
|
||||
evDeactivate();
|
||||
break;
|
||||
}
|
||||
case LORAWAN_COMPLIANCE_CMD_ACTIVATE: {
|
||||
if (isActivateMessage(pMessage, nMessage))
|
||||
evActivate();
|
||||
break;
|
||||
}
|
||||
case LORAWAN_COMPLIANCE_CMD_SET_CONFIRM: {
|
||||
LMIC_Compliance.fsmFlags |= LMIC_COMPLIANCE_FSM_CONFIRM;
|
||||
break;
|
||||
}
|
||||
case LORAWAN_COMPLIANCE_CMD_SET_UNCONFIRM: {
|
||||
LMIC_Compliance.fsmFlags &= ~LMIC_COMPLIANCE_FSM_CONFIRM;
|
||||
break;
|
||||
}
|
||||
case LORAWAN_COMPLIANCE_CMD_ECHO: {
|
||||
evEchoCommand(pMessage, nMessage);
|
||||
break;
|
||||
}
|
||||
case LORAWAN_COMPLIANCE_CMD_LINK: {
|
||||
// not clear what this request does.
|
||||
break;
|
||||
}
|
||||
case LORAWAN_COMPLIANCE_CMD_JOIN: {
|
||||
evJoinCommand();
|
||||
break;
|
||||
}
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
|
||||
Name: evDeactivate()
|
||||
|
||||
Function:
|
||||
Report an deactivation event to the finite state machine.
|
||||
|
||||
Definition:
|
||||
void evDectivate(void);
|
||||
|
||||
Description:
|
||||
We report a deactivation event, and re-evaluate the FSM.
|
||||
We also set a flag so that we're return the appropriate
|
||||
status from the compliance entry point to the real
|
||||
application.
|
||||
|
||||
Returns:
|
||||
No explicit result.
|
||||
|
||||
*/
|
||||
|
||||
static void evDeactivate(void) {
|
||||
LMIC_Compliance.eventflags |= LMIC_COMPLIANCE_EVENT_DEACTIVATE;
|
||||
LMIC_Compliance.state = LMIC_COMPLIANCE_STATE_STOPPING;
|
||||
|
||||
// restore user's event handler.
|
||||
LMIC_registerEventCb(LMIC_Compliance.saveEvent.pEventCb, LMIC_Compliance.saveEvent.pUserData);
|
||||
|
||||
// restore band settings
|
||||
#if CFG_LMIC_EU_like
|
||||
band_t *b = LMIC.bands;
|
||||
lmic_compliance_band_t const *b_save = LMIC_Compliance.saveBands;
|
||||
|
||||
for (; b < &LMIC.bands[MAX_BANDS]; ++b, ++b_save) {
|
||||
b->txcap = b_save->txcap;
|
||||
}
|
||||
#endif // CFG_LMIC_EU_like
|
||||
|
||||
fsmEvalDeferred();
|
||||
}
|
||||
|
||||
/*
|
||||
|
||||
Name: evJoinCommand()
|
||||
|
||||
Function:
|
||||
Report that a join has been commanded.
|
||||
|
||||
Definition:
|
||||
void evJoinCommand(void);
|
||||
|
||||
Description:
|
||||
We unjoin from the network, and then report a deactivation
|
||||
of test mode. That will get us out of test mode and back
|
||||
to the compliance app. The next message send will trigger
|
||||
a join.
|
||||
|
||||
Returns:
|
||||
No explicit result.
|
||||
|
||||
*/
|
||||
|
||||
static void evJoinCommand(
|
||||
void
|
||||
) {
|
||||
LMIC_unjoin();
|
||||
evDeactivate();
|
||||
}
|
||||
|
||||
/*
|
||||
|
||||
Name: evEchoCommand()
|
||||
|
||||
Function:
|
||||
Format and transmit the response to an echo downlink (aka echo request).
|
||||
|
||||
Definition:
|
||||
void evEchoCommand(
|
||||
const uint8_t *pMessage,
|
||||
size_t nMessage
|
||||
);
|
||||
|
||||
Description:
|
||||
The echo response is formatted and transmitted. Since we just received
|
||||
a downlink, it's always safe to do this.
|
||||
|
||||
Returns:
|
||||
No explicit result.
|
||||
|
||||
*/
|
||||
|
||||
static void evEchoCommand(
|
||||
const uint8_t *pMessage,
|
||||
size_t nMessage
|
||||
) {
|
||||
uint8_t *pResponse;
|
||||
|
||||
if (nMessage > sizeof(LMIC_Compliance.uplinkMessage))
|
||||
return;
|
||||
|
||||
// create the echo message.
|
||||
pResponse = LMIC_Compliance.uplinkMessage;
|
||||
|
||||
// copy the command byte unchanged.
|
||||
*pResponse++ = *pMessage++;
|
||||
--nMessage;
|
||||
|
||||
// each byte in the body has to be incremented by one.
|
||||
for (; nMessage > 0; --nMessage) {
|
||||
*pResponse++ = (uint8_t)(*pMessage++ + 1);
|
||||
}
|
||||
|
||||
// now that the message is formatted, tell the fsm to send it;
|
||||
// need to use a separate job.
|
||||
LMIC_Compliance.uplinkSize = (uint8_t) (pResponse - LMIC_Compliance.uplinkMessage);
|
||||
LMIC_Compliance.eventflags |= LMIC_COMPLIANCE_EVENT_ECHO_REQUEST;
|
||||
fsmEvalDeferred();
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
|
||||
Name: fsmEval()
|
||||
|
||||
Function:
|
||||
Evaluate the FSM, preventing recursion.
|
||||
|
||||
Definition:
|
||||
void fsmEval(void);
|
||||
|
||||
Description:
|
||||
We check for a nested call to evaluate the FSM;
|
||||
if detected, the processing is deferred until the
|
||||
current evaluation completes. Otherwise, we start
|
||||
a new FSM evaluation, which proceeds until the FSM
|
||||
returns a "no-change" result.
|
||||
|
||||
Returns:
|
||||
No explicit result.
|
||||
|
||||
*/
|
||||
|
||||
const char * LMICcompliance_fsmstate_getName(lmic_compliance_fsmstate_t state) {
|
||||
const char * const names[] = { LMIC_COMPLIANCE_FSMSTATE__NAMES };
|
||||
|
||||
if ((unsigned) state >= sizeof(names)/sizeof(names[0]))
|
||||
return "<<unknown>>";
|
||||
else
|
||||
return names[state];
|
||||
}
|
||||
|
||||
static void fsmEvalDeferred(void) {
|
||||
os_setCallback(&LMIC_Compliance.fsmJob, fsmJobCb);
|
||||
}
|
||||
|
||||
static void fsmJobCb(osjob_t *j) {
|
||||
LMIC_API_PARAMETER(j);
|
||||
fsmEval();
|
||||
}
|
||||
|
||||
static void fsmEval(void) {
|
||||
bool fNewState;
|
||||
|
||||
// check for reentry.
|
||||
do {
|
||||
lmic_compliance_fsmflags_t const fsmFlags = LMIC_Compliance.fsmFlags;
|
||||
|
||||
if (fsmFlags & LMIC_COMPLIANCE_FSM_ACTIVE) {
|
||||
LMIC_Compliance.fsmFlags = fsmFlags | LMIC_COMPLIANCE_FSM_REENTERED;
|
||||
return;
|
||||
}
|
||||
|
||||
// record that we're active
|
||||
LMIC_Compliance.fsmFlags = fsmFlags | LMIC_COMPLIANCE_FSM_ACTIVE;
|
||||
} while (0);
|
||||
|
||||
// evaluate and change state
|
||||
fNewState = false;
|
||||
for (;;) {
|
||||
lmic_compliance_fsmstate_t const oldState = LMIC_Compliance.fsmState;
|
||||
lmic_compliance_fsmstate_t newState;
|
||||
|
||||
newState = fsmDispatch(oldState, fNewState);
|
||||
|
||||
if (newState == LMIC_COMPLIANCE_FSMSTATE_NOCHANGE) {
|
||||
lmic_compliance_fsmflags_t const fsmFlags = LMIC_Compliance.fsmFlags;
|
||||
|
||||
if ((fsmFlags & LMIC_COMPLIANCE_FSM_REENTERED) == 0) {
|
||||
// not reentered, no change: get out.
|
||||
LMIC_Compliance.fsmFlags = fsmFlags & ~LMIC_COMPLIANCE_FSM_ACTIVE;
|
||||
return;
|
||||
} else {
|
||||
// reentered. reset reentered flag and keep going.
|
||||
LMIC_Compliance.fsmFlags = fsmFlags & ~LMIC_COMPLIANCE_FSM_REENTERED;
|
||||
fNewState = false;
|
||||
}
|
||||
} else {
|
||||
// state change!
|
||||
LMIC_COMPLIANCE_PRINTF("%s: change state %s(%u) => %s(%u)\n",
|
||||
__func__,
|
||||
LMICcompliance_fsmstate_getName(oldState), (unsigned) oldState,
|
||||
LMICcompliance_fsmstate_getName(newState), (unsigned) newState
|
||||
);
|
||||
fNewState = true;
|
||||
LMIC_Compliance.fsmState = newState;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
|
||||
Name: fsmDispatch()
|
||||
|
||||
Function:
|
||||
Dispatch to the appropriate event handler.
|
||||
|
||||
Definition:
|
||||
lmic_compliance_fsmstate_t fsmDispatch(
|
||||
lmic_compliance_fsmstate_t state,
|
||||
bool fEntry
|
||||
);
|
||||
|
||||
Description:
|
||||
This function is called by the evalutator as needed. `state`
|
||||
is set to the current state of the FSM, and `fEntry` is
|
||||
true if and only if this state has just been entered via a
|
||||
transition arrow. (Might be a transition to self.)
|
||||
|
||||
Returns:
|
||||
This function returns LMIC_COMPLIANCE_FSMSTATE_NOCHANGE if
|
||||
the FSM is to remain in this state until an event occurs.
|
||||
Otherwise it returns the new state.
|
||||
|
||||
*/
|
||||
|
||||
static inline lmic_compliance_eventflags_t
|
||||
eventflags_TestAndClear(lmic_compliance_eventflags_t flag) {
|
||||
const lmic_compliance_eventflags_t old = LMIC_Compliance.eventflags;
|
||||
const lmic_compliance_eventflags_t result = old & flag;
|
||||
|
||||
if (result != 0)
|
||||
LMIC_Compliance.eventflags = old ^ result;
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
static lmic_compliance_fsmstate_t
|
||||
fsmDispatch(
|
||||
lmic_compliance_fsmstate_t state,
|
||||
bool fEntry
|
||||
) {
|
||||
lmic_compliance_fsmstate_t newState;
|
||||
|
||||
// currently, this is a stub.
|
||||
newState = LMIC_COMPLIANCE_FSMSTATE_NOCHANGE;
|
||||
|
||||
switch (state) {
|
||||
case LMIC_COMPLIANCE_FSMSTATE_INITIAL: {
|
||||
newState = LMIC_COMPLIANCE_FSMSTATE_INACTIVE;
|
||||
break;
|
||||
}
|
||||
|
||||
case LMIC_COMPLIANCE_FSMSTATE_INACTIVE: {
|
||||
if (fEntry) {
|
||||
acExitActiveMode();
|
||||
}
|
||||
|
||||
if (eventflags_TestAndClear(LMIC_COMPLIANCE_EVENT_ACTIVATE)) {
|
||||
newState = LMIC_COMPLIANCE_FSMSTATE_ACTIVE;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case LMIC_COMPLIANCE_FSMSTATE_ACTIVE: {
|
||||
if (fEntry) {
|
||||
acEnterActiveMode();
|
||||
acSetTimer(sec2osticks(1));
|
||||
}
|
||||
if (eventflags_TestAndClear(LMIC_COMPLIANCE_EVENT_TIMER_EXPIRED)) {
|
||||
newState = LMIC_COMPLIANCE_FSMSTATE_TESTMODE;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case LMIC_COMPLIANCE_FSMSTATE_TXBUSY: {
|
||||
if (fEntry) {
|
||||
acSetTimer(sec2osticks(1));
|
||||
}
|
||||
if (eventflags_TestAndClear(LMIC_COMPLIANCE_EVENT_TIMER_EXPIRED)) {
|
||||
newState = LMIC_COMPLIANCE_FSMSTATE_TESTMODE;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case LMIC_COMPLIANCE_FSMSTATE_TESTMODE: {
|
||||
if (LMIC.opmode & OP_TXDATA) {
|
||||
// go back and wait some more.
|
||||
newState = LMIC_COMPLIANCE_FSMSTATE_TXBUSY;
|
||||
}
|
||||
if (eventflags_TestAndClear(LMIC_COMPLIANCE_EVENT_DEACTIVATE)) {
|
||||
newState = LMIC_COMPLIANCE_FSMSTATE_INACTIVE;
|
||||
} else if (eventflags_TestAndClear(LMIC_COMPLIANCE_EVENT_ECHO_REQUEST)) {
|
||||
newState = LMIC_COMPLIANCE_FSMSTATE_ECHOING;
|
||||
} else {
|
||||
newState = LMIC_COMPLIANCE_FSMSTATE_REPORTING;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case LMIC_COMPLIANCE_FSMSTATE_ECHOING: {
|
||||
if (fEntry)
|
||||
acSendUplinkBuffer();
|
||||
|
||||
if (eventflags_TestAndClear(LMIC_COMPLIANCE_EVENT_UPLINK_COMPLETE)) {
|
||||
newState = LMIC_COMPLIANCE_FSMSTATE_RECOVERY;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case LMIC_COMPLIANCE_FSMSTATE_REPORTING: {
|
||||
if (fEntry)
|
||||
acSendUplink();
|
||||
|
||||
if (eventflags_TestAndClear(LMIC_COMPLIANCE_EVENT_UPLINK_COMPLETE)) {
|
||||
newState = LMIC_COMPLIANCE_FSMSTATE_RECOVERY;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case LMIC_COMPLIANCE_FSMSTATE_RECOVERY: {
|
||||
if (fEntry) {
|
||||
if (LMIC_Compliance.eventflags & (LMIC_COMPLIANCE_EVENT_DEACTIVATE |
|
||||
LMIC_COMPLIANCE_EVENT_ECHO_REQUEST)) {
|
||||
acSetTimer(sec2osticks(1));
|
||||
} else {
|
||||
acSetTimer(sec2osticks(5));
|
||||
}
|
||||
}
|
||||
|
||||
if (eventflags_TestAndClear(LMIC_COMPLIANCE_EVENT_TIMER_EXPIRED)) {
|
||||
newState = LMIC_COMPLIANCE_FSMSTATE_TESTMODE;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
default: {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
return newState;
|
||||
}
|
||||
|
||||
static void acEnterActiveMode(void) {
|
||||
// indicate to the outer world that we're active.
|
||||
LMIC_Compliance.state = LMIC_COMPLIANCE_STATE_ACTIVE;
|
||||
}
|
||||
|
||||
void acSetTimer(ostime_t delay) {
|
||||
os_setTimedCallback(&LMIC_Compliance.timerJob, os_getTime() + delay, timerExpiredCb);
|
||||
}
|
||||
|
||||
static void timerExpiredCb(osjob_t *j) {
|
||||
LMIC_Compliance.eventflags |= LMIC_COMPLIANCE_EVENT_TIMER_EXPIRED;
|
||||
fsmEval();
|
||||
}
|
||||
|
||||
static void lmicEventCb(
|
||||
void *pUserData,
|
||||
ev_t ev
|
||||
) {
|
||||
LMIC_API_PARAMETER(pUserData);
|
||||
|
||||
// pass to user handler
|
||||
if (LMIC_Compliance.saveEvent.pEventCb) {
|
||||
LMIC_Compliance.saveEvent.pEventCb(
|
||||
LMIC_Compliance.saveEvent.pUserData, ev
|
||||
);
|
||||
}
|
||||
|
||||
// if it's a EV_JOINED, or a TXCMOMPLETE, we should tell the FSM.
|
||||
if ((UINT32_C(1) << ev) & (EV_JOINED | EV_TXCOMPLETE)) {
|
||||
fsmEvalDeferred();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static void acExitActiveMode(void) {
|
||||
LMIC_Compliance.state = LMIC_COMPLIANCE_STATE_IDLE;
|
||||
os_clearCallback(&LMIC_Compliance.timerJob);
|
||||
LMIC_clrTxData();
|
||||
}
|
||||
|
||||
|
||||
static void acSendUplink(void) {
|
||||
uint8_t payload[2];
|
||||
uint32_t const downlink = LMIC_Compliance.downlinkCount;
|
||||
|
||||
// build the uplink message
|
||||
payload[0] = (uint8_t) (downlink >> 8);
|
||||
payload[1] = (uint8_t) downlink;
|
||||
|
||||
// reset the flags
|
||||
LMIC_Compliance.eventflags &= ~LMIC_COMPLIANCE_EVENT_UPLINK_COMPLETE;
|
||||
|
||||
// don't try to send if busy; might be sending echo message.
|
||||
lmic_tx_error_t const eSend =
|
||||
LMIC_sendWithCallback_strict(
|
||||
LORAWAN_PORT_COMPLIANCE,
|
||||
payload, sizeof(payload),
|
||||
/* confirmed? */
|
||||
!! (LMIC_Compliance.fsmFlags & LMIC_COMPLIANCE_FSM_CONFIRM),
|
||||
sendUplinkCompleteCb, NULL
|
||||
);
|
||||
|
||||
if (eSend == LMIC_ERROR_SUCCESS) {
|
||||
// queued successfully
|
||||
LMIC_COMPLIANCE_PRINTF(
|
||||
"lmic_compliance.%s: queued uplink message(%u, %p)\n",
|
||||
__func__,
|
||||
(unsigned) downlink & 0xFFFF,
|
||||
LMIC.client.txMessageCb
|
||||
);
|
||||
} else {
|
||||
// failed to queue; just skip this cycle.
|
||||
LMIC_COMPLIANCE_PRINTF(
|
||||
"lmic_compliance.%s: error(%d) sending uplink message(%u), %u bytes\n",
|
||||
__func__,
|
||||
eSend,
|
||||
(unsigned) downlink & 0xFFFF,
|
||||
LMIC.client.txMessageCb
|
||||
);
|
||||
LMIC_Compliance.eventflags |= LMIC_COMPLIANCE_EVENT_UPLINK_COMPLETE;
|
||||
fsmEval();
|
||||
}
|
||||
}
|
||||
|
||||
static void sendUplinkCompleteCb(void *pUserData, int fSuccess) {
|
||||
LMIC_Compliance.eventflags |= LMIC_COMPLIANCE_EVENT_UPLINK_COMPLETE;
|
||||
LMIC_COMPLIANCE_PRINTF("%s(%s)\n", __func__, LMICcompliance_txSuccessToString(fSuccess));
|
||||
fsmEvalDeferred();
|
||||
}
|
||||
|
||||
static void acSendUplinkBuffer(void) {
|
||||
// send uplink data.
|
||||
lmic_tx_error_t const eSend =
|
||||
LMIC_sendWithCallback_strict(
|
||||
LORAWAN_PORT_COMPLIANCE,
|
||||
LMIC_Compliance.uplinkMessage, LMIC_Compliance.uplinkSize,
|
||||
/* confirmed? */ (LMIC_Compliance.fsmFlags & LMIC_COMPLIANCE_FSM_CONFIRM) != 0,
|
||||
sendUplinkCompleteCb,
|
||||
NULL);
|
||||
|
||||
if (eSend == LMIC_ERROR_SUCCESS) {
|
||||
LMIC_COMPLIANCE_PRINTF("%s: queued %u bytes\n", __func__, LMIC_Compliance.uplinkSize);
|
||||
} else {
|
||||
LMIC_COMPLIANCE_PRINTF("%s: uplink %u bytes failed (error %d)\n", __func__, LMIC_Compliance.uplinkSize, eSend);
|
||||
if (eSend == LMIC_ERROR_TX_NOT_FEASIBLE) {
|
||||
// Reverse the increment of the downlink count. Needed for US compliance.
|
||||
if (CFG_region == LMIC_REGION_us915)
|
||||
--LMIC_Compliance.downlinkCount;
|
||||
}
|
||||
LMIC_Compliance.eventflags |= LMIC_COMPLIANCE_EVENT_UPLINK_COMPLETE;
|
||||
fsmEval();
|
||||
}
|
||||
}
|
||||
|
||||
const char *LMICcompliance_txSuccessToString(int fSuccess) {
|
||||
return fSuccess ? "ok" : "failed";
|
||||
}
|
|
@ -0,0 +1,138 @@
|
|||
/*
|
||||
|
||||
Module: lmic_compliance.h
|
||||
|
||||
Function:
|
||||
Internal header file for compliance-related work.
|
||||
|
||||
Copyright notice and license info:
|
||||
See LICENSE file accompanying this project.
|
||||
|
||||
Author:
|
||||
Terry Moore, MCCI Corporation March 2019
|
||||
|
||||
Description:
|
||||
This header file allows us to break up the compliance
|
||||
functions into multiple .c files if we wish.
|
||||
|
||||
*/
|
||||
|
||||
#ifndef _lmic_compliance_h_ /* prevent multiple includes */
|
||||
#define _lmic_compliance_h_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"{
|
||||
#endif
|
||||
|
||||
#ifndef _lmic_h_
|
||||
# include "lmic.h"
|
||||
#endif
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
typedef struct lmic_compliance_s lmic_compliance_t;
|
||||
|
||||
// concrete type for the state enumeration for the compliance engine.
|
||||
typedef uint8_t lmic_compliance_state_t;
|
||||
|
||||
enum lmic_compliance_state_e {
|
||||
LMIC_COMPLIANCE_STATE_IDLE = 0, // app state
|
||||
LMIC_COMPLIANCE_STATE_STOPPING = 1, // transitioning back to app
|
||||
LMIC_COMPLIANCE_STATE_ACTIVATING = 2, // transitioning to compliance state
|
||||
LMIC_COMPLIANCE_STATE_ACTIVE = 3, // in compliance state
|
||||
};
|
||||
|
||||
// return true if a state value indicates that the FSM is active.
|
||||
static inline bool
|
||||
lmic_compliance_state_IsActive(lmic_compliance_state_t s) {
|
||||
return s >= LMIC_COMPLIANCE_STATE_ACTIVATING;
|
||||
}
|
||||
|
||||
// events from the outside world to the FSM
|
||||
typedef uint8_t lmic_compliance_eventflags_t;
|
||||
|
||||
enum lmic_compliance_eventflags_e {
|
||||
LMIC_COMPLIANCE_EVENT_ACTIVATE = 1u << 0,
|
||||
LMIC_COMPLIANCE_EVENT_DEACTIVATE = 1u << 1,
|
||||
LMIC_COMPLIANCE_EVENT_TIMER_EXPIRED = 1u << 2,
|
||||
LMIC_COMPLIANCE_EVENT_UPLINK_COMPLETE = 1u << 3,
|
||||
LMIC_COMPLIANCE_EVENT_ECHO_REQUEST = 1u << 4,
|
||||
};
|
||||
|
||||
typedef uint8_t lmic_compliance_fsmflags_t;
|
||||
enum lmic_compliance_fsmflags_e {
|
||||
LMIC_COMPLIANCE_FSM_ACTIVE = 1u << 0,
|
||||
LMIC_COMPLIANCE_FSM_REENTERED = 1u << 1,
|
||||
LMIC_COMPLIANCE_FSM_CONFIRM = 1u << 2,
|
||||
};
|
||||
|
||||
typedef uint8_t lmic_compliance_fsmstate_t;
|
||||
enum lmic_compliance_fsmstate_e {
|
||||
LMIC_COMPLIANCE_FSMSTATE_INITIAL = 0,
|
||||
LMIC_COMPLIANCE_FSMSTATE_NOCHANGE = 1,
|
||||
LMIC_COMPLIANCE_FSMSTATE_ACTIVE = 2,
|
||||
LMIC_COMPLIANCE_FSMSTATE_INACTIVE = 3,
|
||||
LMIC_COMPLIANCE_FSMSTATE_TESTMODE = 4, // sending test uplinks
|
||||
LMIC_COMPLIANCE_FSMSTATE_ECHOING = 5,
|
||||
LMIC_COMPLIANCE_FSMSTATE_REPORTING = 6,
|
||||
LMIC_COMPLIANCE_FSMSTATE_RECOVERY = 7,
|
||||
LMIC_COMPLIANCE_FSMSTATE_TXBUSY = 8,
|
||||
};
|
||||
|
||||
#define LMIC_COMPLIANCE_FSMSTATE__NAMES \
|
||||
"INITIAL", "NOCHANGE", "ACTIVE", "INACTIVE", "TESTMODE", \
|
||||
"ECHOING", "REPORTING", "RECOVERY", "TXBUSY"
|
||||
|
||||
typedef struct lmic_compliance_eventcb_s lmic_compliance_eventcb_t;
|
||||
struct lmic_compliance_eventcb_s {
|
||||
// save the user's event CB while active.
|
||||
lmic_event_cb_t *pEventCb;
|
||||
// save the user's event data while active.
|
||||
void *pUserData;
|
||||
};
|
||||
|
||||
// structure for saving band settings during test
|
||||
typedef struct lmic_compliance_band_s lmic_compliance_band_t;
|
||||
struct lmic_compliance_band_s {
|
||||
u2_t txcap; // saved 1/duty cycle
|
||||
};
|
||||
|
||||
// the state of the compliance engine.
|
||||
struct lmic_compliance_s {
|
||||
// uint64
|
||||
// uintptr
|
||||
osjob_t timerJob; // the job for driving uplinks
|
||||
osjob_t fsmJob; // job for reevaluating the FSM.
|
||||
lmic_compliance_eventcb_t saveEvent; // the user's event handler.
|
||||
|
||||
// uint32
|
||||
|
||||
// uint16
|
||||
#if CFG_LMIC_EU_like
|
||||
lmic_compliance_band_t saveBands[MAX_BANDS];
|
||||
#endif // CFG_LMIC_EU_like
|
||||
|
||||
// we are required to maintain a downlink count
|
||||
// that is reset on join/test entry and incremented for
|
||||
// each valid test message.
|
||||
uint16_t downlinkCount;
|
||||
|
||||
// uint8
|
||||
|
||||
lmic_compliance_state_t state; // current state of compliance engine.
|
||||
lmic_compliance_eventflags_t eventflags; // incoming events.
|
||||
lmic_compliance_fsmflags_t fsmFlags; // FSM operational flags
|
||||
lmic_compliance_fsmstate_t fsmState; // FSM current state
|
||||
|
||||
uint8_t uplinkSize;
|
||||
uint8_t uplinkMessage[MAX_LEN_PAYLOAD];
|
||||
};
|
||||
|
||||
extern lmic_compliance_t LMIC_Compliance;
|
||||
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
#endif
|
||||
|
||||
#endif /* _lmic_compliance_h_ */
|
|
@ -70,7 +70,7 @@ Revision history:
|
|||
#define LMIC_REGION_au921 5
|
||||
#define LMIC_REGION_cn490 6
|
||||
#define LMIC_REGION_as923 7
|
||||
#define LMIC_REGION_kr921 8
|
||||
#define LMIC_REGION_kr920 8
|
||||
#define LMIC_REGION_in866 9
|
||||
|
||||
// Some regions have country-specific overrides. For generality, we specify
|
||||
|
@ -104,7 +104,7 @@ Revision history:
|
|||
(1 << LMIC_REGION_au921) | \
|
||||
/* (1 << LMIC_REGION_cn490) | */ \
|
||||
(1 << LMIC_REGION_as923) | \
|
||||
/* (1 << LMIC_REGION_kr921) | */ \
|
||||
(1 << LMIC_REGION_kr920) | \
|
||||
(1 << LMIC_REGION_in866) | \
|
||||
0)
|
||||
|
||||
|
@ -128,7 +128,7 @@ Revision history:
|
|||
(defined(CFG_au921) << LMIC_REGION_au921) | \
|
||||
(defined(CFG_cn490) << LMIC_REGION_cn490) | \
|
||||
(defined(CFG_as923) << LMIC_REGION_as923) | \
|
||||
(defined(CFG_kr921) << LMIC_REGION_kr921) | \
|
||||
(defined(CFG_kr920) << LMIC_REGION_kr920) | \
|
||||
(defined(CFG_in866) << LMIC_REGION_in866) | \
|
||||
0)
|
||||
|
||||
|
@ -153,8 +153,8 @@ Revision history:
|
|||
# define LMIC_COUNTRY_CODE LMIC_COUNTRY_CODE_JP
|
||||
#elif defined(CFG_as923)
|
||||
# define CFG_region LMIC_REGION_as923
|
||||
#elif defined(CFG_kr921)
|
||||
# define CFG_region LMIC_REGION_kr921
|
||||
#elif defined(CFG_kr920)
|
||||
# define CFG_region LMIC_REGION_kr920
|
||||
#elif defined(CFG_in866)
|
||||
# define CFG_region LMIC_REGION_in866
|
||||
#else
|
||||
|
@ -174,7 +174,7 @@ Revision history:
|
|||
/* (1 << LMIC_REGION_au921) | */ \
|
||||
/* (1 << LMIC_REGION_cn490) | */ \
|
||||
(1 << LMIC_REGION_as923) | \
|
||||
(1 << LMIC_REGION_kr921) | \
|
||||
(1 << LMIC_REGION_kr920) | \
|
||||
(1 << LMIC_REGION_in866) | \
|
||||
0)
|
||||
|
||||
|
@ -192,7 +192,7 @@ Revision history:
|
|||
(1 << LMIC_REGION_au921) | \
|
||||
/* (1 << LMIC_REGION_cn490) | */ \
|
||||
/* (1 << LMIC_REGION_as923) | */ \
|
||||
/* (1 << LMIC_REGION_kr921) | */ \
|
||||
/* (1 << LMIC_REGION_kr920) | */ \
|
||||
/* (1 << LMIC_REGION_in866) | */ \
|
||||
0)
|
||||
|
||||
|
@ -204,4 +204,13 @@ Revision history:
|
|||
#define CFG_LMIC_EU_like (!!(CFG_LMIC_REGION_MASK & CFG_LMIC_EU_like_MASK))
|
||||
#define CFG_LMIC_US_like (!!(CFG_LMIC_REGION_MASK & CFG_LMIC_US_like_MASK))
|
||||
|
||||
//
|
||||
// The supported LMIC LoRaWAAN spec versions. These need to be numerically ordered,
|
||||
// so that we can (for example) compare
|
||||
//
|
||||
// LMIC_LORAWAN_SPEC_VERSION < LMIC_LORAWAN_SPEC_VERSION_1_0_3.
|
||||
//
|
||||
#define LMIC_LORAWAN_SPEC_VERSION_1_0_2 0x01000200u
|
||||
#define LMIC_LORAWAN_SPEC_VERSION_1_0_3 0x01000300u
|
||||
|
||||
#endif /* _LMIC_CONFIG_PRECONDITIONS_H_ */
|
||||
|
|
|
@ -7,7 +7,7 @@ Function:
|
|||
|
||||
Copyright notice and license info:
|
||||
See LICENSE file accompanying this project.
|
||||
|
||||
|
||||
Author:
|
||||
Terry Moore, MCCI Corporation November 2018
|
||||
|
||||
|
@ -39,7 +39,7 @@ Description:
|
|||
error. The results of using this macro where a declaration is not
|
||||
permitted are unspecified.
|
||||
|
||||
This is different from #if !(fErrorIfFalse) / #error in that the
|
||||
This is different from #if !(fErrorIfFalse) / #error in that the
|
||||
expression is evaluated by the compiler rather than by the pre-
|
||||
processor. Therefore things like sizeof() can be used.
|
||||
|
||||
|
@ -214,4 +214,38 @@ Returns:
|
|||
# endif
|
||||
#endif
|
||||
|
||||
/*
|
||||
|
||||
Macro: LMIC_DECLARE_FUNCTION_WEAK()
|
||||
|
||||
Function:
|
||||
Declare an external function as a weak reference.
|
||||
|
||||
Definition:
|
||||
#define LMIC_DECLARE_FUNCTION_WEAK(ReturnType, FunctionName, Params) ...
|
||||
|
||||
Description:
|
||||
This macro generates a weak reference to the specified function.
|
||||
|
||||
Example:
|
||||
LMIC_DECLARE_FUNCTION_WEAK(void, onEvent, (ev_t e));
|
||||
|
||||
This saya that onEvent is a weak external reference. When calling
|
||||
onEvent, you must always first check whether it's supplied:
|
||||
|
||||
if (onEvent != NULL)
|
||||
onEvent(e);
|
||||
|
||||
Returns:
|
||||
This macro expands to a declaration, without a trailing semicolon.
|
||||
|
||||
Notes:
|
||||
This form allows for compilers that use _Pragma(weak, name) instead
|
||||
of inline attributes.
|
||||
|
||||
*/
|
||||
|
||||
#define LMIC_DECLARE_FUNCTION_WEAK(a_ReturnType, a_FunctionName, a_Params) \
|
||||
a_ReturnType __attribute__((__weak__)) a_FunctionName a_Params
|
||||
|
||||
#endif /* _lmic_env_h_ */
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017 MCCI Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -49,21 +49,28 @@ CONST_TABLE(u1_t, _DR2RPS_CRC)[] = {
|
|||
ILLEGAL_RPS
|
||||
};
|
||||
|
||||
static CONST_TABLE(u1_t, maxFrameLens)[] = { 64,64,64,123 };
|
||||
static CONST_TABLE(u1_t, maxFrameLens)[] = {
|
||||
59+5, 59+5, 59+5, 123+5, 250+5, 250+5, 250+5, 250+5
|
||||
};
|
||||
|
||||
uint8_t LMICeu868_maxFrameLen(uint8_t dr) {
|
||||
if (dr < LENOF_TABLE(maxFrameLens))
|
||||
return TABLE_GET_U1(maxFrameLens, dr);
|
||||
else
|
||||
return 0xFF;
|
||||
return 0;
|
||||
}
|
||||
|
||||
static CONST_TABLE(s1_t, TXPOWLEVELS)[] = {
|
||||
20, 14, 11, 8, 5, 2, 0,0, 0,0,0,0, 0,0,0,0
|
||||
16, 14, 12, 10, 8, 6, 4, 2
|
||||
};
|
||||
|
||||
int8_t LMICeu868_pow2dBm(uint8_t mcmd_ladr_p1) {
|
||||
return TABLE_GET_S1(TXPOWLEVELS, (mcmd_ladr_p1&MCMD_LADR_POW_MASK)>>MCMD_LADR_POW_SHIFT);
|
||||
uint8_t const pindex = (mcmd_ladr_p1&MCMD_LinkADRReq_POW_MASK)>>MCMD_LinkADRReq_POW_SHIFT;
|
||||
if (pindex < LENOF_TABLE(TXPOWLEVELS)) {
|
||||
return TABLE_GET_S1(TXPOWLEVELS, pindex);
|
||||
} else {
|
||||
return -128;
|
||||
}
|
||||
}
|
||||
|
||||
// only used in this module, but used by variant macro dr2hsym().
|
||||
|
@ -75,7 +82,7 @@ static CONST_TABLE(ostime_t, DR2HSYM_osticks)[] = {
|
|||
us2osticksRound(128 << 3), // DR_SF8
|
||||
us2osticksRound(128 << 2), // DR_SF7
|
||||
us2osticksRound(128 << 1), // DR_SF7B
|
||||
us2osticksRound(80) // FSK -- not used (time for 1/2 byte)
|
||||
us2osticksRound(80) // FSK -- time for 1/2 byte (unused by LMIC)
|
||||
};
|
||||
|
||||
ostime_t LMICeu868_dr2hsym(uint8_t dr) {
|
||||
|
@ -93,6 +100,9 @@ static CONST_TABLE(u4_t, iniChannelFreq)[6] = {
|
|||
|
||||
void LMICeu868_initDefaultChannels(bit_t join) {
|
||||
os_clearMem(&LMIC.channelFreq, sizeof(LMIC.channelFreq));
|
||||
#if !defined(DISABLE_MCMD_DlChannelReq)
|
||||
os_clearMem(&LMIC.channelDlFreq, sizeof(LMIC.channelDlFreq));
|
||||
#endif // !DISABLE_MCMD_DlChannelReq
|
||||
os_clearMem(&LMIC.channelDrMap, sizeof(LMIC.channelDrMap));
|
||||
os_clearMem(&LMIC.bands, sizeof(LMIC.bands));
|
||||
|
||||
|
@ -104,18 +114,9 @@ void LMICeu868_initDefaultChannels(bit_t join) {
|
|||
LMIC.channelDrMap[fu] = DR_RANGE_MAP(EU868_DR_SF12, EU868_DR_SF7);
|
||||
}
|
||||
|
||||
LMIC.bands[BAND_MILLI].txcap = 1000; // 0.1%
|
||||
LMIC.bands[BAND_MILLI].txpow = 14;
|
||||
LMIC.bands[BAND_MILLI].lastchnl = os_getRndU1() % MAX_CHANNELS;
|
||||
LMIC.bands[BAND_CENTI].txcap = 100; // 1%
|
||||
LMIC.bands[BAND_CENTI].txpow = 14;
|
||||
LMIC.bands[BAND_CENTI].lastchnl = os_getRndU1() % MAX_CHANNELS;
|
||||
LMIC.bands[BAND_DECI].txcap = 10; // 10%
|
||||
LMIC.bands[BAND_DECI].txpow = 27;
|
||||
LMIC.bands[BAND_DECI].lastchnl = os_getRndU1() % MAX_CHANNELS;
|
||||
LMIC.bands[BAND_MILLI].avail =
|
||||
LMIC.bands[BAND_CENTI].avail =
|
||||
LMIC.bands[BAND_DECI].avail = os_getTime();
|
||||
(void) LMIC_setupBand(BAND_MILLI, 14 /* dBm */, 1000 /* 0.1% */);
|
||||
(void) LMIC_setupBand(BAND_CENTI, 14 /* dBm */, 100 /* 1% */);
|
||||
(void) LMIC_setupBand(BAND_DECI, 27 /* dBm */, 10 /* 10% */);
|
||||
}
|
||||
|
||||
bit_t LMIC_setupBand(u1_t bandidx, s1_t txpow, u2_t txcap) {
|
||||
|
@ -129,26 +130,59 @@ bit_t LMIC_setupBand(u1_t bandidx, s1_t txpow, u2_t txcap) {
|
|||
return 1;
|
||||
}
|
||||
|
||||
// this table is from highest to lowest
|
||||
static CONST_TABLE(u4_t, bandAssignments)[] = {
|
||||
870000000 /* .. and above */ | BAND_MILLI,
|
||||
869700000 /* .. 869700000 */ | BAND_CENTI,
|
||||
869650000 /* .. 869700000 */ | BAND_MILLI,
|
||||
869400000 /* .. 869650000 */ | BAND_DECI,
|
||||
868600000 /* .. 869640000 */ | BAND_MILLI,
|
||||
865000000 /* .. 868400000 */ | BAND_CENTI,
|
||||
};
|
||||
|
||||
bit_t LMIC_setupChannel(u1_t chidx, u4_t freq, u2_t drmap, s1_t band) {
|
||||
// zero the band bits in freq, just in case.
|
||||
freq &= ~3;
|
||||
|
||||
if (chidx < NUM_DEFAULT_CHANNELS) {
|
||||
// can't disable a default channel.
|
||||
if (freq == 0)
|
||||
return 0;
|
||||
// can't change a default channel.
|
||||
else if (freq != (LMIC.channelFreq[chidx] & ~3))
|
||||
return 0;
|
||||
}
|
||||
bit_t fEnable = (freq != 0);
|
||||
if (chidx >= MAX_CHANNELS)
|
||||
return 0;
|
||||
|
||||
if (band == -1) {
|
||||
if (freq >= 869400000 && freq <= 869650000)
|
||||
freq |= BAND_DECI; // 10% 27dBm
|
||||
else if ((freq >= 868000000 && freq <= 868600000) ||
|
||||
(freq >= 869700000 && freq <= 870000000))
|
||||
freq |= BAND_CENTI; // 1% 14dBm
|
||||
else
|
||||
freq |= BAND_MILLI; // 0.1% 14dBm
|
||||
}
|
||||
else {
|
||||
if (band > BAND_AUX) return 0;
|
||||
freq = (freq&~3) | band;
|
||||
for (u1_t i = 0; i < LENOF_TABLE(bandAssignments); ++i) {
|
||||
const u4_t thisFreqBand = TABLE_GET_U4(bandAssignments, i);
|
||||
const u4_t thisFreq = thisFreqBand & ~3;
|
||||
if (freq >= thisFreq) {
|
||||
band = ((u1_t)thisFreqBand & 3);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// if we didn't identify a frequency, it's millis.
|
||||
if (band == -1) {
|
||||
band = BAND_MILLI;
|
||||
}
|
||||
}
|
||||
|
||||
if ((u1_t)band > BAND_AUX)
|
||||
return 0;
|
||||
|
||||
freq |= band;
|
||||
|
||||
LMIC.channelFreq[chidx] = freq;
|
||||
// TODO(tmm@mcci.com): don't use US SF directly, use something from the LMIC context or a static const
|
||||
LMIC.channelDrMap[chidx] = drmap == 0 ? DR_RANGE_MAP(EU868_DR_SF12, EU868_DR_SF7) : drmap;
|
||||
LMIC.channelMap |= 1 << chidx; // enabled right away
|
||||
if (fEnable)
|
||||
LMIC.channelMap |= 1 << chidx; // enabled right away
|
||||
else
|
||||
LMIC.channelMap &= ~(1 << chidx);
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
@ -213,12 +247,28 @@ ostime_t LMICeu868_nextJoinState(void) {
|
|||
}
|
||||
#endif // !DISABLE_JOIN
|
||||
|
||||
// txDone handling for FSK.
|
||||
void
|
||||
LMICeu868_txDoneFSK(ostime_t delay, osjobcb_t func) {
|
||||
LMIC.rxtime = LMIC.txend + delay - PRERX_FSK*us2osticksRound(160);
|
||||
LMIC.rxsyms = RXLEN_FSK;
|
||||
os_setTimedCallback(&LMIC.osjob, LMIC.rxtime - RX_RAMPUP, func);
|
||||
// set the Rx1 dndr, rps.
|
||||
void LMICeu868_setRx1Params(void) {
|
||||
u1_t const txdr = LMIC.dndr;
|
||||
s1_t drOffset;
|
||||
s1_t candidateDr;
|
||||
|
||||
LMICeulike_setRx1Freq();
|
||||
|
||||
if ( LMIC.rx1DrOffset <= 5)
|
||||
drOffset = (s1_t) LMIC.rx1DrOffset;
|
||||
else
|
||||
// make a reasonable assumption for unspecified value.
|
||||
drOffset = 5;
|
||||
|
||||
candidateDr = (s1_t) txdr - drOffset;
|
||||
if (candidateDr < LORAWAN_DR0)
|
||||
candidateDr = 0;
|
||||
else if (candidateDr > LORAWAN_DR7)
|
||||
candidateDr = LORAWAN_DR7;
|
||||
|
||||
LMIC.dndr = (u1_t) candidateDr;
|
||||
LMIC.rps = dndr2rps(LMIC.dndr);
|
||||
}
|
||||
|
||||
void
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017 MCCI Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -32,35 +32,95 @@
|
|||
|
||||
#if CFG_LMIC_EU_like
|
||||
|
||||
void LMIC_enableSubBand(u1_t band) {
|
||||
bit_t LMIC_enableSubBand(u1_t band) {
|
||||
LMIC_API_PARAMETER(band);
|
||||
return 0;
|
||||
}
|
||||
|
||||
void LMIC_disableSubBand(u1_t band) {
|
||||
bit_t LMIC_disableSubBand(u1_t band) {
|
||||
LMIC_API_PARAMETER(band);
|
||||
return 0;
|
||||
}
|
||||
|
||||
void LMIC_disableChannel(u1_t channel) {
|
||||
bit_t LMIC_disableChannel(u1_t channel) {
|
||||
u2_t old_chmap = LMIC.channelMap;
|
||||
LMIC.channelFreq[channel] = 0;
|
||||
LMIC.channelDrMap[channel] = 0;
|
||||
LMIC.channelMap &= ~(1 << channel);
|
||||
LMIC.channelMap = old_chmap & ~(1 << channel);
|
||||
return LMIC.channelMap != old_chmap;
|
||||
}
|
||||
|
||||
// this is a no-op provided for compatibilty
|
||||
void LMIC_enableChannel(u1_t channel) {
|
||||
bit_t LMIC_enableChannel(u1_t channel) {
|
||||
LMIC_API_PARAMETER(channel);
|
||||
return 0;
|
||||
}
|
||||
|
||||
u1_t LMICeulike_mapChannels(u1_t chpage, u2_t chmap) {
|
||||
// Bad page, disable all channel, enable non-existent
|
||||
if (chpage != 0 || chmap == 0 || (chmap & ~LMIC.channelMap) != 0)
|
||||
return 0; // illegal input
|
||||
for (u1_t chnl = 0; chnl<MAX_CHANNELS; chnl++) {
|
||||
if ((chmap & (1 << chnl)) != 0 && LMIC.channelFreq[chnl] == 0)
|
||||
chmap &= ~(1 << chnl); // ignore - channel is not defined
|
||||
// check whether a map operation will work.
|
||||
// chpage is 0 or 6; 6 turns all on; 0 selects channels 0..15 via mask.
|
||||
// The spec is unclear as to whether we should veto a channel mask that enables
|
||||
// a channel that hasn't been configured; we veto it.
|
||||
bit_t LMICeulike_canMapChannels(u1_t chpage, u2_t chmap) {
|
||||
switch (chpage) {
|
||||
case MCMD_LinkADRReq_ChMaskCntl_EULIKE_DIRECT:
|
||||
// we don't allow any channel to be turned on if its frequency is zero.
|
||||
for (u1_t chnl = 0; chnl<MAX_CHANNELS; chnl++) {
|
||||
if ((chmap & (1 << chnl)) != 0 && (LMIC.channelFreq[chnl]&~3) == 0)
|
||||
return 0; // fail - channel is not defined
|
||||
}
|
||||
return 1;
|
||||
|
||||
case MCMD_LinkADRReq_ChMaskCntl_EULIKE_ALL_ON:
|
||||
return 1;
|
||||
|
||||
default:
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
// assumes that LMICeulike_canMapChannels passed. Return true if this would
|
||||
// be a valid final configuration.
|
||||
// chpage is 0 or 0x60; 0x60 turns all on; 0 selects channels 0..15 via mask.
|
||||
// Assumes canMapChannels has already approved this change.
|
||||
bit_t LMICeulike_mapChannels(u1_t chpage, u2_t chmap) {
|
||||
switch (chpage) {
|
||||
case MCMD_LinkADRReq_ChMaskCntl_EULIKE_DIRECT:
|
||||
LMIC.channelMap = chmap;
|
||||
break;
|
||||
|
||||
case MCMD_LinkADRReq_ChMaskCntl_EULIKE_ALL_ON: {
|
||||
u2_t new_chmap = 0;
|
||||
for (u1_t chnl = 0; chnl<MAX_CHANNELS; chnl++) {
|
||||
if ((LMIC.channelFreq[chnl]&~3) != 0) {
|
||||
new_chmap |= (1 << chnl);
|
||||
}
|
||||
}
|
||||
LMIC.channelMap = new_chmap;
|
||||
break;
|
||||
}
|
||||
LMIC.channelMap = chmap;
|
||||
return 1;
|
||||
|
||||
default:
|
||||
// do nothing.
|
||||
break;
|
||||
}
|
||||
return LMIC.channelMap != 0;
|
||||
}
|
||||
|
||||
bit_t LMICeulike_isDataRateFeasible(dr_t dr) {
|
||||
// if the region uses TxpParam, then someone
|
||||
// could have changed TxDwell, which makes some
|
||||
// otherwise-legal DRs infeasible.
|
||||
#if LMIC_ENABLE_TxParamSetupReq
|
||||
if (LMICbandplan_maxFrameLen(dr) == 0) {
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
for (u1_t chnl = 0; chnl < MAX_CHANNELS; ++chnl) {
|
||||
if ((LMIC.channelMap & (1 << chnl)) != 0 && // channel enabled
|
||||
(LMIC.channelDrMap[chnl] & (1 << dr)) != 0)
|
||||
return 1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
#if !defined(DISABLE_JOIN)
|
||||
|
@ -113,25 +173,26 @@ ostime_t LMICeulike_nextJoinState(uint8_t nDefaultChannels) {
|
|||
LMIC.txChnl = 0;
|
||||
if ((++LMIC.txCnt % nDefaultChannels) == 0) {
|
||||
// Lower DR every nth try (having all default channels with same DR)
|
||||
//
|
||||
// TODO(tmm@mcci.com) add new DR_REGIN_JOIN_MIN instead of LORAWAN_DR0;
|
||||
// then we can eliminate the LMIC_REGION_as923 below because we'll set
|
||||
// the failed flag here. This will cause the outer caller to take the
|
||||
// appropriate join path. Or add new LMICeulike_GetLowestJoinDR()
|
||||
//
|
||||
//
|
||||
// TODO(tmm@mcci.com) add new DR_REGION_JOIN_MIN instead of LORAWAN_DR0;
|
||||
// then we can eliminate the LMIC_REGION_as923 below because we'll set
|
||||
// the failed flag here. This will cause the outer caller to take the
|
||||
// appropriate join path. Or add new LMICeulike_GetLowestJoinDR()
|
||||
//
|
||||
|
||||
// TODO(tmm@mcci.com) - see above; please remove regional dependency from this file.
|
||||
#if CFG_region == LMIC_REGION_as923
|
||||
// in the join of AS923 v1.1 or older, only DR2 is used.
|
||||
// no need to change the DR.
|
||||
LMIC.datarate = AS923_DR_SF10;
|
||||
failed = 1;
|
||||
#else
|
||||
if (LMIC.datarate == LORAWAN_DR0)
|
||||
failed = 1; // we have tried all DR - signal EV_JOIN_FAILED
|
||||
else
|
||||
{
|
||||
// TODO(tmm@mcci.com) - see above; please remove regional dependency from this file.
|
||||
#if CFG_region != LMIC_REGION_as923
|
||||
else {
|
||||
LMICcore_setDrJoin(DRCHG_NOJACC, decDR((dr_t)LMIC.datarate));
|
||||
#else
|
||||
// in the join of AS923 v1.1 or older, only DR2 is used.
|
||||
// no need to change the DR.
|
||||
LMIC.datarate = AS923_DR_SF10;
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
}
|
||||
// Clear NEXTCHNL because join state engine controls channel hopping
|
||||
LMIC.opmode &= ~OP_NEXTCHNL;
|
||||
|
@ -139,12 +200,12 @@ ostime_t LMICeulike_nextJoinState(uint8_t nDefaultChannels) {
|
|||
// Duty cycle is based on txend.
|
||||
ostime_t const time = LMICbandplan_nextJoinTime(os_getTime());
|
||||
|
||||
// TODO(tmm@mcci.com): change delay to (0:1) secs + a known t0, but randomized;
|
||||
// TODO(tmm@mcci.com): change delay to (0:1) secs + a known t0, but randomized;
|
||||
// starting adding a bias after 1 hour, 25 hours, etc.; and limit the duty
|
||||
// cycle on power up. For testability, add a way to set the join start time
|
||||
// externally (a test API) so we can check this feature.
|
||||
// See https://github.com/mcci-catena/arduino-lmic/issues/2
|
||||
// Current code doesn't match LoRaWAN 1.0.2 requirements.
|
||||
// Current code doesn't match LoRaWAN 1.0.2 requirements.
|
||||
|
||||
LMIC.txend = time +
|
||||
(isTESTMODE()
|
||||
|
@ -159,4 +220,49 @@ ostime_t LMICeulike_nextJoinState(uint8_t nDefaultChannels) {
|
|||
}
|
||||
#endif // !DISABLE_JOIN
|
||||
|
||||
void LMICeulike_saveAdrState(lmic_saved_adr_state_t *pStateBuffer) {
|
||||
os_copyMem(
|
||||
pStateBuffer->channelFreq,
|
||||
LMIC.channelFreq,
|
||||
sizeof(LMIC.channelFreq)
|
||||
);
|
||||
pStateBuffer->channelMap = LMIC.channelMap;
|
||||
}
|
||||
|
||||
bit_t LMICeulike_compareAdrState(const lmic_saved_adr_state_t *pStateBuffer) {
|
||||
if (memcmp(pStateBuffer->channelFreq, LMIC.channelFreq, sizeof(LMIC.channelFreq)) != 0)
|
||||
return 1;
|
||||
return pStateBuffer->channelMap != LMIC.channelMap;
|
||||
}
|
||||
|
||||
void LMICeulike_restoreAdrState(const lmic_saved_adr_state_t *pStateBuffer) {
|
||||
os_copyMem(
|
||||
LMIC.channelFreq,
|
||||
pStateBuffer->channelFreq,
|
||||
sizeof(LMIC.channelFreq)
|
||||
);
|
||||
LMIC.channelMap = pStateBuffer->channelMap;
|
||||
}
|
||||
|
||||
void LMICeulike_setRx1Freq(void) {
|
||||
#if !defined(DISABLE_MCMD_DlChannelReq)
|
||||
uint32_t dlFreq = LMIC.channelDlFreq[LMIC.txChnl];
|
||||
if (dlFreq != 0)
|
||||
LMIC.freq = dlFreq;
|
||||
#endif // !DISABLE_MCMD_DlChannelReq
|
||||
}
|
||||
|
||||
// Class A txDone handling for FSK.
|
||||
void
|
||||
LMICeulike_txDoneFSK(ostime_t delay, osjobcb_t func) {
|
||||
ostime_t const hsym = us2osticksRound(80);
|
||||
|
||||
// start a little earlier.
|
||||
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);
|
||||
}
|
||||
|
||||
#endif // CFG_LMIC_EU_like
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017 MCCI Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -56,7 +56,8 @@ LMICeulike_isValidBeacon1(const uint8_t *d) {
|
|||
#define LMICbandplan_isFSK() (0)
|
||||
|
||||
// provide a default LMICbandplan_txDoneDoFSK()
|
||||
#define LMICbandplan_txDoneFSK(delay, func) do { } while (0)
|
||||
void LMICeulike_txDoneFSK(ostime_t delay, osjobcb_t func);
|
||||
#define LMICbandplan_txDoneFSK(delay, func) LMICeulike_txDoneFSK(delay, func)
|
||||
|
||||
#define LMICbandplan_joinAcceptChannelClear() LMICbandplan_initDefaultChannels(/* normal, not join */ 0)
|
||||
|
||||
|
@ -74,14 +75,14 @@ enum { BAND_MILLI = 0, BAND_CENTI = 1, BAND_DECI = 2, BAND_AUX = 3 };
|
|||
#define LMICbandplan_setSessionInitDefaultChannels() \
|
||||
do { LMICbandplan_initDefaultChannels(/* normal, not join */ 0); } while (0)
|
||||
|
||||
u1_t LMICeulike_mapChannels(u1_t chpage, u2_t chmap);
|
||||
bit_t LMICeulike_canMapChannels(u1_t chpage, u2_t chmap);
|
||||
#define LMICbandplan_canMapChannels(c, m) LMICeulike_canMapChannels(c, m)
|
||||
|
||||
bit_t LMICeulike_mapChannels(u1_t chpage, u2_t chmap);
|
||||
#define LMICbandplan_mapChannels(c, m) LMICeulike_mapChannels(c, m)
|
||||
|
||||
void LMICeulike_initJoinLoop(u1_t nDefaultChannels, s1_t adrTxPow);
|
||||
|
||||
#define LMICbandplan_setRx1Params() \
|
||||
do { /*LMIC.freq/rps remain unchanged*/ } while (0)
|
||||
|
||||
void LMICeulike_updateTx(ostime_t txbeg);
|
||||
#define LMICbandplan_updateTx(t) LMICeulike_updateTx(t)
|
||||
|
||||
|
@ -95,4 +96,20 @@ static inline ostime_t LMICeulike_nextJoinTime(ostime_t now) {
|
|||
#define LMICbandplan_init() \
|
||||
do { /* nothing */ } while (0)
|
||||
|
||||
void LMICeulike_saveAdrState(lmic_saved_adr_state_t *pStateBuffer);
|
||||
#define LMICbandplan_saveAdrState(pState) LMICeulike_saveAdrState(pState)
|
||||
|
||||
bit_t LMICeulike_compareAdrState(const lmic_saved_adr_state_t *pStateBuffer);
|
||||
#define LMICbandplan_compareAdrState(pState) LMICeulike_compareAdrState(pState)
|
||||
|
||||
void LMICeulike_restoreAdrState(const lmic_saved_adr_state_t *pStateBuffer);
|
||||
#define LMICbandplan_restoreAdrState(pState) LMICeulike_restoreAdrState(pState)
|
||||
|
||||
// set Rx1 frequency (might be different than uplink).
|
||||
void LMICeulike_setRx1Freq(void);
|
||||
|
||||
bit_t LMICeulike_isDataRateFeasible(dr_t dr);
|
||||
#define LMICbandplan_isDataRateFeasible(dr) LMICeulike_isDataRateFeasible(dr)
|
||||
|
||||
|
||||
#endif // _lmic_eu_like_h_
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017 MCCI Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -49,21 +49,28 @@ CONST_TABLE(u1_t, _DR2RPS_CRC)[] = {
|
|||
ILLEGAL_RPS
|
||||
};
|
||||
|
||||
static CONST_TABLE(u1_t, maxFrameLens)[] = { 59+5,59+5,59+5,123+5, 230+5, 230+5 };
|
||||
static CONST_TABLE(u1_t, maxFrameLens)[] = {
|
||||
59+5, 59+5, 59+5, 123+5, 250+5, 250+5, 0, 250+5
|
||||
};
|
||||
|
||||
uint8_t LMICin866_maxFrameLen(uint8_t dr) {
|
||||
if (dr < LENOF_TABLE(maxFrameLens))
|
||||
return TABLE_GET_U1(maxFrameLens, dr);
|
||||
else
|
||||
return 0xFF;
|
||||
else
|
||||
return 0;
|
||||
}
|
||||
|
||||
static CONST_TABLE(s1_t, TXPOWLEVELS)[] = {
|
||||
20, 14, 11, 8, 5, 2, 0,0, 0,0,0,0, 0,0,0,0
|
||||
30, 28, 26, 24, 22, 20, 18, 16, 14, 12, 10
|
||||
};
|
||||
|
||||
int8_t LMICin866_pow2dBm(uint8_t mcmd_ladr_p1) {
|
||||
return TABLE_GET_S1(TXPOWLEVELS, (mcmd_ladr_p1&MCMD_LADR_POW_MASK)>>MCMD_LADR_POW_SHIFT);
|
||||
uint8_t const pindex = (mcmd_ladr_p1&MCMD_LinkADRReq_POW_MASK)>>MCMD_LinkADRReq_POW_SHIFT;
|
||||
if (pindex < LENOF_TABLE(TXPOWLEVELS)) {
|
||||
return TABLE_GET_S1(TXPOWLEVELS, pindex);
|
||||
} else {
|
||||
return -128;
|
||||
}
|
||||
}
|
||||
|
||||
// only used in this module, but used by variant macro dr2hsym().
|
||||
|
@ -88,8 +95,8 @@ ostime_t LMICin866_dr2hsym(uint8_t dr) {
|
|||
enum { NUM_DEFAULT_CHANNELS = 3 };
|
||||
static CONST_TABLE(u4_t, iniChannelFreq)[NUM_DEFAULT_CHANNELS] = {
|
||||
// Default operational frequencies
|
||||
IN866_F1 | BAND_MILLI,
|
||||
IN866_F2 | BAND_MILLI,
|
||||
IN866_F1 | BAND_MILLI,
|
||||
IN866_F2 | BAND_MILLI,
|
||||
IN866_F3 | BAND_MILLI,
|
||||
};
|
||||
|
||||
|
@ -98,6 +105,9 @@ void LMICin866_initDefaultChannels(bit_t join) {
|
|||
LMIC_API_PARAMETER(join);
|
||||
|
||||
os_clearMem(&LMIC.channelFreq, sizeof(LMIC.channelFreq));
|
||||
#if !defined(DISABLE_MCMD_DlChannelReq)
|
||||
os_clearMem(&LMIC.channelDlFreq, sizeof(LMIC.channelDlFreq));
|
||||
#endif // !DISABLE_MCMD_DlChannelReq
|
||||
os_clearMem(&LMIC.channelDrMap, sizeof(LMIC.channelDrMap));
|
||||
os_clearMem(&LMIC.bands, sizeof(LMIC.bands));
|
||||
|
||||
|
@ -125,17 +135,32 @@ bit_t LMIC_setupBand(u1_t bandidx, s1_t txpow, u2_t txcap) {
|
|||
}
|
||||
|
||||
bit_t LMIC_setupChannel(u1_t chidx, u4_t freq, u2_t drmap, s1_t band) {
|
||||
// zero the band bits in freq, just in case.
|
||||
freq &= ~3;
|
||||
|
||||
if (chidx < NUM_DEFAULT_CHANNELS) {
|
||||
// can't disable a default channel.
|
||||
if (freq == 0)
|
||||
return 0;
|
||||
// can't change a default channel.
|
||||
else if (freq != (LMIC.channelFreq[chidx] & ~3))
|
||||
return 0;
|
||||
}
|
||||
bit_t fEnable = (freq != 0);
|
||||
if (chidx >= MAX_CHANNELS)
|
||||
return 0;
|
||||
if (band == -1) {
|
||||
freq |= BAND_MILLI;
|
||||
freq = (freq&~3) | BAND_MILLI;
|
||||
} else {
|
||||
if (band > BAND_MILLI) return 0;
|
||||
freq = (freq&~3) | band;
|
||||
}
|
||||
LMIC.channelFreq[chidx] = freq;
|
||||
LMIC.channelDrMap[chidx] = drmap == 0 ? DR_RANGE_MAP(IN866_DR_SF12, IN866_DR_SF7) : drmap;
|
||||
LMIC.channelMap |= 1 << chidx; // enabled right away
|
||||
if (fEnable)
|
||||
LMIC.channelMap |= 1 << chidx; // enabled right away
|
||||
else
|
||||
LMIC.channelMap &= ~(1 << chidx);
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
@ -169,7 +194,7 @@ ostime_t LMICin866_nextTx(ostime_t now) {
|
|||
}
|
||||
}
|
||||
|
||||
// no enabled channel found! just use the last channel.
|
||||
// no enabled channel found! just use the last channel.
|
||||
return now;
|
||||
}
|
||||
|
||||
|
@ -187,12 +212,27 @@ ostime_t LMICin866_nextJoinState(void) {
|
|||
}
|
||||
#endif // !DISABLE_JOIN
|
||||
|
||||
// txDone handling for FSK.
|
||||
void
|
||||
LMICin866_txDoneFSK(ostime_t delay, osjobcb_t func) {
|
||||
LMIC.rxtime = LMIC.txend + delay - PRERX_FSK*us2osticksRound(160);
|
||||
LMIC.rxsyms = RXLEN_FSK;
|
||||
os_setTimedCallback(&LMIC.osjob, LMIC.rxtime - RX_RAMPUP, func);
|
||||
// set the Rx1 dndr, rps.
|
||||
void LMICin866_setRx1Params(void) {
|
||||
u1_t const txdr = LMIC.dndr;
|
||||
s1_t drOffset;
|
||||
s1_t candidateDr;
|
||||
|
||||
LMICeulike_setRx1Freq();
|
||||
|
||||
if ( LMIC.rx1DrOffset <= 5)
|
||||
drOffset = (s1_t) LMIC.rx1DrOffset;
|
||||
else
|
||||
drOffset = 5 - (s1_t) LMIC.rx1DrOffset;
|
||||
|
||||
candidateDr = (s1_t) txdr - drOffset;
|
||||
if (candidateDr < LORAWAN_DR0)
|
||||
candidateDr = 0;
|
||||
else if (candidateDr > LORAWAN_DR5)
|
||||
candidateDr = LORAWAN_DR5;
|
||||
|
||||
LMIC.dndr = (u1_t) candidateDr;
|
||||
LMIC.rps = dndr2rps(LMIC.dndr);
|
||||
}
|
||||
|
||||
void
|
||||
|
|
|
@ -0,0 +1,274 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
* * Neither the name of the <organization> nor the
|
||||
* names of its contributors may be used to endorse or promote products
|
||||
* derived from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
|
||||
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#define LMIC_DR_LEGACY 0
|
||||
|
||||
#include "lmic_bandplan.h"
|
||||
|
||||
#if defined(CFG_kr920)
|
||||
// ================================================================================
|
||||
//
|
||||
// BEG: KR920 related stuff
|
||||
//
|
||||
|
||||
CONST_TABLE(u1_t, _DR2RPS_CRC)[] = {
|
||||
ILLEGAL_RPS,
|
||||
(u1_t)MAKERPS(SF12, BW125, CR_4_5, 0, 0), // [0]
|
||||
(u1_t)MAKERPS(SF11, BW125, CR_4_5, 0, 0), // [1]
|
||||
(u1_t)MAKERPS(SF10, BW125, CR_4_5, 0, 0), // [2]
|
||||
(u1_t)MAKERPS(SF9, BW125, CR_4_5, 0, 0), // [3]
|
||||
(u1_t)MAKERPS(SF8, BW125, CR_4_5, 0, 0), // [4]
|
||||
(u1_t)MAKERPS(SF7, BW125, CR_4_5, 0, 0), // [5]
|
||||
ILLEGAL_RPS, // [6]
|
||||
};
|
||||
|
||||
static CONST_TABLE(u1_t, maxFrameLens)[] = {
|
||||
59+5, 59+5, 59+5, 123+5, 250+5, 250+5
|
||||
};
|
||||
|
||||
uint8_t LMICkr920_maxFrameLen(uint8_t dr) {
|
||||
if (dr < LENOF_TABLE(maxFrameLens))
|
||||
return TABLE_GET_U1(maxFrameLens, dr);
|
||||
else
|
||||
return 0;
|
||||
}
|
||||
|
||||
static CONST_TABLE(s1_t, TXPOWLEVELS)[] = {
|
||||
14, 12, 10, 8, 6, 4, 2, 0
|
||||
};
|
||||
|
||||
int8_t LMICkr920_pow2dBm(uint8_t mcmd_ladr_p1) {
|
||||
uint8_t const pindex = (mcmd_ladr_p1&MCMD_LinkADRReq_POW_MASK)>>MCMD_LinkADRReq_POW_SHIFT;
|
||||
if (pindex < LENOF_TABLE(TXPOWLEVELS)) {
|
||||
return TABLE_GET_S1(TXPOWLEVELS, pindex);
|
||||
} else {
|
||||
return -128;
|
||||
}
|
||||
}
|
||||
|
||||
// only used in this module, but used by variant macro dr2hsym().
|
||||
static CONST_TABLE(ostime_t, DR2HSYM_osticks)[] = {
|
||||
us2osticksRound(128 << 7), // DR_SF12
|
||||
us2osticksRound(128 << 6), // DR_SF11
|
||||
us2osticksRound(128 << 5), // DR_SF10
|
||||
us2osticksRound(128 << 4), // DR_SF9
|
||||
us2osticksRound(128 << 3), // DR_SF8
|
||||
us2osticksRound(128 << 2), // DR_SF7
|
||||
};
|
||||
|
||||
ostime_t LMICkr920_dr2hsym(uint8_t dr) {
|
||||
return TABLE_GET_OSTIME(DR2HSYM_osticks, dr);
|
||||
}
|
||||
|
||||
|
||||
// All frequencies are marked as BAND_MILLI, and we don't do duty-cycle. But this lets
|
||||
// us reuse code.
|
||||
enum { NUM_DEFAULT_CHANNELS = 3 };
|
||||
static CONST_TABLE(u4_t, iniChannelFreq)[NUM_DEFAULT_CHANNELS] = {
|
||||
// Default operational frequencies
|
||||
KR920_F1 | BAND_MILLI,
|
||||
KR920_F2 | BAND_MILLI,
|
||||
KR920_F3 | BAND_MILLI,
|
||||
};
|
||||
|
||||
// korea ignores the join flag, becuase the channel setup is the same either way.
|
||||
void LMICkr920_initDefaultChannels(bit_t join) {
|
||||
LMIC_API_PARAMETER(join);
|
||||
|
||||
os_clearMem(&LMIC.channelFreq, sizeof(LMIC.channelFreq));
|
||||
#if !defined(DISABLE_MCMD_DlChannelReq)
|
||||
os_clearMem(&LMIC.channelDlFreq, sizeof(LMIC.channelDlFreq));
|
||||
#endif // !DISABLE_MCMD_DlChannelReq
|
||||
os_clearMem(&LMIC.channelDrMap, sizeof(LMIC.channelDrMap));
|
||||
os_clearMem(&LMIC.bands, sizeof(LMIC.bands));
|
||||
|
||||
LMIC.channelMap = (1 << NUM_DEFAULT_CHANNELS) - 1;
|
||||
for (u1_t fu = 0; fu<NUM_DEFAULT_CHANNELS; fu++) {
|
||||
LMIC.channelFreq[fu] = TABLE_GET_U4(iniChannelFreq, fu);
|
||||
LMIC.channelDrMap[fu] = DR_RANGE_MAP(KR920_DR_SF12, KR920_DR_SF7);
|
||||
}
|
||||
|
||||
LMIC.bands[BAND_MILLI].txcap = 1; // no limit, in effect.
|
||||
LMIC.bands[BAND_MILLI].txpow = KR920_TX_EIRP_MAX_DBM;
|
||||
LMIC.bands[BAND_MILLI].lastchnl = os_getRndU1() % MAX_CHANNELS;
|
||||
LMIC.bands[BAND_MILLI].avail = os_getTime();
|
||||
}
|
||||
|
||||
void
|
||||
LMICkr920_init(void) {
|
||||
// set LBT mode
|
||||
LMIC.lbt_ticks = us2osticks(KR920_LBT_US);
|
||||
LMIC.lbt_dbmax = KR920_LBT_DB_MAX;
|
||||
}
|
||||
|
||||
void
|
||||
LMICas923_resetDefaultChannels(void) {
|
||||
// set LBT mode
|
||||
LMIC.lbt_ticks = us2osticks(KR920_LBT_US);
|
||||
LMIC.lbt_dbmax = KR920_LBT_DB_MAX;
|
||||
}
|
||||
|
||||
|
||||
bit_t LMIC_setupBand(u1_t bandidx, s1_t txpow, u2_t txcap) {
|
||||
if (bandidx > BAND_MILLI) return 0;
|
||||
//band_t* b = &LMIC.bands[bandidx];
|
||||
xref2band_t b = &LMIC.bands[bandidx];
|
||||
b->txpow = txpow;
|
||||
b->txcap = txcap;
|
||||
b->avail = os_getTime();
|
||||
b->lastchnl = os_getRndU1() % MAX_CHANNELS;
|
||||
return 1;
|
||||
}
|
||||
|
||||
bit_t LMIC_setupChannel(u1_t chidx, u4_t freq, u2_t drmap, s1_t band) {
|
||||
// zero the band bits in freq, just in case.
|
||||
freq &= ~3;
|
||||
|
||||
if (chidx < NUM_DEFAULT_CHANNELS) {
|
||||
// can't disable a default channel.
|
||||
if (freq == 0)
|
||||
return 0;
|
||||
// can't change a default channel.
|
||||
else if (freq != (LMIC.channelFreq[chidx] & ~3))
|
||||
return 0;
|
||||
}
|
||||
bit_t fEnable = (freq != 0);
|
||||
if (chidx >= MAX_CHANNELS)
|
||||
return 0;
|
||||
if (band == -1) {
|
||||
freq = (freq&~3) | BAND_MILLI;
|
||||
} else {
|
||||
if (band > BAND_MILLI) return 0;
|
||||
freq = (freq&~3) | band;
|
||||
}
|
||||
LMIC.channelFreq[chidx] = freq;
|
||||
LMIC.channelDrMap[chidx] = drmap == 0 ? DR_RANGE_MAP(KR920_DR_SF12, KR920_DR_SF7) : drmap;
|
||||
if (fEnable)
|
||||
LMIC.channelMap |= 1 << chidx; // enabled right away
|
||||
else
|
||||
LMIC.channelMap &= ~(1 << chidx);
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
|
||||
u4_t LMICkr920_convFreq(xref2cu1_t ptr) {
|
||||
u4_t freq = (os_rlsbf4(ptr - 1) >> 8) * 100;
|
||||
if (freq < KR920_FREQ_MIN || freq > KR920_FREQ_MAX)
|
||||
freq = 0;
|
||||
return freq;
|
||||
}
|
||||
|
||||
// return the next time, but also do channel hopping here
|
||||
// since there's no duty cycle limitation, and no dwell limitation,
|
||||
// we simply loop through the channels sequentially.
|
||||
ostime_t LMICkr920_nextTx(ostime_t now) {
|
||||
const u1_t band = BAND_MILLI;
|
||||
|
||||
for (u1_t ci = 0; ci < MAX_CHANNELS; ci++) {
|
||||
// Find next channel in given band
|
||||
u1_t chnl = LMIC.bands[band].lastchnl;
|
||||
for (u1_t ci = 0; ci<MAX_CHANNELS; ci++) {
|
||||
if ((chnl = (chnl + 1)) >= MAX_CHANNELS)
|
||||
chnl -= MAX_CHANNELS;
|
||||
if ((LMIC.channelMap & (1 << chnl)) != 0 && // channel enabled
|
||||
(LMIC.channelDrMap[chnl] & (1 << (LMIC.datarate & 0xF))) != 0 &&
|
||||
band == (LMIC.channelFreq[chnl] & 0x3)) { // in selected band
|
||||
LMIC.txChnl = LMIC.bands[band].lastchnl = chnl;
|
||||
return now;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// no enabled channel found! just use the last channel.
|
||||
return now;
|
||||
}
|
||||
|
||||
#if !defined(DISABLE_BEACONS)
|
||||
void LMICkr920_setBcnRxParams(void) {
|
||||
LMIC.dataLen = 0;
|
||||
LMIC.freq = LMIC.channelFreq[LMIC.bcnChnl] & ~(u4_t)3;
|
||||
LMIC.rps = setIh(setNocrc(dndr2rps((dr_t)DR_BCN), 1), LEN_BCN);
|
||||
}
|
||||
#endif // !DISABLE_BEACONS
|
||||
|
||||
#if !defined(DISABLE_JOIN)
|
||||
ostime_t LMICkr920_nextJoinState(void) {
|
||||
return LMICeulike_nextJoinState(NUM_DEFAULT_CHANNELS);
|
||||
}
|
||||
#endif // !DISABLE_JOIN
|
||||
|
||||
// set the Rx1 dndr, rps.
|
||||
void LMICkr920_setRx1Params(void) {
|
||||
u1_t const txdr = LMIC.dndr;
|
||||
s1_t drOffset;
|
||||
s1_t candidateDr;
|
||||
|
||||
LMICeulike_setRx1Freq();
|
||||
|
||||
if ( LMIC.rx1DrOffset <= 5)
|
||||
drOffset = (s1_t) LMIC.rx1DrOffset;
|
||||
else
|
||||
drOffset = 5 - (s1_t) LMIC.rx1DrOffset;
|
||||
|
||||
candidateDr = (s1_t) txdr - drOffset;
|
||||
if (candidateDr < LORAWAN_DR0)
|
||||
candidateDr = 0;
|
||||
else if (candidateDr > LORAWAN_DR5)
|
||||
candidateDr = LORAWAN_DR5;
|
||||
|
||||
LMIC.dndr = (u1_t) candidateDr;
|
||||
LMIC.rps = dndr2rps(LMIC.dndr);
|
||||
}
|
||||
|
||||
void
|
||||
LMICkr920_initJoinLoop(void) {
|
||||
LMICeulike_initJoinLoop(NUM_DEFAULT_CHANNELS, /* adr dBm */ KR920_TX_EIRP_MAX_DBM);
|
||||
}
|
||||
|
||||
void LMICkr920_updateTx(ostime_t txbeg) {
|
||||
u4_t freq = LMIC.channelFreq[LMIC.txChnl];
|
||||
// Update global/band specific duty cycle stats
|
||||
ostime_t airtime = calcAirTime(LMIC.rps, LMIC.dataLen);
|
||||
// Update channel/global duty cycle stats
|
||||
xref2band_t band = &LMIC.bands[freq & 0x3];
|
||||
LMIC.freq = freq & ~(u4_t)3;
|
||||
LMIC.txpow = band->txpow;
|
||||
if (LMIC.freq <= KR920_FDOWN && LMIC.txpow > KR920_TX_EIRP_MAX_DBM_LOW) {
|
||||
LMIC.txpow = KR920_TX_EIRP_MAX_DBM_LOW;
|
||||
}
|
||||
band->avail = txbeg + airtime * band->txcap;
|
||||
if (LMIC.globalDutyRate != 0)
|
||||
LMIC.globalDutyAvail = txbeg + (airtime << LMIC.globalDutyRate);
|
||||
}
|
||||
|
||||
//
|
||||
// END: KR920 related stuff
|
||||
//
|
||||
// ================================================================================
|
||||
#endif
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017 MCCI Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -55,13 +55,26 @@ CONST_TABLE(u1_t, _DR2RPS_CRC)[] = {
|
|||
ILLEGAL_RPS // [14]
|
||||
};
|
||||
|
||||
static CONST_TABLE(u1_t, maxFrameLens)[] = { 24,66,142,255,255,255,255,255, 66,142 };
|
||||
static CONST_TABLE(u1_t, maxFrameLens)[] = {
|
||||
19+5, 61+5, 133+5, 250+5, 250+5, 0, 0,0,
|
||||
61+5, 133+5, 250+5, 250+5, 250+5, 250+5
|
||||
};
|
||||
|
||||
uint8_t LMICus915_maxFrameLen(uint8_t dr) {
|
||||
if (dr < LENOF_TABLE(maxFrameLens))
|
||||
return TABLE_GET_U1(maxFrameLens, dr);
|
||||
else
|
||||
return 0xFF;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int8_t LMICus915_pow2dbm(uint8_t mcmd_ladr_p1) {
|
||||
if ((mcmd_ladr_p1 & MCMD_LinkADRReq_POW_MASK) >
|
||||
((LMIC_LORAWAN_SPEC_VERSION < LMIC_LORAWAN_SPEC_VERSION_1_0_3)
|
||||
? US915_LinkAdrReq_POW_MAX_1_0_2
|
||||
: US915_LinkAdrReq_POW_MAX_1_0_3))
|
||||
return -128;
|
||||
else
|
||||
return ((s1_t)(US915_TX_MAX_DBM - (((mcmd_ladr_p1)&MCMD_LinkADRReq_POW_MASK)<<1)));
|
||||
}
|
||||
|
||||
static CONST_TABLE(ostime_t, DR2HSYM_osticks)[] = {
|
||||
|
@ -98,9 +111,11 @@ bit_t LMIC_setupChannel(u1_t chidx, u4_t freq, u2_t drmap, s1_t band) {
|
|||
return 1;
|
||||
}
|
||||
|
||||
void LMIC_disableChannel(u1_t channel) {
|
||||
bit_t LMIC_disableChannel(u1_t channel) {
|
||||
bit_t result = 0;
|
||||
if (channel < 72 + MAX_XCHANNELS) {
|
||||
if (ENABLED_CHANNEL(channel)) {
|
||||
result = 1;
|
||||
if (IS_CHANNEL_125khz(channel))
|
||||
LMIC.activeChannels125khz--;
|
||||
else if (IS_CHANNEL_500khz(channel))
|
||||
|
@ -108,11 +123,14 @@ void LMIC_disableChannel(u1_t channel) {
|
|||
}
|
||||
LMIC.channelMap[channel >> 4] &= ~(1 << (channel & 0xF));
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
void LMIC_enableChannel(u1_t channel) {
|
||||
bit_t LMIC_enableChannel(u1_t channel) {
|
||||
bit_t result = 0;
|
||||
if (channel < 72 + MAX_XCHANNELS) {
|
||||
if (!ENABLED_CHANNEL(channel)) {
|
||||
result = 1;
|
||||
if (IS_CHANNEL_125khz(channel))
|
||||
LMIC.activeChannels125khz++;
|
||||
else if (IS_CHANNEL_500khz(channel))
|
||||
|
@ -120,42 +138,52 @@ void LMIC_enableChannel(u1_t channel) {
|
|||
}
|
||||
LMIC.channelMap[channel >> 4] |= (1 << (channel & 0xF));
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
void LMIC_enableSubBand(u1_t band) {
|
||||
bit_t LMIC_enableSubBand(u1_t band) {
|
||||
ASSERT(band < 8);
|
||||
u1_t start = band * 8;
|
||||
u1_t end = start + 8;
|
||||
bit_t result = 0;
|
||||
|
||||
// enable all eight 125 kHz channels in this subband
|
||||
for (int channel = start; channel < end; ++channel)
|
||||
LMIC_enableChannel(channel);
|
||||
result |= LMIC_enableChannel(channel);
|
||||
|
||||
// there's a single 500 kHz channel associated with
|
||||
// each group of 8 125 kHz channels. Enable it, too.
|
||||
LMIC_enableChannel(64 + band);
|
||||
result |= LMIC_enableChannel(64 + band);
|
||||
return result;
|
||||
}
|
||||
void LMIC_disableSubBand(u1_t band) {
|
||||
|
||||
bit_t LMIC_disableSubBand(u1_t band) {
|
||||
ASSERT(band < 8);
|
||||
u1_t start = band * 8;
|
||||
u1_t end = start + 8;
|
||||
bit_t result = 0;
|
||||
|
||||
// disable all eight 125 kHz channels in this subband
|
||||
for (int channel = start; channel < end; ++channel)
|
||||
LMIC_disableChannel(channel);
|
||||
result |= LMIC_disableChannel(channel);
|
||||
|
||||
// there's a single 500 kHz channel associated with
|
||||
// each group of 8 125 kHz channels. Disable it, too.
|
||||
LMIC_disableChannel(64 + band);
|
||||
result |= LMIC_disableChannel(64 + band);
|
||||
return result;
|
||||
}
|
||||
void LMIC_selectSubBand(u1_t band) {
|
||||
|
||||
bit_t LMIC_selectSubBand(u1_t band) {
|
||||
bit_t result = 0;
|
||||
|
||||
ASSERT(band < 8);
|
||||
for (int b = 0; b<8; ++b) {
|
||||
if (band == b)
|
||||
LMIC_enableSubBand(b);
|
||||
result |= LMIC_enableSubBand(b);
|
||||
else
|
||||
LMIC_disableSubBand(b);
|
||||
result |= LMIC_disableSubBand(b);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
void LMICus915_updateTx(ostime_t txbeg) {
|
||||
|
@ -193,16 +221,31 @@ void LMICus915_setBcnRxParams(void) {
|
|||
}
|
||||
#endif // !DISABLE_BEACONS
|
||||
|
||||
// TODO(tmm@mcci.com): parmeterize for US-like
|
||||
// set the Rx1 dndr, rps.
|
||||
void LMICus915_setRx1Params(void) {
|
||||
u1_t const txdr = LMIC.dndr;
|
||||
u1_t candidateDr;
|
||||
LMIC.freq = US915_500kHz_DNFBASE + (LMIC.txChnl & 0x7) * US915_500kHz_DNFSTEP;
|
||||
if( /* TX datarate */LMIC.dndr < US915_DR_SF8C )
|
||||
LMIC.dndr += US915_DR_SF10CR - US915_DR_SF10;
|
||||
else if( LMIC.dndr == US915_DR_SF8C )
|
||||
LMIC.dndr = US915_DR_SF7CR;
|
||||
if ( /* TX datarate */txdr < LORAWAN_DR4)
|
||||
candidateDr = txdr + 10 - LMIC.rx1DrOffset;
|
||||
else
|
||||
candidateDr = LORAWAN_DR13 - LMIC.rx1DrOffset;
|
||||
|
||||
if (candidateDr < LORAWAN_DR8)
|
||||
candidateDr = LORAWAN_DR8;
|
||||
else if (candidateDr > LORAWAN_DR13)
|
||||
candidateDr = LORAWAN_DR13;
|
||||
|
||||
LMIC.dndr = candidateDr;
|
||||
LMIC.rps = dndr2rps(LMIC.dndr);
|
||||
}
|
||||
|
||||
void LMICus915_initJoinLoop(void) {
|
||||
LMICuslike_initJoinLoop();
|
||||
|
||||
// initialize the adrTxPower.
|
||||
LMIC.adrTxPow = 20; // dBm
|
||||
}
|
||||
|
||||
//
|
||||
// END: US915 related stuff
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017 MCCI Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -91,31 +91,54 @@ void LMICuslike_initDefaultChannels(bit_t fJoin) {
|
|||
LMIC.activeChannels500khz = 8;
|
||||
}
|
||||
|
||||
u1_t LMICuslike_mapChannels(u1_t chpage, u2_t chmap) {
|
||||
// verify that a given setting is permitted
|
||||
bit_t LMICuslike_canMapChannels(u1_t chpage, u2_t chmap) {
|
||||
/*
|
||||
|| MCMD_LADR_CHP_125ON and MCMD_LADR_CHP_125OFF are special. The
|
||||
|| MCMD_LinkADRReq_ChMaskCntl_USLIKE_125ON and MCMD_LinkADRReq_ChMaskCntl_USLIKE_125OFF are special. The
|
||||
|| channel map appllies to 500kHz (ch 64..71) and in addition
|
||||
|| all channels 0..63 are turned off or on. MCMC_LADR_CHP_BANK
|
||||
|| is also special, in that it enables subbands.
|
||||
*/
|
||||
u1_t base, top;
|
||||
|
||||
if (chpage < MCMD_LADR_CHP_USLIKE_SPECIAL) {
|
||||
// operate on channels 0..15, 16..31, 32..47, 48..63
|
||||
base = chpage << 4;
|
||||
top = base + 16;
|
||||
if (base == 64) {
|
||||
if (chpage < MCMD_LinkADRReq_ChMaskCntl_USLIKE_SPECIAL) {
|
||||
// operate on channels 0..15, 16..31, 32..47, 48..63, 64..71
|
||||
if (chpage == MCMD_LinkADRReq_ChMaskCntl_USLIKE_500K) {
|
||||
if (chmap & 0xFF00) {
|
||||
// those are reserved bits, fail.
|
||||
return 0;
|
||||
}
|
||||
top = 72;
|
||||
} else {
|
||||
return 1;
|
||||
}
|
||||
} else if (chpage == MCMD_LADR_CHP_BANK) {
|
||||
if (chmap & 0xFF00) {
|
||||
// those are resreved bits, fail.
|
||||
} else if (chpage == MCMD_LinkADRReq_ChMaskCntl_USLIKE_BANK) {
|
||||
if (chmap == 0 || (chmap & 0xFF00) != 0) {
|
||||
// no bits set, or reserved bitsset , fail.
|
||||
return 0;
|
||||
}
|
||||
} else if (chpage == MCMD_LinkADRReq_ChMaskCntl_USLIKE_125ON ||
|
||||
chpage == MCMD_LinkADRReq_ChMaskCntl_USLIKE_125OFF) {
|
||||
u1_t const en125 = chpage == MCMD_LinkADRReq_ChMaskCntl_USLIKE_125ON;
|
||||
|
||||
// if disabling all 125kHz chans, must have at least one 500kHz chan
|
||||
// don't allow reserved bits to be set in chmap.
|
||||
if ((! en125 && chmap == 0) || (chmap & 0xFF00) != 0)
|
||||
return 0;
|
||||
} else {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// if we get here, it looks legal.
|
||||
return 1;
|
||||
}
|
||||
|
||||
// map channels. return true if configuration looks valid.
|
||||
bit_t LMICuslike_mapChannels(u1_t chpage, u2_t chmap) {
|
||||
/*
|
||||
|| MCMD_LinkADRReq_ChMaskCntl_USLIKE_125ON and MCMD_LinkADRReq_ChMaskCntl_USLIKE_125OFF are special. The
|
||||
|| channel map appllies to 500kHz (ch 64..71) and in addition
|
||||
|| all channels 0..63 are turned off or on. MCMC_LADR_CHP_BANK
|
||||
|| is also special, in that it enables subbands.
|
||||
*/
|
||||
if (chpage == MCMD_LinkADRReq_ChMaskCntl_USLIKE_BANK) {
|
||||
// each bit enables a bank of channels
|
||||
for (u1_t subband = 0; subband < 8; ++subband, chmap >>= 1) {
|
||||
if (chmap & 1) {
|
||||
|
@ -123,37 +146,48 @@ u1_t LMICuslike_mapChannels(u1_t chpage, u2_t chmap) {
|
|||
} else {
|
||||
LMIC_disableSubBand(subband);
|
||||
}
|
||||
|
||||
// don't change any channels below
|
||||
base = top = 0;
|
||||
}
|
||||
} else if (chpage == MCMD_LADR_CHP_125ON || chpage == MCMD_LADR_CHP_125OFF) {
|
||||
u1_t const en125 = chpage == MCMD_LADR_CHP_125ON;
|
||||
} else {
|
||||
u1_t base, top;
|
||||
|
||||
// enable or disable all 125kHz channels
|
||||
for (u1_t chnl = 0; chnl < 64; ++chnl) {
|
||||
if (en125)
|
||||
LMIC_enableChannel(chnl);
|
||||
else
|
||||
LMIC_disableChannel(chnl);
|
||||
}
|
||||
if (chpage < MCMD_LinkADRReq_ChMaskCntl_USLIKE_SPECIAL) {
|
||||
// operate on channels 0..15, 16..31, 32..47, 48..63
|
||||
// note that the chpage hasn't been shifted right, so
|
||||
// it's really the base.
|
||||
base = chpage;
|
||||
top = base + 16;
|
||||
if (base == 64) {
|
||||
top = 72;
|
||||
}
|
||||
} else /* if (chpage == MCMD_LinkADRReq_ChMaskCntl_USLIKE_125ON ||
|
||||
chpage == MCMD_LinkADRReq_ChMaskCntl_USLIKE_125OFF) */ {
|
||||
u1_t const en125 = chpage == MCMD_LinkADRReq_ChMaskCntl_USLIKE_125ON;
|
||||
|
||||
// then apply mask to top 8 channels.
|
||||
base = 64;
|
||||
top = 72;
|
||||
} else {
|
||||
return 0;
|
||||
}
|
||||
// enable or disable all 125kHz channels
|
||||
for (u1_t chnl = 0; chnl < 64; ++chnl) {
|
||||
if (en125)
|
||||
LMIC_enableChannel(chnl);
|
||||
else
|
||||
LMIC_disableChannel(chnl);
|
||||
}
|
||||
|
||||
// apply chmap to channels in [base..top-1].
|
||||
// Use enable/disable channel to keep activeChannel counts in sync.
|
||||
for (u1_t chnl = base; chnl < top; ++chnl, chmap >>= 1) {
|
||||
if (chmap & 0x0001)
|
||||
LMIC_enableChannel(chnl);
|
||||
else
|
||||
LMIC_disableChannel(chnl);
|
||||
// then apply mask to top 8 channels.
|
||||
base = 64;
|
||||
top = 72;
|
||||
}
|
||||
|
||||
// apply chmap to channels in [base..top-1].
|
||||
// Use enable/disable channel to keep activeChannel counts in sync.
|
||||
for (u1_t chnl = base; chnl < top; ++chnl, chmap >>= 1) {
|
||||
if (chmap & 0x0001)
|
||||
LMIC_enableChannel(chnl);
|
||||
else
|
||||
LMIC_disableChannel(chnl);
|
||||
}
|
||||
}
|
||||
return 1;
|
||||
|
||||
LMICOS_logEventUint32("LMICuslike_mapChannels", (LMIC.activeChannels125khz << 16u)|(LMIC.activeChannels500khz << 0u));
|
||||
return (LMIC.activeChannels125khz > 0) || (LMIC.activeChannels500khz > 0);
|
||||
}
|
||||
|
||||
// US does not have duty cycling - return now as earliest TX time
|
||||
|
@ -161,16 +195,38 @@ u1_t LMICuslike_mapChannels(u1_t chpage, u2_t chmap) {
|
|||
ostime_t LMICuslike_nextTx(ostime_t now) {
|
||||
// TODO(tmm@mcci.com): use a static const for US-like
|
||||
if (LMIC.datarate >= LMICuslike_getFirst500kHzDR()) { // 500kHz
|
||||
ASSERT(LMIC.activeChannels500khz>0);
|
||||
setNextChannel(64, 64 + 8, LMIC.activeChannels500khz);
|
||||
if (LMIC.activeChannels500khz > 0) {
|
||||
setNextChannel(64, 64 + 8, LMIC.activeChannels500khz);
|
||||
} else if (LMIC.activeChannels125khz > 0) {
|
||||
LMIC.datarate = lowerDR(LMICuslike_getFirst500kHzDR(), 1);
|
||||
setNextChannel(0, 64, LMIC.activeChannels125khz);
|
||||
LMICOS_logEvent("LMICuslike_nextTx: no 500k, choose 125k");
|
||||
} else {
|
||||
LMICOS_logEvent("LMICuslike_nextTx: no channels at all (500)");
|
||||
}
|
||||
}
|
||||
else { // 125kHz
|
||||
ASSERT(LMIC.activeChannels125khz>0);
|
||||
setNextChannel(0, 64, LMIC.activeChannels125khz);
|
||||
if (LMIC.activeChannels125khz > 0) {
|
||||
setNextChannel(0, 64, LMIC.activeChannels125khz);
|
||||
} else if (LMIC.activeChannels500khz > 0) {
|
||||
LMIC.datarate = LMICuslike_getFirst500kHzDR();
|
||||
setNextChannel(64, 64 + 8, LMIC.activeChannels500khz);
|
||||
LMICOS_logEvent("LMICuslike_nextTx: no 125k, choose 500k");
|
||||
} else {
|
||||
LMICOS_logEvent("LMICuslike_nextTx: no channels at all (125)");
|
||||
}
|
||||
}
|
||||
return now;
|
||||
}
|
||||
|
||||
bit_t LMICuslike_isDataRateFeasible(dr_t dr) {
|
||||
if (dr >= LMICuslike_getFirst500kHzDR()) { // 500kHz
|
||||
return LMIC.activeChannels500khz > 0;
|
||||
} else {
|
||||
return LMIC.activeChannels125khz > 6;
|
||||
}
|
||||
}
|
||||
|
||||
#if !defined(DISABLE_JOIN)
|
||||
void LMICuslike_initJoinLoop(void) {
|
||||
// set an initial condition so that setNextChannel()'s preconds are met
|
||||
|
@ -183,18 +239,13 @@ void LMICuslike_initJoinLoop(void) {
|
|||
// starting point.
|
||||
setNextChannel(0, 64, LMIC.activeChannels125khz);
|
||||
|
||||
// initialize the adrTxPower.
|
||||
// TODO(tmm@mcci.com): is this right for all US-like regions
|
||||
LMIC.adrTxPow = 20; // dBm
|
||||
ASSERT((LMIC.opmode & OP_NEXTCHNL) == 0);
|
||||
|
||||
// make sure LMIC.txend is valid.
|
||||
LMIC.txend = os_getTime();
|
||||
ASSERT((LMIC.opmode & OP_NEXTCHNL) == 0);
|
||||
|
||||
// make sure the datarate is set to DR0 per LoRaWAN regional reqts V1.0.2,
|
||||
// section 2.2.2
|
||||
// TODO(tmm@mcci.com): parameterize this for US-like
|
||||
LMICcore_setDrJoin(DRCHG_SET, LORAWAN_DR0);
|
||||
// make sure the datarate is set to DR2 per LoRaWAN regional reqts V1.0.2,
|
||||
// section 2.*.2
|
||||
LMICcore_setDrJoin(DRCHG_SET, LMICbandplan_getInitialDrJoin());
|
||||
|
||||
// TODO(tmm@mcci.com) need to implement the transmit randomization and
|
||||
// duty cycle restrictions from LoRaWAN V1.0.2 section 7.
|
||||
|
@ -233,7 +284,7 @@ ostime_t LMICuslike_nextJoinState(void) {
|
|||
setNextChannel(0, 64, LMIC.activeChannels125khz);
|
||||
|
||||
// TODO(tmm@mcci.com) parameterize
|
||||
s1_t dr = LORAWAN_DR0;
|
||||
s1_t dr = LMICuslike_getJoin125kHzDR();
|
||||
if ((++LMIC.txCnt & 0x7) == 0) {
|
||||
failed = 1; // All DR exhausted - signal failed
|
||||
}
|
||||
|
@ -260,4 +311,29 @@ ostime_t LMICuslike_nextJoinState(void) {
|
|||
}
|
||||
#endif
|
||||
|
||||
void LMICuslike_saveAdrState(lmic_saved_adr_state_t *pStateBuffer) {
|
||||
os_copyMem(
|
||||
pStateBuffer->channelMap,
|
||||
LMIC.channelMap,
|
||||
sizeof(LMIC.channelMap)
|
||||
);
|
||||
pStateBuffer->activeChannels125khz = LMIC.activeChannels125khz;
|
||||
pStateBuffer->activeChannels500khz = LMIC.activeChannels500khz;
|
||||
}
|
||||
|
||||
void LMICuslike_restoreAdrState(const lmic_saved_adr_state_t *pStateBuffer) {
|
||||
os_copyMem(
|
||||
LMIC.channelMap,
|
||||
pStateBuffer->channelMap,
|
||||
sizeof(LMIC.channelMap)
|
||||
);
|
||||
LMIC.activeChannels125khz = pStateBuffer->activeChannels125khz;
|
||||
LMIC.activeChannels500khz = pStateBuffer->activeChannels500khz;
|
||||
}
|
||||
|
||||
|
||||
bit_t LMICuslike_compareAdrState(const lmic_saved_adr_state_t *pStateBuffer) {
|
||||
return memcmp(pStateBuffer->channelMap, LMIC.channelMap, sizeof(LMIC.channelMap)) != 0;
|
||||
}
|
||||
|
||||
#endif // CFG_LMIC_US_like
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2017 MCCI Corporation.
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -43,6 +43,9 @@
|
|||
#define IS_CHANNEL_500khz(c) (c>=64 && c<72)
|
||||
#define ENABLED_CHANNEL(chnl) ((LMIC.channelMap[(chnl >> 4)] & (1<<(chnl & 0x0F))) != 0)
|
||||
|
||||
// library functions: called from bandplan
|
||||
void LMICuslike_initJoinLoop(void);
|
||||
|
||||
// provide the isValidBeacon1 function -- int for bool.
|
||||
static inline int
|
||||
LMICuslike_isValidBeacon1(const uint8_t *d) {
|
||||
|
@ -66,7 +69,7 @@ LMICuslike_isValidBeacon1(const uint8_t *d) {
|
|||
#define LMICbandplan_advanceBeaconChannel() \
|
||||
do { LMIC.bcnChnl = (LMIC.bcnChnl+1) & 7; } while (0)
|
||||
|
||||
// TODO(tmm@mcci.com): decide whether we want to do this on every
|
||||
// TODO(tmm@mcci.com): decide whether we want to do this on every
|
||||
// reset or just restore the last sub-band selected by the user.
|
||||
#define LMICbandplan_resetDefaultChannels() \
|
||||
LMICbandplan_initDefaultChannels(/* normal */ 0)
|
||||
|
@ -77,24 +80,36 @@ void LMICuslike_initDefaultChannels(bit_t fJoin);
|
|||
#define LMICbandplan_setSessionInitDefaultChannels() \
|
||||
do { /* nothing */} while (0)
|
||||
|
||||
u1_t LMICuslike_mapChannels(u1_t chpage, u2_t chmap);
|
||||
bit_t LMICuslike_canMapChannels(u1_t chpage, u2_t chmap);
|
||||
#define LMICbandplan_canMapChannels(chpage, chmap) LMICuslike_canMapChannels(chpage, chmap)
|
||||
|
||||
bit_t LMICuslike_mapChannels(u1_t chpage, u2_t chmap);
|
||||
#define LMICbandplan_mapChannels(chpage, chmap) LMICuslike_mapChannels(chpage, chmap)
|
||||
|
||||
ostime_t LMICuslike_nextTx(ostime_t now);
|
||||
#define LMICbandplan_nextTx(now) LMICuslike_nextTx(now)
|
||||
|
||||
void LMICuslike_initJoinLoop(void);
|
||||
#define LMICbandplan_initJoinLoop() LMICuslike_initJoinLoop()
|
||||
|
||||
ostime_t LMICuslike_nextJoinState(void);
|
||||
#define LMICbandplan_nextJoinState() LMICuslike_nextJoinState();
|
||||
|
||||
static inline ostime_t LMICeulike_nextJoinTime(ostime_t now) {
|
||||
static inline ostime_t LMICuslike_nextJoinTime(ostime_t now) {
|
||||
return now;
|
||||
}
|
||||
#define LMICbandplan_nextJoinTime(now) LMICeulike_nextJoinTime(now)
|
||||
#define LMICbandplan_nextJoinTime(now) LMICuslike_nextJoinTime(now)
|
||||
|
||||
#define LMICbandplan_init() \
|
||||
do { /* nothing */ } while (0)
|
||||
|
||||
void LMICuslike_saveAdrState(lmic_saved_adr_state_t *pStateBuffer);
|
||||
#define LMICbandplan_saveAdrState(pState) LMICuslike_saveAdrState(pState)
|
||||
|
||||
bit_t LMICuslike_compareAdrState(const lmic_saved_adr_state_t *pStateBuffer);
|
||||
#define LMICbandplan_compareAdrState(pState) LMICuslike_compareAdrState(pState)
|
||||
|
||||
void LMICuslike_restoreAdrState(const lmic_saved_adr_state_t *pStateBuffer);
|
||||
#define LMICbandplan_restoreAdrState(pState) LMICuslike_restoreAdrState(pState)
|
||||
|
||||
bit_t LMICuslike_isDataRateFeasible(dr_t dr);
|
||||
#define LMICbandplan_isDataRateFeasible(dr) LMICuslike_isDataRateFeasible(dr)
|
||||
|
||||
#endif // _lmic_us_like_h_
|
||||
|
|
|
@ -44,7 +44,14 @@ typedef u1_t cr_t;
|
|||
typedef u1_t sf_t;
|
||||
typedef u1_t bw_t;
|
||||
typedef u1_t dr_t;
|
||||
|
||||
// Radio parameter set (encodes SF/BW/CR/IH/NOCRC)
|
||||
// 2..0: Spreading factor
|
||||
// 4..3: bandwidth: 0 == 125kHz, 1 == 250 kHz, 2 == 500 kHz. 3 == reserved.
|
||||
// 6..5: coding rate: 0 == 4/5, 1 == 4/6, 2 == 4/7, 3 == 4/8
|
||||
// 7: nocrc: 0 == with crc, 1 == without crc
|
||||
// 15..8: Implicit header control: 0 ==> none, 1..0xFF ==> length in bytes.
|
||||
|
||||
typedef u2_t rps_t;
|
||||
TYPEDEF_xref2rps_t;
|
||||
|
||||
|
@ -52,7 +59,7 @@ enum { ILLEGAL_RPS = 0xFF };
|
|||
|
||||
// Global maximum frame length
|
||||
enum { STD_PREAMBLE_LEN = 8 };
|
||||
enum { MAX_LEN_FRAME = 64 };
|
||||
enum { MAX_LEN_FRAME = LMIC_ENABLE_long_messages ? 255 : 64 };
|
||||
enum { LEN_DEVNONCE = 2 };
|
||||
enum { LEN_ARTNONCE = 3 };
|
||||
enum { LEN_NETID = 3 };
|
||||
|
@ -97,6 +104,8 @@ enum _dr_code_t {
|
|||
// post conditions from this block: symbols used by general code that is not
|
||||
// ostensiblly region-specific.
|
||||
// DR_DFLTMIN must be defined as a suitable substititute value if we get a bogus DR
|
||||
// It is misnamed, it should be the maximum DR (which is the minimum SF) for
|
||||
// 125 kHz.
|
||||
// DR_PAGE is used only for a non-supported debug system, but should be defined.
|
||||
// CHNL_DNW2 is the channel to be used for RX2
|
||||
// FREQ_DNW2 is the frequency to be used for RX2
|
||||
|
@ -221,8 +230,8 @@ enum _dr_configured_t {
|
|||
|
||||
#include "lorabase_au921.h"
|
||||
|
||||
// per 2.5.3: not implemented
|
||||
#define LMIC_ENABLE_TxParamSetupReq 0
|
||||
// per 2.5.3: must be implemented
|
||||
#define LMIC_ENABLE_TxParamSetupReq 1
|
||||
|
||||
enum { DR_DFLTMIN = AU921_DR_SF7 }; // DR5
|
||||
|
||||
|
@ -319,6 +328,51 @@ enum _dr_configured_t {
|
|||
};
|
||||
# endif // LMIC_DR_LEGACY
|
||||
|
||||
#elif defined(CFG_kr920) // ==============================================
|
||||
|
||||
#include "lorabase_kr920.h"
|
||||
|
||||
// per 2.8.3 (1.0.3 2.9.3): is not implemented
|
||||
#define LMIC_ENABLE_TxParamSetupReq 0
|
||||
|
||||
enum { DR_DFLTMIN = KR920_DR_SF12 }; // DR2
|
||||
// DR_PAGE is a debugging parameter
|
||||
enum { DR_PAGE = DR_PAGE_KR920 };
|
||||
|
||||
enum { FREQ_PING = KR920_FBCN }; // default ping freq
|
||||
enum { DR_PING = KR920_DR_SF9 }; // default ping DR: DR3
|
||||
enum { FREQ_DNW2 = KR920_FDOWN };
|
||||
enum { DR_DNW2 = KR920_DR_SF12 };
|
||||
enum { CHNL_BCN = 11 };
|
||||
enum { FREQ_BCN = KR920_FBCN };
|
||||
enum { DR_BCN = KR920_DR_SF9 };
|
||||
enum { AIRTIME_BCN = 144384 }; // micros
|
||||
enum { LMIC_REGION_EIRP = KR920_LMIC_REGION_EIRP }; // region uses EIRP
|
||||
|
||||
enum {
|
||||
// Beacon frame format KR SF9
|
||||
OFF_BCN_NETID = 0,
|
||||
OFF_BCN_TIME = 2,
|
||||
OFF_BCN_CRC1 = 6,
|
||||
OFF_BCN_INFO = 8,
|
||||
OFF_BCN_LAT = 9,
|
||||
OFF_BCN_LON = 12,
|
||||
OFF_BCN_CRC2 = 15,
|
||||
LEN_BCN = 17
|
||||
};
|
||||
|
||||
# if LMIC_DR_LEGACY
|
||||
enum _dr_configured_t {
|
||||
DR_SF12 = KR920_DR_SF12,
|
||||
DR_SF11 = KR920_DR_SF11,
|
||||
DR_SF10 = KR920_DR_SF10,
|
||||
DR_SF9 = KR920_DR_SF9,
|
||||
DR_SF8 = KR920_DR_SF8,
|
||||
DR_SF7 = KR920_DR_SF7,
|
||||
DR_NONE = KR920_DR_NONE
|
||||
};
|
||||
# endif // LMIC_DR_LEGACY
|
||||
|
||||
#elif defined(CFG_in866) // ==============================================
|
||||
|
||||
#include "lorabase_in866.h"
|
||||
|
@ -414,7 +468,6 @@ enum {
|
|||
HDR_FTYPE_DADN = 0x60, // data (unconfirmed) dn
|
||||
HDR_FTYPE_DCUP = 0x80, // data confirmed up
|
||||
HDR_FTYPE_DCDN = 0xA0, // data confirmed dn
|
||||
HDR_FTYPE_REJOIN = 0xC0, // rejoin for roaming
|
||||
HDR_FTYPE_PROP = 0xE0
|
||||
};
|
||||
enum {
|
||||
|
@ -422,16 +475,21 @@ enum {
|
|||
};
|
||||
enum {
|
||||
// Bitfields in frame control octet
|
||||
FCT_ADREN = 0x80,
|
||||
FCT_ADRARQ = 0x40,
|
||||
FCT_ACK = 0x20,
|
||||
FCT_MORE = 0x10, // also in DN direction: Class B indicator
|
||||
FCT_OPTLEN = 0x0F,
|
||||
FCT_ADREN = 0x80,
|
||||
FCT_ADRACKReq = 0x40,
|
||||
FCT_ACK = 0x20,
|
||||
FCT_MORE = 0x10, // also in DN direction: Class B indicator
|
||||
FCT_OPTLEN = 0x0F,
|
||||
};
|
||||
enum {
|
||||
// In UP direction: signals class B enabled
|
||||
FCT_CLASSB = FCT_MORE
|
||||
};
|
||||
|
||||
enum {
|
||||
LWAN_FCtrl_FOptsLen_MAX = 0x0Fu, // maximum size of embedded MAC commands
|
||||
};
|
||||
|
||||
enum {
|
||||
NWKID_MASK = (int)0xFE000000,
|
||||
NWKID_BITS = 7
|
||||
|
@ -440,65 +498,78 @@ enum {
|
|||
// MAC uplink commands downwlink too
|
||||
enum {
|
||||
// Class A
|
||||
MCMD_LCHK_REQ = 0x02, // - LinkCheckReq : -
|
||||
MCMD_LADR_ANS = 0x03, // - LinkADRAnd : u1:7-3:RFU, 3/2/1: pow/DR/Ch ACK
|
||||
MCMD_DCAP_ANS = 0x04, // - DutyCycleAns : -
|
||||
MCMD_DN2P_ANS = 0x05, // - RxParamSetupAns : u1:7-2:RFU 1/0:datarate/channel ack
|
||||
MCMD_DEVS_ANS = 0x06, // - DevStatusAns : u1:battery 0,1-254,255=?, u1:7-6:RFU,5-0:margin(-32..31)
|
||||
MCMD_SNCH_ANS = 0x07, // - NewChannelAns : u1: 7-2=RFU, 1/0:DR/freq ACK
|
||||
MCMD_RXTimingSetupAns = 0x08, // : -
|
||||
MCMD_TxParamSetupAns = 0x09, // : -
|
||||
MCMD_DIChannelAns = 0x0A, // : u1: [7-2]:RFU 1:exists 0:OK
|
||||
MCMD_DeviceTimeReq = 0x0D,
|
||||
MCMD_LinkCheckReq = 0x02, // -
|
||||
MCMD_LinkADRAns = 0x03, // u1:7-3:RFU, 3/2/1: pow/DR/Ch ACK
|
||||
MCMD_DutyCycleAns = 0x04, // -
|
||||
MCMD_RXParamSetupAns = 0x05, // u1:7-2:RFU 1/0:datarate/channel ack
|
||||
MCMD_DevStatusAns = 0x06, // u1:battery 0,1-254,255=?, u1:7-6:RFU,5-0:margin(-32..31)
|
||||
MCMD_NewChannelAns = 0x07, // u1: 7-2=RFU, 1/0:DR/freq ACK
|
||||
MCMD_RXTimingSetupAns = 0x08, // -
|
||||
MCMD_TxParamSetupAns = 0x09, // -
|
||||
MCMD_DlChannelAns = 0x0A, // u1: [7-2]:RFU 1:exists 0:OK
|
||||
MCMD_DeviceTimeReq = 0x0D, // -
|
||||
|
||||
// Class B
|
||||
MCMD_PING_IND = 0x10, // - pingability indic : u1: 7=RFU, 6-4:interval, 3-0:datarate
|
||||
MCMD_PING_ANS = 0x11, // - ack ping freq : u1: 7-1:RFU, 0:freq ok
|
||||
MCMD_BCNI_REQ = 0x12, // - next beacon start : -
|
||||
MCMD_PingSlotInfoReq = 0x10, // u1: 7=RFU, 6-4:interval, 3-0:datarate
|
||||
MCMD_PingSlotChannelAns = 0x11, // u1: 7-1:RFU, 0:freq ok
|
||||
MCMD_BeaconInfoReq = 0x12, // - (DEPRECATED)
|
||||
MCMD_BeaconFreqAns = 0x13, // u1: 7-1:RFU, 0:freq ok
|
||||
};
|
||||
|
||||
// MAC downlink commands
|
||||
enum {
|
||||
// Class A
|
||||
MCMD_LCHK_ANS = 0x02, // LinkCheckAns : u1:margin 0-254,255=unknown margin / u1:gwcnt LinkCheckReq
|
||||
MCMD_LADR_REQ = 0x03, // LinkADRReq : u1:DR/TXPow, u2:chmask, u1:chpage/repeat
|
||||
MCMD_DCAP_REQ = 0x04, // DutyCycleReq : u1:255 dead [7-4]:RFU, [3-0]:cap 2^-k
|
||||
MCMD_DN2P_SET = 0x05, // RXParamSetupReq : u1:7-4:RFU/3-0:datarate, u3:freq
|
||||
MCMD_DEVS_REQ = 0x06, // DevStatusReq : -
|
||||
MCMD_SNCH_REQ = 0x07, // NewChannelReq : u1:chidx, u3:freq, u1:DRrange
|
||||
MCMD_RXTimingSetupReq = 0x08, // : u1: [7-4]:RFU [3-0]: Delay 1-15s (0 => 1)
|
||||
MCMD_TxParamSetupReq = 0x09, // : u1: [7-6]:RFU [5:4]: dl dwell/ul dwell [3:0] max EIRP
|
||||
MCMD_DIChannelReq = 0x0A, // : u1: channel, u3: frequency
|
||||
MCMD_DeviceTimeAns = 0x0D,
|
||||
MCMD_LinkCheckAns = 0x02, // u1:margin 0-254,255=unknown margin / u1:gwcnt LinkCheckReq
|
||||
MCMD_LinkADRReq = 0x03, // u1:DR/TXPow, u2:chmask, u1:chpage/repeat
|
||||
MCMD_DutyCycleReq = 0x04, // u1:255 dead [7-4]:RFU, [3-0]:cap 2^-k
|
||||
MCMD_RXParamSetupReq = 0x05, // u1:7-4:RFU/3-0:datarate, u3:freq
|
||||
MCMD_DevStatusReq = 0x06, // -
|
||||
MCMD_NewChannelReq = 0x07, // u1:chidx, u3:freq, u1:DRrange
|
||||
MCMD_RXTimingSetupReq = 0x08, // u1: [7-4]:RFU [3-0]: Delay 1-15s (0 => 1)
|
||||
MCMD_TxParamSetupReq = 0x09, // u1: [7-6]:RFU [5:4]: dl dwell/ul dwell [3:0] max EIRP
|
||||
MCMD_DlChannelReq = 0x0A, // u1: channel, u3: frequency
|
||||
MCMD_DeviceTimeAns = 0x0D, // u4: seconds since epoch, u1: fractional second
|
||||
|
||||
// Class B
|
||||
MCMD_PING_SET = 0x11, // set ping freq : u3: freq
|
||||
MCMD_BCNI_ANS = 0x12, // next beacon start : u2: delay(in TUNIT millis), u1:channel
|
||||
MCMD_PingSlotInfoAns = 0x10, // -
|
||||
MCMD_PingSlotChannelReq = 0x11, // u3: freq, u1:dr [7-4]:RFU [3:0]:datarate
|
||||
MCMD_BeaconTimingAns = 0x12, // u2: delay(in TUNIT millis), u1:channel (DEPRECATED)
|
||||
MCMD_BeaconFreqReq = 0x13, // u3: freq
|
||||
};
|
||||
|
||||
enum {
|
||||
MCMD_BCNI_TUNIT = 30 // time unit of delay value in millis
|
||||
MCMD_BeaconTimingAns_TUNIT = 30 // time unit of delay value in millis
|
||||
};
|
||||
enum {
|
||||
MCMD_LADR_ANS_RFU = 0xF8, // RFU bits
|
||||
MCMD_LADR_ANS_POWACK = 0x04, // 0=not supported power level
|
||||
MCMD_LADR_ANS_DRACK = 0x02, // 0=unknown data rate
|
||||
MCMD_LADR_ANS_CHACK = 0x01, // 0=unknown channel enabled
|
||||
MCMD_LinkADRAns_RFU = 0xF8, // RFU bits
|
||||
MCMD_LinkADRAns_PowerACK = 0x04, // 0=not supported power level
|
||||
MCMD_LinkADRAns_DataRateACK = 0x02, // 0=unknown data rate
|
||||
MCMD_LinkADRAns_ChannelACK = 0x01, // 0=unknown channel enabled
|
||||
};
|
||||
enum {
|
||||
MCMD_DN2P_ANS_RFU = 0xF8, // RFU bits
|
||||
MCMD_DN2P_ANS_RX1DrOffsetAck = 0x04, // 0=dr2 not allowed
|
||||
MCMD_DN2P_ANS_DRACK = 0x02, // 0=unknown data rate
|
||||
MCMD_DN2P_ANS_CHACK = 0x01, // 0=unknown channel enabled
|
||||
MCMD_RXParamSetupAns_RFU = 0xF8, // RFU bits
|
||||
MCMD_RXParamSetupAns_RX1DrOffsetAck = 0x04, // 0=dr2 not allowed
|
||||
MCMD_RXParamSetupAns_RX2DataRateACK = 0x02, // 0=unknown data rate
|
||||
MCMD_RXParamSetupAns_ChannelACK = 0x01, // 0=unknown channel enabled
|
||||
};
|
||||
enum {
|
||||
MCMD_SNCH_ANS_RFU = 0xFC, // RFU bits
|
||||
MCMD_SNCH_ANS_DRACK = 0x02, // 0=unknown data rate
|
||||
MCMD_SNCH_ANS_FQACK = 0x01, // 0=rejected channel frequency
|
||||
MCMD_NewChannelAns_RFU = 0xFC, // RFU bits
|
||||
MCMD_NewChannelAns_DataRateACK = 0x02, // 0=unknown data rate
|
||||
MCMD_NewChannelAns_ChannelACK = 0x01, // 0=rejected channel frequency
|
||||
};
|
||||
enum {
|
||||
MCMD_PING_ANS_RFU = 0xFE,
|
||||
MCMD_PING_ANS_FQACK = 0x01
|
||||
MCMD_RXTimingSetupReq_RFU = 0xF0, // RFU bits
|
||||
MCMD_RXTimingSetupReq_Delay = 0x0F, // delay in secs, 1..15; 0 is mapped to 1.
|
||||
};
|
||||
enum {
|
||||
MCMD_DlChannelAns_RFU = 0xFC, // RFU bits
|
||||
MCMD_DlChannelAns_FreqACK = 0x02, // 0 = uplink frequency not defined for this channel
|
||||
MCMD_DlChannelAns_ChannelACK = 0x01, // 0 = rejected channel freq
|
||||
};
|
||||
enum {
|
||||
MCMD_PingSlotFreqAns_RFU = 0xFC,
|
||||
MCMD_PingSlotFreqAns_DataRateACK = 0x02,
|
||||
MCMD_PingSlotFreqAns_ChannelACK = 0x01,
|
||||
};
|
||||
|
||||
enum {
|
||||
|
@ -508,65 +579,30 @@ enum {
|
|||
MCMD_DEVS_BATT_NOINFO = 0xFF, // unknown battery level
|
||||
};
|
||||
|
||||
// Bit fields byte#3 of MCMD_LADR_REQ payload
|
||||
// Bit fields byte#3 of MCMD_LinkADRReq payload
|
||||
enum {
|
||||
MCMD_LADR_CHP_USLIKE_SPECIAL = 0x50, // first special for us-like
|
||||
MCMD_LADR_CHP_BANK = 0x50, // special: bits are banks.
|
||||
MCMD_LADR_CHP_125ON = 0x60, // special channel page enable, bits applied to 64..71
|
||||
MCMD_LADR_CHP_125OFF = 0x70, // special channel page: disble 125K, bits apply to 64..71
|
||||
MCMD_LADR_N3RFU_MASK = 0x80,
|
||||
MCMD_LADR_CHPAGE_MASK = 0xF0,
|
||||
MCMD_LADR_REPEAT_MASK = 0x0F,
|
||||
MCMD_LADR_REPEAT_1 = 0x01,
|
||||
MCMD_LADR_CHPAGE_1 = 0x10
|
||||
MCMD_LinkADRReq_Redundancy_RFU = 0x80,
|
||||
MCMD_LinkADRReq_Redundancy_ChMaskCntl_MASK= 0x70,
|
||||
MCMD_LinkADRReq_Redundancy_NbTrans_MASK = 0x0F,
|
||||
|
||||
MCMD_LinkADRReq_ChMaskCntl_EULIKE_DIRECT = 0x00, // direct masking for EU
|
||||
MCMD_LinkADRReq_ChMaskCntl_EULIKE_ALL_ON = 0x60, // EU: enable everything.
|
||||
|
||||
MCMD_LinkADRReq_ChMaskCntl_USLIKE_500K = 0x40, // mask is for the 8 us-like 500 kHz channels
|
||||
MCMD_LinkADRReq_ChMaskCntl_USLIKE_SPECIAL = 0x50, // first special for us-like
|
||||
MCMD_LinkADRReq_ChMaskCntl_USLIKE_BANK = 0x50, // special: bits are banks.
|
||||
MCMD_LinkADRReq_ChMaskCntl_USLIKE_125ON = 0x60, // special channel page enable, bits applied to 64..71
|
||||
MCMD_LinkADRReq_ChMaskCntl_USLIKE_125OFF = 0x70, // special channel page: disble 125K, bits apply to 64..71
|
||||
|
||||
MCMD_LinkADRReq_ChMaskCntl_CN470_ALL_ON = 0x60, // turn all on for China.
|
||||
};
|
||||
// Bit fields byte#0 of MCMD_LADR_REQ payload
|
||||
|
||||
// Bit fields byte#0 of MCMD_LinkADRReq payload
|
||||
enum {
|
||||
MCMD_LADR_DR_MASK = 0xF0,
|
||||
MCMD_LADR_POW_MASK = 0x0F,
|
||||
MCMD_LADR_DR_SHIFT = 4,
|
||||
MCMD_LADR_POW_SHIFT = 0,
|
||||
#if defined(CFG_eu868) // TODO(tmm@mcci.com): complete refactor.
|
||||
EU868_MCMD_LADR_SF12 = EU868_DR_SF12<<4,
|
||||
EU868_MCMD_LADR_SF11 = EU868_DR_SF11<<4,
|
||||
EU868_MCMD_LADR_SF10 = EU868_DR_SF10<<4,
|
||||
EU868_MCMD_LADR_SF9 = EU868_DR_SF9 <<4,
|
||||
EU868_MCMD_LADR_SF8 = EU868_DR_SF8 <<4,
|
||||
EU868_MCMD_LADR_SF7 = EU868_DR_SF7 <<4,
|
||||
EU868_MCMD_LADR_SF7B = EU868_DR_SF7B<<4,
|
||||
EU868_MCMD_LADR_FSK = EU868_DR_FSK <<4,
|
||||
|
||||
EU868_MCMD_LADR_20dBm = 0,
|
||||
EU868_MCMD_LADR_14dBm = 1,
|
||||
EU868_MCMD_LADR_11dBm = 2,
|
||||
EU868_MCMD_LADR_8dBm = 3,
|
||||
EU868_MCMD_LADR_5dBm = 4,
|
||||
EU868_MCMD_LADR_2dBm = 5,
|
||||
#elif defined(CFG_us915)
|
||||
US915_MCMD_LADR_SF10 = US915_DR_SF10<<4,
|
||||
US915_MCMD_LADR_SF9 = US915_DR_SF9 <<4,
|
||||
US915_MCMD_LADR_SF8 = US915_DR_SF8 <<4,
|
||||
US915_MCMD_LADR_SF7 = US915_DR_SF7 <<4,
|
||||
US915_MCMD_LADR_SF8C = US915_DR_SF8C<<4,
|
||||
US915_MCMD_LADR_SF12CR = US915_DR_SF12CR<<4,
|
||||
US915_MCMD_LADR_SF11CR = US915_DR_SF11CR<<4,
|
||||
US915_MCMD_LADR_SF10CR = US915_DR_SF10CR<<4,
|
||||
US915_MCMD_LADR_SF9CR = US915_DR_SF9CR<<4,
|
||||
US915_MCMD_LADR_SF8CR = US915_DR_SF8CR<<4,
|
||||
US915_MCMD_LADR_SF7CR = US915_DR_SF7CR<<4,
|
||||
|
||||
US915_MCMD_LADR_30dBm = 0,
|
||||
US915_MCMD_LADR_28dBm = 1,
|
||||
US915_MCMD_LADR_26dBm = 2,
|
||||
US915_MCMD_LADR_24dBm = 3,
|
||||
US915_MCMD_LADR_22dBm = 4,
|
||||
US915_MCMD_LADR_20dBm = 5,
|
||||
US915_MCMD_LADR_18dBm = 6,
|
||||
US915_MCMD_LADR_16dBm = 7,
|
||||
US915_MCMD_LADR_14dBm = 8,
|
||||
US915_MCMD_LADR_12dBm = 9,
|
||||
US915_MCMD_LADR_10dBm = 10
|
||||
#endif
|
||||
MCMD_LinkADRReq_DR_MASK = 0xF0,
|
||||
MCMD_LinkADRReq_POW_MASK = 0x0F,
|
||||
MCMD_LinkADRReq_DR_SHIFT = 4,
|
||||
MCMD_LinkADRReq_POW_SHIFT = 0,
|
||||
};
|
||||
|
||||
// bit fields of the TxParam request
|
||||
|
|
|
@ -93,4 +93,13 @@ enum { AS923_V102_TX_CAP = 100 }; // v1.0.2 allows 100%
|
|||
# define AS923_TX_CAP AS923_V102_TX_CAP
|
||||
#endif
|
||||
|
||||
// TxParam defaults
|
||||
enum {
|
||||
// initial value of UplinkDwellTime before TxParamSetupReq received.
|
||||
AS923_INITIAL_TxParam_UplinkDwellTime = 1,
|
||||
// initial value of DownlinkDwellTime before TxParamSetupReq received.
|
||||
AS923_INITIAL_TxParam_DownlinkDwellTime = 1,
|
||||
AS923_UPLINK_DWELL_TIME_osticks = sec2osticks(20),
|
||||
};
|
||||
|
||||
#endif /* _lorabase_as923_h_ */
|
||||
|
|
|
@ -76,6 +76,11 @@ enum {
|
|||
enum {
|
||||
AU921_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),
|
||||
};
|
||||
|
||||
enum { DR_PAGE_AU921 = 0x10 * (LMIC_REGION_au921 - 1) };
|
||||
|
||||
|
|
|
@ -0,0 +1,84 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Copyright (c) 2017, 2019 MCCI Corporation
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
* * Neither the name of the <organization> nor the
|
||||
* names of its contributors may be used to endorse or promote products
|
||||
* derived from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
|
||||
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#ifndef _lorabase_kr920_h_
|
||||
#define _lorabase_kr920_h_
|
||||
|
||||
#ifndef _LMIC_CONFIG_PRECONDITIONS_H_
|
||||
# include "lmic_config_preconditions.h"
|
||||
#endif
|
||||
|
||||
/****************************************************************************\
|
||||
|
|
||||
| Basic definitions for KR920 (always in scope)
|
||||
|
|
||||
\****************************************************************************/
|
||||
|
||||
enum _dr_kr920_t {
|
||||
KR920_DR_SF12 = 0, // DR0
|
||||
KR920_DR_SF11, // DR1
|
||||
KR920_DR_SF10, // DR2
|
||||
KR920_DR_SF9, // DR3
|
||||
KR920_DR_SF8, // DR4
|
||||
KR920_DR_SF7, // DR5
|
||||
KR920_DR_NONE
|
||||
};
|
||||
|
||||
// There is no dwell-time or duty-cycle limitation for IN
|
||||
//
|
||||
// max power: 30dBM
|
||||
//
|
||||
// freq datarates
|
||||
enum {
|
||||
KR920_F1 = 922100000, // SF7-12 (DR0-5)
|
||||
KR920_F2 = 922300000, // SF7-12 (DR0-5)
|
||||
KR920_F3 = 922500000, // SF7-12 (DR0-5)
|
||||
KR920_FBCN = 923100000, // beacon/ping
|
||||
KR920_F14DBM = 922100000, // Allows 14 dBm (not 10) if >= this.
|
||||
KR920_FDOWN = 921900000, // RX2 downlink frequency
|
||||
};
|
||||
enum {
|
||||
KR920_FREQ_MIN = 920900000,
|
||||
KR920_FREQ_MAX = 923300000
|
||||
};
|
||||
enum {
|
||||
KR920_TX_EIRP_MAX_DBM = 14, // 14 dBm for most
|
||||
KR920_TX_EIRP_MAX_DBM_LOW = 10, // 10 dBm for some
|
||||
};
|
||||
enum { DR_PAGE_KR920 = 0x10 * (LMIC_REGION_kr920 - 1) };
|
||||
|
||||
enum { KR920_LMIC_REGION_EIRP = 1 }; // region uses EIRP
|
||||
|
||||
enum { KR920_LBT_US = 128 }; // microseconds of LBT time.
|
||||
|
||||
enum { KR920_LBT_DB_MAX = -80 }; // maximum channel strength in dB; if TX
|
||||
// we measure more than this, we don't tx.
|
||||
|
||||
#endif /* _lorabase_in866_h_ */
|
|
@ -73,10 +73,16 @@ enum {
|
|||
US915_FREQ_MAX = 928000000
|
||||
};
|
||||
enum {
|
||||
US915_TX_MAX_DBM = 30 // 30 dBm (but not EIRP): assumes we're
|
||||
US915_TX_MAX_DBM = 30 // 30 dBm (but not EIRP): assumes we're
|
||||
// on an 64-channel bandplan. See code
|
||||
// that computes tx power.
|
||||
};
|
||||
|
||||
enum {
|
||||
US915_LinkAdrReq_POW_MAX_1_0_2 = 0xA,
|
||||
US915_LinkAdrReq_POW_MAX_1_0_3 = 0xE,
|
||||
};
|
||||
|
||||
enum { DR_PAGE_US915 = 0x10 * (LMIC_REGION_us915 - 1) };
|
||||
|
||||
enum { US915_LMIC_REGION_EIRP = 0 }; // region doesn't use EIRP, uses tx power
|
||||
|
|
|
@ -0,0 +1,64 @@
|
|||
/*
|
||||
|
||||
Module: lorawan_spec_compliance.h
|
||||
|
||||
Function:
|
||||
Details from the LoRaWAN specification for compliance.
|
||||
|
||||
Copyright notice and license info:
|
||||
See LICENSE file accompanying this project.
|
||||
|
||||
Author:
|
||||
Terry Moore, MCCI Corporation March 2019
|
||||
|
||||
*/
|
||||
|
||||
#ifndef _lorawan_spec_COMPLIANCE_H_ /* prevent multiple includes */
|
||||
#define _lorawan_spec_COMPLIANCE_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"{
|
||||
#endif
|
||||
|
||||
enum {
|
||||
// the port for MAC commands
|
||||
LORAWAN_PORT_MAC = 0u,
|
||||
// the first port available for applications
|
||||
LORAWAN_PORT_USER_MIN = 1u,
|
||||
// the last port available for applications
|
||||
LORAWAN_PORT_USER_MAX = 223u,
|
||||
// the base of the reserved port numbers
|
||||
LORAWAN_PORT_RESERVED = 224u,
|
||||
// the port for the compliance protocol
|
||||
LORAWAN_PORT_COMPLIANCE = LORAWAN_PORT_RESERVED + 0u,
|
||||
};
|
||||
|
||||
enum lowawan_compliance_cmd_e {
|
||||
LORAWAN_COMPLIANCE_CMD_DEACTIVATE = 0u,
|
||||
LORAWAN_COMPLIANCE_CMD_ACTIVATE = 1u,
|
||||
LORAWAN_COMPLIANCE_CMD_SET_CONFIRM = 2u,
|
||||
LORAWAN_COMPLIANCE_CMD_SET_UNCONFIRM = 3u,
|
||||
LORAWAN_COMPLIANCE_CMD_ECHO = 4u,
|
||||
LORAWAN_COMPLIANCE_CMD_LINK = 5u,
|
||||
LORAWAN_COMPLIANCE_CMD_JOIN = 6u,
|
||||
LORAWAN_COMPLIANCE_CMD_CW = 7u,
|
||||
LORAWAN_COMPLIANCE_CMD_MFG_BASE = 0x80u,
|
||||
};
|
||||
|
||||
typedef unsigned char lorawan_compliance_cmd_t;
|
||||
|
||||
// info on specific commands
|
||||
enum {
|
||||
LORAWAN_COMPLIANCE_CMD_ACTIVATE_LEN = 4u,
|
||||
LORAWAN_COMPLIANCE_CMD_ACTIVATE_MAGIC = 1u,
|
||||
|
||||
// Maximum crypto frame size; although the spec says 18, it
|
||||
// is also used for testing max packet size.
|
||||
LORAWAN_COMPLIANCE_CMD_ECHO_LEN_MAX = 242u,
|
||||
};
|
||||
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
#endif
|
||||
|
||||
#endif /* _lorawan_spec_COMPLIANCE_H_ */
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2016-2017 MCCI Corporation.
|
||||
* Copyright (c) 2016-2017, 2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -68,13 +68,15 @@ static int unlinkjob (osjob_t** pnext, osjob_t* job) {
|
|||
return 0;
|
||||
}
|
||||
|
||||
static osjob_t** getJobQueue(osjob_t* job) {
|
||||
return os_jobIsTimed(job) ? &OS.scheduledjobs : &OS.runnablejobs;
|
||||
}
|
||||
|
||||
// clear scheduled job
|
||||
void os_clearCallback (osjob_t* job) {
|
||||
hal_disableIRQs();
|
||||
|
||||
// if it's not in the scheduled jobs, look in the runnable...
|
||||
if (! unlinkjob(&OS.scheduledjobs, job))
|
||||
unlinkjob(&OS.runnablejobs, job);
|
||||
unlinkjob(getJobQueue(job), job);
|
||||
|
||||
hal_enableIRQs();
|
||||
}
|
||||
|
@ -83,11 +85,15 @@ void os_clearCallback (osjob_t* job) {
|
|||
void os_setCallback (osjob_t* job, osjobcb_t cb) {
|
||||
osjob_t** pnext;
|
||||
hal_disableIRQs();
|
||||
|
||||
// remove if job was already queued
|
||||
unlinkjob(&OS.runnablejobs, job);
|
||||
// fill-in job
|
||||
job->func = cb;
|
||||
unlinkjob(getJobQueue(job), job);
|
||||
|
||||
// fill-in job. Ascending memory order is write-queue friendly
|
||||
job->next = NULL;
|
||||
job->deadline = 0;
|
||||
job->func = cb;
|
||||
|
||||
// add to end of run queue
|
||||
for(pnext=&OS.runnablejobs; *pnext; pnext=&((*pnext)->next));
|
||||
*pnext = job;
|
||||
|
@ -97,13 +103,21 @@ void os_setCallback (osjob_t* job, osjobcb_t cb) {
|
|||
// schedule timed job
|
||||
void os_setTimedCallback (osjob_t* job, ostime_t time, osjobcb_t cb) {
|
||||
osjob_t** pnext;
|
||||
|
||||
// special case time 0 -- it will be one tick late.
|
||||
if (time == 0)
|
||||
time = 1;
|
||||
|
||||
hal_disableIRQs();
|
||||
|
||||
// remove if job was already queued
|
||||
unlinkjob(&OS.scheduledjobs, job);
|
||||
unlinkjob(getJobQueue(job), job);
|
||||
|
||||
// fill-in job
|
||||
job->next = NULL;
|
||||
job->deadline = time;
|
||||
job->func = cb;
|
||||
job->next = NULL;
|
||||
|
||||
// insert into schedule
|
||||
for(pnext=&OS.scheduledjobs; *pnext; pnext=&((*pnext)->next)) {
|
||||
if((*pnext)->deadline - time > 0) { // (cmp diff, not abs!)
|
||||
|
@ -141,3 +155,13 @@ void os_runloop_once() {
|
|||
j->func(j);
|
||||
}
|
||||
}
|
||||
|
||||
// return true if there are any jobs scheduled within time ticks from now.
|
||||
// return false if any jobs scheduled are at least time ticks in the future.
|
||||
bit_t os_queryTimeCriticalJobs(ostime_t time) {
|
||||
if (OS.scheduledjobs &&
|
||||
OS.scheduledjobs->deadline - os_getTime() < time)
|
||||
return 1;
|
||||
else
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2018 MCCI Corporation
|
||||
* Copyright (c) 2018, 2019 MCCI Corporation
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -84,8 +84,7 @@ typedef u1_t* xref2u1_t;
|
|||
|
||||
#define SIZEOFEXPR(x) sizeof(x)
|
||||
|
||||
#define ON_LMIC_EVENT(ev) onEvent(ev)
|
||||
#define DECL_ON_LMIC_EVENT void onEvent(ev_t e)
|
||||
#define DECL_ON_LMIC_EVENT LMIC_DECLARE_FUNCTION_WEAK(void, onEvent, (ev_t e))
|
||||
|
||||
extern u4_t AESAUX[];
|
||||
extern u4_t AESKEY[];
|
||||
|
@ -120,11 +119,19 @@ 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))
|
||||
#endif
|
||||
|
||||
#ifndef TX_RAMPUP
|
||||
// TX_RAMPUP specifies the extra time we must allow to set up a TX 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 TX_RAMPUP (us2osticks(2000))
|
||||
#endif
|
||||
|
||||
|
@ -149,7 +156,13 @@ void radio_monitor_rssi(ostime_t n, oslmic_radio_rssi_t *pRssi);
|
|||
|
||||
|
||||
struct osjob_t; // fwd decl.
|
||||
typedef void (*osjobcb_t) (struct osjob_t*);
|
||||
|
||||
//! the function type for osjob_t callbacks
|
||||
typedef void (osjobcbfn_t)(struct osjob_t*);
|
||||
|
||||
//! the pointer-to-function for osjob_t callbacks
|
||||
typedef osjobcbfn_t *osjobcb_t;
|
||||
|
||||
struct osjob_t {
|
||||
struct osjob_t* next;
|
||||
ostime_t deadline;
|
||||
|
@ -157,6 +170,11 @@ struct osjob_t {
|
|||
};
|
||||
TYPEDEF_xref2osjob_t;
|
||||
|
||||
//! determine whether a job is timed or immediate. os_setTimedCallback()
|
||||
// must treat incoming == 0 as being 1 instead.
|
||||
static inline int os_jobIsTimed(xref2osjob_t job) {
|
||||
return (job->deadline != 0);
|
||||
}
|
||||
|
||||
#ifndef HAS_os_calls
|
||||
|
||||
|
@ -190,6 +208,10 @@ void os_radio (u1_t mode);
|
|||
#ifndef os_getBattLevel
|
||||
u1_t os_getBattLevel (void);
|
||||
#endif
|
||||
#ifndef os_queryTimeCriticalJobs
|
||||
//! Return non-zero if any jobs are scheduled between now and now+time.
|
||||
bit_t os_queryTimeCriticalJobs(ostime_t time);
|
||||
#endif
|
||||
|
||||
#ifndef os_rlsbf4
|
||||
//! Read 32-bit quantity from given pointer in little endian byte order.
|
||||
|
@ -310,6 +332,18 @@ extern xref2u1_t AESaux;
|
|||
u4_t os_aes (u1_t mode, xref2u1_t buf, u2_t len);
|
||||
#endif
|
||||
|
||||
// ======================================================================
|
||||
// Simple logging support. Vanishes unless enabled.
|
||||
|
||||
#if LMIC_ENABLE_event_logging
|
||||
extern void LMICOS_logEvent(const char *pMessage);
|
||||
extern void LMICOS_logEventUint32(const char *pMessage, uint32_t datum);
|
||||
#else // ! LMIC_ENABLE_event_logging
|
||||
# define LMICOS_logEvent(m) do { ; } while (0)
|
||||
# define LMICOS_logEventUint32(m, d) do { ; } while (0)
|
||||
#endif // ! LMIC_ENABLE_event_logging
|
||||
|
||||
|
||||
LMIC_END_DECLS
|
||||
|
||||
#endif // _oslmic_h_
|
||||
|
|
561
src/lmic/radio.c
561
src/lmic/radio.c
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* Copyright (c) 2014-2016 IBM Corporation.
|
||||
* Copyright (c) 2016-2018 MCCI Corporation.
|
||||
* Copyright (c) 2016-2019 MCCI Corporation.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -32,101 +32,106 @@
|
|||
|
||||
// ----------------------------------------
|
||||
// Registers Mapping
|
||||
// // -type- 1272 vs 1276
|
||||
#define RegFifo 0x00 // common
|
||||
#define RegOpMode 0x01 // common
|
||||
#define FSKRegBitrateMsb 0x02
|
||||
#define FSKRegBitrateLsb 0x03
|
||||
#define FSKRegFdevMsb 0x04
|
||||
#define FSKRegFdevLsb 0x05
|
||||
#define RegFrfMsb 0x06 // common
|
||||
#define RegFrfMid 0x07 // common
|
||||
#define RegFrfLsb 0x08 // common
|
||||
#define RegPaConfig 0x09 // common
|
||||
#define RegPaRamp 0x0A // common
|
||||
#define RegOcp 0x0B // common
|
||||
#define RegLna 0x0C // common
|
||||
#define FSKRegRxConfig 0x0D
|
||||
#define RegOpMode 0x01 // common see below
|
||||
#define FSKRegBitrateMsb 0x02 // -
|
||||
#define FSKRegBitrateLsb 0x03 // -
|
||||
#define FSKRegFdevMsb 0x04 // -
|
||||
#define FSKRegFdevLsb 0x05 // -
|
||||
#define RegFrfMsb 0x06 // common FSK: 1272: 915; 1276: 434 MHz
|
||||
#define RegFrfMid 0x07 // common ditto
|
||||
#define RegFrfLsb 0x08 // common ditto
|
||||
#define RegPaConfig 0x09 // common see below, many diffs
|
||||
#define RegPaRamp 0x0A // common see below: bits 6..4 are diff
|
||||
#define RegOcp 0x0B // common -
|
||||
#define RegLna 0x0C // common bits 4..0 are diff.
|
||||
#define FSKRegRxConfig 0x0D // -
|
||||
#define LORARegFifoAddrPtr 0x0D
|
||||
#define FSKRegRssiConfig 0x0E
|
||||
#define FSKRegRssiConfig 0x0E // -
|
||||
#define LORARegFifoTxBaseAddr 0x0E
|
||||
#define FSKRegRssiCollision 0x0F
|
||||
#define FSKRegRssiCollision 0x0F // -
|
||||
#define LORARegFifoRxBaseAddr 0x0F
|
||||
#define FSKRegRssiThresh 0x10
|
||||
#define FSKRegRssiThresh 0x10 // -
|
||||
#define LORARegFifoRxCurrentAddr 0x10
|
||||
#define FSKRegRssiValue 0x11
|
||||
#define FSKRegRssiValue 0x11 // -
|
||||
#define LORARegIrqFlagsMask 0x11
|
||||
#define FSKRegRxBw 0x12
|
||||
#define FSKRegRxBw 0x12 // -
|
||||
#define LORARegIrqFlags 0x12
|
||||
#define FSKRegAfcBw 0x13
|
||||
#define FSKRegAfcBw 0x13 // -
|
||||
#define LORARegRxNbBytes 0x13
|
||||
#define FSKRegOokPeak 0x14
|
||||
#define FSKRegOokPeak 0x14 // -
|
||||
#define LORARegRxHeaderCntValueMsb 0x14
|
||||
#define FSKRegOokFix 0x15
|
||||
#define FSKRegOokFix 0x15 // -
|
||||
#define LORARegRxHeaderCntValueLsb 0x15
|
||||
#define FSKRegOokAvg 0x16
|
||||
#define FSKRegOokAvg 0x16 // -
|
||||
#define LORARegRxPacketCntValueMsb 0x16
|
||||
#define LORARegRxpacketCntValueLsb 0x17
|
||||
#define LORARegModemStat 0x18
|
||||
#define LORARegPktSnrValue 0x19
|
||||
#define FSKRegAfcFei 0x1A
|
||||
#define FSKRegAfcFei 0x1A // -
|
||||
#define LORARegPktRssiValue 0x1A
|
||||
#define FSKRegAfcMsb 0x1B
|
||||
#define FSKRegAfcMsb 0x1B // -
|
||||
#define LORARegRssiValue 0x1B
|
||||
#define FSKRegAfcLsb 0x1C
|
||||
#define FSKRegAfcLsb 0x1C // -
|
||||
#define LORARegHopChannel 0x1C
|
||||
#define FSKRegFeiMsb 0x1D
|
||||
#define FSKRegFeiMsb 0x1D // -
|
||||
#define LORARegModemConfig1 0x1D
|
||||
#define FSKRegFeiLsb 0x1E
|
||||
#define FSKRegFeiLsb 0x1E // -
|
||||
#define LORARegModemConfig2 0x1E
|
||||
#define FSKRegPreambleDetect 0x1F
|
||||
#define FSKRegPreambleDetect 0x1F // -
|
||||
#define LORARegSymbTimeoutLsb 0x1F
|
||||
#define FSKRegRxTimeout1 0x20
|
||||
#define FSKRegRxTimeout1 0x20 // -
|
||||
#define LORARegPreambleMsb 0x20
|
||||
#define FSKRegRxTimeout2 0x21
|
||||
#define FSKRegRxTimeout2 0x21 // -
|
||||
#define LORARegPreambleLsb 0x21
|
||||
#define FSKRegRxTimeout3 0x22
|
||||
#define FSKRegRxTimeout3 0x22 // -
|
||||
#define LORARegPayloadLength 0x22
|
||||
#define FSKRegRxDelay 0x23
|
||||
#define FSKRegRxDelay 0x23 // -
|
||||
#define LORARegPayloadMaxLength 0x23
|
||||
#define FSKRegOsc 0x24
|
||||
#define FSKRegOsc 0x24 // -
|
||||
#define LORARegHopPeriod 0x24
|
||||
#define FSKRegPreambleMsb 0x25
|
||||
#define FSKRegPreambleMsb 0x25 // -
|
||||
#define LORARegFifoRxByteAddr 0x25
|
||||
#define FSKRegPreambleLsb 0x26 // -
|
||||
#define LORARegModemConfig3 0x26
|
||||
#define FSKRegPreambleLsb 0x26
|
||||
#define FSKRegSyncConfig 0x27
|
||||
#define FSKRegSyncConfig 0x27 // -
|
||||
#define LORARegFeiMsb 0x28
|
||||
#define FSKRegSyncValue1 0x28
|
||||
#define FSKRegSyncValue1 0x28 // -
|
||||
#define LORAFeiMib 0x29
|
||||
#define FSKRegSyncValue2 0x29
|
||||
#define FSKRegSyncValue2 0x29 // -
|
||||
#define LORARegFeiLsb 0x2A
|
||||
#define FSKRegSyncValue3 0x2A
|
||||
#define FSKRegSyncValue4 0x2B
|
||||
#define FSKRegSyncValue3 0x2A // -
|
||||
#define FSKRegSyncValue4 0x2B // -
|
||||
#define LORARegRssiWideband 0x2C
|
||||
#define FSKRegSyncValue5 0x2C
|
||||
#define FSKRegSyncValue6 0x2D
|
||||
#define FSKRegSyncValue7 0x2E
|
||||
#define FSKRegSyncValue8 0x2F
|
||||
#define FSKRegPacketConfig1 0x30
|
||||
#define FSKRegPacketConfig2 0x31
|
||||
#define FSKRegSyncValue5 0x2C // -
|
||||
#define FSKRegSyncValue6 0x2D // -
|
||||
#define FSKRegSyncValue7 0x2E // -
|
||||
#define FSKRegSyncValue8 0x2F // -
|
||||
#define LORARegIffReq1 0x2F
|
||||
#define FSKRegPacketConfig1 0x30 // -
|
||||
#define LORARegIffReq2 0x30
|
||||
#define FSKRegPacketConfig2 0x31 // -
|
||||
#define LORARegDetectOptimize 0x31
|
||||
#define FSKRegPayloadLength 0x32
|
||||
#define FSKRegNodeAdrs 0x33
|
||||
#define FSKRegPayloadLength 0x32 // -
|
||||
#define FSKRegNodeAdrs 0x33 // -
|
||||
#define LORARegInvertIQ 0x33
|
||||
#define FSKRegBroadcastAdrs 0x34
|
||||
#define FSKRegFifoThresh 0x35
|
||||
#define FSKRegSeqConfig1 0x36
|
||||
#define FSKRegSeqConfig2 0x37
|
||||
#define FSKRegBroadcastAdrs 0x34 // -
|
||||
#define FSKRegFifoThresh 0x35 // -
|
||||
#define FSKRegSeqConfig1 0x36 // -
|
||||
#define LORARegHighBwOptimize1 0x36
|
||||
#define FSKRegSeqConfig2 0x37 // -
|
||||
#define LORARegDetectionThreshold 0x37
|
||||
#define FSKRegTimerResol 0x38
|
||||
#define FSKRegTimer1Coef 0x39
|
||||
#define FSKRegTimerResol 0x38 // -
|
||||
#define FSKRegTimer1Coef 0x39 // -
|
||||
#define LORARegSyncWord 0x39
|
||||
#define FSKRegTimer2Coef 0x3A
|
||||
#define FSKRegImageCal 0x3B
|
||||
#define FSKRegTemp 0x3C
|
||||
#define FSKRegLowBat 0x3D
|
||||
#define FSKRegIrqFlags1 0x3E
|
||||
#define FSKRegIrqFlags2 0x3F
|
||||
#define FSKRegTimer2Coef 0x3A // -
|
||||
#define LORARegHighBwOptimize2 0x3A
|
||||
#define FSKRegImageCal 0x3B // -
|
||||
#define FSKRegTemp 0x3C // -
|
||||
#define FSKRegLowBat 0x3D // -
|
||||
#define FSKRegIrqFlags1 0x3E // -
|
||||
#define FSKRegIrqFlags2 0x3F // -
|
||||
#define RegDioMapping1 0x40 // common
|
||||
#define RegDioMapping2 0x41 // common
|
||||
#define RegVersion 0x42 // common
|
||||
|
@ -142,8 +147,8 @@
|
|||
// #define RegBitRateFrac 0x70 // common
|
||||
|
||||
#if defined(CFG_sx1276_radio)
|
||||
#define RegTcxo 0x4B // common
|
||||
#define RegPaDac 0x4D // common
|
||||
#define RegTcxo 0x4B // common different addresses, same bits
|
||||
#define RegPaDac 0x4D // common differnet addresses, same bits
|
||||
#elif defined(CFG_sx1272_radio)
|
||||
#define RegTcxo 0x58 // common
|
||||
#define RegPaDac 0x5A // common
|
||||
|
@ -188,6 +193,34 @@
|
|||
|
||||
#define SX1276_MC1_IMPLICIT_HEADER_MODE_ON 0x01
|
||||
|
||||
#ifdef CFG_sx1276_radio
|
||||
# define SX127X_MC1_IMPLICIT_HEADER_MODE_ON SX1276_MC1_IMPLICIT_HEADER_MODE_ON
|
||||
#else
|
||||
# define SX127X_MC1_IMPLICIT_HEADER_MODE_ON SX1272_MC1_IMPLICIT_HEADER_MODE_ON
|
||||
#endif
|
||||
|
||||
// transmit power configuration for RegPaConfig
|
||||
#define SX1276_PAC_PA_SELECT_PA_BOOST 0x80
|
||||
#define SX1276_PAC_PA_SELECT_RFIO_PIN 0x00
|
||||
#define SX1276_PAC_MAX_POWER_MASK 0x70
|
||||
|
||||
// the bits to change for max power.
|
||||
#define SX127X_PADAC_POWER_MASK 0x07
|
||||
#define SX127X_PADAC_POWER_NORMAL 0x04
|
||||
#define SX127X_PADAC_POWER_20dBm 0x07
|
||||
|
||||
// convert milliamperes to equivalent value for
|
||||
// RegOcp; delivers conservative value.
|
||||
#define SX127X_OCP_MAtoBITS(mA) \
|
||||
((mA) < 45 ? 0 : \
|
||||
(mA) <= 120 ? ((mA) - 45) / 5 : \
|
||||
(mA) < 130 ? 0xF : \
|
||||
(mA) < 240 ? ((mA) - 130) / 10 + 0x10 : \
|
||||
27)
|
||||
|
||||
// bit in RegOcp that enables overcurrent protect.
|
||||
#define SX127X_OCP_ENA 0x20
|
||||
|
||||
// sx1276 RegModemConfig2
|
||||
#define SX1276_MC2_RX_PAYLOAD_CRCON 0x04
|
||||
|
||||
|
@ -208,10 +241,13 @@
|
|||
//-----------------------------------------
|
||||
// Parameters for RSSI monitoring
|
||||
#define SX127X_FREQ_LF_MAX 525000000 // per datasheet 6.3
|
||||
|
||||
// per datasheet 5.5.3:
|
||||
#define SX127X_RSSI_ADJUST_LF -164 // add to rssi value to get dB (LF)
|
||||
#define SX127X_RSSI_ADJUST_HF -157 // add to rssi value to get dB (HF)
|
||||
|
||||
// per datasheet 5.5.3 and 5.5.5:
|
||||
#define SX1272_RSSI_ADJUST -139 // add to rssi value to get dB (LF)
|
||||
|
||||
// per datasheet 5.5.3 and 5.5.5:
|
||||
#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)
|
||||
|
||||
// per datasheet 2.5.2 (but note that we ought to ask Semtech to confirm, because
|
||||
// datasheet is unclear).
|
||||
|
@ -230,6 +266,40 @@
|
|||
#define OPMODE_RX_SINGLE 0x06
|
||||
#define OPMODE_CAD 0x07
|
||||
|
||||
// ----------------------------------------
|
||||
// FSK opmode bits
|
||||
// bits 6:5 are the same for 1272 and 1276
|
||||
#define OPMODE_FSK_SX127x_ModulationType_FSK (0u << 5)
|
||||
#define OPMODE_FSK_SX127x_ModulationType_OOK (1u << 5)
|
||||
#define OPMODE_FSK_SX127x_ModulationType_MASK (3u << 5)
|
||||
|
||||
// bits 4:3 are different for 1272
|
||||
#define OPMODE_FSK_SX1272_ModulationShaping_FSK_None (0u << 3)
|
||||
#define OPMODE_FSK_SX1272_ModulationShaping_FSK_BT1_0 (1u << 3)
|
||||
#define OPMODE_FSK_SX1272_ModulationShaping_FSK_BT0_5 (2u << 3)
|
||||
#define OPMODE_FSK_SX1272_ModulationShaping_FSK_BT0_3 (3u << 3)
|
||||
#define OPMODE_FSK_SX1272_ModulationShaping_OOK_None (0u << 3)
|
||||
#define OPMODE_FSK_SX1272_ModulationShaping_OOK_BR (1u << 3)
|
||||
#define OPMODE_FSK_SX1272_ModulationShaping_OOK_2BR (2u << 3)
|
||||
|
||||
#define OPMODE_FSK_SX1272_ModulationShaping_MASK (3u << 3)
|
||||
|
||||
// SX1276
|
||||
#define OPMODE_FSK_SX1276_LowFrequencyModeOn (1u << 3)
|
||||
|
||||
// define the opmode bits apporpriate for the 127x in use.
|
||||
#if defined(CFG_sx1272_radio)
|
||||
# define OPMODE_FSK_SX127X_SETUP (OPMODE_FSK_SX127x_ModulationType_FSK | \
|
||||
OPMODE_FSK_SX1272_ModulationShaping_FSK_BT0_5)
|
||||
#elif defined(CFG_sx1276_radio)
|
||||
# define OPMODE_FSK_SX127X_SETUP (OPMODE_FSK_SX127x_ModulationType_FSK)
|
||||
#endif
|
||||
|
||||
// ----------------------------------------
|
||||
// LoRa opmode bits
|
||||
#define OPMODE_LORA_SX127x_AccessSharedReg (1u << 6)
|
||||
#define OPMODE_LORA_SX1276_LowFrequencyModeOn (1u << 3)
|
||||
|
||||
// ----------------------------------------
|
||||
// Bits masking the corresponding IRQs from the radio
|
||||
#define IRQ_LORA_RXTOUT_MASK 0x80
|
||||
|
@ -264,7 +334,7 @@
|
|||
#define MAP_DIO0_LORA_TXDONE 0x40 // 01------
|
||||
#define MAP_DIO1_LORA_RXTOUT 0x00 // --00----
|
||||
#define MAP_DIO1_LORA_NOP 0x30 // --11----
|
||||
#define MAP_DIO2_LORA_NOP 0xC0 // ----11--
|
||||
#define MAP_DIO2_LORA_NOP 0x0C // ----11--
|
||||
|
||||
#define MAP_DIO0_FSK_READY 0x00 // 00------ (packet sent / payload ready)
|
||||
#define MAP_DIO1_FSK_NOP 0x30 // --11----
|
||||
|
@ -283,20 +353,20 @@
|
|||
#define RF_IMAGECAL_IMAGECAL_RUNNING 0x20
|
||||
#define RF_IMAGECAL_IMAGECAL_DONE 0x00 // Default
|
||||
|
||||
|
||||
// RADIO STATE
|
||||
// (initialized by radio_init(), used by radio_rand1())
|
||||
static u1_t randbuf[16];
|
||||
|
||||
|
||||
// LNA gain constant. Bits 4..0 have different meaning for 1272 and 1276, but
|
||||
// by chance, the bit patterns we use are the same.
|
||||
#ifdef CFG_sx1276_radio
|
||||
#define LNA_RX_GAIN (0x20|0x1)
|
||||
#define LNA_RX_GAIN (0x20|0x3)
|
||||
#elif CFG_sx1272_radio
|
||||
#define LNA_RX_GAIN (0x20|0x03)
|
||||
#else
|
||||
#error Missing CFG_sx1272_radio/CFG_sx1276_radio
|
||||
#endif
|
||||
|
||||
// RADIO STATE
|
||||
// (initialized by radio_init(), used by radio_rand1())
|
||||
static u1_t randbuf[16];
|
||||
|
||||
|
||||
static void writeReg (u1_t addr, u1_t data ) {
|
||||
hal_spi_write(addr | 0x80, &data, 1);
|
||||
|
@ -339,15 +409,20 @@ static void opmode (u1_t mode) {
|
|||
static void opmodeLora() {
|
||||
u1_t u = OPMODE_LORA;
|
||||
#ifdef CFG_sx1276_radio
|
||||
u |= 0x8; // TBD: sx1276 high freq
|
||||
if (LMIC.freq <= SX127X_FREQ_LF_MAX) {
|
||||
u |= OPMODE_FSK_SX1276_LowFrequencyModeOn;
|
||||
}
|
||||
#endif
|
||||
writeOpmode(u);
|
||||
}
|
||||
|
||||
static void opmodeFSK() {
|
||||
u1_t u = 0;
|
||||
u1_t u = OPMODE_FSK_SX127X_SETUP;
|
||||
|
||||
#ifdef CFG_sx1276_radio
|
||||
u |= 0x8; // TBD: sx1276 high freq
|
||||
if (LMIC.freq <= SX127X_FREQ_LF_MAX) {
|
||||
u |= OPMODE_FSK_SX1276_LowFrequencyModeOn;
|
||||
}
|
||||
#endif
|
||||
writeOpmode(u);
|
||||
}
|
||||
|
@ -359,7 +434,9 @@ static void configLoraModem () {
|
|||
#ifdef CFG_sx1276_radio
|
||||
u1_t mc1 = 0, mc2 = 0, mc3 = 0;
|
||||
|
||||
switch (getBw(LMIC.rps)) {
|
||||
bw_t const bw = getBw(LMIC.rps);
|
||||
|
||||
switch (bw) {
|
||||
case BW125: mc1 |= SX1276_MC1_BW_125; break;
|
||||
case BW250: mc1 |= SX1276_MC1_BW_250; break;
|
||||
case BW500: mc1 |= SX1276_MC1_BW_500; break;
|
||||
|
@ -389,10 +466,34 @@ static void configLoraModem () {
|
|||
writeReg(LORARegModemConfig2, mc2);
|
||||
|
||||
mc3 = SX1276_MC3_AGCAUTO;
|
||||
if ((sf == SF11 || sf == SF12) && getBw(LMIC.rps) == BW125) {
|
||||
|
||||
if ( ((sf == SF11 || sf == SF12) && bw == BW125) ||
|
||||
((sf == SF12) && bw == BW250) ) {
|
||||
mc3 |= SX1276_MC3_LOW_DATA_RATE_OPTIMIZE;
|
||||
}
|
||||
writeReg(LORARegModemConfig3, mc3);
|
||||
|
||||
// Errata 2.1: Sensitivity optimization with 500 kHz bandwidth
|
||||
u1_t rHighBwOptimize1;
|
||||
u1_t rHighBwOptimize2;
|
||||
|
||||
rHighBwOptimize1 = 0x03;
|
||||
rHighBwOptimize2 = 0;
|
||||
|
||||
if (bw == BW500) {
|
||||
if (LMIC.freq > SX127X_FREQ_LF_MAX) {
|
||||
rHighBwOptimize1 = 0x02;
|
||||
rHighBwOptimize2 = 0x64;
|
||||
} else {
|
||||
rHighBwOptimize1 = 0x02;
|
||||
rHighBwOptimize2 = 0x7F;
|
||||
}
|
||||
}
|
||||
|
||||
writeReg(LORARegHighBwOptimize1, rHighBwOptimize1);
|
||||
if (rHighBwOptimize2 != 0)
|
||||
writeReg(LORARegHighBwOptimize2, rHighBwOptimize2);
|
||||
|
||||
#elif CFG_sx1272_radio
|
||||
u1_t mc1 = (getBw(LMIC.rps)<<6);
|
||||
|
||||
|
@ -440,69 +541,220 @@ static void configChannel () {
|
|||
writeReg(RegFrfLsb, (u1_t)(frf>> 0));
|
||||
}
|
||||
|
||||
|
||||
// On the SX1276, we have several possible configs.
|
||||
// 1) using RFO, MaxPower==0: in that case power is -4 to 11 dBm
|
||||
// 2) using RFO, MaxPower==7: in that case, power is 0 to 14 dBm
|
||||
// (can't select 15 dBm).
|
||||
// note we can use -4..11 w/o Max and then 12..14 w/Max, and
|
||||
// we really don't need to ask anybody.
|
||||
// 3) using PA_BOOST, PaDac = 4: in that case power range is 2 to 17 dBm;
|
||||
// use this for 15..17 if authorized.
|
||||
// 4) using PA_BOOST, PaDac = 7, OutputPower=0xF: in that case, power is 20 dBm
|
||||
// (and perhaps 0xE is 19, 0xD is 18 dBm, but datasheet isn't clear.)
|
||||
// and duty cycle must be <= 1%.
|
||||
//
|
||||
// In addition, there are some boards for which PA_BOOST can only be used if the
|
||||
// channel frequency is greater than SX127X_FREQ_LF_MAX.
|
||||
//
|
||||
// The SX1272 is similar but has no MaxPower bit:
|
||||
// 1) using RFO: power is -1 to 13 dBm (datasheet implies max OutputPower value is 14 for 13 dBm)
|
||||
// 2) using PA_BOOST, PaDac = 0x84: power is 2 to 17 dBm;
|
||||
// use this for 14..17 if authorized
|
||||
// 3) using PA_BOOST, PaDac = 0x87, OutputPower = 0xF: power is 20dBm
|
||||
// and duty cycle must be <= 1%
|
||||
//
|
||||
// The general policy is to use the lowest power variant that will get us where we
|
||||
// need to be.
|
||||
//
|
||||
|
||||
static void configPower () {
|
||||
// our input paramter -- might be different than LMIC.txpow!
|
||||
s1_t const req_pw = (s1_t)LMIC.radio_txpow;
|
||||
// the effective power
|
||||
s1_t eff_pw;
|
||||
// the policy; we're going to compute this.
|
||||
u1_t policy;
|
||||
// what we'll write to RegPaConfig
|
||||
u1_t rPaConfig;
|
||||
// what we'll write to RegPaDac
|
||||
u1_t rPaDac;
|
||||
// what we'll write to RegOcp
|
||||
u1_t rOcp;
|
||||
|
||||
#ifdef CFG_sx1276_radio
|
||||
// PA_BOOST output is assumed but not 20 dBm.
|
||||
s1_t pw = (s1_t)LMIC.txpow;
|
||||
if(pw > 17) {
|
||||
pw = 17;
|
||||
} else if(pw < 2) {
|
||||
pw = 2;
|
||||
if (req_pw >= 20) {
|
||||
policy = LMICHAL_radio_tx_power_policy_20dBm;
|
||||
eff_pw = 20;
|
||||
} else if (req_pw >= 14) {
|
||||
policy = LMICHAL_radio_tx_power_policy_paboost;
|
||||
if (req_pw > 17) {
|
||||
eff_pw = 17;
|
||||
} else {
|
||||
eff_pw = req_pw;
|
||||
}
|
||||
} else {
|
||||
policy = LMICHAL_radio_tx_power_policy_rfo;
|
||||
if (req_pw < -4) {
|
||||
eff_pw = -4;
|
||||
} else {
|
||||
eff_pw = req_pw;
|
||||
}
|
||||
}
|
||||
|
||||
policy = hal_getTxPowerPolicy(policy, eff_pw, LMIC.freq);
|
||||
|
||||
switch (policy) {
|
||||
default:
|
||||
case LMICHAL_radio_tx_power_policy_rfo:
|
||||
rPaDac = SX127X_PADAC_POWER_NORMAL;
|
||||
rOcp = SX127X_OCP_MAtoBITS(80);
|
||||
|
||||
if (eff_pw > 14)
|
||||
eff_pw = 14;
|
||||
if (eff_pw > 11) {
|
||||
// some Semtech code uses this down to eff_pw == 0.
|
||||
rPaConfig = eff_pw | SX1276_PAC_MAX_POWER_MASK;
|
||||
} else {
|
||||
if (eff_pw < -4)
|
||||
eff_pw = -4;
|
||||
rPaConfig = eff_pw + 4;
|
||||
}
|
||||
break;
|
||||
|
||||
// some radios (HopeRF RFM95W) don't support RFO well,
|
||||
// so the policy might *raise* rfo to paboost. That means
|
||||
// we have to re-check eff_pw, which might be too small.
|
||||
// (And, of course, it might also be too large.)
|
||||
case LMICHAL_radio_tx_power_policy_paboost:
|
||||
// It seems that SX127x doesn't like eff_pw 10 when in FSK mode.
|
||||
if (getSf(LMIC.rps) == FSK && eff_pw < 11) {
|
||||
eff_pw = 11;
|
||||
}
|
||||
rPaDac = SX127X_PADAC_POWER_NORMAL;
|
||||
rOcp = SX127X_OCP_MAtoBITS(100);
|
||||
if (eff_pw > 17)
|
||||
eff_pw = 17;
|
||||
else if (eff_pw < 2)
|
||||
eff_pw = 2;
|
||||
rPaConfig = (eff_pw - 2) | SX1276_PAC_PA_SELECT_PA_BOOST;
|
||||
break;
|
||||
|
||||
case LMICHAL_radio_tx_power_policy_20dBm:
|
||||
rPaDac = SX127X_PADAC_POWER_20dBm;
|
||||
rOcp = SX127X_OCP_MAtoBITS(130);
|
||||
rPaConfig = 0xF | SX1276_PAC_PA_SELECT_PA_BOOST;
|
||||
break;
|
||||
}
|
||||
// 0x80 forces use of PA_BOOST; but we don't
|
||||
// turn on 20 dBm mode. So powers are:
|
||||
// 0000 => 2dBm, 0001 => 3dBm, ... 1111 => 17dBm
|
||||
// But we also enforce that the high-power mode
|
||||
// is off by writing RegPaDac.
|
||||
writeReg(RegPaConfig, (u1_t)(0x80|(pw - 2)));
|
||||
writeReg(RegPaDac, readReg(RegPaDac)|0x4);
|
||||
|
||||
#elif CFG_sx1272_radio
|
||||
// set PA config (2-17 dBm using PA_BOOST)
|
||||
s1_t pw = (s1_t)LMIC.txpow;
|
||||
if(pw > 17) {
|
||||
pw = 17;
|
||||
} else if(pw < 2) {
|
||||
pw = 2;
|
||||
if (req_pw >= 20) {
|
||||
policy = LMICHAL_radio_tx_power_policy_20dBm;
|
||||
eff_pw = 20;
|
||||
} else if (eff_pw >= 14) {
|
||||
policy = LMICHAL_radio_tx_power_policy_paboost;
|
||||
if (eff_pw > 17) {
|
||||
eff_pw = 17;
|
||||
} else {
|
||||
eff_pw = req_pw;
|
||||
}
|
||||
} else {
|
||||
policy = LMICHAL_radio_tx_power_policy_rfo;
|
||||
if (req_pw < -1) {
|
||||
eff_pw = -1;
|
||||
} else {
|
||||
eff_pw = req_pw;
|
||||
}
|
||||
}
|
||||
|
||||
policy = hal_getTxPowerPolicy(policy, eff_pw, LMIC.freq);
|
||||
|
||||
switch (policy) {
|
||||
default:
|
||||
case LMICHAL_radio_tx_power_policy_rfo:
|
||||
rPaDac = SX127X_PADAC_POWER_NORMAL;
|
||||
rOcp = SX127X_OCP_MAtoBITS(50);
|
||||
|
||||
if (eff_pw > 13)
|
||||
eff_pw = 13;
|
||||
|
||||
rPaConfig = eff_pw + 1;
|
||||
break;
|
||||
|
||||
case LMICHAL_radio_tx_power_policy_paboost:
|
||||
rPaDac = SX127X_PADAC_POWER_NORMAL;
|
||||
rOcp = SX127X_OCP_MAtoBITS(100);
|
||||
|
||||
if (eff_pw > 17)
|
||||
eff_pw = 17;
|
||||
|
||||
rPaConfig = (eff_pw - 2) | SX1272_PAC_PA_SELECT_PA_BOOST;
|
||||
break;
|
||||
|
||||
case LMICHAL_radio_tx_power_policy_20dBm:
|
||||
rPaDac = SX127X_PADAC_POWER_20dBm;
|
||||
rOcp = SX127X_OCP_MAtoBITS(130);
|
||||
|
||||
rPaConfig = 0xF | SX1276_PAC_PA_SELECT_PA_BOOST;
|
||||
break;
|
||||
}
|
||||
writeReg(RegPaConfig, (u1_t)(0x80|(pw-2)));
|
||||
#else
|
||||
#error Missing CFG_sx1272_radio/CFG_sx1276_radio
|
||||
#endif /* CFG_sx1272_radio */
|
||||
|
||||
writeReg(RegPaConfig, rPaConfig);
|
||||
writeReg(RegPaDac, (readReg(RegPaDac) & ~SX127X_PADAC_POWER_MASK) | rPaDac);
|
||||
writeReg(RegOcp, rOcp | SX127X_OCP_ENA);
|
||||
}
|
||||
|
||||
static void txfsk () {
|
||||
// select FSK modem (from sleep mode)
|
||||
writeOpmode(0x10); // FSK, BT=0.5
|
||||
ASSERT(readReg(RegOpMode) == 0x10);
|
||||
// enter standby mode (required for FIFO loading))
|
||||
opmode(OPMODE_STANDBY);
|
||||
static void setupFskRxTx(bit_t fDisableAutoClear) {
|
||||
// set bitrate
|
||||
writeReg(FSKRegBitrateMsb, 0x02); // 50kbps
|
||||
writeReg(FSKRegBitrateLsb, 0x80);
|
||||
// set frequency deviation
|
||||
writeReg(FSKRegFdevMsb, 0x01); // +/- 25kHz
|
||||
writeReg(FSKRegFdevLsb, 0x99);
|
||||
// frame and packet handler settings
|
||||
writeReg(FSKRegPreambleMsb, 0x00);
|
||||
writeReg(FSKRegPreambleLsb, 0x05);
|
||||
writeReg(FSKRegSyncConfig, 0x12);
|
||||
writeReg(FSKRegPacketConfig1, 0xD0);
|
||||
writeReg(FSKRegPacketConfig2, 0x40);
|
||||
|
||||
// set sync config
|
||||
writeReg(FSKRegSyncConfig, 0x12); // no auto restart, preamble 0xAA, enable, fill FIFO, 3 bytes sync
|
||||
|
||||
// set packet config
|
||||
writeReg(FSKRegPacketConfig1, fDisableAutoClear ? 0xD8 : 0xD0); // var-length, whitening, crc, no auto-clear, no adr filter
|
||||
writeReg(FSKRegPacketConfig2, 0x40); // packet mode
|
||||
|
||||
// set sync value
|
||||
writeReg(FSKRegSyncValue1, 0xC1);
|
||||
writeReg(FSKRegSyncValue2, 0x94);
|
||||
writeReg(FSKRegSyncValue3, 0xC1);
|
||||
}
|
||||
|
||||
static void txfsk () {
|
||||
// select FSK modem (from sleep mode)
|
||||
opmodeFSK();
|
||||
|
||||
// enter standby mode (required for FIFO loading))
|
||||
opmode(OPMODE_STANDBY);
|
||||
// set bitrate etc
|
||||
setupFskRxTx(/* don't autoclear CRC */ 0);
|
||||
|
||||
// frame and packet handler settings
|
||||
writeReg(FSKRegPreambleMsb, 0x00);
|
||||
writeReg(FSKRegPreambleLsb, 0x05);
|
||||
|
||||
// configure frequency
|
||||
configChannel();
|
||||
// configure output power
|
||||
configPower();
|
||||
|
||||
#ifdef CFG_sx1276_radio
|
||||
// select Gausian filter BT=0.5, default ramp.
|
||||
writeReg(RegPaRamp, 0x29);
|
||||
#endif
|
||||
|
||||
// set the IRQ mapping DIO0=PacketSent DIO1=NOP DIO2=NOP
|
||||
writeReg(RegDioMapping1, MAP_DIO0_FSK_READY|MAP_DIO1_FSK_NOP|MAP_DIO2_FSK_TXNOP);
|
||||
|
||||
// initialize the payload size and address pointers
|
||||
// TODO(tmm@mcci.com): datasheet says this is not used in variable packet length mode
|
||||
writeReg(FSKRegPayloadLength, LMIC.dataLen+1); // (insert length byte into payload))
|
||||
|
||||
// download length byte and buffer to the radio FIFO
|
||||
|
@ -529,7 +781,11 @@ static void txlora () {
|
|||
// configure frequency
|
||||
configChannel();
|
||||
// configure output power
|
||||
#ifdef CFG_sx1272_radio
|
||||
writeReg(RegPaRamp, (readReg(RegPaRamp) & 0xF0) | 0x08); // set PA ramp-up time 50 uSec
|
||||
#elif defined(CFG_sx1276_radio)
|
||||
writeReg(RegPaRamp, 0x08); // set PA ramp-up time 50 uSec, clear FSK bits
|
||||
#endif
|
||||
configPower();
|
||||
// set sync word
|
||||
writeReg(LORARegSyncWord, LORA_MAC_PREAMBLE);
|
||||
|
@ -587,7 +843,7 @@ static void starttx () {
|
|||
oslmic_radio_rssi_t rssi;
|
||||
radio_monitor_rssi(LMIC.lbt_ticks, &rssi);
|
||||
#if LMIC_X_DEBUG_LEVEL > 0
|
||||
LMIC_X_DEBUG_PRINTF("LBT rssi max:min=%d:%d %d times in %d\n", rssi.max_rssi, rssi.min_rssi, rssi.n_rssi, LMIC.lbt_ticks);
|
||||
LMIC_X_DEBUG_PRINTF("LBT rssi max:min=%d:%d %d times in %d\n", rssi.max_rssi, rssi.min_rssi, rssi.n_rssi, LMIC.lbt_ticks);
|
||||
#endif
|
||||
|
||||
if (rssi.max_rssi >= LMIC.lbt_dbmax) {
|
||||
|
@ -634,8 +890,8 @@ static void rxlora (u1_t rxmode) {
|
|||
// set LNA gain
|
||||
writeReg(RegLna, LNA_RX_GAIN);
|
||||
// set max payload size
|
||||
writeReg(LORARegPayloadMaxLength, 64);
|
||||
#if !defined(DISABLE_INVERT_IQ_ON_RX)
|
||||
writeReg(LORARegPayloadMaxLength, MAX_LEN_FRAME);
|
||||
#if !defined(DISABLE_INVERT_IQ_ON_RX) /* DEPRECATED(tmm@mcci.com); #250. remove test, always include code in V3 */
|
||||
// use inverted I/Q signal (prevent mote-to-mote communication)
|
||||
|
||||
// XXX: use flag to switch on/off inversion
|
||||
|
@ -645,6 +901,18 @@ static void rxlora (u1_t rxmode) {
|
|||
writeReg(LORARegInvertIQ, readReg(LORARegInvertIQ)|(1<<6));
|
||||
}
|
||||
#endif
|
||||
|
||||
// Errata 2.3 - receiver spurious reception of a LoRa signal
|
||||
bw_t const bw = getBw(LMIC.rps);
|
||||
u1_t const rDetectOptimize = (readReg(LORARegDetectOptimize) & 0x78) | 0x03;
|
||||
if (bw < BW500) {
|
||||
writeReg(LORARegDetectOptimize, rDetectOptimize);
|
||||
writeReg(LORARegIffReq1, 0x40);
|
||||
writeReg(LORARegIffReq2, 0x40);
|
||||
} else {
|
||||
writeReg(LORARegDetectOptimize, rDetectOptimize | 0x80);
|
||||
}
|
||||
|
||||
// set symbol timeout (for single rx)
|
||||
writeReg(LORARegSymbTimeoutLsb, LMIC.rxsyms);
|
||||
// set sync word
|
||||
|
@ -660,13 +928,16 @@ static void rxlora (u1_t rxmode) {
|
|||
// enable antenna switch for RX
|
||||
hal_pin_rxtx(0);
|
||||
|
||||
writeReg(LORARegFifoAddrPtr, 0);
|
||||
writeReg(LORARegFifoRxBaseAddr, 0);
|
||||
|
||||
// now instruct the radio to receive
|
||||
if (rxmode == RXMODE_SINGLE) { // single rx
|
||||
hal_waitUntil(LMIC.rxtime); // busy wait until exact rx time
|
||||
opmode(OPMODE_RX_SINGLE);
|
||||
#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);
|
||||
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)
|
||||
opmode(OPMODE_RX);
|
||||
|
@ -703,33 +974,19 @@ static void rxfsk (u1_t rxmode) {
|
|||
// configure frequency
|
||||
configChannel();
|
||||
// set LNA gain
|
||||
//writeReg(RegLna, 0x20|0x03); // max gain, boost enable
|
||||
writeReg(RegLna, LNA_RX_GAIN);
|
||||
writeReg(RegLna, LNA_RX_GAIN); // max gain, boost enable.
|
||||
// configure receiver
|
||||
writeReg(FSKRegRxConfig, 0x1E); // AFC auto, AGC, trigger on preamble?!?
|
||||
// set receiver bandwidth
|
||||
writeReg(FSKRegRxBw, 0x0B); // 50kHz SSb
|
||||
writeReg(FSKRegRxBw, 0x0B); // 50kHz SSb
|
||||
// set AFC bandwidth
|
||||
writeReg(FSKRegAfcBw, 0x12); // 83.3kHz SSB
|
||||
writeReg(FSKRegAfcBw, 0x12); // 83.3kHz SSB
|
||||
// set preamble detection
|
||||
writeReg(FSKRegPreambleDetect, 0xAA); // enable, 2 bytes, 10 chip errors
|
||||
// set sync config
|
||||
writeReg(FSKRegSyncConfig, 0x12); // no auto restart, preamble 0xAA, enable, fill FIFO, 3 bytes sync
|
||||
// set packet config
|
||||
writeReg(FSKRegPacketConfig1, 0xD8); // var-length, whitening, crc, no auto-clear, no adr filter
|
||||
writeReg(FSKRegPacketConfig2, 0x40); // packet mode
|
||||
// set sync value
|
||||
writeReg(FSKRegSyncValue1, 0xC1);
|
||||
writeReg(FSKRegSyncValue2, 0x94);
|
||||
writeReg(FSKRegSyncValue3, 0xC1);
|
||||
// set preamble timeout
|
||||
writeReg(FSKRegRxTimeout2, 0xFF);//(LMIC.rxsyms+1)/2);
|
||||
// set bitrate
|
||||
writeReg(FSKRegBitrateMsb, 0x02); // 50kbps
|
||||
writeReg(FSKRegBitrateLsb, 0x80);
|
||||
// set frequency deviation
|
||||
writeReg(FSKRegFdevMsb, 0x01); // +/- 25kHz
|
||||
writeReg(FSKRegFdevLsb, 0x99);
|
||||
// set bitrate, autoclear CRC
|
||||
setupFskRxTx(1);
|
||||
|
||||
// configure DIO mapping DIO0=PayloadReady DIO1=NOP DIO2=TimeOut
|
||||
writeReg(RegDioMapping1, MAP_DIO0_FSK_READY|MAP_DIO1_FSK_NOP|MAP_DIO2_FSK_TIMEOUT);
|
||||
|
@ -864,11 +1121,15 @@ void radio_monitor_rssi(ostime_t nTicks, oslmic_radio_rssi_t *pRssi) {
|
|||
|
||||
// while we're waiting for the PLLs to spin up, determine which
|
||||
// band we're in and choose the base RSSI.
|
||||
#if defined(CFG_sx1276_radio)
|
||||
if (LMIC.freq > SX127X_FREQ_LF_MAX) {
|
||||
rssiAdjust = SX127X_RSSI_ADJUST_HF;
|
||||
rssiAdjust = SX1276_RSSI_ADJUST_HF;
|
||||
} else {
|
||||
rssiAdjust = SX127X_RSSI_ADJUST_LF;
|
||||
rssiAdjust = SX1276_RSSI_ADJUST_LF;
|
||||
}
|
||||
#elif defined(CFG_sx1272_radio)
|
||||
rssiAdjust = SX1272_RSSI_ADJUST;
|
||||
#endif
|
||||
rssiAdjust += hal_getRssiCal();
|
||||
|
||||
// zero the results
|
||||
|
@ -903,7 +1164,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().
|
||||
// TODO(tmm@mcci.com) move this to os_getTime().
|
||||
hal_enableIRQs();
|
||||
now = os_getTime();
|
||||
hal_disableIRQs();
|
||||
|
@ -958,6 +1219,8 @@ void radio_irq_handler_v2 (u1_t dio, ostime_t now) {
|
|||
#endif
|
||||
if( (readReg(RegOpMode) & OPMODE_LORA) != 0) { // LORA modem
|
||||
u1_t flags = readReg(LORARegIrqFlags);
|
||||
LMIC.saveIrqFlags = flags;
|
||||
LMICOS_logEventUint32("radio_irq_handler_v2: LoRa", flags);
|
||||
LMIC_X_DEBUG_PRINTF("IRQ=%02x\n", flags);
|
||||
if( flags & IRQ_LORA_TXDONE_MASK ) {
|
||||
// save exact tx time
|
||||
|
@ -969,7 +1232,7 @@ void radio_irq_handler_v2 (u1_t dio, ostime_t now) {
|
|||
}
|
||||
LMIC.rxtime = now;
|
||||
// read the PDU and inform the MAC that we received something
|
||||
LMIC.dataLen = (readReg(LORARegModemConfig1) & SX1272_MC1_IMPLICIT_HEADER_MODE_ON) ?
|
||||
LMIC.dataLen = (readReg(LORARegModemConfig1) & SX127X_MC1_IMPLICIT_HEADER_MODE_ON) ?
|
||||
readReg(LORARegPayloadLength) : readReg(LORARegRxNbBytes);
|
||||
// set FIFO read address pointer
|
||||
writeReg(LORARegFifoAddrPtr, readReg(LORARegFifoRxCurrentAddr));
|
||||
|
@ -984,8 +1247,8 @@ void radio_irq_handler_v2 (u1_t dio, ostime_t now) {
|
|||
// indicate timeout
|
||||
LMIC.dataLen = 0;
|
||||
#if LMIC_DEBUG_LEVEL > 0
|
||||
ostime_t now2 = os_getTime();
|
||||
LMIC_DEBUG_PRINTF("rxtimeout: entry: %"LMIC_PRId_ostime_t" rxtime: %"LMIC_PRId_ostime_t" entry-rxtime: %"LMIC_PRId_ostime_t" now-entry: %"LMIC_PRId_ostime_t" rxtime-txend: %"LMIC_PRId_ostime_t"\n", entry,
|
||||
ostime_t now2 = os_getTime();
|
||||
LMIC_DEBUG_PRINTF("rxtimeout: entry: %"LMIC_PRId_ostime_t" rxtime: %"LMIC_PRId_ostime_t" entry-rxtime: %"LMIC_PRId_ostime_t" now-entry: %"LMIC_PRId_ostime_t" rxtime-txend: %"LMIC_PRId_ostime_t"\n", entry,
|
||||
LMIC.rxtime, entry - LMIC.rxtime, now2 - entry, LMIC.rxtime-LMIC.txend);
|
||||
#endif
|
||||
}
|
||||
|
@ -996,6 +1259,9 @@ void radio_irq_handler_v2 (u1_t dio, ostime_t now) {
|
|||
} else { // FSK modem
|
||||
u1_t flags1 = readReg(FSKRegIrqFlags1);
|
||||
u1_t flags2 = readReg(FSKRegIrqFlags2);
|
||||
|
||||
LMICOS_logEventUint32("radio_irq_handler_v2: FSK", (flags2 << UINT32_C(8)) | flags1);
|
||||
|
||||
if( flags2 & IRQ_FSK2_PACKETSENT_MASK ) {
|
||||
// save exact tx time
|
||||
LMIC.txend = now;
|
||||
|
@ -1013,10 +1279,15 @@ void radio_irq_handler_v2 (u1_t dio, ostime_t now) {
|
|||
// indicate timeout
|
||||
LMIC.dataLen = 0;
|
||||
} else {
|
||||
ASSERT(0);
|
||||
// ASSERT(0);
|
||||
// we're not sure why we're here... treat as timeout.
|
||||
LMIC.dataLen = 0;
|
||||
}
|
||||
|
||||
// in FSK, we need to put the radio in standby first.
|
||||
opmode(OPMODE_STANDBY);
|
||||
}
|
||||
// go from stanby to sleep
|
||||
// go from standby to sleep
|
||||
opmode(OPMODE_SLEEP);
|
||||
// run os job (use preset func ptr)
|
||||
os_setCallback(&LMIC.osjob, LMIC.osjob.func);
|
||||
|
|
Loading…
Reference in New Issue