15 Commits

Author SHA1 Message Date
bb41c4960f README updated for 3.2.0 2020-08-02 10:19:58 +02:00
f70ad2a996 Version 2.3 2020-08-01 18:32:10 +02:00
fdacae73f8 Add rssi() function 2020-08-01 18:30:47 +02:00
9489f34542 RF parameter monitoring 2020-08-01 18:21:42 +02:00
2a31ef0096 Update example build configuration 2020-08-01 10:28:25 +02:00
e15d936bb4 Merge send_recv example into hello_world 2020-08-01 10:23:30 +02:00
a8cd58214d Modify example for PlatformIO.ini 2020-08-01 10:13:11 +02:00
b3e0b567b3 Merge branch 'cc32d9-dev' into dev 2020-07-31 21:54:26 +02:00
0853fe05ec Rename reset options 2020-07-31 21:54:09 +02:00
625968cd99 Add shutdown function 2020-07-31 20:14:40 +02:00
8d7d157445 Add shutdown function 2020-07-31 20:14:31 +02:00
b73ed23a97 Enable/disable ADR 2020-07-31 17:48:11 +02:00
513ac44268 Upgrade to LMIC version 3.2.0 2020-07-31 16:32:28 +02:00
45778d2186 New config option: TTN_RADIO_RST_KEEP_ASSERTED 2020-05-25 23:00:00 +02:00
e29477fa7e Update to latest LMIC version (3.0.99.10) 2020-01-01 17:00:47 +01:00
47 changed files with 1292 additions and 374 deletions

19
Kconfig
View File

@ -16,8 +16,8 @@ config TTN_LORA_FREQ_EU_868
config TTN_LORA_FREQ_US_915
bool "North and South America (915 MHz)"
config TTN_LORA_FREQ_AU_921
bool "Australia (921 MHz)"
config TTN_LORA_FREQ_AU_915
bool "Australia (915 MHz)"
config TTN_LORA_FREQ_AS_923
bool "Asia (923 MHz)"
@ -55,6 +55,21 @@ config TTN_SPI_FREQ
help
SPI frequency to communicate between ESP32 and SX127x radio chip
choice TTN_RESET
prompt "Reset states"
default TTN_RESET_STATES_FLOATING
help
Reset pin can be floating for most boards and shields.
A few boards/shields require the pin to be held high for operation.
config TTN_RESET_STATES_FLOATING
bool "Toggle between low and floating"
config TTN_RESET_STATES_ASSERTED
bool "Toggle between low and high"
endchoice
config TTN_BG_TASK_PRIO
int "Background task priority"
default 10

View File

@ -8,9 +8,15 @@ This ESP32 component provides LoRaWAN communication with [The Things Network](ht
- uplink and downlink messages
- saving the EUIs and key in non-volatile memory
- [AT commands](https://github.com/manuelbl/ttn-esp32/wiki/AT-Commands) for provisioning EUIs and key (so the same code can be flashed to several devices)
- support for regions Eurpe, North America, Australia, Asia and India
- support for regions Eurpe, North and South America, Australia, Korea, Asia and India
The library is based on the LMIC library from IBM (specifically the version maintained by MCCI see their [GitHub repository](https://github.com/mcci-catena/arduino-lmic)) and provides a high-level API specifically targeted at The Things Network.
The library is based on the LMIC library from IBM (specifically the well-maintained version by MCCI see their [GitHub repository](https://github.com/mcci-catena/arduino-lmic)) and provides a high-level API specifically targeted at The Things Network.
## New in version 3.2
- Based on latest version of LMIC library (3.2.0) and ESP-IDF v4.0.x
- Monitoring of RF parameters (frequency, bandwidth, spreading factor, RSSI)
- Shutdown/startup of radio, enabling/disabling of ADR
## Get Started

View File

@ -1,9 +1,8 @@
# The following lines of boilerplate have to be in your project's
# CMakeLists in this exact order for cmake to work correctly
cmake_minimum_required(VERSION 3.5)
get_filename_component(TTN_DIR ../.. ABSOLUTE)
set(EXTRA_COMPONENT_DIRS "${TTN_DIR}")
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
# Update the below line to match the path to the ttn-esp32 library,
# e.g. list(APPEND EXTRA_COMPONENT_DIRS "/Users/me/Documents/ttn-esp32")
list(APPEND EXTRA_COMPONENT_DIRS "../..")
project(hello_world)

View File

@ -1,4 +1,4 @@
set(COMPONENT_SRCS "main.cpp")
set(COMPONENT_ADD_INCLUDEDIRS "")
register_component()
idf_component_register(
SRCS "main.cpp"
INCLUDE_DIRS "."
REQUIRES ttn-esp32)

View File

@ -7,12 +7,12 @@
* Licensed under MIT License
* https://opensource.org/licenses/MIT
*
* Sample program showing how to send a test message every 30 second.
* Sample program showing how to send and receive messages.
*******************************************************************************/
#include "freertos/FreeRTOS.h"
#include "driver/gpio.h"
#include "esp_event.h"
#include "driver/gpio.h"
#include "nvs_flash.h"
#include "TheThingsNetwork.h"
@ -37,9 +37,9 @@ const char *appKey = "????????????????????????????????";
#define TTN_PIN_SPI_MISO 19
#define TTN_PIN_NSS 18
#define TTN_PIN_RXTX TTN_NOT_CONNECTED
#define TTN_PIN_RST TTN_NOT_CONNECTED
#define TTN_PIN_RST 14
#define TTN_PIN_DIO0 26
#define TTN_PIN_DIO1 33
#define TTN_PIN_DIO1 35
static TheThingsNetwork ttn;
@ -54,17 +54,25 @@ void sendMessages(void* pvParameter)
TTNResponseCode res = ttn.transmitMessage(msgData, sizeof(msgData) - 1);
printf(res == kTTNSuccessfulTransmission ? "Message sent.\n" : "Transmission failed.\n");
vTaskDelay(TX_INTERVAL * 1000 / portTICK_PERIOD_MS);
vTaskDelay(TX_INTERVAL * pdMS_TO_TICKS(1000));
}
}
void messageReceived(const uint8_t* message, size_t length, port_t port)
{
printf("Message of %d bytes received on port %d:", length, port);
for (int i = 0; i < length; i++)
printf(" %02x", message[i]);
printf("\n");
}
extern "C" void app_main(void)
{
esp_err_t err;
// Initialize the GPIO ISR handler service
err = gpio_install_isr_service(ESP_INTR_FLAG_IRAM);
ESP_ERROR_CHECK(err);
// Initialize the NVS (non-volatile storage) for saving and restoring the keys
err = nvs_flash_init();
ESP_ERROR_CHECK(err);
@ -86,6 +94,9 @@ extern "C" void app_main(void)
// The below line can be commented after the first run as the data is saved in NVS
ttn.provision(devEui, appEui, appKey);
// Register callback for received messages
ttn.onMessage(messageReceived);
printf("Joining...\n");
if (ttn.join())
{

View File

@ -1,9 +1,8 @@
# The following lines of boilerplate have to be in your project's
# CMakeLists in this exact order for cmake to work correctly
cmake_minimum_required(VERSION 3.5)
get_filename_component(TTN_DIR ../.. ABSOLUTE)
set(EXTRA_COMPONENT_DIRS "${TTN_DIR}")
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
# Update the below line to match the path to the ttn-esp32 library,
# e.g. list(APPEND EXTRA_COMPONENT_DIRS "/Users/me/Documents/ttn-esp32")
list(APPEND EXTRA_COMPONENT_DIRS "../..")
project(mac_address)

View File

@ -1,4 +1,4 @@
set(COMPONENT_SRCS "main.cpp")
set(COMPONENT_ADD_INCLUDEDIRS "")
register_component()
idf_component_register(
SRCS "main.cpp"
INCLUDE_DIRS "."
REQUIRES ttn-esp32)

View File

@ -51,7 +51,7 @@ void sendMessages(void* pvParameter)
TTNResponseCode res = ttn.transmitMessage(msgData, sizeof(msgData) - 1);
printf(res == kTTNSuccessfulTransmission ? "Message sent.\n" : "Transmission failed.\n");
vTaskDelay(TX_INTERVAL * 1000 / portTICK_PERIOD_MS);
vTaskDelay(TX_INTERVAL * pdMS_TO_TICKS(1000));
}
}

View File

@ -0,0 +1,8 @@
cmake_minimum_required(VERSION 3.5)
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
# Update the below line to match the path to the ttn-esp32 library,
# e.g. list(APPEND EXTRA_COMPONENT_DIRS "/Users/me/Documents/ttn-esp32")
list(APPEND EXTRA_COMPONENT_DIRS "../..")
project(monitoring)

View File

@ -0,0 +1,5 @@
PROJECT_NAME := monitoring
EXTRA_COMPONENT_DIRS := $(abspath ../..)
include $(IDF_PATH)/make/project.mk

View File

@ -0,0 +1,4 @@
idf_component_register(
SRCS "main.cpp"
INCLUDE_DIRS "."
REQUIRES ttn-esp32)

View File

@ -0,0 +1,142 @@
/*******************************************************************************
*
* ttn-esp32 - The Things Network device library for ESP-IDF / SX127x
*
* Copyright (c) 2018 Manuel Bleichenbacher
*
* Licensed under MIT License
* https://opensource.org/licenses/MIT
*
* Sample program showing how to send and receive messages.
*******************************************************************************/
#include "freertos/FreeRTOS.h"
#include "esp_event.h"
#include "driver/gpio.h"
#include "nvs_flash.h"
#include "TheThingsNetwork.h"
// NOTE:
// The LoRaWAN frequency and the radio chip must be configured by running 'make menuconfig'.
// Go to Components / The Things Network, select the appropriate values and save.
// Copy the below hex string from the "Device EUI" field
// on your device's overview page in the TTN console.
const char *devEui = "????????????????";
// Copy the below two lines from bottom of the same page
const char *appEui = "????????????????";
const char *appKey = "????????????????????????????????";
// Pins and other resources
#define TTN_SPI_HOST HSPI_HOST
#define TTN_SPI_DMA_CHAN 1
#define TTN_PIN_SPI_SCLK 5
#define TTN_PIN_SPI_MOSI 27
#define TTN_PIN_SPI_MISO 19
#define TTN_PIN_NSS 18
#define TTN_PIN_RXTX TTN_NOT_CONNECTED
#define TTN_PIN_RST 14
#define TTN_PIN_DIO0 26
#define TTN_PIN_DIO1 35
static TheThingsNetwork ttn;
const unsigned TX_INTERVAL = 30;
static uint8_t msgData[] = "Hello, world";
void printRFSettings(const char* window, const TTNRFSettings& settings)
{
int bw = (1 << (static_cast<int>(settings.bandwidth) - 1)) * 125;
int sf = static_cast<int>(settings.spreadingFactor) + 5;
if (settings.spreadingFactor == kTTNSFNone)
{
printf("%s: not used\n", window);
}
else if (settings.spreadingFactor == kTTNFSK)
{
printf("%s: FSK, BW %dkHz, %d.%d MHz\n",
window, bw, settings.frequency / 1000000, (settings.frequency % 1000000 + 50000) / 100000);
}
else
{
printf("%s: SF%d, BW %dkHz, %d.%d MHz\n",
window, sf, bw, settings.frequency / 1000000, (settings.frequency % 1000000 + 50000) / 100000);
}
}
void printAllRFSettings()
{
printRFSettings("TX ", ttn.txSettings());
printRFSettings("RX1", ttn.rx1Settings());
printRFSettings("RX2", ttn.rx2Settings());
}
void sendMessages(void* pvParameter)
{
while (1) {
printf("Sending message...\n");
TTNResponseCode res = ttn.transmitMessage(msgData, sizeof(msgData) - 1);
printf(res == kTTNSuccessfulTransmission ? "Message sent.\n" : "Transmission failed.\n");
printAllRFSettings();
vTaskDelay(TX_INTERVAL * pdMS_TO_TICKS(1000));
}
}
void messageReceived(const uint8_t* message, size_t length, port_t port)
{
printf("Message of %d bytes received on port %d:", length, port);
for (int i = 0; i < length; i++)
printf(" %02x", message[i]);
printf("\n");
printf("RSSI: %d dBm\n", ttn.rssi());
}
extern "C" void app_main(void)
{
esp_err_t err;
// Initialize the GPIO ISR handler service
err = gpio_install_isr_service(ESP_INTR_FLAG_IRAM);
ESP_ERROR_CHECK(err);
// Initialize the NVS (non-volatile storage) for saving and restoring the keys
err = nvs_flash_init();
ESP_ERROR_CHECK(err);
// Initialize SPI bus
spi_bus_config_t spi_bus_config;
spi_bus_config.miso_io_num = TTN_PIN_SPI_MISO;
spi_bus_config.mosi_io_num = TTN_PIN_SPI_MOSI;
spi_bus_config.sclk_io_num = TTN_PIN_SPI_SCLK;
spi_bus_config.quadwp_io_num = -1;
spi_bus_config.quadhd_io_num = -1;
spi_bus_config.max_transfer_sz = 0;
err = spi_bus_initialize(TTN_SPI_HOST, &spi_bus_config, TTN_SPI_DMA_CHAN);
ESP_ERROR_CHECK(err);
// Configure the SX127x pins
ttn.configurePins(TTN_SPI_HOST, TTN_PIN_NSS, TTN_PIN_RXTX, TTN_PIN_RST, TTN_PIN_DIO0, TTN_PIN_DIO1);
// The below line can be commented after the first run as the data is saved in NVS
ttn.provision(devEui, appEui, appKey);
// Register callback for received messages
ttn.onMessage(messageReceived);
printf("Joining...\n");
if (ttn.join())
{
printf("Joined.\n");
printAllRFSettings();
printf("RSSI: %d dBm\n", ttn.rssi());
xTaskCreate(sendMessages, "send_messages", 1024 * 4, (void* )0, 3, nullptr);
}
else
{
printf("Join failed. Goodbye\n");
}
}

View File

@ -1,9 +1,8 @@
# The following lines of boilerplate have to be in your project's
# CMakeLists in this exact order for cmake to work correctly
cmake_minimum_required(VERSION 3.5)
get_filename_component(TTN_DIR ../.. ABSOLUTE)
set(EXTRA_COMPONENT_DIRS "${TTN_DIR}")
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
# Update the below line to match the path to the ttn-esp32 library,
# e.g. list(APPEND EXTRA_COMPONENT_DIRS "/Users/me/Documents/ttn-esp32")
list(APPEND EXTRA_COMPONENT_DIRS "../..")
project(provisioning)

View File

@ -1,4 +1,4 @@
set(COMPONENT_SRCS "main.cpp")
set(COMPONENT_ADD_INCLUDEDIRS "")
register_component()
idf_component_register(
SRCS "main.cpp"
INCLUDE_DIRS "."
REQUIRES ttn-esp32)

View File

@ -46,7 +46,7 @@ void sendMessages(void* pvParameter)
TTNResponseCode res = ttn.transmitMessage(msgData, sizeof(msgData) - 1);
printf(res == kTTNSuccessfulTransmission ? "Message sent.\n" : "Transmission failed.\n");
vTaskDelay(TX_INTERVAL * 1000 / portTICK_PERIOD_MS);
vTaskDelay(TX_INTERVAL * pdMS_TO_TICKS(1000));
}
}

View File

@ -1,9 +0,0 @@
# The following lines of boilerplate have to be in your project's
# CMakeLists in this exact order for cmake to work correctly
cmake_minimum_required(VERSION 3.5)
get_filename_component(TTN_DIR ../.. ABSOLUTE)
set(EXTRA_COMPONENT_DIRS "${TTN_DIR}")
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
project(send_recv)

View File

@ -1,4 +0,0 @@
set(COMPONENT_SRCS "main.cpp")
set(COMPONENT_ADD_INCLUDEDIRS "")
register_component()

View File

@ -0,0 +1,8 @@
cmake_minimum_required(VERSION 3.5)
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
# Update the below line to match the path to the ttn-esp32 library,
# e.g. list(APPEND EXTRA_COMPONENT_DIRS "/Users/me/Documents/ttn-esp32")
list(APPEND EXTRA_COMPONENT_DIRS "../..")
project(shutdown)

View File

@ -1,4 +1,4 @@
PROJECT_NAME := send_recv
PROJECT_NAME := shutdown
EXTRA_COMPONENT_DIRS := $(abspath ../..)

View File

@ -0,0 +1,4 @@
idf_component_register(
SRCS "main.cpp"
INCLUDE_DIRS "."
REQUIRES ttn-esp32)

View File

View File

@ -39,22 +39,56 @@ const char *appKey = "????????????????????????????????";
#define TTN_PIN_RXTX TTN_NOT_CONNECTED
#define TTN_PIN_RST 14
#define TTN_PIN_DIO0 26
#define TTN_PIN_DIO1 33
#define TTN_PIN_DIO1 35
static TheThingsNetwork ttn;
const unsigned TX_INTERVAL = 30;
static uint8_t msgData[] = "Hello, world";
bool join()
{
printf("Joining...\n");
if (ttn.join())
{
printf("Joined.\n");
return true;
}
else
{
printf("Join failed. Goodbye\n");
return false;
}
}
void sendMessages(void* pvParameter)
{
while (1) {
printf("Sending message...\n");
TTNResponseCode res = ttn.transmitMessage(msgData, sizeof(msgData) - 1);
printf(res == kTTNSuccessfulTransmission ? "Message sent.\n" : "Transmission failed.\n");
vTaskDelay(TX_INTERVAL * 1000 / portTICK_PERIOD_MS);
// Send 2 messages
for (int i = 0; i < 2; i++)
{
printf("Sending message...\n");
TTNResponseCode res = ttn.transmitMessage(msgData, sizeof(msgData) - 1);
printf(res == kTTNSuccessfulTransmission ? "Message sent.\n" : "Transmission failed.\n");
vTaskDelay(TX_INTERVAL * pdMS_TO_TICKS(1000));
}
// shutdown
ttn.shutdown();
// go to sleep
printf("Sleeping for 30s...\n");
vTaskDelay(pdMS_TO_TICKS(30000));
// startup
ttn.startup();
// join again
if (!join())
return;
}
}
@ -96,14 +130,8 @@ extern "C" void app_main(void)
ttn.onMessage(messageReceived);
printf("Joining...\n");
if (ttn.join())
if (join())
{
printf("Joined.\n");
xTaskCreate(sendMessages, "send_messages", 1024 * 4, (void* )0, 3, nullptr);
}
else
{
printf("Join failed. Goodbye\n");
}
}

View File

@ -29,12 +29,121 @@ typedef uint8_t port_t;
*/
enum TTNResponseCode
{
kTTNErrorTransmissionFailed = -1,
kTTNErrorUnexpected = -10,
kTTNSuccessfulTransmission = 1,
kTTNSuccessfulReceive = 2
kTTNErrorTransmissionFailed = -1,
kTTNErrorUnexpected = -10,
kTTNSuccessfulTransmission = 1,
kTTNSuccessfulReceive = 2
};
/**
* @brief RX/TX window
*/
enum TTNRxTxWindow
{
/**
* @brief Outside RX/TX window
*/
kTTNIdleWindow = 0,
/**
* @brief Transmission window (up to RX1 window)
*/
kTTNTxWindow = 1,
/**
* @brief Reception window 1 (up to RX2 window)
*/
kTTNRx1Window = 2,
/**
* @brief Reception window 2
*/
kTTNRx2Window = 3
};
/**
* @brief Spreading Factor
*/
enum TTNSpreadingFactor
{
/**
* @brief Unused / undefined spreading factor
*/
kTTNSFNone = 0,
/**
* @brief Frequency Shift Keying (FSK)
*/
kTTNFSK = 1,
/**
* @brief Spreading Factor 7 (SF7)
*/
kTTNSF7 = 2,
/**
* @brief Spreading Factor 8 (SF8)
*/
kTTNSF8 = 3,
/**
* @brief Spreading Factor 9 (SF9)
*/
kTTNSF9 = 4,
/**
* @brief Spreading Factor 10 (SF10)
*/
kTTNSF10 = 5,
/**
* @brief Spreading Factor 11 (SF11)
*/
kTTNSF11 = 6,
/**
* @brief Spreading Factor 12 (SF12)
*/
kTTNSF12 = 7
};
/**
* @brief Bandwidth
*/
enum TTNBandwidth
{
/**
* @brief Undefined/unused bandwidth
*/
kTTNBWNone = 0,
/**
* @brief Bandwidth of 125 kHz
*/
kTTNBW125 = 1,
/**
* @brief Bandwidth of 250 kHz
*/
kTTNBW250 = 2,
/**
* @brief Bandwidth of 500 kHz
*/
kTTNBW500 = 3
};
/**
* @brief RF settings for TX or RX
*/
struct TTNRFSettings
{
/**
* @brief Spreading Factor (SF)
*/
TTNSpreadingFactor spreadingFactor;
/**
* @brief Bandwidth (BW)
*/
TTNBandwidth bandwidth;
/**
* @brief Frequency, in Hz
*/
uint32_t frequency;
};
/**
* @brief Callback for recieved messages
*
@ -68,7 +177,8 @@ public:
/**
* @brief Reset the LoRaWAN radio.
*
* Does not clear provisioned keys.
* To restart communication, `join()` must be called.
* Neither clears the provisioned keys nor the configured pins.
*/
void reset();
@ -76,8 +186,8 @@ public:
* @brief Configures the pins used to communicate with the LoRaWAN radio chip.
*
*
* The SPI bus must be first configured using spi_bus_initialize(). Then it is passed as the first parameter.
* Additionally, 'gpio_install_isr_service()' must be called to initialize the GPIO ISR handler service.
* Before calling this member function, the SPI bus needs to be configured using `spi_bus_initialize()`.
* Additionally, `gpio_install_isr_service()` must have been called to initialize the GPIO ISR handler service.
*
* @param spi_host The SPI bus/peripherial to use (SPI_HOST, HSPI_HOST or VSPI_HOST).
* @param nss The GPIO pin number connected to the radio chip's NSS pin (serving as the SPI chip select)
@ -199,7 +309,7 @@ public:
* parameters. The values are only valid during the duration of the
* callback. So they must be immediately processed or copied.
*
* Messages are received as a result of 'transmitMessage' or 'poll'. The callback is called
* Messages are received as a result of 'transmitMessage'. The callback is called
* in the task that called any of these functions and it occurs before these functions
* return control to the caller.
*
@ -221,12 +331,84 @@ public:
*
* This value is added to RSSI measured prior to decision. It must include the guardband.
* Ignored in US, EU, IN and other countries where LBT is not required.
* Default to 10 dB.
* Defaults to 10 dB.
*
* @param rssiCal RSSI calibration value, in dB
*/
void setRSSICal(int8_t rssiCal);
/**
* Returns whether Adaptive Data Rate (ADR) is enabled.
*
* @return true if enabled
* @return false if disabled
*/
bool adrEnabled();
/**
* @brief Enables or disabled Adaptive Data Rate (ADR).
*
* ADR is enabled by default. It optimizes data rate, airtime and energy consumption
* for devices with stable RF conditions. It should be turned off for mobile devices.
*
* @param enabled `true` to enable, `false` to disable
*/
void setAdrEnabled(bool enabled);
/**
* @brief Stops all activies and shuts down the RF module and the background tasks.
*
* To restart communication, `startup()` and `join()` must be called.
* Neither clears the provisioned keys nor the configured pins.
*/
void shutdown();
/**
* @brief Restarts the background tasks and RF module.
*
* This member function must only be called after a call to `shutdowna()`.
*/
void startup();
/**
* @brief Gets currentRX/TX window
* @return window
*/
TTNRxTxWindow rxTxWindow();
/**
* @brief Gets the RF settings for the specified window
* @param window RX/TX windows (valid values are `kTTNTxWindow`, `kTTNRx1Window` and `kTTNRx2Window`)
*/
TTNRFSettings getRFSettings(TTNRxTxWindow window);
/**
* @brief Gets the RF settings of the last (or ongoing) transmission.
* @return RF settings
*/
TTNRFSettings txSettings();
/**
* @brief Gets the RF settings of the last (or ongoing) reception of RX window 1.
* @return RF settings
*/
TTNRFSettings rx1Settings();
/**
* @brief Gets the RF settings of the last (or ongoing) reception of RX window 2.
* @return RF settings
*/
TTNRFSettings rx2Settings();
/**
* @brief Gets the received signal strength indicator (RSSI).
*
* RSSI is the measured signal strength of the last recevied message (incl. join responses).
*
* @return RSSI, in dBm
*/
int rssi();
private:
TTNMessageCallback messageCallback;

View File

@ -11,15 +11,14 @@
"repository": {
"type": "git",
"url": "https://github.com/manuelbl/ttn-esp32.git",
"branch": "dev"
"branch": "master"
},
"version": "3.0.99",
"version": "3.2.0",
"license": "MIT License",
"export": {
"include": [
"include",
"src",
"esp_idf_lmic_config.h"
"src"
]
},
"frameworks": "espidf",

View File

@ -97,6 +97,7 @@ void ttn_provisioning_task_caller(void* pvParameter)
{
TTNProvisioning* provisioning = (TTNProvisioning*)pvParameter;
provisioning->provisioningTask();
vTaskDelete(nullptr);
}
void TTNProvisioning::provisioningTask()
@ -132,7 +133,6 @@ void TTNProvisioning::provisioningTask()
free(line_buf);
uart_driver_delete(UART_NUM);
vTaskDelete(nullptr);
}
void TTNProvisioning::addLineData(int numBytes)

