Merge branch 'geeksville-master'

This commit is contained in:
Kyle Gabriel 2020-08-20 15:13:31 -04:00
commit 5b67743915
11 changed files with 557 additions and 140 deletions

11
.gitignore vendored
View File

@ -1,3 +1,12 @@
.pio
main/configuration.h main/configuration.h
main/credentials.h main/credentials.h
credentials-private.h
# ignore vscode IDE settings files
.vscode/*
!.vscode/settings.json
!.vscode/tasks.json
!.vscode/launch.json
!.vscode/extensions.json
*.code-workspace

7
.vscode/extensions.json vendored Normal file
View File

@ -0,0 +1,7 @@
{
// See http://go.microsoft.com/fwlink/?LinkId=827846
// for the documentation about the extensions.json format
"recommendations": [
"platformio.platformio-ide"
]
}

32
.vscode/launch.json vendored Normal file
View File

@ -0,0 +1,32 @@
// AUTOMATICALLY GENERATED FILE. PLEASE DO NOT MODIFY IT MANUALLY
// PIO Unified Debugger
//
// Documentation: https://docs.platformio.org/page/plus/debugging.html
// Configuration: https://docs.platformio.org/page/projectconf/section_env_debug.html
{
"version": "0.2.0",
"configurations": [
{
"type": "platformio-debug",
"request": "launch",
"name": "PIO Debug",
"executable": "/home/kevinh/development/lora/ttgo-tbeam-ttn-tracker/.pio/build/esp32/firmware.elf",
"toolchainBinDir": "/home/kevinh/.platformio/packages/toolchain-xtensa32/bin",
"preLaunchTask": {
"type": "PlatformIO",
"task": "Pre-Debug"
},
"internalConsoleOptions": "openOnSessionStart"
},
{
"type": "platformio-debug",
"request": "launch",
"name": "PIO Debug (skip Pre-Debug)",
"executable": "/home/kevinh/development/lora/ttgo-tbeam-ttn-tracker/.pio/build/esp32/firmware.elf",
"toolchainBinDir": "/home/kevinh/.platformio/packages/toolchain-xtensa32/bin",
"internalConsoleOptions": "openOnSessionStart"
}
]
}

15
.vscode/settings.json vendored Normal file
View File

@ -0,0 +1,15 @@
{
"files.associations": {
"*.tcc": "cpp",
"deque": "cpp",
"string": "cpp",
"unordered_map": "cpp",
"unordered_set": "cpp",
"vector": "cpp",
"fstream": "cpp",
"iomanip": "cpp",
"limits": "cpp",
"sstream": "cpp",
"system_error": "cpp"
}
}

View File

@ -40,8 +40,8 @@ void ttn_register(void (*callback)(uint8_t message));
// ----------------------------------------------------------------------------- // -----------------------------------------------------------------------------
// Select which T-Beam board is being used. Only uncomment one. // Select which T-Beam board is being used. Only uncomment one.
#define T_BEAM_V07 // AKA Rev0 (first board released) // #define T_BEAM_V07 // AKA Rev0 (first board released)
//#define T_BEAM_V10 // AKA Rev1 (second board released) #define T_BEAM_V10 // AKA Rev1 (second board released)
// Select the payload format. Change on TTN as well. Only uncomment one. // Select the payload format. Change on TTN as well. Only uncomment one.
#define PAYLOAD_USE_FULL #define PAYLOAD_USE_FULL
@ -56,15 +56,18 @@ void ttn_register(void (*callback)(uint8_t message));
#define DEBUG_PORT Serial // Serial debug port #define DEBUG_PORT Serial // Serial debug port
#define SERIAL_BAUD 115200 // Serial debug baud rate #define SERIAL_BAUD 115200 // Serial debug baud rate
#define SLEEP_BETWEEN_MESSAGES 0 // Do sleep between messages #define SLEEP_BETWEEN_MESSAGES true // Do sleep between messages
#define SEND_INTERVAL 10000 // Sleep for these many millis #define SEND_INTERVAL (5 * 60 * 1000) // Sleep for these many millis
#define MESSAGE_TO_SLEEP_DELAY 5000 // Time after message before going to sleep #define MESSAGE_TO_SLEEP_DELAY 5000 // Time after message before going to sleep
#define LOGO_DELAY 5000 // Time to show logo on first boot #define LOGO_DELAY 5000 // Time to show logo on first boot
#define LORAWAN_PORT 10 // Port the messages will be sent to #define LORAWAN_PORT 10 // Port the messages will be sent to
#define LORAWAN_CONFIRMED_EVERY 0 // Send confirmed message every these many messages (0 means never) #define LORAWAN_CONFIRMED_EVERY 0 // Send confirmed message every these many messages (0 means never)
#define LORAWAN_SF DR_SF7 // Spreading factor #define LORAWAN_SF DR_SF10 // Spreading factor (recommended DR_SF7 for ttn network map purposes, DR_SF10 works for slow moving trackers)
#define LORAWAN_ADR 0 // Enable ADR #define LORAWAN_ADR 0 // Enable ADR
#define GPS_WAIT_FOR_LOCK 5000 // Wait 5s after every boot for GPS lock #define REQUIRE_RADIO true // If true, we will fail to start if the radio is not found
// If not defined, we will wait for lock forever
#define GPS_WAIT_FOR_LOCK (60 * 1000) // Wait after every boot for GPS lock (may need longer than 5s because we turned the gps off during deep sleep)
// ----------------------------------------------------------------------------- // -----------------------------------------------------------------------------
// DEBUG // DEBUG
@ -91,9 +94,9 @@ void ttn_register(void (*callback)(uint8_t message));
#define I2C_SDA 21 #define I2C_SDA 21
#define I2C_SCL 22 #define I2C_SCL 22
#define LED_PIN 14
#if defined(T_BEAM_V07) #if defined(T_BEAM_V07)
#define LED_PIN 14
#define BUTTON_PIN 39 #define BUTTON_PIN 39
#elif defined(T_BEAM_V10) #elif defined(T_BEAM_V10)
#define BUTTON_PIN 38 #define BUTTON_PIN 38
@ -129,16 +132,20 @@ void ttn_register(void (*callback)(uint8_t message));
#define MISO_GPIO 19 #define MISO_GPIO 19
#define MOSI_GPIO 27 #define MOSI_GPIO 27
#define NSS_GPIO 18 #define NSS_GPIO 18
#if defined(T_BEAM_V10)
#define RESET_GPIO 14
#else
#define RESET_GPIO 23 #define RESET_GPIO 23
#endif
#define DIO0_GPIO 26 #define DIO0_GPIO 26
#define DIO1_GPIO 33 #define DIO1_GPIO 33 // Note: not really used on this board
#define DIO2_GPIO 32 #define DIO2_GPIO 32 // Note: not really used on this board
// ----------------------------------------------------------------------------- // -----------------------------------------------------------------------------
// AXP192 (Rev1-specific options) // AXP192 (Rev1-specific options)
// ----------------------------------------------------------------------------- // -----------------------------------------------------------------------------
#define AXP192_SLAVE_ADDRESS 0x34 // #define AXP192_SLAVE_ADDRESS 0x34 // Now defined in axp20x.h
#define GPS_POWER_CTRL_CH 3 #define GPS_POWER_CTRL_CH 3
#define LORA_POWER_CTRL_CH 2 #define LORA_POWER_CTRL_CH 2
#define PMU_IRQ 35 #define PMU_IRQ 35

View File

@ -7,8 +7,8 @@ Credentials file
#pragma once #pragma once
// Only one of these settings must be defined // Only one of these settings must be defined
#define USE_ABP //#define USE_ABP
//#define USE_OTAA #define USE_OTAA
#ifdef USE_ABP #ifdef USE_ABP
@ -24,6 +24,9 @@ Credentials file
#ifdef USE_OTAA #ifdef USE_OTAA
#if 0
// copy these variables to ../credentials-private.h and customize with your secret appkey.
// This EUI must be in little-endian format, so least-significant-byte // This EUI must be in little-endian format, so least-significant-byte
// first. When copying an EUI from ttnctl output, this means to reverse // first. When copying an EUI from ttnctl output, this means to reverse
// the bytes. For TTN issued EUIs the last bytes should be 0x00, 0x00, // the bytes. For TTN issued EUIs the last bytes should be 0x00, 0x00,
@ -31,12 +34,14 @@ Credentials file
static const u1_t PROGMEM APPEUI[8] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; static const u1_t PROGMEM APPEUI[8] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
// This should also be in little endian format, see above. // This should also be in little endian format, see above.
static const u1_t PROGMEM DEVEUI[8] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; // Note: You do not need to set this field, if unset it will be generated automatically based on the device macaddr
static u1_t DEVEUI[8] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
// This key should be in big endian format (or, since it is not really a // This key should be in big endian format (or, since it is not really a
// number but a block of memory, endianness does not really apply). In // number but a block of memory, endianness does not really apply). In
// practice, a key taken from ttnctl can be copied as-is. // practice, a key taken from ttnctl can be copied as-is.
// The key shown here is the semtech default key. // The key shown here is the semtech default key.
static const u1_t PROGMEM APPKEY[16] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; static const u1_t PROGMEM APPKEY[16] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
#endif
#endif #endif

View File

@ -80,7 +80,7 @@ static void gps_loop() {
Serial.println(t); Serial.println(t);
sprintf(t, "Lng: %f", _gps.location.lng()); sprintf(t, "Lng: %f", _gps.location.lng());
Serial.println(t); Serial.println(t);
sprintf(t, "Alt: %f", altitudeGps); sprintf(t, "Alt: %d", altitudeGps);
Serial.println(t); Serial.println(t);
sprintf(t, "Hdop: %d", hdopGps); sprintf(t, "Hdop: %d", hdopGps);
Serial.println(t); Serial.println(t);

View File

@ -36,22 +36,35 @@ String baChStatus = "No charging";
bool ssd1306_found = false; bool ssd1306_found = false;
bool axp192_found = false; bool axp192_found = false;
// Message counter, stored in RTC memory, survives deep sleep bool packetSent, packetQueued;
RTC_DATA_ATTR uint32_t count = 0;
#if defined(PAYLOAD_USE_FULL) #if defined(PAYLOAD_USE_FULL)
// includes number of satellites and accuracy // includes number of satellites and accuracy
uint8_t txBuffer[10]; static uint8_t txBuffer[10];
#elif defined(PAYLOAD_USE_CAYENNE) #elif defined(PAYLOAD_USE_CAYENNE)
// CAYENNE DF // CAYENNE DF
static uint8_t txBuffer[11] = {0x03, 0x88, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}; static uint8_t txBuffer[11] = {0x03, 0x88, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00};
#endif #endif
// deep sleep support
RTC_DATA_ATTR int bootCount = 0;
esp_sleep_source_t wakeCause; // the reason we booted this time
// ----------------------------------------------------------------------------- // -----------------------------------------------------------------------------
// Application // Application
// ----------------------------------------------------------------------------- // -----------------------------------------------------------------------------
void send() { void buildPacket(uint8_t txBuffer[]); // needed for platformio
/**
* If we have a valid position send it to the server.
* @return true if we decided to send.
*/
bool trySend() {
packetSent = false;
// We also wait for altitude being not exactly zero, because the GPS chip generates a bogus 0 alt report when first powered on
if (0 < gps_hdop() && gps_hdop() < 50 && gps_latitude() != 0 && gps_longitude() != 0 && gps_altitude() != 0)
{
char buffer[40]; char buffer[40];
snprintf(buffer, sizeof(buffer), "Latitude: %10.6f\n", gps_latitude()); snprintf(buffer, sizeof(buffer), "Latitude: %10.6f\n", gps_latitude());
screen_print(buffer); screen_print(buffer);
@ -68,15 +81,54 @@ void send() {
bool confirmed = false; bool confirmed = false;
#endif #endif
ttn_cnt(count); packetQueued = true;
ttn_send(txBuffer, sizeof(txBuffer), LORAWAN_PORT, confirmed); ttn_send(txBuffer, sizeof(txBuffer), LORAWAN_PORT, confirmed);
return true;
count++; }
else {
return false;
}
} }
void doDeepSleep(uint64_t msecToWake)
{
Serial.printf("Entering deep sleep for %llu seconds\n", msecToWake / 1000);
// not using wifi yet, but once we are this is needed to shutoff the radio hw
// esp_wifi_stop();
screen_off(); // datasheet says this will draw only 10ua
LMIC_shutdown(); // cleanly shutdown the radio
if(axp192_found) {
// turn on after initial testing with real hardware
axp.setPowerOutPut(AXP192_LDO2, AXP202_OFF); // LORA radio
axp.setPowerOutPut(AXP192_LDO3, AXP202_OFF); // GPS main power
}
// FIXME - use an external 10k pulldown so we can leave the RTC peripherals powered off
// until then we need the following lines
esp_sleep_pd_config(ESP_PD_DOMAIN_RTC_PERIPH, ESP_PD_OPTION_ON);
// Only GPIOs which are have RTC functionality can be used in this bit map: 0,2,4,12-15,25-27,32-39.
uint64_t gpioMask = (1ULL << BUTTON_PIN);
// FIXME change polarity so we can wake on ANY_HIGH instead - that would allow us to use all three buttons (instead of just the first)
gpio_pullup_en((gpio_num_t) BUTTON_PIN);
esp_sleep_enable_ext1_wakeup(gpioMask, ESP_EXT1_WAKEUP_ALL_LOW);
esp_sleep_enable_timer_wakeup(msecToWake * 1000ULL); // call expects usecs
esp_deep_sleep_start(); // TBD mA sleep current (battery)
}
void sleep() { void sleep() {
#if SLEEP_BETWEEN_MESSAGES #if SLEEP_BETWEEN_MESSAGES
// If the user has a screen, tell them we are about to sleep
if(ssd1306_found) {
// Show the going to sleep message on the screen // Show the going to sleep message on the screen
char buffer[20]; char buffer[20];
snprintf(buffer, sizeof(buffer), "Sleeping in %3.1fs\n", (MESSAGE_TO_SLEEP_DELAY / 1000.0)); snprintf(buffer, sizeof(buffer), "Sleeping in %3.1fs\n", (MESSAGE_TO_SLEEP_DELAY / 1000.0));
@ -87,6 +139,7 @@ void sleep() {
// Turn off screen // Turn off screen
screen_off(); screen_off();
}
// Set the user button to wake the board // Set the user button to wake the board
sleep_interrupt(BUTTON_PIN, LOW); sleep_interrupt(BUTTON_PIN, LOW);
@ -94,14 +147,19 @@ void sleep() {
// We sleep for the interval between messages minus the current millis // We sleep for the interval between messages minus the current millis
// this way we distribute the messages evenly every SEND_INTERVAL millis // this way we distribute the messages evenly every SEND_INTERVAL millis
uint32_t sleep_for = (millis() < SEND_INTERVAL) ? SEND_INTERVAL - millis() : SEND_INTERVAL; uint32_t sleep_for = (millis() < SEND_INTERVAL) ? SEND_INTERVAL - millis() : SEND_INTERVAL;
sleep_millis(sleep_for); doDeepSleep(sleep_for);
#endif #endif
} }
void callback(uint8_t message) { void callback(uint8_t message) {
if (EV_JOINING == message) screen_print("Joining TTN...\n"); if (EV_JOINING == message) screen_print("Joining TTN...\n");
if (EV_JOINED == message) screen_print("TTN joined!\n"); if (EV_JOINED == message) {
screen_print("TTN joined!\n");
}
if (EV_JOIN_FAILED == message) screen_print("TTN join failed\n"); if (EV_JOIN_FAILED == message) screen_print("TTN join failed\n");
if (EV_REJOIN_FAILED == message) screen_print("TTN rejoin failed\n"); if (EV_REJOIN_FAILED == message) screen_print("TTN rejoin failed\n");
if (EV_RESET == message) screen_print("Reset TTN connection\n"); if (EV_RESET == message) screen_print("Reset TTN connection\n");
@ -110,9 +168,11 @@ void callback(uint8_t message) {
if (EV_PENDING == message) screen_print("Message discarded\n"); if (EV_PENDING == message) screen_print("Message discarded\n");
if (EV_QUEUED == message) screen_print("Message queued\n"); if (EV_QUEUED == message) screen_print("Message queued\n");
if (EV_TXCOMPLETE == message) { // We only want to say 'packetSent' for our packets (not packets needed for joining)
if (EV_TXCOMPLETE == message && packetQueued) {
screen_print("Message sent\n"); screen_print("Message sent\n");
sleep(); packetQueued = false;
packetSent = true;
} }
if (EV_RESPONSE == message) { if (EV_RESPONSE == message) {
@ -132,9 +192,7 @@ void callback(uint8_t message) {
} }
} }
uint32_t get_count() {
return count;
}
void scanI2Cdevice(void) void scanI2Cdevice(void)
{ {
@ -172,18 +230,18 @@ void scanI2Cdevice(void)
Serial.println("done\n"); Serial.println("done\n");
} }
void setup() { /**
// Debug * Init the power manager chip
#ifdef DEBUG_PORT *
DEBUG_PORT.begin(SERIAL_BAUD); * axp192 power
#endif DCDC1 0.7-3.5V @ 1200mA max -> OLED // If you turn this off you'll lose comms to the axp192 because the OLED and the axp192 share the same i2c bus, instead use ssd1306 sleep mode
DCDC2 -> unused
delay(1000); DCDC3 0.7-3.5V @ 700mA max -> ESP32 (keep this on!)
LDO1 30mA -> charges GPS backup battery // charges the tiny J13 battery by the GPS to power the GPS ram (for a couple of days), can not be turned off
#ifdef T_BEAM_V10 LDO2 200mA -> LORA
Wire.begin(I2C_SDA, I2C_SCL); LDO3 200mA -> GPS
scanI2Cdevice(); */
axp192_found = true; void axp192Init() {
if (axp192_found) { if (axp192_found) {
if (!axp.begin(Wire, AXP192_SLAVE_ADDRESS)) { if (!axp.begin(Wire, AXP192_SLAVE_ADDRESS)) {
Serial.println("AXP192 Begin PASS"); Serial.println("AXP192 Begin PASS");
@ -199,12 +257,12 @@ void setup() {
Serial.printf("Exten: %s\n", axp.isExtenEnable() ? "ENABLE" : "DISABLE"); Serial.printf("Exten: %s\n", axp.isExtenEnable() ? "ENABLE" : "DISABLE");
Serial.println("----------------------------------------"); Serial.println("----------------------------------------");
axp.setPowerOutPut(AXP192_LDO2, AXP202_ON); axp.setPowerOutPut(AXP192_LDO2, AXP202_ON); // LORA radio
axp.setPowerOutPut(AXP192_LDO3, AXP202_ON); axp.setPowerOutPut(AXP192_LDO3, AXP202_ON); // GPS main power
axp.setPowerOutPut(AXP192_DCDC2, AXP202_ON); axp.setPowerOutPut(AXP192_DCDC2, AXP202_ON);
axp.setPowerOutPut(AXP192_EXTEN, AXP202_ON); axp.setPowerOutPut(AXP192_EXTEN, AXP202_ON);
axp.setPowerOutPut(AXP192_DCDC1, AXP202_ON); axp.setPowerOutPut(AXP192_DCDC1, AXP202_ON);
axp.setDCDC1Voltage(3300); axp.setDCDC1Voltage(3300); // for the OLED power
Serial.printf("DCDC1: %s\n", axp.isDCDC1Enable() ? "ENABLE" : "DISABLE"); Serial.printf("DCDC1: %s\n", axp.isDCDC1Enable() ? "ENABLE" : "DISABLE");
Serial.printf("DCDC2: %s\n", axp.isDCDC2Enable() ? "ENABLE" : "DISABLE"); Serial.printf("DCDC2: %s\n", axp.isDCDC2Enable() ? "ENABLE" : "DISABLE");
@ -228,23 +286,58 @@ void setup() {
} else { } else {
Serial.println("AXP192 not found"); Serial.println("AXP192 not found");
} }
}
// Perform power on init that we do on each wake from deep sleep
void initDeepSleep() {
bootCount++;
wakeCause = esp_sleep_get_wakeup_cause();
/*
Not using yet because we are using wake on all buttons being low
wakeButtons = esp_sleep_get_ext1_wakeup_status(); // If one of these buttons is set it was the reason we woke
if (wakeCause == ESP_SLEEP_WAKEUP_EXT1 && !wakeButtons) // we must have been using the 'all buttons rule for waking' to support busted boards, assume button one was pressed
wakeButtons = ((uint64_t)1) << buttons.gpios[0];
*/
Serial.printf("booted, wake cause %d (boot count %d)\n", wakeCause, bootCount);
}
void setup() {
// Debug
#ifdef DEBUG_PORT
DEBUG_PORT.begin(SERIAL_BAUD);
#endif #endif
initDeepSleep();
Wire.begin(I2C_SDA, I2C_SCL);
scanI2Cdevice();
axp192Init();
// Buttons & LED // Buttons & LED
pinMode(BUTTON_PIN, INPUT_PULLUP); pinMode(BUTTON_PIN, INPUT_PULLUP);
#ifdef LED_PIN
pinMode(LED_PIN, OUTPUT); pinMode(LED_PIN, OUTPUT);
#endif
// Hello // Hello
DEBUG_MSG(APP_NAME " " APP_VERSION "\n"); DEBUG_MSG(APP_NAME " " APP_VERSION "\n");
// Display // Don't init display if we don't have one or we are waking headless due to a timer event
if(wakeCause == ESP_SLEEP_WAKEUP_TIMER)
ssd1306_found = false; // forget we even have the hardware
if(ssd1306_found)
screen_setup(); screen_setup();
// Init GPS // Init GPS
gps_setup(); gps_setup();
// Show logo on first boot // Show logo on first boot after removing battery
if (0 == count) { if (bootCount == 0) {
screen_print(APP_NAME " " APP_VERSION, 0, 0); screen_print(APP_NAME " " APP_VERSION, 0, 0);
screen_show_logo(); screen_show_logo();
screen_update(); screen_update();
@ -254,17 +347,17 @@ void setup() {
// TTN setup // TTN setup
if (!ttn_setup()) { if (!ttn_setup()) {
screen_print("[ERR] Radio module not found!\n"); screen_print("[ERR] Radio module not found!\n");
if(REQUIRE_RADIO) {
delay(MESSAGE_TO_SLEEP_DELAY); delay(MESSAGE_TO_SLEEP_DELAY);
screen_off(); screen_off();
sleep_forever(); sleep_forever();
} }
}
else {
ttn_register(callback); ttn_register(callback);
ttn_join(); ttn_join();
ttn_sf(LORAWAN_SF);
ttn_adr(LORAWAN_ADR); ttn_adr(LORAWAN_ADR);
if(!LORAWAN_ADR){
LMIC_setLinkCheckMode(0); // Link check problematic if not using ADR. Must be set after join
} }
} }
@ -273,23 +366,54 @@ void loop() {
ttn_loop(); ttn_loop();
screen_loop(); screen_loop();
if(packetSent) {
packetSent = false;
sleep();
}
// if user presses button for more than 3 secs, discard our network prefs and reboot (FIXME, use a debounce lib instead of this boilerplate)
static bool wasPressed = false;
static uint32_t minPressMs; // what tick should we call this press long enough
if(!digitalRead(BUTTON_PIN)) {
if(!wasPressed) { // just started a new press
Serial.println("pressing");
wasPressed = true;
minPressMs = millis() + 3000;
}
} else if(wasPressed) {
// we just did a release
wasPressed = false;
if(millis() > minPressMs) {
// held long enough
screen_print("Erasing prefs");
ttn_erase_prefs();
delay(5000); // Give some time to read the screen
ESP.restart();
}
}
// Send every SEND_INTERVAL millis // Send every SEND_INTERVAL millis
static uint32_t last = 0; static uint32_t last = 0;
static bool first = true; static bool first = true;
if (0 == last || millis() - last > SEND_INTERVAL) { if (0 == last || millis() - last > SEND_INTERVAL) {
if (0 < gps_hdop() && gps_hdop() < 50 && gps_latitude() != 0 && gps_longitude() != 0) { if (trySend()) {
last = millis(); last = millis();
first = false; first = false;
Serial.println("TRANSMITTING"); Serial.println("TRANSMITTED");
send();
} else { } else {
if (first) { if (first) {
screen_print("Waiting GPS lock\n"); screen_print("Waiting GPS lock\n");
first = false; first = false;
} }
#ifdef GPS_WAIT_FOR_LOCK
if (millis() > GPS_WAIT_FOR_LOCK) { if (millis() > GPS_WAIT_FOR_LOCK) {
sleep(); sleep();
} }
#endif
// No GPS lock yet, let the OS put the main CPU in low power mode for 100ms (or until another interrupt comes in)
// i.e. don't just keep spinning in loop as fast as we can.
delay(100);
} }
} }
} }

View File

@ -32,10 +32,12 @@ SSD1306Wire * display;
uint8_t _screen_line = SCREEN_HEADER_HEIGHT - 1; uint8_t _screen_line = SCREEN_HEADER_HEIGHT - 1;
void _screen_header() { void _screen_header() {
if(!display) return;
char buffer[20]; char buffer[20];
// Message count // Message count
snprintf(buffer, sizeof(buffer), "#%03d", get_count() % 1000); snprintf(buffer, sizeof(buffer), "#%03d", ttn_get_count() % 1000);
display->setTextAlignment(TEXT_ALIGN_LEFT); display->setTextAlignment(TEXT_ALIGN_LEFT);
display->drawString(0, 2, buffer); display->drawString(0, 2, buffer);
@ -57,25 +59,36 @@ void _screen_header() {
} }
void screen_show_logo() { void screen_show_logo() {
if(!display) return;
uint8_t x = (display->getWidth() - TTN_IMAGE_WIDTH) / 2; uint8_t x = (display->getWidth() - TTN_IMAGE_WIDTH) / 2;
uint8_t y = SCREEN_HEADER_HEIGHT + (display->getHeight() - SCREEN_HEADER_HEIGHT - TTN_IMAGE_HEIGHT) / 2 + 1; uint8_t y = SCREEN_HEADER_HEIGHT + (display->getHeight() - SCREEN_HEADER_HEIGHT - TTN_IMAGE_HEIGHT) / 2 + 1;
display->drawXbm(x, y, TTN_IMAGE_WIDTH, TTN_IMAGE_HEIGHT, TTN_IMAGE); display->drawXbm(x, y, TTN_IMAGE_WIDTH, TTN_IMAGE_HEIGHT, TTN_IMAGE);
} }
void screen_off() { void screen_off() {
if(!display) return;
display->displayOff(); display->displayOff();
} }
void screen_on() { void screen_on() {
if(!display) return;
display->displayOn(); display->displayOn();
} }
void screen_clear() { void screen_clear() {
if(!display) return;
display->clear(); display->clear();
} }
void screen_print(const char * text, uint8_t x, uint8_t y, uint8_t alignment) { void screen_print(const char * text, uint8_t x, uint8_t y, uint8_t alignment) {
DEBUG_MSG(text); DEBUG_MSG(text);
if(!display) return;
display->setTextAlignment((OLEDDISPLAY_TEXT_ALIGNMENT) alignment); display->setTextAlignment((OLEDDISPLAY_TEXT_ALIGNMENT) alignment);
display->drawString(x, y, text); display->drawString(x, y, text);
} }
@ -85,6 +98,9 @@ void screen_print(const char * text, uint8_t x, uint8_t y) {
} }
void screen_print(const char * text) { void screen_print(const char * text) {
Serial.printf("Screen: %s\n", text);
if(!display) return;
display->print(text); display->print(text);
if (_screen_line + 8 > display->getHeight()) { if (_screen_line + 8 > display->getHeight()) {
// scroll // scroll
@ -94,6 +110,7 @@ void screen_print(const char * text) {
} }
void screen_update() { void screen_update() {
if(display)
display->display(); display->display();
} }
@ -109,6 +126,8 @@ void screen_setup() {
} }
void screen_loop() { void screen_loop() {
if(!display) return;
#ifdef T_BEAM_V10 #ifdef T_BEAM_V10
if (axp192_found && pmu_irq) { if (axp192_found && pmu_irq) {
pmu_irq = false; pmu_irq = false;

View File

@ -27,9 +27,13 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#include <hal/hal.h> #include <hal/hal.h>
#include <SPI.h> #include <SPI.h>
#include <vector> #include <vector>
#include <Preferences.h>
#include "configuration.h" #include "configuration.h"
#include "credentials.h" #include "credentials.h"
// This file should not be in any publig git repos, it contains your secret APPKEY
#include "../credentials-private.h"
// ----------------------------------------------------------------------------- // -----------------------------------------------------------------------------
// Globals // Globals
// ----------------------------------------------------------------------------- // -----------------------------------------------------------------------------
@ -42,6 +46,10 @@ const lmic_pinmap lmic_pins = {
.dio = {DIO0_GPIO, DIO1_GPIO, DIO2_GPIO}, .dio = {DIO0_GPIO, DIO1_GPIO, DIO2_GPIO},
}; };
// Message counter, stored in RTC memory, survives deep sleep.
static RTC_DATA_ATTR uint32_t count = 0;
#ifdef USE_ABP #ifdef USE_ABP
// These callbacks are only used in over-the-air activation, so they are // These callbacks are only used in over-the-air activation, so they are
// left empty here (we cannot leave them out completely unless // left empty here (we cannot leave them out completely unless
@ -53,7 +61,7 @@ void os_getDevKey (u1_t* buf) { }
#ifdef USE_OTAA #ifdef USE_OTAA
void os_getArtEui (u1_t* buf) { memcpy_P(buf, APPEUI, 8); } void os_getArtEui (u1_t* buf) { memcpy_P(buf, APPEUI, 8); }
void os_getDevEui (u1_t* buf) { memcpy_P(buf, DEVEUI, 8); } void os_getDevEui (u1_t* buf) { memcpy(buf, DEVEUI, 8); }
void os_getDevKey (u1_t* buf) { memcpy_P(buf, APPKEY, 16); } void os_getDevKey (u1_t* buf) { memcpy_P(buf, APPKEY, 16); }
#endif #endif
@ -85,14 +93,100 @@ void forceTxSingleChannelDr() {
ttn_sf(LORAWAN_SF); ttn_sf(LORAWAN_SF);
} }
// DevEUI generator using devices's MAC address - from https://github.com/cyberman54/ESP32-Paxcounter/blob/master/src/lorawan.cpp
void gen_lora_deveui(uint8_t *pdeveui) {
uint8_t *p = pdeveui, dmac[6];
int i = 0;
esp_efuse_mac_get_default(dmac);
// deveui is LSB, we reverse it so TTN DEVEUI display
// will remain the same as MAC address
// MAC is 6 bytes, devEUI 8, set first 2 ones
// with an arbitrary value
*p++ = 0xFF;
*p++ = 0xFE;
// Then next 6 bytes are mac address reversed
for (i = 0; i < 6; i++) {
*p++ = dmac[5 - i];
}
}
static void printHex2(unsigned v) {
v &= 0xff;
if (v < 16)
Serial.print('0');
Serial.print(v, HEX);
}
// generate DevEUI from macaddr if needed
void initDevEUI() {
bool needInit = true;
for(int i = 0; i < sizeof(DEVEUI); i++)
if(DEVEUI[i]) needInit = false;
if(needInit)
gen_lora_deveui(DEVEUI);
Serial.print("DevEUI: ");
for(int i = 0; i < sizeof(DEVEUI); i++) {
if (i != 0)
Serial.print("-");
printHex2(DEVEUI[i]);
}
Serial.println();
}
// LMIC library will call this method when an event is fired // LMIC library will call this method when an event is fired
void onEvent(ev_t event) { void onEvent(ev_t event) {
switch(event) { switch(event) {
case EV_JOINED: case EV_JOINED: {
#ifdef SINGLE_CHANNEL_GATEWAY #ifdef SINGLE_CHANNEL_GATEWAY
forceTxSingleChannelDr(); forceTxSingleChannelDr();
#endif #endif
break;
// Disable link check validation (automatically enabled
// during join, but because slow data rates change max TX
// size, we don't use it in this example.
if(!LORAWAN_ADR){
LMIC_setLinkCheckMode(0); // Link check problematic if not using ADR. Must be set after join
}
Serial.println(F("EV_JOINED"));
u4_t netid = 0;
devaddr_t devaddr = 0;
u1_t nwkKey[16];
u1_t artKey[16];
LMIC_getSessionKeys(&netid, &devaddr, nwkKey, artKey);
Serial.print("netid: ");
Serial.println(netid, DEC);
Serial.print("devaddr: ");
Serial.println(devaddr, HEX);
Serial.print("AppSKey: ");
for (size_t i=0; i<sizeof(artKey); ++i) {
if (i != 0)
Serial.print("-");
printHex2(artKey[i]);
}
Serial.println("");
Serial.print("NwkSKey: ");
for (size_t i=0; i<sizeof(nwkKey); ++i) {
if (i != 0)
Serial.print("-");
printHex2(nwkKey[i]);
}
Serial.println();
Preferences p;
if(p.begin("lora", false)) {
p.putUInt("netId", netid);
p.putUInt("devAddr", devaddr);
p.putBytes("nwkKey", nwkKey, sizeof(nwkKey));
p.putBytes("artKey", artKey, sizeof(artKey));
p.end();
}
break; }
case EV_TXCOMPLETE: case EV_TXCOMPLETE:
Serial.println(F("EV_TXCOMPLETE (inc. RX win. wait)")); Serial.println(F("EV_TXCOMPLETE (inc. RX win. wait)"));
if (LMIC.txrxFlags & TXRX_ACK) { if (LMIC.txrxFlags & TXRX_ACK) {
@ -132,7 +226,22 @@ void ttn_response(uint8_t * buffer, size_t len) {
} }
} }
// If the value for LORA packet counts is unknown, restore from flash
static void initCount() {
if(count == 0) {
Preferences p;
if(p.begin("lora", true)) {
count = p.getUInt("count", 0);
p.end();
}
}
}
bool ttn_setup() { bool ttn_setup() {
initCount();
initDevEUI();
// SPI interface // SPI interface
SPI.begin(SCK_GPIO, MISO_GPIO, MOSI_GPIO, NSS_GPIO); SPI.begin(SCK_GPIO, MISO_GPIO, MOSI_GPIO, NSS_GPIO);
@ -148,16 +257,6 @@ void ttn_join() {
LMIC_setClockError(MAX_CLOCK_ERROR * CLOCK_ERROR / 100); LMIC_setClockError(MAX_CLOCK_ERROR * CLOCK_ERROR / 100);
#endif #endif
#if defined(USE_ABP)
// Set static session parameters. Instead of dynamically establishing a session
// by joining the network, precomputed session parameters are be provided.
uint8_t appskey[sizeof(APPSKEY)];
uint8_t nwkskey[sizeof(NWKSKEY)];
memcpy_P(appskey, APPSKEY, sizeof(APPSKEY));
memcpy_P(nwkskey, NWKSKEY, sizeof(NWKSKEY));
LMIC_setSession(0x1, DEVADDR, nwkskey, appskey);
#if defined(CFG_eu868) #if defined(CFG_eu868)
// Set up the channels used by the Things Network, which corresponds // Set up the channels used by the Things Network, which corresponds
@ -184,6 +283,10 @@ void ttn_join() {
// but only one group of 8 should (a subband) should be active // but only one group of 8 should (a subband) should be active
// TTN recommends the second sub band, 1 in a zero based count. // TTN recommends the second sub band, 1 in a zero based count.
// https://github.com/TheThingsNetwork/gateway-conf/blob/master/US-global_conf.json // https://github.com/TheThingsNetwork/gateway-conf/blob/master/US-global_conf.json
// in the US, with TTN, it saves join time if we start on subband 1
// (channels 8-15). This will get overridden after the join by
// parameters from the network. If working with other networks or in
// other regions, this will need to be changed.
LMIC_selectSubBand(1); LMIC_selectSubBand(1);
#elif defined(CFG_au915) #elif defined(CFG_au915)
@ -202,9 +305,6 @@ void ttn_join() {
// Disable link check validation // Disable link check validation
LMIC_setLinkCheckMode(0); LMIC_setLinkCheckMode(0);
// TTN uses SF9 for its RX2 window.
LMIC.dn2Dr = DR_SF9;
#ifdef SINGLE_CHANNEL_GATEWAY #ifdef SINGLE_CHANNEL_GATEWAY
forceTxSingleChannelDr(); forceTxSingleChannelDr();
#else #else
@ -212,6 +312,19 @@ void ttn_join() {
ttn_sf(LORAWAN_SF); ttn_sf(LORAWAN_SF);
#endif #endif
#if defined(USE_ABP)
// Set static session parameters. Instead of dynamically establishing a session
// by joining the network, precomputed session parameters are be provided.
uint8_t appskey[sizeof(APPSKEY)];
uint8_t nwkskey[sizeof(NWKSKEY)];
memcpy_P(appskey, APPSKEY, sizeof(APPSKEY));
memcpy_P(nwkskey, NWKSKEY, sizeof(NWKSKEY));
LMIC_setSession(0x1, DEVADDR, nwkskey, appskey);
// TTN uses SF9 for its RX2 window.
LMIC.dn2Dr = DR_SF9;
// Trigger a false joined // Trigger a false joined
_ttn_callback(EV_JOINED); _ttn_callback(EV_JOINED);
@ -227,6 +340,30 @@ void ttn_join() {
LMIC.txChnl = SINGLE_CHANNEL_GATEWAY; LMIC.txChnl = SINGLE_CHANNEL_GATEWAY;
#endif #endif
Preferences p;
p.begin("lora", true); // we intentionally ignore failure here
uint32_t netId = p.getUInt("netId", UINT32_MAX);
uint32_t devAddr = p.getUInt("devAddr", UINT32_MAX);
uint8_t nwkKey[16], artKey[16];
bool keysgood = p.getBytes("nwkKey", nwkKey, sizeof(nwkKey)) == sizeof(nwkKey) &&
p.getBytes("artKey", artKey, sizeof(artKey)) == sizeof(artKey);
p.end(); // close our prefs
if(!keysgood) {
// We have not yet joined a network, start a full join attempt
// Make LMiC initialize the default channels, choose a channel, and
// schedule the OTAA join
Serial.println("No session saved, joining from scratch");
LMIC_startJoining();
}
else {
Serial.println("Rejoining saved session");
LMIC_setSession(netId, devAddr, nwkKey, artKey);
// Trigger a false joined
_ttn_callback(EV_JOINED);
}
#endif #endif
} }
@ -239,11 +376,41 @@ void ttn_adr(bool enabled) {
LMIC_setLinkCheckMode(!enabled); LMIC_setLinkCheckMode(!enabled);
} }
void ttn_cnt(uint32_t num) { uint32_t ttn_get_count() {
LMIC_setSeqnoUp(num); return count;
}
static void ttn_set_cnt() {
LMIC_setSeqnoUp(count);
// We occasionally mirror our count to flash, to ensure that if we lose power we will at least start with a count that is almost correct
// (otherwise the TNN network will discard packets until count once again reaches the value they've seen). We limit these writes to a max rate
// of one write every 5 minutes. Which should let the FLASH last for 300 years (given the ESP32 NVS algoritm)
static uint32_t lastWriteMsec = UINT32_MAX; // Ensure we write at least once
uint32_t now = millis();
if(now < lastWriteMsec || (now - lastWriteMsec) > 5 * 60 * 1000L) { // write if we roll over (50 days) or 5 mins
lastWriteMsec = now;
Preferences p;
if(p.begin("lora", false)) {
p.putUInt("count", count);
p.end();
}
}
}
/// Blow away our prefs (i.e. to rejoin from scratch)
void ttn_erase_prefs() {
Preferences p;
if(p.begin("lora", false)) {
p.clear();
p.end();
}
} }
void ttn_send(uint8_t * data, uint8_t data_size, uint8_t port, bool confirmed){ void ttn_send(uint8_t * data, uint8_t data_size, uint8_t port, bool confirmed){
ttn_set_cnt(); // we are about to send using the current packet count
// Check if there is not a current TX/RX job running // Check if there is not a current TX/RX job running
if (LMIC.opmode & OP_TXRXPEND) { if (LMIC.opmode & OP_TXRXPEND) {
_ttn_callback(EV_PENDING); _ttn_callback(EV_PENDING);
@ -255,6 +422,7 @@ void ttn_send(uint8_t * data, uint8_t data_size, uint8_t port, bool confirmed){
LMIC_setTxData2(port, data, data_size, confirmed ? 1 : 0); LMIC_setTxData2(port, data, data_size, confirmed ? 1 : 0);
_ttn_callback(EV_QUEUED); _ttn_callback(EV_QUEUED);
count++;
} }
void ttn_loop() { void ttn_loop() {

31
platformio.ini Normal file
View File

@ -0,0 +1,31 @@
; PlatformIO Project Configuration File
;
; Build options: build flags, source filter
; Upload options: custom upload port, speed and extra flags
; Library options: dependencies, extra library storages
; Advanced options: extra scripting
;
; Please visit documentation for the other options and examples
; https://docs.platformio.org/page/projectconf.html
[platformio]
src_dir = main
[env:esp32]
platform = espressif32
board = ttgo-t-beam
framework = arduino
; note: we add src to our include search path so that lmic_project_config can override
build_flags = -Wall -Wextra -Wno-missing-field-initializers -O3 -Wl,-Map,.pio/build/esp32/output.map -D CFG_us915 -D CFG_sx1276_radio
; -DLOG_LOCAL_LEVEL=ESP_LOG_DEBUG -DCORE_DEBUG_LEVEL=ARDUHAL_LOG_LEVEL_DEBUG
monitor_speed = 115200
lib_deps =
https://github.com/mcci-catena/arduino-lmic
TinyGPSPlus
ESP8266_SSD1306
AXP202X_Library
SPI