View File

@ -63,10 +63,14 @@ static TTNProvisioning provisioning;
#if LMIC_ENABLE_event_logging
static TTNLogging* logging;
#endif
static TTNRFSettings lastRfSettings[4];
static TTNRxTxWindow currentWindow;
static void eventCallback(void* userData, ev_t event);
static void messageReceivedCallback(void *userData, uint8_t port, const uint8_t *message, size_t messageSize);
static void messageTransmittedCallback(void *userData, int success);
static void saveRFSettings(TTNRFSettings& rfSettings);
static void clearRFSettings(TTNRFSettings& rfSettings);
TheThingsNetwork::TheThingsNetwork()
@ -110,11 +114,25 @@ void TheThingsNetwork::reset()
{
ttn_hal.enterCriticalSection();
LMIC_reset();
LMIC_setClockError(MAX_CLOCK_ERROR * 4 / 100);
waitingReason = eWaitingNone;
if (lmicEventQueue != nullptr)
{
xQueueReset(lmicEventQueue);
}
ttn_hal.leaveCriticalSection();
}
void TheThingsNetwork::shutdown()
{
ttn_hal.enterCriticalSection();
LMIC_shutdown();
ttn_hal.stopLMICTask();
waitingReason = eWaitingNone;
ttn_hal.leaveCriticalSection();
}
void TheThingsNetwork::startup()
{
ttn_hal.enterCriticalSection();
LMIC_reset();
ttn_hal.startLMICTask();
ttn_hal.leaveCriticalSection();
}
@ -156,7 +174,7 @@ void TheThingsNetwork::waitForProvisioning()
}
while (!provisioning.haveKeys())
vTaskDelay(1000 / portTICK_PERIOD_MS);
vTaskDelay(pdMS_TO_TICKS(1000));
ESP_LOGI(TAG, "Device successfully provisioned");
#else
@ -194,6 +212,7 @@ bool TheThingsNetwork::joinCore()
}
ttn_hal.enterCriticalSection();
xQueueReset(lmicEventQueue);
waitingReason = eWaitingForJoin;
LMIC_startJoining();
ttn_hal.wakeUp();
@ -265,6 +284,47 @@ void TheThingsNetwork::setRSSICal(int8_t rssiCal)
ttn_hal.rssiCal = rssiCal;
}
bool TheThingsNetwork::adrEnabled()
{
return LMIC.adrEnabled != 0;
}
void TheThingsNetwork::setAdrEnabled(bool enabled)
{
LMIC_setAdrMode(enabled);
}
TTNRFSettings TheThingsNetwork::getRFSettings(TTNRxTxWindow window)
{
int index = static_cast<int>(window) & 0x03;
return lastRfSettings[index];
}
TTNRFSettings TheThingsNetwork::txSettings()
{
return lastRfSettings[static_cast<int>(kTTNTxWindow)];
}
TTNRFSettings TheThingsNetwork::rx1Settings()
{
return lastRfSettings[static_cast<int>(kTTNRx1Window)];
}
TTNRFSettings TheThingsNetwork::rx2Settings()
{
return lastRfSettings[static_cast<int>(kTTNRx2Window)];
}
TTNRxTxWindow TheThingsNetwork::rxTxWindow()
{
return currentWindow;
}
int TheThingsNetwork::rssi()
{
return LMIC.rssi;
}
// --- Callbacks ---
@ -276,6 +336,34 @@ const char *eventNames[] = { LMIC_EVENT_NAME_TABLE__INIT };
// Called by LMIC when an LMIC event (join, join failed, reset etc.) occurs
void eventCallback(void* userData, ev_t event)
{
// update monitoring information
switch(event)
{
case EV_TXSTART:
currentWindow = kTTNTxWindow;
saveRFSettings(lastRfSettings[static_cast<int>(kTTNTxWindow)]);
clearRFSettings(lastRfSettings[static_cast<int>(kTTNRx1Window)]);
clearRFSettings(lastRfSettings[static_cast<int>(kTTNRx2Window)]);
break;
case EV_RXSTART:
if (currentWindow != kTTNRx1Window)
{
currentWindow = kTTNRx1Window;
saveRFSettings(lastRfSettings[static_cast<int>(kTTNRx1Window)]);
}
else
{
currentWindow = kTTNRx2Window;
saveRFSettings(lastRfSettings[static_cast<int>(kTTNRx2Window)]);
}
break;
default:
currentWindow = kTTNIdleWindow;
break;
};
#if LMIC_ENABLE_event_logging
logging->logEvent(event, eventNames[event], 0);
#elif CONFIG_LOG_DEFAULT_LEVEL >= 3
@ -321,3 +409,19 @@ void messageTransmittedCallback(void *userData, int success)
TTNLmicEvent result(success ? eEvtTransmissionCompleted : eEvtTransmissionFailed);
xQueueSend(lmicEventQueue, &result, pdMS_TO_TICKS(100));
}
// --- Helpers
void saveRFSettings(TTNRFSettings& rfSettings)
{
rfSettings.spreadingFactor = static_cast<TTNSpreadingFactor>(getSf(LMIC.rps) + 1);
rfSettings.bandwidth = static_cast<TTNBandwidth>(getBw(LMIC.rps) + 1);
rfSettings.frequency = LMIC.freq;
}
void clearRFSettings(TTNRFSettings& rfSettings)
{
memset(&rfSettings, 0, sizeof(rfSettings));
}

View File

@ -17,7 +17,10 @@
#elif defined(CONFIG_TTN_LORA_FREQ_US_915)
#define CFG_us915 1
#elif defined(CONFIG_TTN_LORA_FREQ_AU_921)
#define CFG_au921 1
# warning "CONFIG_TTN_LORA_FREQ_AU_921 was deprecated in favour of CONFIG_TTN_LORA_FREQ_AU_921. Support for CONFIG_TTN_LORA_FREQ_AU_921 will be removed in the future."
#define CFG_au915 1
#elif defined(CONFIG_TTN_LORA_FREQ_AU_915)
#define CFG_au915 1
#elif defined(CONFIG_TTN_LORA_FREQ_AS_923)
#define CFG_as923 1
#elif defined(CONFIG_TTN_LORA_FREQ_AS_923_JP)

View File

@ -25,6 +25,7 @@
#define NOTIFY_BIT_DIO 1
#define NOTIFY_BIT_TIMER 2
#define NOTIFY_BIT_WAKEUP 4
#define NOTIFY_BIT_STOP 8
static const char* const TAG = "ttn_hal";
@ -123,14 +124,22 @@ void hal_pin_rst(u1_t val)
return;
if (val == 0 || val == 1)
{ // drive pin
{
// drive pin
gpio_set_level(ttn_hal.pinRst, val);
gpio_set_direction(ttn_hal.pinRst, GPIO_MODE_OUTPUT);
}
else
{ // keep pin floating
{
#if defined(CONFIG_TTN_RESET_STATES_ASSERTED)
// drive up the pin because the hardware is nonstandard
gpio_set_level(ttn_hal.pinRst, 1);
gpio_set_direction(ttn_hal.pinRst, GPIO_MODE_OUTPUT);
#else
// keep pin floating
gpio_set_level(ttn_hal.pinRst, val);
gpio_set_direction(ttn_hal.pinRst, GPIO_MODE_INPUT);
#endif
}
}
@ -155,6 +164,7 @@ uint8_t hal_getTxPowerPolicy(u1_t inputPolicy, s1_t requestedPower, u4_t frequen
}
// -----------------------------------------------------------------------------
// SPI
@ -210,6 +220,7 @@ void HAL_ESP32::spiRead(uint8_t cmd, uint8_t *buf, size_t len)
ESP_ERROR_CHECK(err);
}
// -----------------------------------------------------------------------------
// TIME
@ -303,6 +314,9 @@ bool HAL_ESP32::wait(WaitKind waitKind)
if (bits == 0)
return false;
if ((bits & NOTIFY_BIT_STOP) != 0)
return false;
if ((bits & NOTIFY_BIT_WAKEUP) != 0)
{
if (waitKind != WAIT_FOR_TIMER)
@ -342,18 +356,22 @@ u4_t hal_ticks()
// Wait until the specified time.
// Called if the LMIC code needs to wait for a precise time.
// All other events are ignored and will be served later.
void hal_waitUntil(u4_t time)
u4_t hal_waitUntil(u4_t time)
{
ttn_hal.waitUntil(time);
return ttn_hal.waitUntil(time);
}
void HAL_ESP32::waitUntil(uint32_t osTime)
uint32_t HAL_ESP32::waitUntil(uint32_t osTime)
{
int64_t espNow = esp_timer_get_time();
int64_t espTime = osTimeToEspTime(espNow, osTime);
setNextAlarm(espTime);
armTimer(espNow);
wait(WAIT_FOR_TIMER);
u4_t osNow = hal_ticks();
u4_t diff = osNow - osTime;
return diff < 0x80000000U ? diff : 0;
}
// Called by client code to wake up LMIC to do something,
@ -416,6 +434,12 @@ void hal_enableIRQs()
// and don't access any shared data structures
}
void hal_processPendingIRQs()
{
// nothing to do as interrupt handlers post message to queue
// and don't access any shared data structures
}
// -----------------------------------------------------------------------------
// Synchronization between application code and background task
@ -437,8 +461,12 @@ void HAL_ESP32::leaveCriticalSection()
// -----------------------------------------------------------------------------
void HAL_ESP32::lmicBackgroundTask(void* pvParameter) {
os_runloop();
void HAL_ESP32::lmicBackgroundTask(void* pvParameter)
{
HAL_ESP32* instance = (HAL_ESP32*)pvParameter;
while (instance->runBackgroundTask)
os_runloop_once();
vTaskDelete(nullptr);
}
void hal_init_ex(const void *pContext)
@ -456,14 +484,25 @@ void HAL_ESP32::init()
timerInit();
}
void HAL_ESP32::startLMICTask() {
xTaskCreate(lmicBackgroundTask, "ttn_lmic", 1024 * 4, nullptr, CONFIG_TTN_BG_TASK_PRIO, &lmicTask);
void HAL_ESP32::startLMICTask()
{
runBackgroundTask = true;
xTaskCreate(lmicBackgroundTask, "ttn_lmic", 1024 * 4, this, CONFIG_TTN_BG_TASK_PRIO, &lmicTask);
// enable interrupts
gpio_isr_handler_add(pinDIO0, dioIrqHandler, (void *)0);
gpio_isr_handler_add(pinDIO1, dioIrqHandler, (void *)1);
}
void HAL_ESP32::stopLMICTask()
{
runBackgroundTask = false;
gpio_isr_handler_remove(pinDIO0);
gpio_isr_handler_remove(pinDIO1);
disarmTimer();
xTaskNotify(lmicTask, NOTIFY_BIT_STOP, eSetBits);
}
// -----------------------------------------------------------------------------
// Fatal failure

View File

@ -39,6 +39,7 @@ public:
void configurePins(spi_host_device_t spi_host, uint8_t nss, uint8_t rxtx, uint8_t rst, uint8_t dio0, uint8_t dio1);
void init();
void startLMICTask();
void stopLMICTask();
void wakeUp();
void initCriticalSection();
@ -50,7 +51,7 @@ public:
uint8_t checkTimer(uint32_t osTime);
void sleep();
void waitUntil(uint32_t osTime);
uint32_t waitUntil(uint32_t osTime);
spi_host_device_t spiHost;
gpio_num_t pinNSS;
@ -84,6 +85,7 @@ private:
SemaphoreHandle_t mutex;
esp_timer_handle_t timer;
int64_t nextAlarm;
volatile bool runBackgroundTask;
};
extern HAL_ESP32 ttn_hal;

View File

@ -204,4 +204,12 @@
# define LMIC_LORAWAN_SPEC_VERSION LMIC_LORAWAN_SPEC_VERSION_1_0_3
#endif
// LMIC_ENABLE_arbitrary_clock_error
// We normally don't want to allow users to set wide clock errors, because
// we assume reasonably-disciplined os_getTime() values. But... there might
// be platforms that require wider errors.
#if !defined(LMIC_ENABLE_arbitrary_clock_error)
# define LMIC_ENABLE_arbitrary_clock_error 0 /* PARAM */
#endif
#endif // _lmic_config_h_

View File

@ -110,9 +110,10 @@ void hal_sleep (void);
u4_t hal_ticks (void);
/*
* busy-wait until specified timestamp (in ticks) is reached.
* busy-wait until specified timestamp (in ticks) is reached. If on-time, return 0,
* otherwise return the number of ticks we were late.
*/
void hal_waitUntil (u4_t time);
u4_t hal_waitUntil (u4_t time);
/*
* check and rewind timer for target time.
@ -168,6 +169,17 @@ uint8_t hal_getTxPowerPolicy(
u4_t freq
);
void hal_pollPendingIRQs_helper();
void hal_processPendingIRQs(void);
/// \brief check for any pending interrupts: stub if interrupts are enabled.
static void inline hal_pollPendingIRQs(void)
{
#if !defined(LMIC_USE_INTERRUPTS)
hal_pollPendingIRQs_helper();
#endif /* !defined(LMIC_USE_INTERRUPTS) */
}
#ifdef __cplusplus
} // extern "C"
#endif

View File

@ -294,6 +294,16 @@ ostime_t calcAirTime (rps_t rps, u1_t plen) {
// 500kHz | 0 1 2 3 4 5
//
static void setRxsyms (ostime_t rxsyms) {
if (rxsyms >= (((ostime_t)1) << 10u)) {
LMIC.rxsyms = (1u << 10u) - 1;
} else if (rxsyms < 0) {
LMIC.rxsyms = 0;
} else {
LMIC.rxsyms = rxsyms;
}
}
#if !defined(DISABLE_BEACONS)
static ostime_t calcRxWindow (u1_t secs, dr_t dr) {
ostime_t rxoff, err;
@ -306,9 +316,9 @@ static ostime_t calcRxWindow (u1_t secs, dr_t dr) {
rxoff = (LMIC.drift * (ostime_t)secs) >> BCN_INTV_exp;
err = (LMIC.lastDriftDiff * (ostime_t)secs) >> BCN_INTV_exp;
}
u1_t rxsyms = LMICbandplan_MINRX_SYMS_LoRa_ClassB;
rxsyms_t rxsyms = LMICbandplan_MINRX_SYMS_LoRa_ClassB;
err += (ostime_t)LMIC.maxDriftDiff * LMIC.missedBcns;
LMIC.rxsyms = LMICbandplan_MINRX_SYMS_LoRa_ClassB + (err / dr2hsym(dr));
setRxsyms(LMICbandplan_MINRX_SYMS_LoRa_ClassB + (err / dr2hsym(dr)));
return (rxsyms-LMICbandplan_PAMBL_SYMS) * dr2hsym(dr) + rxoff;
}
@ -616,7 +626,9 @@ static void stateJustJoined (void) {
#if !defined(DISABLE_BEACONS)
// Decode beacon - do not overwrite bcninfo unless we have a match!
static lmic_beacon_error_t decodeBeacon (void) {
ASSERT(LMIC.dataLen == LEN_BCN); // implicit header RX guarantees this
if (LMIC.dataLen != LEN_BCN) { // implicit header RX guarantees this
return LMIC_BEACON_ERROR_INVALID;
}
xref2u1_t d = LMIC.frame;
if(! LMICbandplan_isValidBeacon1(d))
return LMIC_BEACON_ERROR_INVALID; // first (common) part fails CRC check
@ -709,11 +721,17 @@ static CONST_TABLE(u1_t, macCmdSize)[] = {
};
static u1_t getMacCmdSize(u1_t macCmd) {
if (macCmd < 2)
return 0;
if (macCmd >= LENOF_TABLE(macCmdSize) - 2)
return 0;
return TABLE_GET_U1(macCmdSize, macCmd - 2);
if (macCmd >= 2) {
const unsigned macCmdMinus2 = macCmd - 2u;
if (macCmdMinus2 < LENOF_TABLE(macCmdSize)) {
// macCmd in table, fetch it's size.
return TABLE_GET_U1(macCmdSize, macCmdMinus2);
}
}
// macCmd too small or too large: return zero. Zero is
// never a legal command size, so it signals an error
// to the caller.
return 0;
}
static bit_t
@ -747,7 +765,7 @@ applyAdrRequests(
u1_t chpage = p4 & MCMD_LinkADRReq_Redundancy_ChMaskCntl_MASK; // channel page
map_ok = LMICbandplan_mapChannels(chpage, chmap);
LMICOS_logEventUint32("applyAdrRequests: mapChannels", (chpage << 16)|(chmap << 0));
LMICOS_logEventUint32("applyAdrRequests: mapChannels", ((u4_t)chpage << 16)|(chmap << 0));
}
}
@ -789,7 +807,7 @@ applyAdrRequests(
changes = 1;
}
LMICOS_logEventUint32("applyAdrRequests: setDrTxPow", (adrAns << 16)|(dr << 8)|(p1 << 0));
LMICOS_logEventUint32("applyAdrRequests: setDrTxPow", ((u4_t)adrAns << 16)|(dr << 8)|(p1 << 0));
// handle power changes here, too.
changes |= setDrTxpow(DRCHG_NWKCMD, dr, pow2dBm(p1));
@ -836,7 +854,7 @@ scan_mac_cmds_link_adr(
if( !LMICbandplan_canMapChannels(chpage, chmap) ) {
adrAns &= ~MCMD_LinkADRAns_ChannelACK;
LMICOS_logEventUint32("scan_mac_cmds_link_adr: failed canMapChannels", (chpage << UINT32_C(16))|(chmap << UINT32_C(0)));
LMICOS_logEventUint32("scan_mac_cmds_link_adr: failed canMapChannels", ((u4_t)chpage << 16)|((u4_t)chmap << 0));
}
if( !validDR(dr) ) {
@ -871,10 +889,14 @@ scan_mac_cmds(
uint8_t cmd;
LMIC.pendMacLen = 0;
if (port == 0)
if (port == 0) {
// port zero: mac data is in the normal payload, and there can't be
// piggyback mac data.
LMIC.pendMacPiggyback = 0;
else
} else {
// port is either -1 (no port) or non-zero (piggyback): treat as piggyback.
LMIC.pendMacPiggyback = 1;
}
while( oidx < olen ) {
bit_t response_fit;
@ -883,8 +905,9 @@ scan_mac_cmds(
cmd = opts[oidx];
/* compute length, and exit for illegal commands */
// cmdlen == 0 for error, or > 0 length of command.
int const cmdlen = getMacCmdSize(cmd);
if (cmdlen > olen - oidx) {
if (cmdlen <= 0 || cmdlen > olen - oidx) {
// "the first unknown command terminates processing"
olen = oidx;
break;
@ -993,7 +1016,7 @@ scan_mac_cmds(
if( ans == (MCMD_NewChannelAns_DataRateACK|MCMD_NewChannelAns_ChannelACK)) {
if ( ! LMIC_setupChannel(chidx, freq, DR_RANGE_MAP(MinDR, MaxDR), -1) ) {
LMICOS_logEventUint32("NewChannelReq: setupChannel failed", (MaxDR << 24u) | (MinDR << 16u) | (raw_f_not_zero << 8) | (chidx << 0));
LMICOS_logEventUint32("NewChannelReq: setupChannel failed", ((u4_t)MaxDR << 24u) | ((u4_t)MinDR << 16u) | (raw_f_not_zero << 8) | (chidx << 0));
ans &= ~MCMD_NewChannelAns_ChannelACK;
}
}
@ -1059,13 +1082,12 @@ scan_mac_cmds(
#if defined(ENABLE_MCMD_BeaconTimingAns) && !defined(DISABLE_BEACONS)
case MCMD_BeaconTimingAns: {
// Ignore if tracking already enabled
if( (LMIC.opmode & OP_TRACK) == 0 ) {
// Ignore if tracking already enabled or bcninfoTries == 0
if( (LMIC.opmode & OP_TRACK) == 0 && LMIC.bcninfoTries != 0) {
LMIC.bcnChnl = opts[oidx+3];
// Enable tracking - bcninfoTries
LMIC.opmode |= OP_TRACK;
// Cleared later in txComplete handling - triggers EV_BEACON_FOUND
ASSERT(LMIC.bcninfoTries!=0);
// LMIC.bcninfoTries is cleared later in txComplete handling - triggers EV_BEACON_FOUND
// Setup RX parameters
LMIC.bcninfo.txtime = (LMIC.rxtime
+ ms2osticks(os_rlsbf2(&opts[oidx+1]) * MCMD_BeaconTimingAns_TUNIT)
@ -1204,7 +1226,7 @@ static bit_t decodeFrame (void) {
goto norx;
}
if( poff > pend ) {
LMICOS_logEventUint32("decodeFrame: corrupted frame", (dlen << 16) | (fct << 8) | (poff - pend));
LMICOS_logEventUint32("decodeFrame: corrupted frame", ((u4_t)dlen << 16) | (fct << 8) | (poff - pend));
EV(specCond, ERR, (e_.reason = EV::specCond_t::CORRUPTED_FRAME,
e_.eui = MAIN::CDEV->getEui(),
e_.info = 0x1000000 + (poff-pend) + (fct<<8) + (dlen<<16)));
@ -1245,7 +1267,7 @@ static bit_t decodeFrame (void) {
e_.eui = MAIN::CDEV->getEui(),
e_.info = LMIC.seqnoDn,
e_.info2 = seqno));
LMICOS_logEventUint32("decodeFrame: rollover discarded", (seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
LMICOS_logEventUint32("decodeFrame: rollover discarded", ((u4_t)seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
goto norx;
}
if( seqno != LMIC.seqnoDn-1 || !LMIC.lastDnConf || ftype != HDR_FTYPE_DCDN ) {
@ -1253,19 +1275,19 @@ static bit_t decodeFrame (void) {
e_.eui = MAIN::CDEV->getEui(),
e_.info = LMIC.seqnoDn,
e_.info2 = seqno));
LMICOS_logEventUint32("decodeFrame: Retransmit confimed discarded", (seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
LMICOS_logEventUint32("decodeFrame: Retransmit confimed discarded", ((u4_t)seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
goto norx;
}
// Replay of previous sequence number allowed only if
// previous frame and repeated both requested confirmation
// but set a flag, so we don't actually process the message.
LMICOS_logEventUint32("decodeFrame: Retransmit confimed accepted", (seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
LMICOS_logEventUint32("decodeFrame: Retransmit confimed accepted", ((u4_t)seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
replayConf = 1;
LMIC.dnConf = FCT_ACK;
}
else {
if( seqnoDiff > LMICbandplan_MAX_FCNT_GAP) {
LMICOS_logEventUint32("decodeFrame: gap too big", (seqnoDiff << 16) | (seqno & 0xFFFFu));
LMICOS_logEventUint32("decodeFrame: gap too big", ((u4_t)seqnoDiff << 16) | (seqno & 0xFFFFu));
goto norx;
}
if( seqno > LMIC.seqnoDn ) {
@ -1279,7 +1301,7 @@ static bit_t decodeFrame (void) {
// DN frame requested confirmation - provide ACK once with next UP frame
LMIC.dnConf = LMIC.lastDnConf = (ftype == HDR_FTYPE_DCDN ? FCT_ACK : 0);
if (LMIC.dnConf)
LMICOS_logEventUint32("decodeFrame: Confirmed downlink", (seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
LMICOS_logEventUint32("decodeFrame: Confirmed downlink", ((u4_t)seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
}
if (port == 0 && olen != 0 && pend > poff) {
@ -1364,7 +1386,7 @@ static bit_t decodeFrame (void) {
e_.info = Base::lsbf4(&d[pend]),
e_.info2 = seqno));
// discard the data
LMICOS_logEventUint32("decodeFrame: discarding replay", (seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
LMICOS_logEventUint32("decodeFrame: discarding replay", ((u4_t)seqno << 16) | (LMIC.lastDnConf << 8) | (ftype << 0));
goto norx;
}
@ -1420,59 +1442,84 @@ static void setupRx2 (void) {
radioRx();
}
ostime_t LMICcore_adjustForDrift (ostime_t delay, ostime_t hsym) {
if (LMIC.client.clockError != 0) {
// Calculate how much the clock will drift maximally after delay has
// passed. This indicates the amount of time we can be early
// _or_ late.
ostime_t drift = (int64_t)delay * LMIC.client.clockError / MAX_CLOCK_ERROR;
// Increase the receive window by twice the maximum drift (to
// compensate for a slow or a fast clock).
delay -= drift;
// adjust rxsyms (the size of the window in syms) according to our
// uncertainty. do this in a strange order to avoid a divide if we can.
// rely on hsym = Tsym / 2
if ((255 - LMIC.rxsyms) * hsym < drift) {
LMIC.rxsyms = 255;
} else {
LMIC.rxsyms = (u1_t) (LMIC.rxsyms + drift / hsym);
}
}
return delay;
}
ostime_t LMICcore_RxWindowOffset (ostime_t hsym, u1_t rxsyms_in) {
ostime_t const Tsym = 2 * hsym;
ostime_t rxsyms;
//! \brief Adjust the delay (in ticks) of the target window-open time from nominal.
//! \param hsym the duration of one-half symbol in osticks.
//! \param rxsyms_in the nominal window length -- minimum length of time to delay.
//! \return Effective delay to use (positive for later, negative for earlier).
//! \post LMIC.rxsyms is set to the number of rxsymbols to be used for preamble timeout.
//! \bug For FSK, the radio driver ignores LMIC.rxsysms, and uses a fixed value of 4080 bits
//! (81 ms)
//!
//! \details The calculation of the RX Window opening time has to balance several things.
//! The system clock might be inaccurate. Generally, the LMIC assumes that the timebase
//! is accurage to 100 ppm, or 0.01%. 0.01% of a 6 second window is 600 microseconds.
//! For LoRa, the fastest data rates of interest is SF7 (1024 us/symbol); with an 8-byte
//! preamble, the shortest preamble is 8.092ms long. If using FSK, the symbol rate is
//! 20 microseconds, but the preamble is 8*5 bits long, so the preamble is 800 microseconds.
//! Unless LMIC_ENABLE_arbitrary_clock_error is true, we fold clock errors of > 0.4% back
//! to 0.4%.
ostime_t LMICcore_adjustForDrift (ostime_t delay, ostime_t hsym, rxsyms_t rxsyms_in) {
ostime_t rxoffset;
rxsyms = ((2 * (int)rxsyms_in - 8) * Tsym + LMICbandplan_RX_ERROR_ABS_osticks * 2 + Tsym - 1) / Tsym;
if (rxsyms < rxsyms_in) {
rxsyms = rxsyms_in;
}
LMIC.rxsyms = (u1_t) rxsyms;
// decide if we want to move left or right of the reference time.
rxoffset = -LMICbandplan_RX_EXTRA_MARGIN_osticks;
rxoffset = (8 - rxsyms) * hsym - LMICbandplan_RX_EXTRA_MARGIN_osticks;
u2_t clockerr = LMIC.client.clockError;
return rxoffset;
// Most crystal oscillators are 100 ppm. If things are that tight, there's
// no point in specifying a drift, as 6 seconds at 100ppm is +/- 600 microseconds.
// We position the windows at the front, and there's some extra margin, so...
// don't bother setting values <= 100 ppm.
if (clockerr != 0)
{
// client has set clock error. Limit this to 0.1% unless there's
// a compile-time configuration. (In other words, assume that millis()
// clock is accurate to 0.1%.) You should never use clockerror to
// compensate for system-late problems.
u2_t const maxError = LMIC_kMaxClockError_ppm * MAX_CLOCK_ERROR / (1000 * 1000);
if (! LMIC_ENABLE_arbitrary_clock_error && clockerr > maxError)
{
clockerr = maxError;
}
}
// If the clock is slow, the window needs to open earlier in our time
// in order to open at or before the specified time (in real world),.
// Don't bother to round, as this is very fine-grained.
ostime_t drift = (ostime_t)(((int64_t)delay * clockerr) / MAX_CLOCK_ERROR);
// calculate the additional rxsyms needed to hit the window nominally.
ostime_t const tsym = 2 * hsym;
ostime_t driftwin;
driftwin = 2 * drift;
if (rxoffset < 0)
driftwin += -rxoffset;
// else we'll hit the window nominally.
rxsyms_in += (driftwin + tsym - 1) / tsym;
// reduce the rxoffset by the drift; this compensates for a slow clock;
// but it makes the rxtime too early by approximately `drift` if clock
// is fast.
rxoffset -= drift;
setRxsyms(rxsyms_in);
return delay + rxoffset;
}
static void schedRx12 (ostime_t delay, osjobcb_t func, u1_t dr) {
ostime_t hsym = dr2hsym(dr);
// Center the receive window on the center of the expected preamble and timeout.
// (again note that hsym is half a sumbol time, so no /2 needed)
// we leave RX_RAMPUP unadjusted for the clock drift. The IBM LMIC generates delays
// that are too long for SF12, and too short for other SFs, so we follow the
// Semtech reference code.
// Schedule the start of the receive window. os_getRadioRxRampup() is used to make sure we
// exit "sleep" well enough in advance of the receive window to be able to
// time things accurately.
//
// This also sets LMIC.rxsyms.
LMIC.rxtime = LMIC.txend + LMICcore_adjustForDrift(delay + LMICcore_RxWindowOffset(hsym, LMICbandplan_MINRX_SYMS_LoRa_ClassA), hsym);
// This also sets LMIC.rxsyms. This is NOT normally used for FSK; see LMICbandplan_txDoneFSK()
LMIC.rxtime = LMIC.txend + LMICcore_adjustForDrift(delay, hsym, LMICbandplan_MINRX_SYMS_LoRa_ClassA);
LMIC_X_DEBUG_PRINTF("%"LMIC_PRId_ostime_t": sched Rx12 %"LMIC_PRId_ostime_t"\n", os_getTime(), LMIC.rxtime - RX_RAMPUP);
os_setTimedCallback(&LMIC.osjob, LMIC.rxtime - RX_RAMPUP, func);
LMIC_X_DEBUG_PRINTF("%"LMIC_PRId_ostime_t": sched Rx12 %"LMIC_PRId_ostime_t"\n", os_getTime(), LMIC.rxtime - os_getRadioRxRampup());
os_setTimedCallback(&LMIC.osjob, LMIC.rxtime - os_getRadioRxRampup(), func);
}
static void setupRx1 (osjobcb_t func) {
@ -1498,9 +1545,8 @@ static void txDone (ostime_t delay, osjobcb_t func) {
// change params and rps (US only) before we increment txChnl
LMICbandplan_setRx1Params();
// LMIC.rxsyms carries the TX datarate (can be != LMIC.datarate [confirm retries etc.])
// Setup receive - LMIC.rxtime is preloaded with 1.5 symbols offset to tune
// into the middle of the 8 symbols preamble.
// LMIC.dndr carries the TX datarate (can be != LMIC.datarate [confirm retries etc.])
// Setup receive -- either schedule FSK or schedule rx1 or rx2 window.
if( LMICbandplan_isFSK() ) {
LMICbandplan_txDoneFSK(delay, func);
}
@ -1527,12 +1573,22 @@ static bit_t processJoinAccept (void) {
if ((LMIC.txrxFlags & TXRX_DNW1) != 0 && LMIC.dataLen == 0)
return 0;
ASSERT((LMIC.opmode & OP_TXRXPEND)!=0);
// formerly we asserted.
if ((LMIC.opmode & OP_TXRXPEND) == 0)
// nothing we can do.
return 1;
// formerly we asserted.
if ((LMIC.opmode & (OP_JOINING|OP_REJOIN)) == 0) {
// we shouldn't be here. just drop the frame, but clean up txrxpend.
return processJoinAccept_badframe();
}
if( LMIC.dataLen == 0 ) {
// we didn't get any data and we're in slot 2. So... there's no join frame.
return processJoinAccept_nojoinframe();
}
u1_t hdr = LMIC.frame[0];
u1_t dlen = LMIC.dataLen;
u4_t mic = os_rlsbf4(&LMIC.frame[dlen-4]); // safe before modified by encrypt!
@ -1594,7 +1650,6 @@ static bit_t processJoinAccept (void) {
? EV::joininfo_t::REJOIN_ACCEPT
: EV::joininfo_t::ACCEPT)));
ASSERT((LMIC.opmode & (OP_JOINING|OP_REJOIN))!=0);
//
// XXX(tmm@mcci.com) OP_REJOIN confuses me, and I'm not sure why we're
// adjusting DRs here. We've just received a join accept, and the
@ -1646,7 +1701,12 @@ static bit_t processJoinAccept_nojoinframe(void) {
// the rejoin-sent count. Internal callers will turn on rejoin
// occasionally.
if( (LMIC.opmode & OP_JOINING) == 0) {
ASSERT((LMIC.opmode & OP_REJOIN) != 0);
// formerly, we asserted ((LMIC.opmode & OP_REJOIN) != 0);
// but now we just return 1 if it's not asserted.
if ( (LMIC.opmode & OP_REJOIN) == 0) {
LMIC.opmode &= ~OP_TXRXPEND;
return 1;
}
LMIC.opmode &= ~(OP_REJOIN|OP_TXRXPEND);
if( LMIC.rejoinCnt < 10 )
LMIC.rejoinCnt++;
@ -1805,7 +1865,8 @@ static bit_t buildDataFrame (void) {
// highest importance are the ones in the pendMac buffer.
int end = OFF_DAT_OPTS;
if (LMIC.pendTxPort != 0 && LMIC.pendMacPiggyback && LMIC.pendMacLen != 0) {
// Send piggyback data if: !txdata or txport != 0
if ((! txdata || LMIC.pendTxPort != 0) && LMIC.pendMacPiggyback && LMIC.pendMacLen != 0) {
os_copyMem(LMIC.frame + end, LMIC.pendMacData, LMIC.pendMacLen);
end += LMIC.pendMacLen;
}
@ -1882,7 +1943,7 @@ static bit_t buildDataFrame (void) {
u1_t maxFlen = LMICbandplan_maxFrameLen(LMIC.datarate);
if (flen > maxFlen) {
LMICOS_logEventUint32("frame too long for this bandplan", (dlen << 16) | (flen << 8) | maxFlen);
LMICOS_logEventUint32("frame too long for this bandplan", ((u4_t)dlen << 16) | (flen << 8) | maxFlen);
return 0;
}
@ -1896,7 +1957,7 @@ static bit_t buildDataFrame (void) {
LMIC.seqnoUp += 1;
DO_DEVDB(LMIC.seqnoUp,seqnoUp);
} else {
LMICOS_logEventUint32("retransmit", (LMIC.frame[OFF_DAT_FCT] << 24u) | (LMIC.txCnt << 16u) | (LMIC.upRepeatCount << 8u) | (LMIC.upRepeat<<0u));
LMICOS_logEventUint32("retransmit", ((u4_t)LMIC.frame[OFF_DAT_FCT] << 24u) | ((u4_t)LMIC.txCnt << 16u) | (LMIC.upRepeatCount << 8u) | (LMIC.upRepeat<<0u));
EV(devCond, INFO, (e_.reason = EV::devCond_t::RE_TX,
e_.eui = MAIN::CDEV->getEui(),
e_.info = LMIC.seqnoUp-1,
@ -1981,7 +2042,9 @@ static void onBcnRx (xref2osjob_t osjob) {
// Implicitely cancels any pending TX/RX transaction.
// Also cancels an onpoing joining procedure.
static void startScan (void) {
ASSERT(LMIC.devaddr!=0 && (LMIC.opmode & OP_JOINING)==0);
// formerly, we asserted.
if (LMIC.devaddr == 0 || (LMIC.opmode & OP_JOINING) != 0)
return;
if( (LMIC.opmode & OP_SHUTDOWN) != 0 )
return;
// Cancel onging TX/RX transaction
@ -2170,7 +2233,10 @@ static bit_t processDnData_norx(void);
static bit_t processDnData_txcomplete(void);
static bit_t processDnData (void) {
ASSERT((LMIC.opmode & OP_TXRXPEND)!=0);
// if no TXRXPEND, we shouldn't be here and can do nothign.
// formerly we asserted.
if ((LMIC.opmode & OP_TXRXPEND) == 0)
return 1;
if( LMIC.dataLen == 0 ) {
// if this is an RX1 window, shouldn't we return 0 to schedule
@ -2416,7 +2482,7 @@ static void processBeacon (xref2osjob_t osjob) {
e_.eui = MAIN::CDEV->getEui(),
e_.info = drift,
e_.info2 = /*occasion BEACON*/0));
ASSERT((LMIC.bcninfo.flags & (BCN_PARTIAL|BCN_FULL)) != 0);
// formerly we'd assert on BCN_PARTIAL|BCN_FULL, but we can't get here if so
} else {
ev = EV_BEACON_MISSED;
LMIC.bcninfo.txtime += BCN_INTV_osticks - LMIC.drift;
@ -2424,9 +2490,9 @@ static void processBeacon (xref2osjob_t osjob) {
LMIC.missedBcns++;
// Delay any possible TX after surmised beacon - it's there although we missed it
txDelay(LMIC.bcninfo.txtime + BCN_RESERVE_osticks, 4);
if( LMIC.missedBcns > MAX_MISSED_BCNS )
LMIC.opmode |= OP_REJOIN; // try if we can roam to another network
if( LMIC.bcnRxsyms > MAX_RXSYMS ) {
// if too many missed beacons or we lose sync, drop back to Class A.
if( LMIC.missedBcns > MAX_MISSED_BCNS ||
LMIC.bcnRxsyms > MAX_RXSYMS ) {
LMIC.opmode &= ~(OP_TRACK|OP_PINGABLE|OP_PINGINI|OP_REJOIN);
reportEventAndUpdate(EV_LOST_TSYNC);
return;
@ -2495,8 +2561,14 @@ static void engineUpdate_inner (void) {
if( (LMIC.opmode & OP_TRACK) != 0 ) {
// We are tracking a beacon
ASSERT( now + RX_RAMPUP - LMIC.bcnRxtime <= 0 );
rxtime = LMIC.bcnRxtime - RX_RAMPUP;
// formerly asserted ( now - (LMIC.bcnRxtime - os_getRadioRxRampup()) <= 0 );
rxtime = LMIC.bcnRxtime - os_getRadioRxRampup();
if (now - rxtime < 0) {
// too late: drop out of Class B.
LMIC.opmode &= ~(OP_TRACK|OP_PINGABLE|OP_PINGINI|OP_REJOIN);
reportEventNoUpdate(EV_LOST_TSYNC);
return;
}
}
#endif // !DISABLE_BEACONS
@ -2609,7 +2681,7 @@ static void engineUpdate_inner (void) {
#if !defined(DISABLE_PING)
if( (LMIC.opmode & OP_PINGINI) != 0 ) {
// One more RX slot in this beacon period?
if( rxschedNext(&LMIC.ping, now+RX_RAMPUP) ) {
if( rxschedNext(&LMIC.ping, now+os_getRadioRxRampup()) ) {
if( txbeg != 0 && (txbeg - LMIC.ping.rxtime) < 0 )
goto txdelay;
LMIC.rxsyms = LMIC.ping.rxsyms;
@ -2617,8 +2689,14 @@ static void engineUpdate_inner (void) {
LMIC.freq = LMIC.ping.freq;
LMIC.rps = dndr2rps(LMIC.ping.dr);
LMIC.dataLen = 0;
ASSERT(LMIC.rxtime - now+RX_RAMPUP >= 0 );
os_setTimedCallback(&LMIC.osjob, LMIC.rxtime - RX_RAMPUP, FUNC_ADDR(startRxPing));
ostime_t rxtime_ping = LMIC.rxtime - os_getRadioRxRampup();
// did we miss the time?
if (now - rxtime_ping > 0) {
LMIC.opmode &= ~(OP_TRACK|OP_PINGABLE|OP_PINGINI|OP_REJOIN);
reportEventNoUpdate(EV_LOST_TSYNC);
} else {
os_setTimedCallback(&LMIC.osjob, rxtime_ping, FUNC_ADDR(startRxPing));
}
return;
}
// no - just wait for the beacon
@ -2713,6 +2791,11 @@ void LMIC_reset (void) {
LMIC.adrEnabled = FCT_ADREN;
resetJoinParams();
LMIC.rxDelay = DELAY_DNW1;
// LMIC.pendMacLen = 0;
// LMIC.pendMacPiggyback = 0;
// LMIC.dn2Ans = 0;
// LMIC.macDlChannelAns = 0;
// LMIC.macRxTimingSetupAns = 0;
#if !defined(DISABLE_PING)
LMIC.ping.freq = FREQ_PING; // defaults for ping
LMIC.ping.dr = DR_PING; // ditto
@ -2819,7 +2902,7 @@ void LMIC_setTxData (void) {
}
void LMIC_setTxData_strict (void) {
LMICOS_logEventUint32(__func__, (LMIC.pendTxPort << 24u) | (LMIC.pendTxConf << 16u) | (LMIC.pendTxLen << 0u));
LMICOS_logEventUint32(__func__, ((u4_t)LMIC.pendTxPort << 24u) | ((u4_t)LMIC.pendTxConf << 16u) | (LMIC.pendTxLen << 0u));
LMIC.opmode |= OP_TXDATA;
if( (LMIC.opmode & OP_JOINING) == 0 ) {
LMIC.txCnt = 0; // reset the confirmed uplink FSM
@ -3013,6 +3096,8 @@ int LMIC_getNetworkTimeReference(lmic_time_reference_t *pReference) {
pReference->tNetwork = LMIC.netDeviceTime;
return 1;
}
#else
LMIC_API_PARAMETER(pReference);
#endif // LMIC_ENABLE_DeviceTimeReq
return 0;
}

View File

@ -1,7 +1,7 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* Copyright (c) 2016 Matthijs Kooijman.
* Copyright (c) 2016-2019 MCCI Corporation.
* Copyright (c) 2016-2020 MCCI Corporation.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
@ -103,18 +103,18 @@ extern "C"{
// Arduino LMIC version
#define ARDUINO_LMIC_VERSION_CALC(major, minor, patch, local) \
(((major) << 24ul) | ((minor) << 16ul) | ((patch) << 8ul) | ((local) << 0ul))
((((major)*UINT32_C(1)) << 24) | (((minor)*UINT32_C(1)) << 16) | (((patch)*UINT32_C(1)) << 8) | (((local)*UINT32_C(1)) << 0))
#define ARDUINO_LMIC_VERSION ARDUINO_LMIC_VERSION_CALC(3, 0, 99, 5) /* v3.0.99.5 */
#define ARDUINO_LMIC_VERSION ARDUINO_LMIC_VERSION_CALC(3, 2, 0, 0) /* v3.2.0 */
#define ARDUINO_LMIC_VERSION_GET_MAJOR(v) \
(((v) >> 24u) & 0xFFu)
((((v)*UINT32_C(1)) >> 24u) & 0xFFu)
#define ARDUINO_LMIC_VERSION_GET_MINOR(v) \
(((v) >> 16u) & 0xFFu)
((((v)*UINT32_C(1)) >> 16u) & 0xFFu)
#define ARDUINO_LMIC_VERSION_GET_PATCH(v) \
(((v) >> 8u) & 0xFFu)
((((v)*UINT32_C(1)) >> 8u) & 0xFFu)
#define ARDUINO_LMIC_VERSION_GET_LOCAL(v) \
((v) & 0xFFu)
@ -127,8 +127,15 @@ extern "C"{
enum { MAX_FRAME_LEN = MAX_LEN_FRAME }; //!< Library cap on max frame length
enum { TXCONF_ATTEMPTS = 8 }; //!< Transmit attempts for confirmed frames
enum { MAX_MISSED_BCNS = 20 }; // threshold for triggering rejoin requests
enum { MAX_RXSYMS = 100 }; // stop tracking beacon beyond this
enum { MAX_MISSED_BCNS = (2 * 60 * 60 + 127) / 128 }; //!< threshold for dropping out of class B, triggering rejoin requests
// note that we need 100 ppm timing accuracy for
// this, to keep the timing error to +/- 700ms.
enum { MAX_RXSYMS = 350 }; // Stop tracking beacon if sync error grows beyond this. A 0.4% clock error
// at SF9.125k means 512 ms; one sybol is 4.096 ms,
// so this needs to be at least 125 for an STM32L0.
// And for 100ppm clocks and 2 hours of beacon misses,
// this needs to accomodate 1.4 seconds of error at
// 4.096 ms/sym or at least 342 symbols.
enum { LINK_CHECK_CONT = 0 , // continue with this after reported dead link
LINK_CHECK_DEAD = 32 , // after this UP frames and no response to ack from NWK assume link is dead (ADR_ACK_DELAY)
@ -185,10 +192,10 @@ enum { KEEP_TXPOW = -128 };
#if !defined(DISABLE_PING)
//! \internal
struct rxsched_t {
u1_t dr;
dr_t dr;
u1_t intvExp; // 0..7
u1_t slot; // runs from 0 to 128
u1_t rxsyms;
rxsyms_t rxsyms;
ostime_t rxbase;
ostime_t rxtime; // start of next spot
u4_t freq;
@ -219,7 +226,7 @@ struct bcninfo_t {
#endif // !DISABLE_BEACONS
// purpose of receive window - lmic_t.rxState
enum { RADIO_RST=0, RADIO_TX=1, RADIO_RX=2, RADIO_RXON=3 };
enum { RADIO_RST=0, RADIO_TX=1, RADIO_RX=2, RADIO_RXON=3, RADIO_TX_AT=4, };
// Netid values / lmic_t.netid
enum { NETID_NONE=(int)~0U, NETID_MASK=(int)0xFFFFFF };
// MAC operation modes (lmic_t.opmode).
@ -320,9 +327,25 @@ static inline bit_t LMIC_BEACON_SUCCESSFUL(lmic_beacon_error_t e) {
return e < 0;
}
// LMIC_CFG_max_clock_error_ppm
#if !defined(LMIC_CFG_max_clock_error_ppm)
# define LMIC_CFG_max_clock_error_ppm 2000 /* max clock error: 0.2% (2000 ppm) */
#endif
enum {
// This value represents 100% error in LMIC.clockError
MAX_CLOCK_ERROR = 65536,
//! \brief maximum clock error that users can specify: 2000 ppm (0.2%).
//! \details This is the limit for clock error, unless LMIC_ENABLE_arbitrary_clock_error is set.
//! The default is 4,000 ppm, which is .004, or 0.4%; this is what you get on an
//! STM32L0 running with the HSI oscillator after cal. If your clock error is bigger,
//! usually you want to calibrate it so that millis() and micros() are reasonably
//! accurate. Important: do not use clock error to compensate for late serving
//! of the LMIC. If you see that LMIC.radio.rxlate_count is increasing, you need
//! to adjust your application logic so the LMIC gets serviced promptly when a
//! Class A downlink (or beacon) is pending.
LMIC_kMaxClockError_ppm = 4000,
};
// callbacks for client alerts.
@ -417,6 +440,32 @@ struct lmic_client_data_s {
/*
Structure: lmic_radio_data_t
Function:
Holds LMIC radio driver.
Description:
Eventually this will be used for all portable things for the radio driver,
but for now it's where we can start to add things.
*/
typedef struct lmic_radio_data_s lmic_radio_data_t;
struct lmic_radio_data_s {
// total os ticks of accumulated delay error. Can overflow!
ostime_t rxlate_ticks;
// number of rx late launches.
unsigned rxlate_count;
// total os ticks of accumulated tx delay error. Can overflow!
ostime_t txlate_ticks;
// number of tx late launches.
unsigned txlate_count;
};
/*
Structure: lmic_t
Function:
@ -439,6 +488,9 @@ struct lmic_t {
rxsched_t ping; // pingable setup
#endif
// the radio driver portable context
lmic_radio_data_t radio;
/* (u)int32_t things */
// Radio settings TX/RX (also accessed by HAL)
@ -498,13 +550,14 @@ struct lmic_t {
s2_t drift; // last measured drift
s2_t lastDriftDiff;
s2_t maxDriftDiff;
rxsyms_t bcnRxsyms; //
#endif
/* (u)int8_t things */
lmic_engine_update_state_t engineUpdateState; // state of the engineUpdate() evaluator.
s1_t rssi;
s1_t snr; // LMIC.snr is SNR times 4
u1_t rxsyms;
rxsyms_t rxsyms; // symbols for receive timeout.
u1_t dndr;
s1_t txpow; // transmit dBm (administrative)
s1_t radio_txpow; // the radio driver's copy of txpow, in dB limited by adrTxPow, and
@ -586,7 +639,6 @@ struct lmic_t {
#if !defined(DISABLE_BEACONS)
u1_t bcnChnl;
u1_t bcnRxsyms; //
#endif
u1_t noRXIQinversion;
@ -678,4 +730,7 @@ DECL_ON_LMIC_EVENT;
} // extern "C"
#endif
// names for backward compatibility
#include "lmic_compat.h"
#endif // _lmic_h_

View File

@ -30,10 +30,10 @@
#include "lmic_bandplan.h"
#if defined(CFG_au921)
#if defined(CFG_au915)
// ================================================================================
//
// BEG: AU921 related stuff
// BEG: AU915 related stuff
//
CONST_TABLE(u1_t, _DR2RPS_CRC)[] = {
@ -64,16 +64,16 @@ static CONST_TABLE(u1_t, maxFrameLens_dwell1)[] = {
61+5, 137+5, 250+5, 250+5, 250+5, 250+5 };
static bit_t
LMICau921_getUplinkDwellBit() {
LMICau915_getUplinkDwellBit() {
// if uninitialized, return default.
if (LMIC.txParam == 0xFF) {
return AU921_INITIAL_TxParam_UplinkDwellTime;
return AU915_INITIAL_TxParam_UplinkDwellTime;
}
return (LMIC.txParam & MCMD_TxParam_TxDWELL_MASK) != 0;
}
uint8_t LMICau921_maxFrameLen(uint8_t dr) {
if (LMICau921_getUplinkDwellBit()) {
uint8_t LMICau915_maxFrameLen(uint8_t dr) {
if (LMICau915_getUplinkDwellBit()) {
if (dr < LENOF_TABLE(maxFrameLens_dwell0))
return TABLE_GET_U1(maxFrameLens_dwell0, dr);
else
@ -91,10 +91,10 @@ static CONST_TABLE(s1_t, TXMAXEIRP)[16] = {
8, 10, 12, 13, 14, 16, 18, 20, 21, 24, 26, 27, 29, 30, 33, 36
};
static int8_t LMICau921_getMaxEIRP(uint8_t mcmd_txparam) {
static int8_t LMICau915_getMaxEIRP(uint8_t mcmd_txparam) {
// if uninitialized, return default.
if (mcmd_txparam == 0xFF)
return AU921_TX_EIRP_MAX_DBM;
return AU915_TX_EIRP_MAX_DBM;
else
return TABLE_GET_S1(
TXMAXEIRP,
@ -103,11 +103,11 @@ static int8_t LMICau921_getMaxEIRP(uint8_t mcmd_txparam) {
);
}
int8_t LMICau921_pow2dbm(uint8_t mcmd_ladr_p1) {
int8_t LMICau915_pow2dbm(uint8_t mcmd_ladr_p1) {
if ((mcmd_ladr_p1 & MCMD_LinkADRReq_POW_MASK) == MCMD_LinkADRReq_POW_MASK)
return -128;
else {
return ((s1_t)(LMICau921_getMaxEIRP(LMIC.txParam) - (((mcmd_ladr_p1)&MCMD_LinkADRReq_POW_MASK)<<1)));
return ((s1_t)(LMICau915_getMaxEIRP(LMIC.txParam) - (((mcmd_ladr_p1)&MCMD_LinkADRReq_POW_MASK)<<1)));
}
}
@ -131,20 +131,20 @@ static CONST_TABLE(ostime_t, DR2HSYM_osticks)[] = {
// get ostime for symbols based on datarate. This is not like us915,
// becuase the times don't match between the upper half and lower half
// of the table.
ostime_t LMICau921_dr2hsym(uint8_t dr) {
ostime_t LMICau915_dr2hsym(uint8_t dr) {
return TABLE_GET_OSTIME(DR2HSYM_osticks, dr);
}
u4_t LMICau921_convFreq(xref2cu1_t ptr) {
u4_t LMICau915_convFreq(xref2cu1_t ptr) {
u4_t freq = (os_rlsbf4(ptr - 1) >> 8) * 100;
if (freq < AU921_FREQ_MIN || freq > AU921_FREQ_MAX)
if (freq < AU915_FREQ_MIN || freq > AU915_FREQ_MAX)
freq = 0;
return freq;
}
// au921: no support for xchannels.
// au915: no support for xchannels.
bit_t LMIC_setupChannel(u1_t chidx, u4_t freq, u2_t drmap, s1_t band) {
LMIC_API_PARAMETER(chidx);
LMIC_API_PARAMETER(freq);
@ -229,14 +229,14 @@ bit_t LMIC_selectSubBand(u1_t band) {
return result;
}
void LMICau921_updateTx(ostime_t txbeg) {
void LMICau915_updateTx(ostime_t txbeg) {
u1_t chnl = LMIC.txChnl;
LMIC.txpow = LMICau921_getMaxEIRP(LMIC.txParam);
LMIC.txpow = LMICau915_getMaxEIRP(LMIC.txParam);
if (chnl < 64) {
LMIC.freq = AU921_125kHz_UPFBASE + chnl*AU921_125kHz_UPFSTEP;
LMIC.freq = AU915_125kHz_UPFBASE + chnl*AU915_125kHz_UPFSTEP;
} else {
ASSERT(chnl < 64 + 8);
LMIC.freq = AU921_500kHz_UPFBASE + (chnl - 64)*AU921_500kHz_UPFSTEP;
LMIC.freq = AU915_500kHz_UPFBASE + (chnl - 64)*AU915_500kHz_UPFSTEP;
}
// Update global duty cycle stat and deal with dwell time.
@ -248,8 +248,8 @@ void LMICau921_updateTx(ostime_t txbeg) {
ostime_t airtime = calcAirTime(LMIC.rps, LMIC.dataLen);
globalDutyDelay = txbeg + (airtime << LMIC.globalDutyRate);
}
if (LMICau921_getUplinkDwellBit(LMIC.txParam)) {
dwellDelay = AU921_UPLINK_DWELL_TIME_osticks;
if (LMICau915_getUplinkDwellBit(LMIC.txParam)) {
dwellDelay = AU915_UPLINK_DWELL_TIME_osticks;
}
if (dwellDelay > globalDutyDelay) {
globalDutyDelay = dwellDelay;
@ -260,22 +260,22 @@ void LMICau921_updateTx(ostime_t txbeg) {
}
#if !defined(DISABLE_BEACONS)
void LMICau921_setBcnRxParams(void) {
void LMICau915_setBcnRxParams(void) {
LMIC.dataLen = 0;
LMIC.freq = AU921_500kHz_DNFBASE + LMIC.bcnChnl * AU921_500kHz_DNFSTEP;
LMIC.freq = AU915_500kHz_DNFBASE + LMIC.bcnChnl * AU915_500kHz_DNFSTEP;
LMIC.rps = setIh(setNocrc(dndr2rps((dr_t)DR_BCN), 1), LEN_BCN);
}
#endif // !DISABLE_BEACONS
// set the Rx1 dndr, rps.
void LMICau921_setRx1Params(void) {
void LMICau915_setRx1Params(void) {
u1_t const txdr = LMIC.dndr;
u1_t candidateDr;
LMIC.freq = AU921_500kHz_DNFBASE + (LMIC.txChnl & 0x7) * AU921_500kHz_DNFSTEP;
if ( /* TX datarate */txdr < AU921_DR_SF8C)
LMIC.freq = AU915_500kHz_DNFBASE + (LMIC.txChnl & 0x7) * AU915_500kHz_DNFSTEP;
if ( /* TX datarate */txdr < AU915_DR_SF8C)
candidateDr = txdr + 8 - LMIC.rx1DrOffset;
else
candidateDr = AU921_DR_SF7CR;
candidateDr = AU915_DR_SF7CR;
if (candidateDr < LORAWAN_DR8)
candidateDr = LORAWAN_DR8;
@ -286,17 +286,17 @@ void LMICau921_setRx1Params(void) {
LMIC.rps = dndr2rps(LMIC.dndr);
}
void LMICau921_initJoinLoop(void) {
void LMICau915_initJoinLoop(void) {
// LMIC.txParam is set to 0xFF by the central code at init time.
LMICuslike_initJoinLoop();
// initialize the adrTxPower.
LMIC.adrTxPow = LMICau921_getMaxEIRP(LMIC.txParam); // dBm
LMIC.adrTxPow = LMICau915_getMaxEIRP(LMIC.txParam); // dBm
}
//
// END: AU921 related stuff
// END: AU915 related stuff
//
// ================================================================================
#endif

View File

@ -37,8 +37,8 @@
# include "lmic_bandplan_eu868.h"
#elif defined(CFG_us915)
# include "lmic_bandplan_us915.h"
#elif defined(CFG_au921)
# include "lmic_bandplan_au921.h"
#elif defined(CFG_au915)
# include "lmic_bandplan_au915.h"
#elif defined(CFG_as923)
# include "lmic_bandplan_as923.h"
#elif defined(CFG_kr920)
@ -226,7 +226,6 @@
// internal APIs
ostime_t LMICcore_rndDelay(u1_t secSpan);
void LMICcore_setDrJoin(u1_t reason, u1_t dr);
ostime_t LMICcore_adjustForDrift(ostime_t delay, ostime_t hsym);
ostime_t LMICcore_RxWindowOffset(ostime_t hsym, u1_t rxsyms_in);
ostime_t LMICcore_adjustForDrift(ostime_t delay, ostime_t hsym, rxsyms_t rxsyms_in);
#endif // _lmic_bandplan_h_

View File

@ -26,8 +26,8 @@
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _lmic_bandplan_au921_h_
# define _lmic_bandplan_au921_h_
#ifndef _lmic_bandplan_au915_h_
# define _lmic_bandplan_au915_h_
// preconditions for lmic_us_like.h
#define LMICuslike_getFirst500kHzDR() (LORAWAN_DR6)
@ -37,33 +37,33 @@
# include "lmic_us_like.h"
#endif
// return maximum frame length (including PHY header) for this data rate (au921); 0 --> not valid dr.
uint8_t LMICau921_maxFrameLen(uint8_t dr);
// return maximum frame length (including PHY header) for this data rate (au915); 0 --> not valid dr.
uint8_t LMICau915_maxFrameLen(uint8_t dr);
// return maximum frame length (including PHY header) for this data rate; 0 --> not valid dr.
#define LMICbandplan_maxFrameLen(dr) LMICau921_maxFrameLen(dr)
#define LMICbandplan_maxFrameLen(dr) LMICau915_maxFrameLen(dr)
int8_t LMICau921_pow2dbm(uint8_t mcmd_ladr_p1);
#define pow2dBm(mcmd_ladr_p1) LMICau921_pow2dbm(mcmd_ladr_p1)
int8_t LMICau915_pow2dbm(uint8_t mcmd_ladr_p1);
#define pow2dBm(mcmd_ladr_p1) LMICau915_pow2dbm(mcmd_ladr_p1)
ostime_t LMICau921_dr2hsym(uint8_t dr);
#define dr2hsym(dr) LMICau921_dr2hsym(dr)
ostime_t LMICau915_dr2hsym(uint8_t dr);
#define dr2hsym(dr) LMICau915_dr2hsym(dr)
#define LMICbandplan_getInitialDrJoin() (LORAWAN_DR2)
void LMICau921_initJoinLoop(void);
#define LMICbandplan_initJoinLoop() LMICau921_initJoinLoop()
void LMICau915_initJoinLoop(void);
#define LMICbandplan_initJoinLoop() LMICau915_initJoinLoop()
void LMICau921_setBcnRxParams(void);
#define LMICbandplan_setBcnRxParams() LMICau921_setBcnRxParams()
void LMICau915_setBcnRxParams(void);
#define LMICbandplan_setBcnRxParams() LMICau915_setBcnRxParams()
u4_t LMICau921_convFreq(xref2cu1_t ptr);
#define LMICbandplan_convFreq(ptr) LMICau921_convFreq(ptr)
u4_t LMICau915_convFreq(xref2cu1_t ptr);
#define LMICbandplan_convFreq(ptr) LMICau915_convFreq(ptr)
void LMICau921_setRx1Params(void);
#define LMICbandplan_setRx1Params() LMICau921_setRx1Params()
void LMICau915_setRx1Params(void);
#define LMICbandplan_setRx1Params() LMICau915_setRx1Params()
void LMICau921_updateTx(ostime_t txbeg);
#define LMICbandplan_updateTx(txbeg) LMICau921_updateTx(txbeg)
void LMICau915_updateTx(ostime_t txbeg);
#define LMICbandplan_updateTx(txbeg) LMICau915_updateTx(txbeg)
#endif // _lmic_bandplan_au921_h_
#endif // _lmic_bandplan_au915_h_

72
src/lmic/lmic_compat.h Normal file
View File

@ -0,0 +1,72 @@
/*
Module: lmic_compat.h
Function:
Symbols that are defined for backward compatibility
Copyright notice and license info:
See LICENSE file accompanying this project.
Author:
Terry Moore, MCCI Corporation January 2020
Description:
This include file centralizes backwards compatibility
definitions. The idea is to centralize the decision,
so it's clear as to what's deprecated.
*/
#ifndef _lmic_compat_h_ /* prevent multiple includes */
#define _lmic_compat_h_
#ifdef __cplusplus
extern "C"{
#endif
#ifndef ARDUINO_LMIC_VERSION
# error "This file is normally included from lmic.h, not stand alone"
#endif
#define LMIC_DEPRECATE(m) _Pragma(#m)
#if ! defined(LMIC_REGION_au921) && ARDUINO_LMIC_VERSION < ARDUINO_LMIC_VERSION_CALC(5,0,0,0)
# define LMIC_REGION_au921 LMIC_DEPRECATE(GCC warning "LMIC_REGION_au921 is deprecated, EOL at V5, use LMIC_REGION_au915") \
LMIC_REGION_au915
// Frequency plan symbols
# define AU921_DR_SF12 LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF12
# define AU921_DR_SF11 LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF11
# define AU921_DR_SF10 LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF10
# define AU921_DR_SF9 LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF9
# define AU921_DR_SF8 LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF8
# define AU921_DR_SF7 LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF7
# define AU921_DR_SF8C LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF8C
# define AU921_DR_NONE LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_NONE
# define AU921_DR_SF12CR LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF12CR
# define AU921_DR_SF11CR LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF11CR
# define AU921_DR_SF10CR LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF10CR
# define AU921_DR_SF9CR LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF9CR
# define AU921_DR_SF8CR LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF8CR
# define AU921_DR_SF7CR LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_DR_SF7CR
# define AU921_125kHz_UPFBASE LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_125kHz_UPFBASE
# define AU921_125kHz_UPFSTEP LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_125kHz_UPFSTEP
# define AU921_500kHz_UPFBASE LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_500kHz_UPFBASE
# define AU921_500kHz_UPFSTEP LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_500kHz_UPFSTEP
# define AU921_500kHz_DNFBASE LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_500kHz_DNFBASE
# define AU921_500kHz_DNFSTEP LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_500kHz_DNFSTEP
# define AU921_FREQ_MIN LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_FREQ_MIN
# define AU921_FREQ_MAX LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_FREQ_MAX
# define AU921_TX_EIRP_MAX_DBM LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_TX_EIRP_MAX_DBM
# define AU921_INITIAL_TxParam_UplinkDwellTime LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_INITIAL_TxParam_UplinkDwellTime
# define AU921_UPLINK_DWELL_TIME_osticks LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_UPLINK_DWELL_TIME_osticks
# define DR_PAGE_AU921 LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") DR_PAGE_AU915
# define AU921_LMIC_REGION_EIRP LMIC_DEPRECATE(GCC warning "A921 symbols are deprecated EOL V5, use AU915") AU915_LMIC_REGION_EIRP
#endif
#ifdef __cplusplus
}
#endif
#endif /* _lmic_compat_h_ */

View File

@ -659,6 +659,7 @@ void acSetTimer(ostime_t delay) {
}
static void timerExpiredCb(osjob_t *j) {
LMIC_API_PARAMETER(j);
LMIC_Compliance.eventflags |= LMIC_COMPLIANCE_EVENT_TIMER_EXPIRED;
fsmEval();
}
@ -726,7 +727,7 @@ static void acSendUplink(void) {
__func__,
eSend,
(unsigned) downlink & 0xFFFF,
LMIC.client.txMessageCb
(unsigned) sizeof(payload)
);
LMIC_Compliance.eventflags |= LMIC_COMPLIANCE_EVENT_UPLINK_COMPLETE;
fsmEval();
@ -734,6 +735,8 @@ static void acSendUplink(void) {
}
static void sendUplinkCompleteCb(void *pUserData, int fSuccess) {
LMIC_API_PARAMETER(pUserData);
LMIC_API_PARAMETER(fSuccess);
LMIC_Compliance.eventflags |= LMIC_COMPLIANCE_EVENT_UPLINK_COMPLETE;
LMIC_COMPLIANCE_PRINTF("%s(%s)\n", __func__, LMICcompliance_txSuccessToString(fSuccess));
fsmEvalDeferred();

View File

@ -67,7 +67,7 @@ Revision history:
#define LMIC_REGION_us915 2
#define LMIC_REGION_cn783 3
#define LMIC_REGION_eu433 4
#define LMIC_REGION_au921 5
#define LMIC_REGION_au915 5
#define LMIC_REGION_cn490 6
#define LMIC_REGION_as923 7
#define LMIC_REGION_kr920 8
@ -93,6 +93,16 @@ Revision history:
# include CFG_TEXT_1(ARDUINO_LMIC_PROJECT_CONFIG_H)
#endif /* ARDUINO_LMIC_PROJECT_CONFIG_H_SUPPRESS */
#if defined(CFG_au921) && !defined(CFG_au915)
# warning "CFG_au921 was deprecated in favour of CFG_au915. Support for CFG_au921 might be removed in the future."
# define CFG_au915
#endif
// for backwards compatibility to legacy code, define CFG_au921 if we see CFG_au915.
#if defined(CFG_au915) && !defined(CFG_au921)
# define CFG_au921
#endif
// a mask of the supported regions
// TODO(tmm@mcci.com) consider moving this block to a central file as it's not
// user-editable.
@ -101,7 +111,7 @@ Revision history:
(1 << LMIC_REGION_us915) | \
/* (1 << LMIC_REGION_cn783) | */ \
/* (1 << LMIC_REGION_eu433) | */ \
(1 << LMIC_REGION_au921) | \
(1 << LMIC_REGION_au915) | \
/* (1 << LMIC_REGION_cn490) | */ \
(1 << LMIC_REGION_as923) | \
(1 << LMIC_REGION_kr920) | \
@ -125,7 +135,7 @@ Revision history:
(defined(CFG_us915) << LMIC_REGION_us915) | \
(defined(CFG_cn783) << LMIC_REGION_cn783) | \
(defined(CFG_eu433) << LMIC_REGION_eu433) | \
(defined(CFG_au921) << LMIC_REGION_au921) | \
(defined(CFG_au915) << LMIC_REGION_au915) | \
(defined(CFG_cn490) << LMIC_REGION_cn490) | \
(defined(CFG_as923) << LMIC_REGION_as923) | \
(defined(CFG_kr920) << LMIC_REGION_kr920) | \
@ -143,8 +153,8 @@ Revision history:
# define CFG_region LMIC_REGION_cn783
#elif defined(CFG_eu433)
# define CFG_region LMIC_REGION_eu433
#elif defined(CFG_au921)
# define CFG_region LMIC_REGION_au921
#elif defined(CFG_au915)
# define CFG_region LMIC_REGION_au915
#elif defined(CFG_cn490)
# define CFG_region LMIC_REGION_cn490
#elif defined(CFG_as923jp)
@ -171,7 +181,7 @@ Revision history:
/* (1 << LMIC_REGION_us915) | */ \
(1 << LMIC_REGION_cn783) | \
(1 << LMIC_REGION_eu433) | \
/* (1 << LMIC_REGION_au921) | */ \
/* (1 << LMIC_REGION_au915) | */ \
/* (1 << LMIC_REGION_cn490) | */ \
(1 << LMIC_REGION_as923) | \
(1 << LMIC_REGION_kr920) | \
@ -189,7 +199,7 @@ Revision history:
(1 << LMIC_REGION_us915) | \
/* (1 << LMIC_REGION_cn783) | */ \
/* (1 << LMIC_REGION_eu433) | */ \
(1 << LMIC_REGION_au921) | \
(1 << LMIC_REGION_au915) | \
/* (1 << LMIC_REGION_cn490) | */ \
/* (1 << LMIC_REGION_as923) | */ \
/* (1 << LMIC_REGION_kr920) | */ \

View File

@ -255,14 +255,15 @@ void LMICeulike_setRx1Freq(void) {
// Class A txDone handling for FSK.
void
LMICeulike_txDoneFSK(ostime_t delay, osjobcb_t func) {
ostime_t const hsym = us2osticksRound(80);
// one symbol == one bit at 50kHz == 20us.
ostime_t const hsym = us2osticksRound(10);
// start a little earlier.
// start a little earlier. PRERX_FSK is in bytes; one byte at 50 kHz == 160us
delay -= LMICbandplan_PRERX_FSK * us2osticksRound(160);
// set LMIC.rxtime and LMIC.rxsyms:
LMIC.rxtime = LMIC.txend + LMICcore_adjustForDrift(delay + LMICcore_RxWindowOffset(hsym, LMICbandplan_RXLEN_FSK), hsym);
os_setTimedCallback(&LMIC.osjob, LMIC.rxtime - RX_RAMPUP, func);
LMIC.rxtime = LMIC.txend + LMICcore_adjustForDrift(delay, hsym, 8 * LMICbandplan_RXLEN_FSK);
os_setTimedCallback(&LMIC.osjob, LMIC.rxtime - os_getRadioRxRampup(), func);
}
#endif // CFG_LMIC_EU_like

View File

@ -186,7 +186,7 @@ bit_t LMICuslike_mapChannels(u1_t chpage, u2_t chmap) {
}
}
LMICOS_logEventUint32("LMICuslike_mapChannels", (LMIC.activeChannels125khz << 16u)|(LMIC.activeChannels500khz << 0u));
LMICOS_logEventUint32("LMICuslike_mapChannels", ((u4_t)LMIC.activeChannels125khz << 16u)|(LMIC.activeChannels500khz << 0u));
return (LMIC.activeChannels125khz > 0) || (LMIC.activeChannels500khz > 0);
}

View File

@ -44,6 +44,7 @@ typedef u1_t cr_t;
typedef u1_t sf_t;
typedef u1_t bw_t;
typedef u1_t dr_t;
typedef u2_t rxsyms_t;
// Radio parameter set (encodes SF/BW/CR/IH/NOCRC)
// 2..0: Spreading factor
@ -226,28 +227,28 @@ enum _dr_configured_t {
};
# endif // LMIC_DR_LEGACY
#elif defined(CFG_au921) // =========================================
#elif defined(CFG_au915) // =========================================
#include "lorabase_au921.h"
#include "lorabase_au915.h"
// per 2.5.3: must be implemented
#define LMIC_ENABLE_TxParamSetupReq 1
enum { DR_DFLTMIN = AU921_DR_SF7 }; // DR5
enum { DR_DFLTMIN = AU915_DR_SF7 }; // DR5
// DR_PAGE is a debugging parameter; it must be defined but it has no use in arduino-lmic
enum { DR_PAGE = DR_PAGE_AU921 };
enum { DR_PAGE = DR_PAGE_AU915 };
//enum { CHNL_PING = 0 }; // used only for default init of state (follows beacon - rotating)
enum { FREQ_PING = AU921_500kHz_DNFBASE + 0*AU921_500kHz_DNFSTEP }; // default ping freq
enum { DR_PING = AU921_DR_SF10CR }; // default ping DR
enum { FREQ_PING = AU915_500kHz_DNFBASE + 0*AU915_500kHz_DNFSTEP }; // default ping freq
enum { DR_PING = AU915_DR_SF10CR }; // default ping DR
//enum { CHNL_DNW2 = 0 };
enum { FREQ_DNW2 = AU921_500kHz_DNFBASE + 0*AU921_500kHz_DNFSTEP };
enum { DR_DNW2 = AU921_DR_SF12CR }; // DR8
enum { FREQ_DNW2 = AU915_500kHz_DNFBASE + 0*AU915_500kHz_DNFSTEP };
enum { DR_DNW2 = AU915_DR_SF12CR }; // DR8
enum { CHNL_BCN = 0 }; // used only for default init of state (rotating beacon scheme)
enum { DR_BCN = AU921_DR_SF10CR };
enum { DR_BCN = AU915_DR_SF10CR };
enum { AIRTIME_BCN = 72192 }; // micros ... TODO(tmm@mcci.com) check.
enum { LMIC_REGION_EIRP = AU921_LMIC_REGION_EIRP }; // region uses EIRP
enum { LMIC_REGION_EIRP = AU915_LMIC_REGION_EIRP }; // region uses EIRP
enum {
// Beacon frame format AU DR10/SF10 500kHz
@ -264,20 +265,20 @@ enum {
# if LMIC_DR_LEGACY
enum _dr_configured_t {
DR_SF12 = AU921_DR_SF12,
DR_SF11 = AU921_DR_SF11,
DR_SF10 = AU921_DR_SF10,
DR_SF9 = AU921_DR_SF9,
DR_SF8 = AU921_DR_SF8,
DR_SF7 = AU921_DR_SF7,
DR_SF8C = AU921_DR_SF8C,
DR_NONE = AU921_DR_NONE,
DR_SF12CR = AU921_DR_SF12CR,
DR_SF11CR = AU921_DR_SF11CR,
DR_SF10CR = AU921_DR_SF10CR,
DR_SF9CR = AU921_DR_SF9CR,
DR_SF8CR = AU921_DR_SF8CR,
DR_SF7CR = AU921_DR_SF7CR
DR_SF12 = AU915_DR_SF12,
DR_SF11 = AU915_DR_SF11,
DR_SF10 = AU915_DR_SF10,
DR_SF9 = AU915_DR_SF9,
DR_SF8 = AU915_DR_SF8,
DR_SF7 = AU915_DR_SF7,
DR_SF8C = AU915_DR_SF8C,
DR_NONE = AU915_DR_NONE,
DR_SF12CR = AU915_DR_SF12CR,
DR_SF11CR = AU915_DR_SF11CR,
DR_SF10CR = AU915_DR_SF10CR,
DR_SF9CR = AU915_DR_SF9CR,
DR_SF8CR = AU915_DR_SF8CR,
DR_SF7CR = AU915_DR_SF7CR
};
# endif // LMIC_DR_LEGACY

View File

@ -28,8 +28,8 @@
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _lorabase_au921_h_
#define _lorabase_au921_h_
#ifndef _lorabase_au915_h_
#define _lorabase_au915_h_
#ifndef _LMIC_CONFIG_PRECONDITIONS_H_
# include "lmic_config_preconditions.h"
@ -37,53 +37,53 @@
/****************************************************************************\
|
| Basic definitions for AS921 (always in scope)
| Basic definitions for AU 915 (always in scope)
|
\****************************************************************************/
// Frequency plan for AU 921 MHz
enum _dr_as921_t {
AU921_DR_SF12 = 0,
AU921_DR_SF11,
AU921_DR_SF10,
AU921_DR_SF9,
AU921_DR_SF8,
AU921_DR_SF7,
AU921_DR_SF8C,
AU921_DR_NONE,
// Frequency plan for AU 915 MHz
enum _dr_au915_t {
AU915_DR_SF12 = 0,
AU915_DR_SF11,
AU915_DR_SF10,
AU915_DR_SF9,
AU915_DR_SF8,
AU915_DR_SF7,
AU915_DR_SF8C,
AU915_DR_NONE,
// Devices behind a router:
AU921_DR_SF12CR = 8,
AU921_DR_SF11CR,
AU921_DR_SF10CR,
AU921_DR_SF9CR,
AU921_DR_SF8CR,
AU921_DR_SF7CR
AU915_DR_SF12CR = 8,
AU915_DR_SF11CR,
AU915_DR_SF10CR,
AU915_DR_SF9CR,
AU915_DR_SF8CR,
AU915_DR_SF7CR
};
// Default frequency plan for AU 921MHz
// Default frequency plan for AU 915MHz
enum {
AU921_125kHz_UPFBASE = 915200000,
AU921_125kHz_UPFSTEP = 200000,
AU921_500kHz_UPFBASE = 915900000,
AU921_500kHz_UPFSTEP = 1600000,
AU921_500kHz_DNFBASE = 923300000,
AU921_500kHz_DNFSTEP = 600000
AU915_125kHz_UPFBASE = 915200000,
AU915_125kHz_UPFSTEP = 200000,
AU915_500kHz_UPFBASE = 915900000,
AU915_500kHz_UPFSTEP = 1600000,
AU915_500kHz_DNFBASE = 923300000,
AU915_500kHz_DNFSTEP = 600000
};
enum {
AU921_FREQ_MIN = 915000000,
AU921_FREQ_MAX = 928000000
AU915_FREQ_MIN = 915000000,
AU915_FREQ_MAX = 928000000
};
enum {
AU921_TX_EIRP_MAX_DBM = 30 // 30 dBm
AU915_TX_EIRP_MAX_DBM = 30 // 30 dBm
};
enum {
// initial value of UplinkDwellTime before TxParamSetupReq received.
AU921_INITIAL_TxParam_UplinkDwellTime = 1,
AU921_UPLINK_DWELL_TIME_osticks = sec2osticks(20),
AU915_INITIAL_TxParam_UplinkDwellTime = 1,
AU915_UPLINK_DWELL_TIME_osticks = sec2osticks(20),
};
enum { DR_PAGE_AU921 = 0x10 * (LMIC_REGION_au921 - 1) };
enum { DR_PAGE_AU915 = 0x10 * (LMIC_REGION_au915 - 1) };
enum { AU921_LMIC_REGION_EIRP = 1 }; // region uses EIRP
enum { AU915_LMIC_REGION_EIRP = 1 }; // region uses EIRP
#endif /* _lorabase_au921_h_ */
#endif /* _lorabase_au915_h_ */

View File

@ -139,6 +139,8 @@ void os_runloop () {
void os_runloop_once() {
osjob_t* j = NULL;
hal_processPendingIRQs();
hal_disableIRQs();
// check for runnable jobs
if(OS.runnablejobs) {

View File

@ -119,12 +119,13 @@ void radio_monitor_rssi(ostime_t n, oslmic_radio_rssi_t *pRssi);
//================================================================================
#ifndef RX_RAMPUP
// RX_RAMPUP specifies the extra time we must allow to set up an RX event due
// to platform issues. It's specified in units of ostime_t. It must reflect
// platform jitter and latency, as well as the speed of the LMIC when running
// on this plaform.
#define RX_RAMPUP (us2osticks(2000))
#ifndef RX_RAMPUP_DEFAULT
//! \brief RX_RAMPUP_DEFAULT specifies the extra time we must allow to set up an RX event due
//! to platform issues. It's specified in units of ostime_t. It must reflect
//! platform jitter and latency, as well as the speed of the LMIC when running
//! on this plaform. It's not used directly; clients call os_getRadioRxRampup(),
//! which might adaptively vary this based on observed timeouts.
#define RX_RAMPUP_DEFAULT (us2osticks(10000))
#endif
#ifndef TX_RAMPUP
@ -132,7 +133,7 @@ void radio_monitor_rssi(ostime_t n, oslmic_radio_rssi_t *pRssi);
// to platform issues. It's specified in units of ostime_t. It must reflect
// platform jitter and latency, as well as the speed of the LMIC when running
// on this plaform.
#define TX_RAMPUP (us2osticks(2000))
#define TX_RAMPUP (us2osticks(10000))
#endif
#ifndef OSTICKS_PER_SEC
@ -196,6 +197,9 @@ void os_setTimedCallback (xref2osjob_t job, ostime_t time, osjobcb_t cb);
#ifndef os_clearCallback
void os_clearCallback (xref2osjob_t job);
#endif
#ifndef os_getRadioRxRampup
ostime_t os_getRadioRxRampup (void);
#endif
#ifndef os_getTime
ostime_t os_getTime (void);
#endif

View File

@ -26,6 +26,8 @@
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
//! \file
#define LMIC_DR_LEGACY 0
#include "lmic.h"
@ -249,6 +251,14 @@
#define SX1276_RSSI_ADJUST_LF -164 // add to rssi value to get dB (LF)
#define SX1276_RSSI_ADJUST_HF -157 // add to rssi value to get dB (HF)
#ifdef CFG_sx1276_radio
# define SX127X_RSSI_ADJUST_LF SX1276_RSSI_ADJUST_LF
# define SX127X_RSSI_ADJUST_HF SX1276_RSSI_ADJUST_HF
#else
# define SX127X_RSSI_ADJUST_LF SX1272_RSSI_ADJUST
# define SX127X_RSSI_ADJUST_HF SX1272_RSSI_ADJUST
#endif
// per datasheet 2.5.2 (but note that we ought to ask Semtech to confirm, because
// datasheet is unclear).
#define SX127X_RX_POWER_UP us2osticks(500) // delay this long to let the receiver power up.
@ -459,10 +469,15 @@ static void configLoraModem () {
// set ModemConfig1
writeReg(LORARegModemConfig1, mc1);
mc2 = (SX1272_MC2_SF7 + ((sf-1)<<4));
mc2 = (SX1272_MC2_SF7 + ((sf-1)<<4) + ((LMIC.rxsyms >> 8) & 0x3) );
if (getNocrc(LMIC.rps) == 0) {
mc2 |= SX1276_MC2_RX_PAYLOAD_CRCON;
}
#if CFG_TxContinuousMode
// Only for testing
// set ModemConfig2 (sf, TxContinuousMode=1, AgcAutoOn=1 SymbTimeoutHi=00)
mc2 |= 0x8;
#endif
writeReg(LORARegModemConfig2, mc2);
mc3 = SX1276_MC3_AGCAUTO;
@ -519,15 +534,18 @@ static void configLoraModem () {
// set ModemConfig1
writeReg(LORARegModemConfig1, mc1);
// set ModemConfig2 (sf, AgcAutoOn=1 SymbTimeoutHi=00)
writeReg(LORARegModemConfig2, (SX1272_MC2_SF7 + ((sf-1)<<4)) | 0x04);
// set ModemConfig2 (sf, AgcAutoOn=1 SymbTimeoutHi)
u1_t mc2;
mc2 = (SX1272_MC2_SF7 + ((sf-1)<<4)) | 0x04 | ((LMIC.rxsyms >> 8) & 0x3);
#if CFG_TxContinuousMode
// Only for testing
// set ModemConfig2 (sf, TxContinuousMode=1, AgcAutoOn=1 SymbTimeoutHi=00)
writeReg(LORARegModemConfig2, (SX1272_MC2_SF7 + ((sf-1)<<4)) | 0x06);
mc2 |= 0x8;
#endif
writeReg(LORARegModemConfig2, mc2);
#else
#error Missing CFG_sx1272_radio/CFG_sx1276_radio
#endif /* CFG_sx1272_radio */
@ -765,6 +783,14 @@ static void txfsk () {
hal_pin_rxtx(1);
// now we actually start the transmission
if (LMIC.txend) {
u4_t nLate = hal_waitUntil(LMIC.txend); // busy wait until exact tx time
if (nLate > 0) {
LMIC.radio.txlate_ticks += nLate;
++LMIC.radio.txlate_count;
}
}
LMICOS_logEventUint32("+Tx FSK", LMIC.dataLen);
opmode(OPMODE_TX);
}
@ -809,6 +835,14 @@ static void txlora () {
hal_pin_rxtx(1);
// now we actually start the transmission
if (LMIC.txend) {
u4_t nLate = hal_waitUntil(LMIC.txend); // busy wait until exact tx time
if (nLate) {
LMIC.radio.txlate_ticks += nLate;
++LMIC.radio.txlate_count;
}
}
LMICOS_logEventUint32("+Tx LoRa", LMIC.dataLen);
opmode(OPMODE_TX);
#if LMIC_DEBUG_LEVEL > 0
@ -870,6 +904,18 @@ static CONST_TABLE(u1_t, rxlorairqmask)[] = {
[RXMODE_RSSI] = 0x00,
};
//! \brief handle late RX events.
//! \param nLate is the number of `ostime_t` ticks that the event was late.
//! \details If nLate is non-zero, increment the count of events, totalize
//! the number of ticks late, and (if implemented) adjust the estimate of
//! what would be best to return from `os_getRadioRxRampup()`.
static void rxlate (u4_t nLate) {
if (nLate) {
LMIC.radio.rxlate_ticks += nLate;
++LMIC.radio.rxlate_count;
}
}
// start LoRa receiver (time=LMIC.rxtime, timeout=LMIC.rxsyms, result=LMIC.frame[LMIC.dataLen])
static void rxlora (u1_t rxmode) {
// select LoRa modem (from sleep mode)
@ -914,7 +960,7 @@ static void rxlora (u1_t rxmode) {
}
// set symbol timeout (for single rx)
writeReg(LORARegSymbTimeoutLsb, LMIC.rxsyms);
writeReg(LORARegSymbTimeoutLsb, (uint8_t) LMIC.rxsyms);
// set sync word
writeReg(LORARegSyncWord, LORA_MAC_PREAMBLE);
@ -933,13 +979,16 @@ static void rxlora (u1_t rxmode) {
// now instruct the radio to receive
if (rxmode == RXMODE_SINGLE) { // single rx
hal_waitUntil(LMIC.rxtime); // busy wait until exact rx time
u4_t nLate = hal_waitUntil(LMIC.rxtime); // busy wait until exact rx time
opmode(OPMODE_RX_SINGLE);
LMICOS_logEventUint32("+Rx LoRa Single", nLate);
rxlate(nLate);
#if LMIC_DEBUG_LEVEL > 0
ostime_t now = os_getTime();
LMIC_DEBUG_PRINTF("start single rx: now-rxtime: %"LMIC_PRId_ostime_t"\n", now - LMIC.rxtime);
#endif
} else { // continous rx (scan or rssi)
LMICOS_logEventUint32("+Rx LoRa Continuous", rxmode);
opmode(OPMODE_RX);
}
@ -963,8 +1012,14 @@ static void rxlora (u1_t rxmode) {
}
static void rxfsk (u1_t rxmode) {
// only single rx (no continuous scanning, no noise sampling)
ASSERT( rxmode == RXMODE_SINGLE );
// only single or continuous rx (no noise sampling)
if (rxmode == RXMODE_SCAN) {
// indicate no bytes received.
LMIC.dataLen = 0;
// complete the request by scheduling the job.
os_setCallback(&LMIC.osjob, LMIC.osjob.func);
}
// select FSK modem (from sleep mode)
//writeReg(RegOpMode, 0x00); // (not LoRa)
opmodeFSK();
@ -995,8 +1050,15 @@ static void rxfsk (u1_t rxmode) {
hal_pin_rxtx(0);
// now instruct the radio to receive
hal_waitUntil(LMIC.rxtime); // busy wait until exact rx time
opmode(OPMODE_RX); // no single rx mode available in FSK
if (rxmode == RXMODE_SINGLE) {
u4_t nLate = hal_waitUntil(LMIC.rxtime); // busy wait until exact rx time
opmode(OPMODE_RX); // no single rx mode available in FSK
LMICOS_logEventUint32("+Rx FSK", nLate);
rxlate(nLate);
} else {
LMICOS_logEvent("+Rx FSK Continuous");
opmode(OPMODE_RX);
}
}
static void startrx (u1_t rxmode) {
@ -1010,10 +1072,26 @@ static void startrx (u1_t rxmode) {
// or timed out, and the corresponding IRQ will inform us about completion.
}
// get random seed from wideband noise rssi
//! \brief Initialize radio at system startup.
//!
//! \details This procedure is called during initialization by the `os_init()`
//! routine. It does a hardware reset of the radio, checks the version and confirms
//! that we're operating a suitable chip, and gets a random seed from wideband
//! noise rssi. It then puts the radio to sleep.
//!
//! \result True if successful, false if it doesn't look like the right radio is attached.
//!
//! \pre
//! Preconditions must be observed, or you'll get hangs during initialization.
//!
//! - The `hal_pin_..()` functions must be ready for use.
//! - The `hal_waitUntl()` function must be ready for use. This may mean that interrupts
//! are enabled.
//! - The `hal_spi_..()` functions must be ready for use.
//!
//! Generally, all these are satisfied by a call to `hal_init_with_pinmap()`.
//!
int radio_init () {
hal_disableIRQs();
requestModuleActive(1);
// manually reset radio
@ -1076,7 +1154,6 @@ int radio_init () {
opmode(OPMODE_SLEEP);
hal_enableIRQs();
return 1;
}
@ -1095,19 +1172,23 @@ u1_t radio_rand1 () {
}
u1_t radio_rssi () {
hal_disableIRQs();
u1_t r = readReg(LORARegRssiValue);
hal_enableIRQs();
return r;
}
// monitor rssi for specified number of ostime_t ticks, and return statistics
// This puts the radio into RX continuous mode, waits long enough for the
// oscillators to start and the PLL to lock, and then measures for the specified
// period of time. The radio is then returned to idle.
//
// RSSI returned is expressed in units of dB, and is offset according to the
// current radio setting per section 5.5.5 of Semtech 1276 datasheet.
/// \brief get the current RSSI on the current channel.
///
/// monitor rssi for specified number of ostime_t ticks, and return statistics
/// This puts the radio into RX continuous mode, waits long enough for the
/// oscillators to start and the PLL to lock, and then measures for the specified
/// period of time. The radio is then returned to idle.
///
/// RSSI returned is expressed in units of dB, and is offset according to the
/// current radio setting per section 5.5.5 of Semtech 1276 datasheet.
///
/// \param nTicks How long to monitor
/// \param pRssi pointer to structure to fill in with RSSI data.
///
void radio_monitor_rssi(ostime_t nTicks, oslmic_radio_rssi_t *pRssi) {
uint8_t rssiMax, rssiMin;
uint16_t rssiSum;
@ -1145,13 +1226,8 @@ void radio_monitor_rssi(ostime_t nTicks, oslmic_radio_rssi_t *pRssi) {
tBegin = os_getTime();
rssiMax = 0;
/* XXX(tanupoo)
* In this loop, micros() in os_getTime() returns a past time sometimes.
* At least, it happens on Dragino LoRa Mini.
* the return value of micros() looks not to be stable in IRQ disabled.
* Once it happens, this loop never exit infinitely.
* In order to prevent it, it enables IRQ before calling os_getTime(),
* disable IRQ again after that.
/* Per bug report from tanupoo, it's critical that interrupts be enabled
* in the loop below so that `os_getTime()` always advances.
*/
do {
ostime_t now;
@ -1164,10 +1240,7 @@ void radio_monitor_rssi(ostime_t nTicks, oslmic_radio_rssi_t *pRssi) {
rssiMin = rssiNow;
rssiSum += rssiNow;
++rssiN;
// TODO(tmm@mcci.com) move this to os_getTime().
hal_enableIRQs();
now = os_getTime();
hal_disableIRQs();
notDone = now - (tBegin + nTicks) < 0;
} while (notDone);
@ -1210,6 +1283,7 @@ void radio_irq_handler_v2 (u1_t dio, ostime_t now) {
writeReg(LORARegFifoAddrPtr, 0x00);
u1_t s = readReg(RegOpMode);
u1_t c = readReg(LORARegModemConfig2);
LMICOS_logEventUint32("+Tx LoRa Continuous", (r << 8) + c);
opmode(OPMODE_TX);
return;
#else /* ! CFG_TxContinuousMode */
@ -1240,9 +1314,22 @@ void radio_irq_handler_v2 (u1_t dio, ostime_t now) {
readBuf(RegFifo, LMIC.frame, LMIC.dataLen);
// read rx quality parameters
LMIC.snr = readReg(LORARegPktSnrValue); // SNR [dB] * 4
LMIC.rssi = readReg(LORARegPktRssiValue);
LMIC_X_DEBUG_PRINTF("RX snr=%u rssi=%d\n", LMIC.snr/4, SX127X_RSSI_ADJUST_HF + LMIC.rssi);
LMIC.rssi = LMIC.rssi - 125 + 64; // RSSI [dBm] (-196...+63)
u1_t const rRssi = readReg(LORARegPktRssiValue);
s2_t rssi = rRssi;
if (LMIC.freq > SX127X_FREQ_LF_MAX)
rssi += SX127X_RSSI_ADJUST_HF;
else
rssi += SX127X_RSSI_ADJUST_LF;
if (LMIC.snr < 0)
rssi = rssi - (-LMIC.snr >> 2);
else if (rssi > -100) {
// correct nonlinearity -- this is the same as multiplying rRssi * 16/15 initially.
rssi += (rRssi / 15);
}
LMIC_X_DEBUG_PRINTF("RX snr=%u rssi=%d\n", LMIC.snr/4, rssi);
// ugh compatibility requires a biased range. RSSI
LMIC.rssi = (s1_t) (RSSI_OFF + (rssi < -196 ? -196 : rssi > 63 ? 63 : rssi)); // RSSI [dBm] (-196...+63)
} else if( flags & IRQ_LORA_RXTOUT_MASK ) {
// indicate timeout
LMIC.dataLen = 0;
@ -1260,7 +1347,7 @@ void radio_irq_handler_v2 (u1_t dio, ostime_t now) {
u1_t flags1 = readReg(FSKRegIrqFlags1);
u1_t flags2 = readReg(FSKRegIrqFlags2);
LMICOS_logEventUint32("radio_irq_handler_v2: FSK", (flags2 << UINT32_C(8)) | flags1);
LMICOS_logEventUint32("*radio_irq_handler_v2: FSK", ((u2_t)flags2 << 8) | flags1);
if( flags2 & IRQ_FSK2_PACKETSENT_MASK ) {
// save exact tx time
@ -1273,8 +1360,9 @@ void radio_irq_handler_v2 (u1_t dio, ostime_t now) {
// now read the FIFO
readBuf(RegFifo, LMIC.frame, LMIC.dataLen);
// read rx quality parameters
LMIC.snr = 0; // determine snr
LMIC.rssi = 0; // determine rssi
LMIC.snr = 0; // SX127x doesn't give SNR for FSK.
LMIC.rssi = -64 + RSSI_OFF; // SX127x doesn't give packet RSSI for FSK,
// so substitute a dummy value.
} else if( flags1 & IRQ_FSK1_TIMEOUT_MASK ) {
// indicate timeout
LMIC.dataLen = 0;
@ -1294,8 +1382,32 @@ void radio_irq_handler_v2 (u1_t dio, ostime_t now) {
#endif /* ! CFG_TxContinuousMode */
}
/*!
\brief Initiate a radio operation.
\param mode Selects the operation to be performed.
The requested radio operation is initiated. Some operations complete
immediately; others require hardware to do work, and don't complete until
an interrupt occurs. In that case, `LMIC.osjob` is scheduled. Because the
interrupt may occur right away, it's important that the caller initialize
`LMIC.osjob` before calling this routine.
- `RADIO_RST` causes the radio to be put to sleep. No interrupt follows;
when control returns, the radio is ready for the next operation.
- `RADIO_TX` and `RADIO_TX_AT` launch the transmission of a frame. An interrupt will
occur, which will cause `LMIC.osjob` to be scheduled with its current
function.
- `RADIO_RX` and `RADIO_RX_ON` launch either single or continuous receives.
An interrupt will occur when a packet is recieved or the receive times out,
which will cause `LMIC.osjob` to be scheduled with its current function.
*/
void os_radio (u1_t mode) {
hal_disableIRQs();
switch (mode) {
case RADIO_RST:
// put radio to sleep
@ -1304,9 +1416,16 @@ void os_radio (u1_t mode) {
case RADIO_TX:
// transmit frame now
LMIC.txend = 0;
starttx(); // buf=LMIC.frame, len=LMIC.dataLen
break;
case RADIO_TX_AT:
if (LMIC.txend == 0)
LMIC.txend = 1;
starttx();
break;
case RADIO_RX:
// receive frame now (exactly at rxtime)
startrx(RXMODE_SINGLE); // buf=LMIC.frame, time=LMIC.rxtime, timeout=LMIC.rxsyms
@ -1317,5 +1436,8 @@ void os_radio (u1_t mode) {
startrx(RXMODE_SCAN); // buf=LMIC.frame
break;
}
hal_enableIRQs();
}
ostime_t os_getRadioRxRampup (void) {
return RX_RAMPUP_DEFAULT;
}