From c7f6071f703146711433b428b14a2b6c48c6d5de Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Tue, 28 Nov 2023 20:40:51 -0600 Subject: [PATCH 001/472] Enable IO2 toggling on RAK if the coast is clear (#2968) * Enable IO2 toggling on RAK if the coast is clear * Guard against monteops target which doesn't use 3V3 pin * Also check for en_gpio = 0 to avoid re-setting the value --- src/gps/GPS.cpp | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index af622e3d8..11c16ede9 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -264,6 +264,20 @@ bool GPS::setup() isProblematicGPS = true; } #endif + +#if defined(RAK4630) && defined(PIN_3V3_EN) + // If we are using the RAK4630 and we have no other peripherals on the I2C bus or module interest in 3V3_S, + // then we can safely set en_gpio turn off power to 3V3 (IO2) to hard sleep the GPS + if (rtc_found.port == ScanI2C::DeviceType::NONE && rgb_found.type == ScanI2C::DeviceType::NONE && + accelerometer_found.port == ScanI2C::DeviceType::NONE && !moduleConfig.detection_sensor.enabled && + !moduleConfig.telemetry.air_quality_enabled && !moduleConfig.telemetry.environment_measurement_enabled && + config.power.device_battery_ina_address == 0 && en_gpio == 0) { + LOG_DEBUG("Since no problematic peripherals or interested modules were found, setting power save GPS_EN to pin %i\n", + PIN_3V3_EN); + en_gpio = PIN_3V3_EN; + } +#endif + if (tx_gpio && gnssModel == GNSS_MODEL_UNKNOWN) { LOG_DEBUG("Probing for GPS at %d \n", serialSpeeds[speedSelect]); gnssModel = probe(serialSpeeds[speedSelect]); @@ -436,6 +450,7 @@ bool GPS::setup() notifyDeepSleepObserver.observe(¬ifyDeepSleep); notifyGPSSleepObserver.observe(¬ifyGPSSleep); + return true; } From 18cf8ca4fa61483bb6cb25874be94f2bd0ed082c Mon Sep 17 00:00:00 2001 From: S5NC <145265251+S5NC@users.noreply.github.com> Date: Wed, 29 Nov 2023 21:51:05 +0000 Subject: [PATCH 002/472] Generalise SPI pin names (#2970) * Generalise SPI pin names * CS not NSS * trunk fmt * Update variant.h --------- Co-authored-by: Ben Meadors --- src/main.cpp | 22 ++++++------- src/platform/esp32/architecture.h | 10 +++--- src/platform/portduino/PortduinoGlue.cpp | 2 +- variants/ai-c3/variant.h | 10 +++--- variants/betafpv_2400_tx_micro/variant.h | 8 ++--- variants/betafpv_900_tx_nano/variant.h | 8 ++--- variants/bpi_picow_esp32_s3/variant.h | 28 ++++++++--------- variants/diy/dr-dev/variant.h | 20 ++++++------ variants/diy/hydra/variant.h | 8 ++--- variants/diy/v1/variant.h | 8 ++--- variants/diy/v1_1/variant.h | 16 +++++----- variants/feather_diy/variant.h | 10 +++--- variants/heltec_esp32c3/variant.h | 18 +++++------ variants/heltec_v3/variant.h | 10 +++--- variants/heltec_wireless_paper/variant.h | 10 +++--- variants/heltec_wireless_tracker/variant.h | 10 +++--- variants/heltec_wsl_v3/variant.h | 10 +++--- variants/m5stack-stamp-c3/variant.h | 36 +++++++++++----------- variants/m5stack_core/variant.h | 16 +++++----- variants/m5stack_coreink/variant.h | 26 ++++++++-------- variants/my_esp32s3_diy_eink/variant.h | 12 ++++---- variants/my_esp32s3_diy_oled/variant.h | 12 ++++---- variants/nano-g1-explorer/variant.h | 2 +- variants/nano-g1/variant.h | 2 +- variants/picomputer-s3/variant.h | 8 ++--- variants/portduino/variant.h | 8 ++--- variants/rak11200/variant.h | 16 +++++----- variants/rak11310/variant.h | 18 +++++------ variants/rpipico/variant.h | 18 +++++------ variants/rpipicow/variant.h | 18 +++++------ variants/station-g1/variant.h | 2 +- variants/t-deck/variant.h | 10 +++--- variants/t-watch-s3/variant.h | 10 +++--- variants/tbeam-s3-core/variant.h | 8 ++--- variants/tbeam/variant.h | 2 +- variants/tlora_t3s3_v1/variant.h | 12 ++++---- 36 files changed, 222 insertions(+), 222 deletions(-) diff --git a/src/main.cpp b/src/main.cpp index cfd6279e0..4913f1091 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -628,24 +628,24 @@ void setup() initSPI(); #ifdef ARCH_RP2040 #ifdef HW_SPI1_DEVICE - SPI1.setSCK(RF95_SCK); - SPI1.setTX(RF95_MOSI); - SPI1.setRX(RF95_MISO); - pinMode(RF95_NSS, OUTPUT); - digitalWrite(RF95_NSS, HIGH); + SPI1.setSCK(LORA_SCK); + SPI1.setTX(LORA_MOSI); + SPI1.setRX(LORA_MISO); + pinMode(LORA_CS, OUTPUT); + digitalWrite(LORA_CS, HIGH); SPI1.begin(false); #else // HW_SPI1_DEVICE - SPI.setSCK(RF95_SCK); - SPI.setTX(RF95_MOSI); - SPI.setRX(RF95_MISO); + SPI.setSCK(LORA_SCK); + SPI.setTX(LORA_MOSI); + SPI.setRX(LORA_MISO); SPI.begin(false); #endif // HW_SPI1_DEVICE #elif !defined(ARCH_ESP32) // ARCH_RP2040 SPI.begin(); #else // ESP32 - SPI.begin(RF95_SCK, RF95_MISO, RF95_MOSI, RF95_NSS); - LOG_WARN("SPI.begin(SCK=%d, MISO=%d, MOSI=%d, NSS=%d)\n", RF95_SCK, RF95_MISO, RF95_MOSI, RF95_NSS); + SPI.begin(LORA_SCK, LORA_MISO, LORA_MOSI, LORA_CS); + LOG_WARN("SPI.begin(SCK=%d, MISO=%d, MOSI=%d, NSS=%d)\n", LORA_SCK, LORA_MISO, LORA_MOSI, LORA_CS); SPI.setFrequency(4000000); #endif @@ -755,7 +755,7 @@ void setup() #if defined(RF95_IRQ) if (!rIf) { - rIf = new RF95Interface(RadioLibHAL, RF95_NSS, RF95_IRQ, RF95_RESET, RF95_DIO1); + rIf = new RF95Interface(RadioLibHAL, LORA_CS, RF95_IRQ, RF95_RESET, RF95_DIO1); if (!rIf->init()) { LOG_WARN("Failed to find RF95 radio\n"); delete rIf; diff --git a/src/platform/esp32/architecture.h b/src/platform/esp32/architecture.h index 163cc8b84..781d41678 100644 --- a/src/platform/esp32/architecture.h +++ b/src/platform/esp32/architecture.h @@ -128,11 +128,11 @@ // ----------------------------------------------------------------------------- // NRF52 boards will define this in variant.h -#ifndef RF95_SCK -#define RF95_SCK 5 -#define RF95_MISO 19 -#define RF95_MOSI 27 -#define RF95_NSS 18 +#ifndef LORA_SCK +#define LORA_SCK 5 +#define LORA_MISO 19 +#define LORA_MOSI 27 +#define LORA_CS 18 #endif #define SERIAL0_RX_GPIO 3 // Always GPIO3 on ESP32 \ No newline at end of file diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index 2e402c0a0..d2a00e1e1 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -192,6 +192,6 @@ void portduinoSetup() gpioBind(new SimGPIOPin(LORA_DIO1, "fakeLoraIrq")); } // gpioBind((new SimGPIOPin(LORA_RESET, "LORA_RESET"))); - // gpioBind((new SimGPIOPin(RF95_NSS, "RF95_NSS"))->setSilent()); + // gpioBind((new SimGPIOPin(LORA_CS, "LORA_CS"))->setSilent()); #endif } \ No newline at end of file diff --git a/variants/ai-c3/variant.h b/variants/ai-c3/variant.h index 254f5fd36..6c4f4d38a 100644 --- a/variants/ai-c3/variant.h +++ b/variants/ai-c3/variant.h @@ -7,10 +7,10 @@ #define LED_PIN 30 // RGB LED #define USE_RF95 -#define RF95_SCK 4 -#define RF95_MISO 5 -#define RF95_MOSI 6 -#define RF95_NSS 7 +#define LORA_SCK 4 +#define LORA_MISO 5 +#define LORA_MOSI 6 +#define LORA_CS 7 #define LORA_DIO0 10 #define LORA_DIO1 3 @@ -19,7 +19,7 @@ // WaveShare Core1262-868M // https://www.waveshare.com/wiki/Core1262-868M #define USE_SX1262 -#define SX126X_CS RF95_NSS +#define SX126X_CS LORA_CS #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY 10 #define SX126X_RESET LORA_RESET diff --git a/variants/betafpv_2400_tx_micro/variant.h b/variants/betafpv_2400_tx_micro/variant.h index 2a8b2f40c..8c615d168 100644 --- a/variants/betafpv_2400_tx_micro/variant.h +++ b/variants/betafpv_2400_tx_micro/variant.h @@ -9,10 +9,10 @@ #undef GPS_RX_PIN #undef GPS_TX_PIN -#define RF95_SCK 18 -#define RF95_MISO 19 -#define RF95_MOSI 23 -#define RF95_NSS 5 +#define LORA_SCK 18 +#define LORA_MISO 19 +#define LORA_MOSI 23 +#define LORA_CS 5 #define RF95_FAN_EN 17 #define LED_PIN 16 // This is a LED_WS2812 not a standard LED diff --git a/variants/betafpv_900_tx_nano/variant.h b/variants/betafpv_900_tx_nano/variant.h index 01961d92d..7a4ae9190 100644 --- a/variants/betafpv_900_tx_nano/variant.h +++ b/variants/betafpv_900_tx_nano/variant.h @@ -9,10 +9,10 @@ #define USE_RF95 -#define RF95_SCK 18 -#define RF95_MISO 19 -#define RF95_MOSI 23 -#define RF95_NSS 5 +#define LORA_SCK 18 +#define LORA_MISO 19 +#define LORA_MOSI 23 +#define LORA_CS 5 #define LORA_DIO0 4 #define LORA_RESET 14 diff --git a/variants/bpi_picow_esp32_s3/variant.h b/variants/bpi_picow_esp32_s3/variant.h index 8114b9ea3..d8d9413d7 100644 --- a/variants/bpi_picow_esp32_s3/variant.h +++ b/variants/bpi_picow_esp32_s3/variant.h @@ -22,24 +22,24 @@ // #define USE_RF95 // RFM95/SX127x -#undef RF95_SCK -#undef RF95_MISO -#undef RF95_MOSI -#undef RF95_NSS +#undef LORA_SCK +#undef LORA_MISO +#undef LORA_MOSI +#undef LORA_CS // WaveShare Core1262-868M OK // https://www.waveshare.com/wiki/Core1262-868M #define USE_SX1262 #ifdef USE_SX1262 -#define RF95_MISO 39 -#define RF95_SCK 21 -#define RF95_MOSI 38 -#define RF95_NSS 17 +#define LORA_MISO 39 +#define LORA_SCK 21 +#define LORA_MOSI 38 +#define LORA_CS 17 #define LORA_RESET 42 #define LORA_DIO1 5 #define LORA_BUSY 47 -#define SX126X_CS RF95_NSS +#define SX126X_CS LORA_CS #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY LORA_BUSY #define SX126X_RESET LORA_RESET @@ -49,14 +49,14 @@ // #define USE_SX1280 #ifdef USE_SX1280 -#define RF95_MISO 1 -#define RF95_SCK 3 -#define RF95_MOSI 4 -#define RF95_NSS 2 +#define LORA_MISO 1 +#define LORA_SCK 3 +#define LORA_MOSI 4 +#define LORA_CS 2 #define LORA_RESET 17 #define LORA_DIO1 12 #define LORA_BUSY 47 -#define SX128X_CS RF95_NSS +#define SX128X_CS LORA_CS #define SX128X_DIO1 LORA_DIO1 #define SX128X_BUSY LORA_BUSY #define SX128X_RESET LORA_RESET diff --git a/variants/diy/dr-dev/variant.h b/variants/diy/dr-dev/variant.h index 08d57eec9..35b18ee74 100644 --- a/variants/diy/dr-dev/variant.h +++ b/variants/diy/dr-dev/variant.h @@ -22,12 +22,12 @@ // In receiving, set RXEN as high communication level, TXEN is lowlevel; // Before powering off, set TXEN、RXEN as low level. -#undef RF95_SCK -#define RF95_SCK 18 -#undef RF95_MISO -#define RF95_MISO 19 -#undef RF95_MOSI -#define RF95_MOSI 23 +#undef LORA_SCK +#define LORA_SCK 18 +#undef LORA_MISO +#define LORA_MISO 19 +#undef LORA_MOSI +#define LORA_MOSI 23 // PINS FOR THE 900M22S @@ -38,8 +38,8 @@ // E22_TXEN_CONNECTED_TO_DIO2 wasn't defined, so RXEN wasn't controlled. Commented it out to maintain behavior, but shouldn't be. // Need to comment out defining SX126X_RXEN as LORA_RXEN too // #define LORA_RXEN 17 // Input - RF switch RX control, connecting external MCU IO, valid in high level -#undef RF95_NSS -#define RF95_NSS 16 +#undef LORA_CS +#define LORA_CS 16 #define SX126X_BUSY 22 #define SX126X_CS 16 @@ -49,8 +49,8 @@ #define LORA_DIO2 35 // BUSY for SX1262/SX1268 #define LORA_TXEN NOT_A_PIN // Input - RF switch TX control, connecting external MCU IO or DIO2, valid in high level #define LORA_RXEN 21 // Input - RF switch RX control, connecting external MCU IO, valid in high level -#undef RF95_NSS -#define RF95_NSS 33 +#undef LORA_CS +#define LORA_CS 33 #define SX126X_BUSY 35 #define SX126X_CS 33 */ diff --git a/variants/diy/hydra/variant.h b/variants/diy/hydra/variant.h index 64bdd73f7..a51b21653 100644 --- a/variants/diy/hydra/variant.h +++ b/variants/diy/hydra/variant.h @@ -33,8 +33,8 @@ #define SX126X_TXEN 13 // Schematic connects EBYTE module's TXEN pin to MCU #define SX126X_RXEN 14 // Schematic connects EBYTE module's RXEN pin to MCU -#define RF95_NSS SX126X_CS // Compatibility with variant file configuration structure -#define RF95_SCK SX126X_SCK // Compatibility with variant file configuration structure -#define RF95_MOSI SX126X_MOSI // Compatibility with variant file configuration structure -#define RF95_MISO SX126X_MISO // Compatibility with variant file configuration structure +#define LORA_CS SX126X_CS // Compatibility with variant file configuration structure +#define LORA_SCK SX126X_SCK // Compatibility with variant file configuration structure +#define LORA_MOSI SX126X_MOSI // Compatibility with variant file configuration structure +#define LORA_MISO SX126X_MISO // Compatibility with variant file configuration structure #define LORA_DIO1 SX126X_DIO1 // Compatibility with variant file configuration structure diff --git a/variants/diy/v1/variant.h b/variants/diy/v1/variant.h index 48906515b..4802dbe89 100644 --- a/variants/diy/v1/variant.h +++ b/variants/diy/v1/variant.h @@ -23,10 +23,10 @@ #define LORA_DIO2 32 // BUSY for SX1262/SX1268 #define LORA_DIO3 // Not connected on PCB, but internally on the TTGO SX1262/SX1268, if DIO3 is high the TXCO is enabled -#define RF95_SCK 5 -#define RF95_MISO 19 -#define RF95_MOSI 27 -#define RF95_NSS 18 +#define LORA_SCK 5 +#define LORA_MISO 19 +#define LORA_MOSI 27 +#define LORA_CS 18 // supported modules list #define USE_RF95 // RFM95/SX127x diff --git a/variants/diy/v1_1/variant.h b/variants/diy/v1_1/variant.h index fd5276ced..8a006d0d2 100644 --- a/variants/diy/v1_1/variant.h +++ b/variants/diy/v1_1/variant.h @@ -22,14 +22,14 @@ #define LORA_RXEN 14 // Input - RF switch RX control, connecting external MCU IO, valid in high level #define LORA_TXEN 13 // Input - RF switch TX control, connecting external MCU IO or DIO2, valid in high level -#undef RF95_SCK -#define RF95_SCK 18 -#undef RF95_MISO -#define RF95_MISO 19 -#undef RF95_MOSI -#define RF95_MOSI 23 -#undef RF95_NSS -#define RF95_NSS 5 +#undef LORA_SCK +#define LORA_SCK 18 +#undef LORA_MISO +#define LORA_MISO 19 +#undef LORA_MOSI +#define LORA_MOSI 23 +#undef LORA_CS +#define LORA_CS 5 // RX/TX for RFM95/SX127x #define RF95_RXEN LORA_RXEN diff --git a/variants/feather_diy/variant.h b/variants/feather_diy/variant.h index 5e889b04e..1c0979f82 100644 --- a/variants/feather_diy/variant.h +++ b/variants/feather_diy/variant.h @@ -81,10 +81,10 @@ extern "C" { #define LORA_DIO2 (0 + 8) // P0.08 12 // BUSY for SX1262/SX1268 #define LORA_DIO3 // Not connected on PCB, but internally on the TTGO SX1262/SX1268, if DIO3 is high the TXCO is enabled -#define RF95_SCK SCK -#define RF95_MISO MI -#define RF95_MOSI MO -#define RF95_NSS SS +#define LORA_SCK SCK +#define LORA_MISO MI +#define LORA_MOSI MO +#define LORA_CS SS // enables 3.3V periphery like GPS or IO Module #define PIN_3V3_EN (-1) @@ -95,7 +95,7 @@ extern "C" { #define USE_SX1262 // common pinouts for SX126X modules -#define SX126X_CS RF95_NSS // NSS for SX126X +#define SX126X_CS LORA_CS // NSS for SX126X #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY LORA_DIO2 #define SX126X_RESET LORA_RESET diff --git a/variants/heltec_esp32c3/variant.h b/variants/heltec_esp32c3/variant.h index 7d113720d..de6462a38 100644 --- a/variants/heltec_esp32c3/variant.h +++ b/variants/heltec_esp32c3/variant.h @@ -14,22 +14,22 @@ #undef GPS_RX_PIN #undef GPS_TX_PIN -#undef RF95_SCK -#undef RF95_MISO -#undef RF95_MOSI -#undef RF95_NSS +#undef LORA_SCK +#undef LORA_MISO +#undef LORA_MOSI +#undef LORA_CS #define USE_SX1262 -#define RF95_SCK 10 -#define RF95_MISO 6 -#define RF95_MOSI 7 -#define RF95_NSS 8 +#define LORA_SCK 10 +#define LORA_MISO 6 +#define LORA_MOSI 7 +#define LORA_CS 8 #define LORA_DIO0 RADIOLIB_NC #define LORA_RESET 5 #define LORA_DIO1 3 #define LORA_DIO2 RADIOLIB_NC #define LORA_BUSY 4 -#define SX126X_CS RF95_NSS +#define SX126X_CS LORA_CS #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY LORA_BUSY #define SX126X_RESET LORA_RESET diff --git a/variants/heltec_v3/variant.h b/variants/heltec_v3/variant.h index 4ce47996b..2532ea682 100644 --- a/variants/heltec_v3/variant.h +++ b/variants/heltec_v3/variant.h @@ -24,12 +24,12 @@ #define LORA_DIO2 13 // SX1262 BUSY #define LORA_DIO3 // Not connected on PCB, but internally on the TTGO SX1262, if DIO3 is high the TXCO is enabled -#define RF95_SCK 9 -#define RF95_MISO 11 -#define RF95_MOSI 10 -#define RF95_NSS 8 +#define LORA_SCK 9 +#define LORA_MISO 11 +#define LORA_MOSI 10 +#define LORA_CS 8 -#define SX126X_CS RF95_NSS +#define SX126X_CS LORA_CS #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY LORA_DIO2 #define SX126X_RESET LORA_RESET diff --git a/variants/heltec_wireless_paper/variant.h b/variants/heltec_wireless_paper/variant.h index b73596f50..88c5faaa1 100644 --- a/variants/heltec_wireless_paper/variant.h +++ b/variants/heltec_wireless_paper/variant.h @@ -31,12 +31,12 @@ #define LORA_DIO2 13 // SX1262 BUSY #define LORA_DIO3 // Not connected on PCB, but internally on the TTGO SX1262, if DIO3 is high the TXCO is enabled -#define RF95_SCK 9 -#define RF95_MISO 11 -#define RF95_MOSI 10 -#define RF95_NSS 8 +#define LORA_SCK 9 +#define LORA_MISO 11 +#define LORA_MOSI 10 +#define LORA_CS 8 -#define SX126X_CS RF95_NSS +#define SX126X_CS LORA_CS #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY LORA_DIO2 #define SX126X_RESET LORA_RESET diff --git a/variants/heltec_wireless_tracker/variant.h b/variants/heltec_wireless_tracker/variant.h index 4a1b61038..88b4804a1 100644 --- a/variants/heltec_wireless_tracker/variant.h +++ b/variants/heltec_wireless_tracker/variant.h @@ -58,12 +58,12 @@ #define LORA_DIO2 13 // SX1262 BUSY #define LORA_DIO3 // Not connected on PCB, but internally on the TTGO SX1262, if DIO3 is high the TXCO is enabled -#define RF95_SCK 9 -#define RF95_MISO 11 -#define RF95_MOSI 10 -#define RF95_NSS 8 +#define LORA_SCK 9 +#define LORA_MISO 11 +#define LORA_MOSI 10 +#define LORA_CS 8 -#define SX126X_CS RF95_NSS +#define SX126X_CS LORA_CS #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY LORA_DIO2 #define SX126X_RESET LORA_RESET diff --git a/variants/heltec_wsl_v3/variant.h b/variants/heltec_wsl_v3/variant.h index 417abf34d..0ad1b8487 100644 --- a/variants/heltec_wsl_v3/variant.h +++ b/variants/heltec_wsl_v3/variant.h @@ -21,12 +21,12 @@ #define LORA_DIO2 13 // SX1262 BUSY #define LORA_DIO3 // Not connected on PCB, but internally on the TTGO SX1262, if DIO3 is high the TXCO is enabled -#define RF95_SCK 9 -#define RF95_MISO 11 -#define RF95_MOSI 10 -#define RF95_NSS 8 +#define LORA_SCK 9 +#define LORA_MISO 11 +#define LORA_MOSI 10 +#define LORA_CS 8 -#define SX126X_CS RF95_NSS +#define SX126X_CS LORA_CS #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY LORA_DIO2 #define SX126X_RESET LORA_RESET diff --git a/variants/m5stack-stamp-c3/variant.h b/variants/m5stack-stamp-c3/variant.h index 87adbc226..8242ef499 100644 --- a/variants/m5stack-stamp-c3/variant.h +++ b/variants/m5stack-stamp-c3/variant.h @@ -9,18 +9,18 @@ #undef GPS_RX_PIN #undef GPS_TX_PIN -#undef RF95_SCK -#undef RF95_MISO -#undef RF95_MOSI -#undef RF95_NSS +#undef LORA_SCK +#undef LORA_MISO +#undef LORA_MOSI +#undef LORA_CS // Adafruit RFM95W OK // https://www.adafruit.com/product/3072 #define USE_RF95 -#define RF95_SCK 4 -#define RF95_MISO 5 -#define RF95_MOSI 6 -#define RF95_NSS 7 +#define LORA_SCK 4 +#define LORA_MISO 5 +#define LORA_MOSI 6 +#define LORA_CS 7 #define LORA_DIO0 10 #define LORA_RESET 8 #define LORA_DIO1 RADIOLIB_NC @@ -29,16 +29,16 @@ // WaveShare Core1262-868M OK // https://www.waveshare.com/wiki/Core1262-868M // #define USE_SX1262 -// #define RF95_SCK 4 -// #define RF95_MISO 5 -// #define RF95_MOSI 6 -// #define RF95_NSS 7 +// #define LORA_SCK 4 +// #define LORA_MISO 5 +// #define LORA_MOSI 6 +// #define LORA_CS 7 // #define LORA_DIO0 RADIOLIB_NC // #define LORA_RESET 8 // #define LORA_DIO1 10 // #define LORA_DIO2 RADIOLIB_NC // #define LORA_BUSY 18 -// #define SX126X_CS RF95_NSS +// #define SX126X_CS LORA_CS // #define SX126X_DIO1 LORA_DIO1 // #define SX126X_BUSY LORA_BUSY // #define SX126X_RESET LORA_RESET @@ -47,16 +47,16 @@ // SX128X 2.4 Ghz LoRa module Not OK - RadioLib issue ? still to confirm // #define USE_SX1280 -// #define RF95_SCK 4 -// #define RF95_MISO 5 -// #define RF95_MOSI 6 -// #define RF95_NSS 7 +// #define LORA_SCK 4 +// #define LORA_MISO 5 +// #define LORA_MOSI 6 +// #define LORA_CS 7 // #define LORA_DIO0 -1 // #define LORA_DIO1 10 // #define LORA_DIO2 21 // #define LORA_RESET 8 // #define LORA_BUSY 1 -// #define SX128X_CS RF95_NSS +// #define SX128X_CS LORA_CS // #define SX128X_DIO1 LORA_DIO1 // #define SX128X_BUSY LORA_BUSY // #define SX128X_RESET LORA_RESET diff --git a/variants/m5stack_core/variant.h b/variants/m5stack_core/variant.h index c671d77fa..72aeb160e 100644 --- a/variants/m5stack_core/variant.h +++ b/variants/m5stack_core/variant.h @@ -12,15 +12,15 @@ #define PIN_BUZZER 25 -#undef RF95_SCK -#undef RF95_MISO -#undef RF95_MOSI -#undef RF95_NSS +#undef LORA_SCK +#undef LORA_MISO +#undef LORA_MOSI +#undef LORA_CS -#define RF95_SCK 18 -#define RF95_MISO 19 -#define RF95_MOSI 23 -#define RF95_NSS 5 +#define LORA_SCK 18 +#define LORA_MISO 19 +#define LORA_MOSI 23 +#define LORA_CS 5 #define USE_RF95 #define LORA_DIO0 36 // a No connect on the SX1262 module diff --git a/variants/m5stack_coreink/variant.h b/variants/m5stack_coreink/variant.h index 90ce41334..0fc56477c 100644 --- a/variants/m5stack_coreink/variant.h +++ b/variants/m5stack_coreink/variant.h @@ -34,18 +34,18 @@ // BUZZER #define PIN_BUZZER 2 -#undef RF95_SCK -#undef RF95_MISO -#undef RF95_MOSI -#undef RF95_NSS +#undef LORA_SCK +#undef LORA_MISO +#undef LORA_MOSI +#undef LORA_CS #define USE_RF95 // #define USE_SX1280 #ifdef USE_RF95 -#define RF95_SCK 18 -#define RF95_MISO 34 -#define RF95_MOSI 23 -#define RF95_NSS 14 +#define LORA_SCK 18 +#define LORA_MISO 34 +#define LORA_MOSI 23 +#define LORA_CS 14 #define LORA_DIO0 25 #define LORA_RESET 26 #define LORA_DIO1 RADIOLIB_NC @@ -53,14 +53,14 @@ #endif #ifdef USE_SX1280 -#define RF95_SCK 18 -#define RF95_MISO 34 -#define RF95_MOSI 23 -#define RF95_NSS 14 +#define LORA_SCK 18 +#define LORA_MISO 34 +#define LORA_MOSI 23 +#define LORA_CS 14 #define LORA_RESET 26 #define LORA_DIO1 25 #define LORA_DIO2 13 -#define SX128X_CS RF95_NSS +#define SX128X_CS LORA_CS #define SX128X_DIO1 LORA_DIO1 #define SX128X_BUSY LORA_DIO2 #define SX128X_RESET LORA_RESET diff --git a/variants/my_esp32s3_diy_eink/variant.h b/variants/my_esp32s3_diy_eink/variant.h index 7e4fe2756..a5bebdacc 100644 --- a/variants/my_esp32s3_diy_eink/variant.h +++ b/variants/my_esp32s3_diy_eink/variant.h @@ -20,16 +20,16 @@ // #define USE_SX1262 #define USE_SX1280 -#define RF95_MISO 3 -#define RF95_SCK 5 -#define RF95_MOSI 6 -#define RF95_NSS 7 +#define LORA_MISO 3 +#define LORA_SCK 5 +#define LORA_MOSI 6 +#define LORA_CS 7 #define LORA_RESET 8 #define LORA_DIO1 16 #ifdef USE_SX1262 -#define SX126X_CS RF95_NSS // FIXME - we really should define LORA_CS instead +#define SX126X_CS LORA_CS // FIXME - we really should define LORA_CS instead #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY 15 #define SX126X_RESET LORA_RESET @@ -38,7 +38,7 @@ #endif #ifdef USE_SX1280 -#define SX128X_CS RF95_NSS +#define SX128X_CS LORA_CS #define SX128X_DIO1 LORA_DIO1 #define SX128X_BUSY 15 #define SX128X_RESET LORA_RESET diff --git a/variants/my_esp32s3_diy_oled/variant.h b/variants/my_esp32s3_diy_oled/variant.h index bb9657c5b..6dd18c236 100644 --- a/variants/my_esp32s3_diy_oled/variant.h +++ b/variants/my_esp32s3_diy_oled/variant.h @@ -20,16 +20,16 @@ // #define USE_SX1262 #define USE_SX1280 -#define RF95_MISO 3 -#define RF95_SCK 5 -#define RF95_MOSI 6 -#define RF95_NSS 7 +#define LORA_MISO 3 +#define LORA_SCK 5 +#define LORA_MOSI 6 +#define LORA_CS 7 #define LORA_RESET 8 #define LORA_DIO1 16 #ifdef USE_SX1262 -#define SX126X_CS RF95_NSS // FIXME - we really should define LORA_CS instead +#define SX126X_CS LORA_CS // FIXME - we really should define LORA_CS instead #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY 15 #define SX126X_RESET LORA_RESET @@ -38,7 +38,7 @@ #endif #ifdef USE_SX1280 -#define SX128X_CS RF95_NSS +#define SX128X_CS LORA_CS #define SX128X_DIO1 LORA_DIO1 #define SX128X_BUSY 15 #define SX128X_RESET LORA_RESET diff --git a/variants/nano-g1-explorer/variant.h b/variants/nano-g1-explorer/variant.h index 71dd49f05..3d5d71acc 100644 --- a/variants/nano-g1-explorer/variant.h +++ b/variants/nano-g1-explorer/variant.h @@ -23,7 +23,7 @@ #define LORA_DIO3 // Not connected on PCB #ifdef USE_SX1262 -#define SX126X_CS RF95_NSS // FIXME - we really should define LORA_CS instead +#define SX126X_CS LORA_CS // FIXME - we really should define LORA_CS instead #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY LORA_DIO2 #define SX126X_RESET LORA_RESET diff --git a/variants/nano-g1/variant.h b/variants/nano-g1/variant.h index 5ceb96f0c..dd8355492 100644 --- a/variants/nano-g1/variant.h +++ b/variants/nano-g1/variant.h @@ -23,7 +23,7 @@ #define LORA_DIO3 // Not connected on PCB #ifdef USE_SX1262 -#define SX126X_CS RF95_NSS // FIXME - we really should define LORA_CS instead +#define SX126X_CS LORA_CS // FIXME - we really should define LORA_CS instead #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY LORA_DIO2 #define SX126X_RESET LORA_RESET diff --git a/variants/picomputer-s3/variant.h b/variants/picomputer-s3/variant.h index 732be4bcf..fc746c599 100644 --- a/variants/picomputer-s3/variant.h +++ b/variants/picomputer-s3/variant.h @@ -15,10 +15,10 @@ #define USE_RF95 // RFM95/SX127x -#define RF95_SCK SCK // 21 -#define RF95_MISO MISO // 39 -#define RF95_MOSI MOSI // 38 -#define RF95_NSS SS // 40 +#define LORA_SCK SCK // 21 +#define LORA_MISO MISO // 39 +#define LORA_MOSI MOSI // 38 +#define LORA_CS SS // 40 #define LORA_RESET RADIOLIB_NC // per SX1276_Receive_Interrupt/utilities.h diff --git a/variants/portduino/variant.h b/variants/portduino/variant.h index 46f7d1f0c..8e1c0b1f2 100644 --- a/variants/portduino/variant.h +++ b/variants/portduino/variant.h @@ -9,10 +9,10 @@ #define USE_SX1262 // Fake SPI device selections -#define RF95_SCK 5 -#define RF95_MISO 19 -#define RF95_MOSI 27 -#define RF95_NSS RADIOLIB_NC // the ch341f spi controller does CS for us +#define LORA_SCK 5 +#define LORA_MISO 19 +#define LORA_MOSI 27 +#define LORA_CS RADIOLIB_NC // the ch341f spi controller does CS for us #define LORA_DIO0 26 // a No connect on the SX1262 module #define LORA_RESET 14 diff --git a/variants/rak11200/variant.h b/variants/rak11200/variant.h index b6d9c4229..007ed8f15 100644 --- a/variants/rak11200/variant.h +++ b/variants/rak11200/variant.h @@ -66,14 +66,14 @@ static const uint8_t SCK = 33; #define LORA_DIO3 \ RADIOLIB_NC // Not connected on PCB, but internally on the TTGO SX1262/SX1268, if DIO3 is high the TXCO is enabled -#undef RF95_SCK -#define RF95_SCK SCK -#undef RF95_MISO -#define RF95_MISO MISO -#undef RF95_MOSI -#define RF95_MOSI MOSI -#undef RF95_NSS -#define RF95_NSS SS +#undef LORA_SCK +#define LORA_SCK SCK +#undef LORA_MISO +#define LORA_MISO MISO +#undef LORA_MOSI +#define LORA_MOSI MOSI +#undef LORA_CS +#define LORA_CS SS #define USE_SX1262 #define SX126X_CS SS // NSS for SX126X diff --git a/variants/rak11310/variant.h b/variants/rak11310/variant.h index acc21ce99..6334157f5 100644 --- a/variants/rak11310/variant.h +++ b/variants/rak11310/variant.h @@ -19,17 +19,17 @@ #define USE_SX1262 -#undef RF95_SCK -#undef RF95_MISO -#undef RF95_MOSI -#undef RF95_NSS +#undef LORA_SCK +#undef LORA_MISO +#undef LORA_MOSI +#undef LORA_CS // RAK BSP somehow uses SPI1 instead of SPI0 #define HW_SPI1_DEVICE -#define RF95_SCK PIN_SPI0_SCK -#define RF95_MOSI PIN_SPI0_MOSI -#define RF95_MISO PIN_SPI0_MISO -#define RF95_NSS PIN_SPI0_SS +#define LORA_SCK PIN_SPI0_SCK +#define LORA_MOSI PIN_SPI0_MOSI +#define LORA_MISO PIN_SPI0_MISO +#define LORA_CS PIN_SPI0_SS #define LORA_DIO0 RADIOLIB_NC #define LORA_RESET 14 @@ -38,7 +38,7 @@ #define LORA_DIO3 RADIOLIB_NC #ifdef USE_SX1262 -#define SX126X_CS RF95_NSS +#define SX126X_CS LORA_CS #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY LORA_DIO2 #define SX126X_RESET LORA_RESET diff --git a/variants/rpipico/variant.h b/variants/rpipico/variant.h index be26099de..aeda3d833 100644 --- a/variants/rpipico/variant.h +++ b/variants/rpipico/variant.h @@ -25,15 +25,15 @@ #define USE_SX1262 -#undef RF95_SCK -#undef RF95_MISO -#undef RF95_MOSI -#undef RF95_NSS +#undef LORA_SCK +#undef LORA_MISO +#undef LORA_MOSI +#undef LORA_CS -#define RF95_SCK 10 -#define RF95_MISO 12 -#define RF95_MOSI 11 -#define RF95_NSS 3 +#define LORA_SCK 10 +#define LORA_MISO 12 +#define LORA_MOSI 11 +#define LORA_CS 3 #define LORA_DIO0 RADIOLIB_NC #define LORA_RESET 15 @@ -42,7 +42,7 @@ #define LORA_DIO3 RADIOLIB_NC #ifdef USE_SX1262 -#define SX126X_CS RF95_NSS +#define SX126X_CS LORA_CS #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY LORA_DIO2 #define SX126X_RESET LORA_RESET diff --git a/variants/rpipicow/variant.h b/variants/rpipicow/variant.h index 77cb1ffd6..abbd1c465 100644 --- a/variants/rpipicow/variant.h +++ b/variants/rpipicow/variant.h @@ -23,15 +23,15 @@ #define USE_SX1262 -#undef RF95_SCK -#undef RF95_MISO -#undef RF95_MOSI -#undef RF95_NSS +#undef LORA_SCK +#undef LORA_MISO +#undef LORA_MOSI +#undef LORA_CS -#define RF95_SCK 10 -#define RF95_MISO 12 -#define RF95_MOSI 11 -#define RF95_NSS 3 +#define LORA_SCK 10 +#define LORA_MISO 12 +#define LORA_MOSI 11 +#define LORA_CS 3 #define LORA_DIO0 RADIOLIB_NC #define LORA_RESET 15 @@ -40,7 +40,7 @@ #define LORA_DIO3 RADIOLIB_NC #ifdef USE_SX1262 -#define SX126X_CS RF95_NSS +#define SX126X_CS LORA_CS #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY LORA_DIO2 #define SX126X_RESET LORA_RESET diff --git a/variants/station-g1/variant.h b/variants/station-g1/variant.h index 79a49fc96..e58853fb7 100644 --- a/variants/station-g1/variant.h +++ b/variants/station-g1/variant.h @@ -23,7 +23,7 @@ #define LORA_DIO3 // Not connected on PCB #ifdef USE_SX1262 -#define SX126X_CS RF95_NSS // FIXME - we really should define LORA_CS instead +#define SX126X_CS LORA_CS // FIXME - we really should define LORA_CS instead #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY LORA_DIO2 #define SX126X_RESET LORA_RESET diff --git a/variants/t-deck/variant.h b/variants/t-deck/variant.h index b1673d338..446e22732 100644 --- a/variants/t-deck/variant.h +++ b/variants/t-deck/variant.h @@ -69,10 +69,10 @@ #define USE_SX1262 #define USE_SX1268 -#define RF95_SCK 40 -#define RF95_MISO 38 -#define RF95_MOSI 41 -#define RF95_NSS 9 +#define LORA_SCK 40 +#define LORA_MISO 38 +#define LORA_MOSI 41 +#define LORA_CS 9 #define LORA_DIO0 -1 // a No connect on the SX1262 module #define LORA_RESET 17 @@ -80,7 +80,7 @@ #define LORA_DIO2 13 // SX1262 BUSY #define LORA_DIO3 // Not connected on PCB, but internally on the TTGO SX1262, if DIO3 is high the TXCO is enabled -#define SX126X_CS RF95_NSS // FIXME - we really should define LORA_CS instead +#define SX126X_CS LORA_CS // FIXME - we really should define LORA_CS instead #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY LORA_DIO2 #define SX126X_RESET LORA_RESET diff --git a/variants/t-watch-s3/variant.h b/variants/t-watch-s3/variant.h index c87845afa..c30224034 100644 --- a/variants/t-watch-s3/variant.h +++ b/variants/t-watch-s3/variant.h @@ -48,10 +48,10 @@ #define USE_SX1262 #define USE_SX1268 -#define RF95_SCK 3 -#define RF95_MISO 4 -#define RF95_MOSI 1 -#define RF95_NSS 5 +#define LORA_SCK 3 +#define LORA_MISO 4 +#define LORA_MOSI 1 +#define LORA_CS 5 #define LORA_DIO0 -1 // a No connect on the SX1262 module #define LORA_RESET 8 @@ -59,7 +59,7 @@ #define LORA_DIO2 7 // SX1262 BUSY #define LORA_DIO3 // Not connected on PCB, but internally on the TTGO SX1262, if DIO3 is high the TXCO is enabled -#define SX126X_CS RF95_NSS // FIXME - we really should define LORA_CS instead +#define SX126X_CS LORA_CS // FIXME - we really should define LORA_CS instead #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY LORA_DIO2 #define SX126X_RESET LORA_RESET diff --git a/variants/tbeam-s3-core/variant.h b/variants/tbeam-s3-core/variant.h index 5e9894cc6..0fa9f8fe8 100644 --- a/variants/tbeam-s3-core/variant.h +++ b/variants/tbeam-s3-core/variant.h @@ -47,10 +47,10 @@ #define PMU_USE_WIRE1 #define RTC_USE_WIRE1 -#define RF95_SCK 12 -#define RF95_MISO 13 -#define RF95_MOSI 11 -#define RF95_NSS 10 +#define LORA_SCK 12 +#define LORA_MISO 13 +#define LORA_MOSI 11 +#define LORA_CS 10 #define GPS_RX_PIN 9 #define GPS_TX_PIN 8 diff --git a/variants/tbeam/variant.h b/variants/tbeam/variant.h index a0ba70bfd..d237f542b 100644 --- a/variants/tbeam/variant.h +++ b/variants/tbeam/variant.h @@ -24,7 +24,7 @@ #define LORA_DIO3 // Not connected on PCB, but internally on the TTGO SX1262, if DIO3 is high the TXCO is enabled #ifdef USE_SX1262 -#define SX126X_CS RF95_NSS // FIXME - we really should define LORA_CS instead +#define SX126X_CS LORA_CS // FIXME - we really should define LORA_CS instead #define SX126X_DIO1 LORA_DIO1 #define SX126X_BUSY LORA_DIO2 #define SX126X_RESET LORA_RESET diff --git a/variants/tlora_t3s3_v1/variant.h b/variants/tlora_t3s3_v1/variant.h index 6e1d1d0eb..8a1af1ec2 100644 --- a/variants/tlora_t3s3_v1/variant.h +++ b/variants/tlora_t3s3_v1/variant.h @@ -25,10 +25,10 @@ #define USE_SX1262 #define USE_SX1280 -#define RF95_SCK 5 -#define RF95_MISO 3 -#define RF95_MOSI 6 -#define RF95_NSS 7 +#define LORA_SCK 5 +#define LORA_MISO 3 +#define LORA_MOSI 6 +#define LORA_CS 7 #define LORA_RESET 8 // per SX1276_Receive_Interrupt/utilities.h @@ -40,7 +40,7 @@ // per SX1262_Receive_Interrupt/utilities.h #ifdef USE_SX1262 -#define SX126X_CS RF95_NSS +#define SX126X_CS LORA_CS #define SX126X_DIO1 33 #define SX126X_BUSY 34 #define SX126X_RESET LORA_RESET @@ -50,7 +50,7 @@ // per SX128x_Receive_Interrupt/utilities.h #ifdef USE_SX1280 -#define SX128X_CS RF95_NSS +#define SX128X_CS LORA_CS #define SX128X_DIO1 9 #define SX128X_DIO2 33 #define SX128X_DIO3 34 From 102efd49548e5c1c6673da2c4b462692544ebee2 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 26 Nov 2023 15:08:20 -0600 Subject: [PATCH 003/472] Move to portduino GPIO, adding user button support --- bin/config-dist.yaml | 5 +++ src/ButtonThread.h | 28 ++++++++++++- src/main.cpp | 8 ++-- src/platform/portduino/PiHal.h | 31 ++++---------- src/platform/portduino/PortduinoGlue.cpp | 52 +++++++++++++++++++++++- src/platform/portduino/PortduinoGlue.h | 3 +- 6 files changed, 96 insertions(+), 31 deletions(-) diff --git a/bin/config-dist.yaml b/bin/config-dist.yaml index 6c8f1946f..d6cf8f878 100644 --- a/bin/config-dist.yaml +++ b/bin/config-dist.yaml @@ -24,3 +24,8 @@ Lora: # Reset: 22 # CS: 7 # IRQ: 25 + +# Define GPIO buttons here: + +GPIO: +# User: 6 diff --git a/src/ButtonThread.h b/src/ButtonThread.h index a8a89e82e..2ca5d4c28 100644 --- a/src/ButtonThread.h +++ b/src/ButtonThread.h @@ -36,6 +36,9 @@ class ButtonThread : public concurrency::OSThread #endif #ifdef BUTTON_PIN_TOUCH OneButton userButtonTouch; +#endif +#if defined(ARCH_RASPBERRY_PI) + OneButton userButton; #endif static bool shutdown_on_long_stop; @@ -45,8 +48,13 @@ class ButtonThread : public concurrency::OSThread // callback returns the period for the next callback invocation (or 0 if we should no longer be called) ButtonThread() : OSThread("Button") { -#ifdef BUTTON_PIN +#if defined(ARCH_RASPBERRY_PI) + if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) + userButton = OneButton(settingsMap[user], true, true); +#elif defined(BUTTON_PIN) + userButton = OneButton(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN, true, true); +#endif #ifdef INPUT_PULLUP_SENSE // Some platforms (nrf52) have a SENSE variant which allows wake from sleep - override what OneButton did pinMode(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN, INPUT_PULLUP_SENSE); @@ -58,6 +66,10 @@ class ButtonThread : public concurrency::OSThread userButton.attachMultiClick(userButtonMultiPressed); userButton.attachLongPressStart(userButtonPressedLongStart); userButton.attachLongPressStop(userButtonPressedLongStop); +#if defined(ARCH_RASPBERRY_PI) + if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) + wakeOnIrq(settingsMap[user], FALLING); +#else wakeOnIrq(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN, FALLING); #endif #ifdef BUTTON_PIN_ALT @@ -87,9 +99,14 @@ class ButtonThread : public concurrency::OSThread { canSleep = true; // Assume we should not keep the board awake -#ifdef BUTTON_PIN +#if defined(BUTTON_PIN) userButton.tick(); canSleep &= userButton.isIdle(); +#elif defined(ARCH_RASPBERRY_PI) + if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) { + userButton.tick(); + canSleep &= userButton.isIdle(); + } #endif #ifdef BUTTON_PIN_ALT userButtonAlt.tick(); @@ -121,6 +138,13 @@ class ButtonThread : public concurrency::OSThread !moduleConfig.canned_message.enabled) { powerFSM.trigger(EVENT_PRESS); } +#endif +#if defined(ARCH_RASPBERRY_PI) + if ((settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) && + (settingsMap[user] != moduleConfig.canned_message.inputbroker_pin_press) || + !moduleConfig.canned_message.enabled) { + powerFSM.trigger(EVENT_PRESS); + } #endif } static void userButtonPressedLong() diff --git a/src/main.cpp b/src/main.cpp index 4913f1091..b8432c5ad 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -75,7 +75,7 @@ NRF52Bluetooth *nrf52Bluetooth; #include #endif -#if HAS_BUTTON +#if HAS_BUTTON || defined(ARCH_RASPBERRY_PI) #include "ButtonThread.h" #endif #include "PowerFSMThread.h" @@ -206,13 +206,13 @@ static int32_t ledBlinker() uint32_t timeLastPowered = 0; -#if HAS_BUTTON +#if HAS_BUTTON || defined(ARCH_RASPBERRY_PI) bool ButtonThread::shutdown_on_long_stop = false; #endif static Periodic *ledPeriodic; static OSThread *powerFSMthread; -#if HAS_BUTTON +#if HAS_BUTTON || defined(ARCH_RASPBERRY_PI) static OSThread *buttonThread; uint32_t ButtonThread::longPressTime = 0; #endif @@ -583,7 +583,7 @@ void setup() else router = new ReliableRouter(); -#if HAS_BUTTON +#if HAS_BUTTON || defined(ARCH_RASPBERRY_PI) // Buttons. Moved here cause we need NodeDB to be initialized buttonThread = new ButtonThread(); #endif diff --git a/src/platform/portduino/PiHal.h b/src/platform/portduino/PiHal.h index f10040583..d80009450 100644 --- a/src/platform/portduino/PiHal.h +++ b/src/platform/portduino/PiHal.h @@ -7,6 +7,8 @@ // include the library for Raspberry GPIO pins #include "pigpio.h" +#include "linux/gpio/LinuxGPIOPin.h" + // create a new Raspberry Pi hardware abstraction layer // using the pigpio library // the HAL must inherit from the base RadioLibHal class @@ -54,8 +56,7 @@ class PiHal : public RadioLibHal if (pin == RADIOLIB_NC) { return; } - - gpioSetMode(pin, mode); + ::pinMode(pin, RADIOLIB_ARDUINOHAL_PIN_MODE_CAST mode); } void digitalWrite(uint32_t pin, uint32_t value) override @@ -63,8 +64,7 @@ class PiHal : public RadioLibHal if (pin == RADIOLIB_NC) { return; } - - gpioWrite(pin, value); + ::digitalWrite(pin, RADIOLIB_ARDUINOHAL_PIN_STATUS_CAST value); } uint32_t digitalRead(uint32_t pin) override @@ -73,7 +73,7 @@ class PiHal : public RadioLibHal return (0); } - return (gpioRead(pin)); + return (::digitalRead(pin)); } void attachInterrupt(uint32_t interruptNum, void (*interruptCb)(void), uint32_t mode) override @@ -81,11 +81,7 @@ class PiHal : public RadioLibHal if (interruptNum == RADIOLIB_NC) { return; } - if (gpioRead(interruptNum) == 1) { - interruptCb(); - } else { - gpioSetAlertFunc(interruptNum, (gpioISRFunc_t)interruptCb); - } + ::attachInterrupt(interruptNum, interruptCb, RADIOLIB_ARDUINOHAL_INTERRUPT_MODE_CAST mode); } void detachInterrupt(uint32_t interruptNum) override @@ -94,7 +90,7 @@ class PiHal : public RadioLibHal return; } - gpioSetAlertFunc(interruptNum, NULL); + ::detachInterrupt(interruptNum); } void delay(unsigned long ms) override { gpioDelay(ms * 1000); } @@ -111,19 +107,8 @@ class PiHal : public RadioLibHal return (0); } - this->pinMode(pin, PI_INPUT); - uint32_t start = this->micros(); - uint32_t curtick = this->micros(); - - while (this->digitalRead(pin) == state) { - if ((this->micros() - curtick) > timeout) { - return (0); - } - } - - return (this->micros() - start); + return (::pulseIn(pin, state, timeout)); } - void spiBegin() { if (_spiHandle < 0) { diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index d2a00e1e1..f7389431b 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -10,6 +10,7 @@ #ifdef ARCH_RASPBERRY_PI #include "PortduinoGlue.h" +#include "linux/gpio/LinuxGPIOPin.h" #include "pigpio.h" #include "yaml-cpp/yaml.h" #include @@ -101,6 +102,7 @@ void portduinoSetup() printf("Setting up Meshtastic on Portduino...\n"); #ifdef ARCH_RASPBERRY_PI + gpioInit(); YAML::Node yamlConfig; if (access("config.yaml", R_OK) == 0) { @@ -138,6 +140,9 @@ void portduinoSetup() settingsMap[busy] = yamlConfig["Lora"]["Busy"].as(RADIOLIB_NC); settingsMap[reset] = yamlConfig["Lora"]["Reset"].as(RADIOLIB_NC); } + if (yamlConfig["GPIO"]) { + settingsMap[user] = yamlConfig["GPIO"]["User"].as(RADIOLIB_NC); + } } catch (YAML::Exception e) { std::cout << "*** Exception " << e.what() << std::endl; @@ -147,6 +152,34 @@ void portduinoSetup() std::cout << "Cannot read Bluetooth MAC Address. Please run as root" << std::endl; exit(EXIT_FAILURE); } + + // Need to bind all the configured GPIO pins so they're not simulated + if (settingsMap.count(cs) > 0 && settingsMap[cs] != RADIOLIB_NC) { + if (initGPIOPin(settingsMap[cs]) != ERRNO_OK) { + settingsMap[cs] = RADIOLIB_NC; + } + } + if (settingsMap.count(irq) > 0 && settingsMap[irq] != RADIOLIB_NC) { + if (initGPIOPin(settingsMap[irq]) != ERRNO_OK) { + settingsMap[irq] = RADIOLIB_NC; + } + } + if (settingsMap.count(busy) > 0 && settingsMap[busy] != RADIOLIB_NC) { + if (initGPIOPin(settingsMap[busy]) != ERRNO_OK) { + settingsMap[busy] = RADIOLIB_NC; + } + } + if (settingsMap.count(reset) > 0 && settingsMap[reset] != RADIOLIB_NC) { + if (initGPIOPin(settingsMap[reset]) != ERRNO_OK) { + settingsMap[reset] = RADIOLIB_NC; + } + } + if (settingsMap.count(user) > 0 && settingsMap[user] != RADIOLIB_NC) { + if (initGPIOPin(settingsMap[user]) != ERRNO_OK) { + settingsMap[user] = RADIOLIB_NC; + } + } + return; #endif @@ -194,4 +227,21 @@ void portduinoSetup() // gpioBind((new SimGPIOPin(LORA_RESET, "LORA_RESET"))); // gpioBind((new SimGPIOPin(LORA_CS, "LORA_CS"))->setSilent()); #endif -} \ No newline at end of file +} + +#ifdef ARCH_RASPBERRY_PI +int initGPIOPin(int pinNum) +{ + std::string gpio_name = "GPIO" + std::to_string(pinNum); + try { + GPIOPin *csPin; + csPin = new LinuxGPIOPin(pinNum, "gpiochip0", pinNum, gpio_name.c_str()); + csPin->setSilent(); + gpioBind(csPin); + return ERRNO_OK; + } catch (std::invalid_argument &e) { + std::cout << "Warning, cannot claim pin" << gpio_name << std::endl; + return ERRNO_DISABLED; + } +} +#endif \ No newline at end of file diff --git a/src/platform/portduino/PortduinoGlue.h b/src/platform/portduino/PortduinoGlue.h index 7dc563038..7544a0853 100644 --- a/src/platform/portduino/PortduinoGlue.h +++ b/src/platform/portduino/PortduinoGlue.h @@ -4,6 +4,7 @@ extern std::map settingsMap; -enum { use_sx1262, cs, irq, busy, reset, dio2_as_rf_switch, use_rf95 }; +enum { use_sx1262, cs, irq, busy, reset, dio2_as_rf_switch, use_rf95, user }; +int initGPIOPin(int pinNum); #endif \ No newline at end of file From d3e64350d9ebe413b0380d066843c63f1b76b809 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 26 Nov 2023 20:29:01 -0600 Subject: [PATCH 004/472] Remove RADIOLIB_SPI_PARANOID compile option, as it does nothing --- platformio.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/platformio.ini b/platformio.ini index cb79565f1..451fe3f1a 100644 --- a/platformio.ini +++ b/platformio.ini @@ -93,7 +93,7 @@ lib_deps = end2endzone/NonBlockingRTTTL@^1.3.0 https://github.com/meshtastic/SparkFun_ATECCX08a_Arduino_Library.git#5cf62b36c6f30bc72a07bdb2c11fc9a22d1e31da -build_flags = ${env.build_flags} -Os -DRADIOLIB_SPI_PARANOID=0 +build_flags = ${env.build_flags} -Os build_src_filter = ${env.build_src_filter} - ; Common libs for communicating over TCP/IP networks such as MQTT @@ -123,4 +123,4 @@ lib_deps = adafruit/Adafruit PM25 AQI Sensor@^1.0.6 adafruit/Adafruit MPU6050@^2.2.4 adafruit/Adafruit LIS3DH@^1.2.4 - https://github.com/lewisxhe/BMA423_Library@^0.0.1 \ No newline at end of file + https://github.com/lewisxhe/BMA423_Library@^0.0.1 From d10b1e1d00034b1d80ea063a110f6651b47e9a11 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 26 Nov 2023 20:31:52 -0600 Subject: [PATCH 005/472] Add better error reporting for RF95 init failure --- src/mesh/RadioLibRF95.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/mesh/RadioLibRF95.cpp b/src/mesh/RadioLibRF95.cpp index 0fa6c7fe8..eca2509aa 100644 --- a/src/mesh/RadioLibRF95.cpp +++ b/src/mesh/RadioLibRF95.cpp @@ -14,8 +14,10 @@ int16_t RadioLibRF95::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_ { // execute common part int16_t state = SX127x::begin(RF95_CHIP_VERSION, syncWord, preambleLength); - if (state != RADIOLIB_ERR_NONE) + if (state != RADIOLIB_ERR_NONE) { + LOG_WARN("Initial probe for RF95 failed with %d, trying again with alternative hardware version\n", state); state = SX127x::begin(RF95_ALT_VERSION, syncWord, preambleLength); + } RADIOLIB_ASSERT(state); // current limit was removed from module' ctor @@ -80,4 +82,4 @@ bool RadioLibRF95::isReceiving() uint8_t RadioLibRF95::readReg(uint8_t addr) { return mod->SPIreadRegister(addr); -} \ No newline at end of file +} From 1ca29236580c3994eb7fc623edec599759b0fb76 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 26 Nov 2023 20:41:22 -0600 Subject: [PATCH 006/472] Fix missed #if defined() logic --- src/ButtonThread.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/ButtonThread.h b/src/ButtonThread.h index 2ca5d4c28..a60b7730a 100644 --- a/src/ButtonThread.h +++ b/src/ButtonThread.h @@ -48,6 +48,7 @@ class ButtonThread : public concurrency::OSThread // callback returns the period for the next callback invocation (or 0 if we should no longer be called) ButtonThread() : OSThread("Button") { +#if defined(ARCH_RASPBERRY_PI) || defined(BUTTON_PIN) #if defined(ARCH_RASPBERRY_PI) if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) userButton = OneButton(settingsMap[user], true, true); @@ -72,6 +73,7 @@ class ButtonThread : public concurrency::OSThread #else wakeOnIrq(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN, FALLING); #endif +#endif #ifdef BUTTON_PIN_ALT userButtonAlt = OneButton(BUTTON_PIN_ALT, true, true); #ifdef INPUT_PULLUP_SENSE @@ -223,4 +225,4 @@ class ButtonThread : public concurrency::OSThread } }; -} // namespace concurrency \ No newline at end of file +} // namespace concurrency From 57227c0f85f82c955c9a8ce30890f59a38a3ef77 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 26 Nov 2023 21:29:19 -0600 Subject: [PATCH 007/472] Add gpiochip setting --- bin/config-dist.yaml | 4 ++++ src/platform/portduino/PortduinoGlue.cpp | 18 +++++++++++------- src/platform/portduino/PortduinoGlue.h | 4 ++-- 3 files changed, 17 insertions(+), 9 deletions(-) diff --git a/bin/config-dist.yaml b/bin/config-dist.yaml index d6cf8f878..43360eb2e 100644 --- a/bin/config-dist.yaml +++ b/bin/config-dist.yaml @@ -25,6 +25,10 @@ Lora: # CS: 7 # IRQ: 25 +# Set gpio chip to use in /dev/. Defaults to 0. +# Notably the Raspberry Pi 5 puts the GPIO header on gpiochip4 +# gpiochip: 4 + # Define GPIO buttons here: GPIO: diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index f7389431b..54d633530 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -103,6 +103,8 @@ void portduinoSetup() #ifdef ARCH_RASPBERRY_PI gpioInit(); + + std::string gpioChipName = "gpiochip"; YAML::Node yamlConfig; if (access("config.yaml", R_OK) == 0) { @@ -139,6 +141,8 @@ void portduinoSetup() settingsMap[irq] = yamlConfig["Lora"]["IRQ"].as(RADIOLIB_NC); settingsMap[busy] = yamlConfig["Lora"]["Busy"].as(RADIOLIB_NC); settingsMap[reset] = yamlConfig["Lora"]["Reset"].as(RADIOLIB_NC); + settingsMap[gpiochip] = yamlConfig["Lora"]["gpiochip"].as(0); + gpioChipName += std::to_string(settingsMap[gpiochip]); } if (yamlConfig["GPIO"]) { settingsMap[user] = yamlConfig["GPIO"]["User"].as(RADIOLIB_NC); @@ -155,27 +159,27 @@ void portduinoSetup() // Need to bind all the configured GPIO pins so they're not simulated if (settingsMap.count(cs) > 0 && settingsMap[cs] != RADIOLIB_NC) { - if (initGPIOPin(settingsMap[cs]) != ERRNO_OK) { + if (initGPIOPin(settingsMap[cs], gpioChipName) != ERRNO_OK) { settingsMap[cs] = RADIOLIB_NC; } } if (settingsMap.count(irq) > 0 && settingsMap[irq] != RADIOLIB_NC) { - if (initGPIOPin(settingsMap[irq]) != ERRNO_OK) { + if (initGPIOPin(settingsMap[irq], gpioChipName) != ERRNO_OK) { settingsMap[irq] = RADIOLIB_NC; } } if (settingsMap.count(busy) > 0 && settingsMap[busy] != RADIOLIB_NC) { - if (initGPIOPin(settingsMap[busy]) != ERRNO_OK) { + if (initGPIOPin(settingsMap[busy], gpioChipName) != ERRNO_OK) { settingsMap[busy] = RADIOLIB_NC; } } if (settingsMap.count(reset) > 0 && settingsMap[reset] != RADIOLIB_NC) { - if (initGPIOPin(settingsMap[reset]) != ERRNO_OK) { + if (initGPIOPin(settingsMap[reset], gpioChipName) != ERRNO_OK) { settingsMap[reset] = RADIOLIB_NC; } } if (settingsMap.count(user) > 0 && settingsMap[user] != RADIOLIB_NC) { - if (initGPIOPin(settingsMap[user]) != ERRNO_OK) { + if (initGPIOPin(settingsMap[user], gpioChipName) != ERRNO_OK) { settingsMap[user] = RADIOLIB_NC; } } @@ -230,12 +234,12 @@ void portduinoSetup() } #ifdef ARCH_RASPBERRY_PI -int initGPIOPin(int pinNum) +int initGPIOPin(int pinNum, std::string gpioChipName) { std::string gpio_name = "GPIO" + std::to_string(pinNum); try { GPIOPin *csPin; - csPin = new LinuxGPIOPin(pinNum, "gpiochip0", pinNum, gpio_name.c_str()); + csPin = new LinuxGPIOPin(pinNum, gpioChipName.c_str(), pinNum, gpio_name.c_str()); csPin->setSilent(); gpioBind(csPin); return ERRNO_OK; diff --git a/src/platform/portduino/PortduinoGlue.h b/src/platform/portduino/PortduinoGlue.h index 7544a0853..ac356607f 100644 --- a/src/platform/portduino/PortduinoGlue.h +++ b/src/platform/portduino/PortduinoGlue.h @@ -4,7 +4,7 @@ extern std::map settingsMap; -enum { use_sx1262, cs, irq, busy, reset, dio2_as_rf_switch, use_rf95, user }; -int initGPIOPin(int pinNum); +enum { use_sx1262, cs, irq, busy, reset, dio2_as_rf_switch, use_rf95, user, gpiochip }; +int initGPIOPin(int pinNum, std::string gpioChipname); #endif \ No newline at end of file From ce8342d3e528692849854e0eca4f55ff93c7f761 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 26 Nov 2023 21:30:08 -0600 Subject: [PATCH 008/472] Drop Pi HAL --- src/main.cpp | 5 +- src/platform/portduino/PiHal.h | 140 --------------------------------- 2 files changed, 2 insertions(+), 143 deletions(-) delete mode 100644 src/platform/portduino/PiHal.h diff --git a/src/main.cpp b/src/main.cpp index b8432c5ad..83f3b721e 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -68,7 +68,6 @@ NRF52Bluetooth *nrf52Bluetooth; #endif #ifdef ARCH_RASPBERRY_PI -#include "platform/portduino/PiHal.h" #include "platform/portduino/PortduinoGlue.h" #include #include @@ -693,7 +692,7 @@ void setup() #ifdef ARCH_RASPBERRY_PI if (settingsMap[use_sx1262]) { if (!rIf) { - PiHal *RadioLibHAL = new PiHal(1); + LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(SPI, spiSettings); rIf = new SX1262Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset], settingsMap[busy]); if (!rIf->init()) { @@ -706,7 +705,7 @@ void setup() } } else if (settingsMap[use_rf95]) { if (!rIf) { - PiHal *RadioLibHAL = new PiHal(1); + LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(SPI, spiSettings); rIf = new RF95Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset], settingsMap[busy]); if (!rIf->init()) { diff --git a/src/platform/portduino/PiHal.h b/src/platform/portduino/PiHal.h deleted file mode 100644 index d80009450..000000000 --- a/src/platform/portduino/PiHal.h +++ /dev/null @@ -1,140 +0,0 @@ -#ifndef PI_HAL_H -#define PI_HAL_H - -// include RadioLib -#include - -// include the library for Raspberry GPIO pins -#include "pigpio.h" - -#include "linux/gpio/LinuxGPIOPin.h" - -// create a new Raspberry Pi hardware abstraction layer -// using the pigpio library -// the HAL must inherit from the base RadioLibHal class -// and implement all of its virtual methods -class PiHal : public RadioLibHal -{ - public: - // default constructor - initializes the base HAL and any needed private members - PiHal(uint8_t spiChannel, uint32_t spiSpeed = 2000000) - : RadioLibHal(PI_INPUT, PI_OUTPUT, PI_LOW, PI_HIGH, RISING_EDGE, FALLING_EDGE), _spiChannel(spiChannel), - _spiSpeed(spiSpeed) - { - } - - void init() override - { - // first initialise pigpio library - gpioInitialise(); - - // now the SPI - spiBegin(); - - // Waveshare LoRaWAN Hat also needs pin 18 to be pulled high to enable the radio - // gpioSetMode(18, PI_OUTPUT); - // gpioWrite(18, PI_HIGH); - } - - void term() override - { - // stop the SPI - spiEnd(); - - // pull the enable pin low - // gpioSetMode(18, PI_OUTPUT); - // gpioWrite(18, PI_LOW); - - // finally, stop the pigpio library - gpioTerminate(); - } - - // GPIO-related methods (pinMode, digitalWrite etc.) should check - // RADIOLIB_NC as an alias for non-connected pins - void pinMode(uint32_t pin, uint32_t mode) override - { - if (pin == RADIOLIB_NC) { - return; - } - ::pinMode(pin, RADIOLIB_ARDUINOHAL_PIN_MODE_CAST mode); - } - - void digitalWrite(uint32_t pin, uint32_t value) override - { - if (pin == RADIOLIB_NC) { - return; - } - ::digitalWrite(pin, RADIOLIB_ARDUINOHAL_PIN_STATUS_CAST value); - } - - uint32_t digitalRead(uint32_t pin) override - { - if (pin == RADIOLIB_NC) { - return (0); - } - - return (::digitalRead(pin)); - } - - void attachInterrupt(uint32_t interruptNum, void (*interruptCb)(void), uint32_t mode) override - { - if (interruptNum == RADIOLIB_NC) { - return; - } - ::attachInterrupt(interruptNum, interruptCb, RADIOLIB_ARDUINOHAL_INTERRUPT_MODE_CAST mode); - } - - void detachInterrupt(uint32_t interruptNum) override - { - if (interruptNum == RADIOLIB_NC) { - return; - } - - ::detachInterrupt(interruptNum); - } - - void delay(unsigned long ms) override { gpioDelay(ms * 1000); } - - void delayMicroseconds(unsigned long us) override { gpioDelay(us); } - - unsigned long millis() override { return (gpioTick() / 1000); } - - unsigned long micros() override { return (gpioTick()); } - - long pulseIn(uint32_t pin, uint32_t state, unsigned long timeout) override - { - if (pin == RADIOLIB_NC) { - return (0); - } - - return (::pulseIn(pin, state, timeout)); - } - void spiBegin() - { - if (_spiHandle < 0) { - _spiHandle = spiOpen(_spiChannel, _spiSpeed, 0); - } - } - - void spiBeginTransaction() {} - - void spiTransfer(uint8_t *out, size_t len, uint8_t *in) { spiXfer(_spiHandle, (char *)out, (char *)in, len); } - - void spiEndTransaction() {} - - void spiEnd() - { - if (_spiHandle >= 0) { - spiClose(_spiHandle); - _spiHandle = -1; - } - } - - private: - // the HAL can contain any additional private members - const unsigned int _spiSpeed; - const uint8_t _spiChannel; - int _spiHandle = -1; -}; - -#endif \ No newline at end of file From 423b8ad6036342c723bbe5f3151a1f441f424ebf Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Tue, 28 Nov 2023 12:39:32 -0600 Subject: [PATCH 009/472] Adds real GPS support to Raspberry Pi arch --- bin/config-dist.yaml | 5 +++++ src/gps/GPS.cpp | 10 ++++++---- src/platform/portduino/PortduinoGlue.cpp | 7 +++++++ src/platform/portduino/PortduinoGlue.h | 2 +- 4 files changed, 19 insertions(+), 5 deletions(-) diff --git a/bin/config-dist.yaml b/bin/config-dist.yaml index 43360eb2e..cde45d1f8 100644 --- a/bin/config-dist.yaml +++ b/bin/config-dist.yaml @@ -33,3 +33,8 @@ Lora: GPIO: # User: 6 + +# Define GPS + +GPS: +# SerialPath: /dev/ttyS0 diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 11c16ede9..7ea36c860 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -7,6 +7,7 @@ #include "ubx.h" #ifdef ARCH_PORTDUINO +#include "PortduinoGlue.h" #include "meshUtils.h" #include #endif @@ -15,11 +16,8 @@ #define GPS_RESET_MODE HIGH #endif -#if defined(NRF52840_XXAA) || defined(NRF52833_XXAA) || defined(ARCH_ESP32) +#if defined(NRF52840_XXAA) || defined(NRF52833_XXAA) || defined(ARCH_ESP32) || defined(ARCH_RASPBERRY_PI) HardwareSerial *GPS::_serial_gps = &Serial1; -#elif defined(ARCH_RASPBERRY_PI) -// need a translation layer to make _serial_gps work with pigpio https://abyz.me.uk/rpi/pigpio/cif.html#serOpen -HardwareSerial *GPS::_serial_gps = NULL; #else HardwareSerial *GPS::_serial_gps = NULL; #endif @@ -907,6 +905,10 @@ GPS *GPS::createGps() #if defined(PIN_GPS_EN) if (!_en_gpio) _en_gpio = PIN_GPS_EN; +#endif +#ifdef ARCH_RASPBERRY_PI + if (!settingsMap[has_gps]) + return nullptr; #endif if (!_rx_gpio || !_serial_gps) // Configured to have no GPS at all return nullptr; diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index 54d633530..06e18eb91 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -147,6 +147,13 @@ void portduinoSetup() if (yamlConfig["GPIO"]) { settingsMap[user] = yamlConfig["GPIO"]["User"].as(RADIOLIB_NC); } + if (yamlConfig["GPS"]) { + std::string serialPath = yamlConfig["GPS"]["SerialPath"].as(""); + if (serialPath != "") { + Serial1.setPath(serialPath); + settingsMap[has_gps] = 1; + } + } } catch (YAML::Exception e) { std::cout << "*** Exception " << e.what() << std::endl; diff --git a/src/platform/portduino/PortduinoGlue.h b/src/platform/portduino/PortduinoGlue.h index ac356607f..b942ab46a 100644 --- a/src/platform/portduino/PortduinoGlue.h +++ b/src/platform/portduino/PortduinoGlue.h @@ -4,7 +4,7 @@ extern std::map settingsMap; -enum { use_sx1262, cs, irq, busy, reset, dio2_as_rf_switch, use_rf95, user, gpiochip }; +enum { use_sx1262, cs, irq, busy, reset, dio2_as_rf_switch, use_rf95, user, gpiochip, has_gps }; int initGPIOPin(int pinNum, std::string gpioChipname); #endif \ No newline at end of file From 14d03a2bda24f69fec7dcd42f7fe043b6eb74bc9 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Wed, 29 Nov 2023 00:48:30 -0600 Subject: [PATCH 010/472] Initial implementation of I2C --- src/detect/ScanI2CTwoWire.cpp | 11 ++++++++++- src/graphics/Screen.cpp | 2 +- src/main.cpp | 1 + src/platform/portduino/architecture.h | 2 +- variants/portduino/variant.h | 3 ++- 5 files changed, 15 insertions(+), 4 deletions(-) diff --git a/src/detect/ScanI2CTwoWire.cpp b/src/detect/ScanI2CTwoWire.cpp index b3873dc91..a5c932f1f 100644 --- a/src/detect/ScanI2CTwoWire.cpp +++ b/src/detect/ScanI2CTwoWire.cpp @@ -2,7 +2,9 @@ #include "concurrency/LockGuard.h" #include "configuration.h" - +#if defined(ARCH_RASPBERRY_PI) +#include "linux/LinuxHardwareI2C.h" +#endif #if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) #include "main.h" // atecc #endif @@ -162,7 +164,14 @@ void ScanI2CTwoWire::scanPort(I2CPort port) for (addr.address = 1; addr.address < 127; addr.address++) { i2cBus->beginTransmission(addr.address); +#ifdef ARCH_PORTDUINO + if (i2cBus->read() != -1) + err = 0; + else + err = 2; +#else err = i2cBus->endTransmission(); +#endif type = NONE; if (err == 0) { LOG_DEBUG("I2C device found at address 0x%x\n", addr.address); diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index b626e393a..2e144e41a 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -1564,7 +1564,7 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16 // Jm void DebugInfo::drawFrameWiFi(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) { -#if HAS_WIFI +#if HAS_WIFI && !defined(ARCH_RASPBERRY_PI) const char *wifiName = config.network.wifi_ssid; display->setFont(FONT_SMALL); diff --git a/src/main.cpp b/src/main.cpp index 83f3b721e..5cea142bc 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -68,6 +68,7 @@ NRF52Bluetooth *nrf52Bluetooth; #endif #ifdef ARCH_RASPBERRY_PI +#include "linux/LinuxHardwareI2C.h" #include "platform/portduino/PortduinoGlue.h" #include #include diff --git a/src/platform/portduino/architecture.h b/src/platform/portduino/architecture.h index 9408ad19c..a98769222 100644 --- a/src/platform/portduino/architecture.h +++ b/src/platform/portduino/architecture.h @@ -16,4 +16,4 @@ #endif #ifndef HAS_TELEMETRY #define HAS_TELEMETRY 1 -#endif +#endif \ No newline at end of file diff --git a/variants/portduino/variant.h b/variants/portduino/variant.h index 8e1c0b1f2..23066276b 100644 --- a/variants/portduino/variant.h +++ b/variants/portduino/variant.h @@ -1,5 +1,6 @@ #if defined(ARCH_RASPBERRY_PI) -#define NO_SCREEN +#define HAS_WIRE 1 +#define HAS_SCREEN 1 #else // Pine64 mode. From c489c251ab1dd701f7cfb52145a765b42891a887 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Wed, 29 Nov 2023 19:03:07 -0600 Subject: [PATCH 011/472] Pull in Portduino changes for Raspberry Pi support --- arch/portduino/portduino.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index b39974853..e4a60306b 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -1,6 +1,6 @@ ; The Portduino based sim environment on top of any host OS, all hardware will be simulated [portduino_base] -platform = https://github.com/meshtastic/platform-native.git#489ff929dca0bb768256ba2de45f95815111490f +platform = https://github.com/meshtastic/platform-native.git#05255283879a0c65a7d3eba6c468b9186438bb14 framework = arduino build_src_filter = From bd2675caf169b1f86c396470148a4f0c9371d4b9 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Wed, 29 Nov 2023 19:46:15 -0600 Subject: [PATCH 012/472] Temporarily Pin RadioLib to 6.2.0 --- arch/esp32/esp32.ini | 4 ++-- arch/nrf52/nrf52.ini | 2 +- arch/portduino/portduino.ini | 2 +- arch/rp2040/rp2040.ini | 2 +- arch/stm32/stm32wl5e.ini | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/arch/esp32/esp32.ini b/arch/esp32/esp32.ini index aa31db13e..ab18e5500 100644 --- a/arch/esp32/esp32.ini +++ b/arch/esp32/esp32.ini @@ -39,7 +39,7 @@ lib_deps = ${environmental_base.lib_deps} https://github.com/meshtastic/esp32_https_server.git#23665b3adc080a311dcbb586ed5941b5f94d6ea2 h2zero/NimBLE-Arduino@^1.4.1 - jgromes/RadioLib@^6.1.0 + jgromes/RadioLib@ 6.2.0 https://github.com/lewisxhe/XPowersLib.git#84b7373faea3118b6c37954d52f98b8a337148d6 https://github.com/meshtastic/ESP32_Codec2.git#633326c78ac251c059ab3a8c430fcdf25b41672f @@ -57,4 +57,4 @@ lib_ignore = ; customize the partition table ; http://docs.platformio.org/en/latest/platforms/espressif32.html#partition-tables -board_build.partitions = partition-table.csv +board_build.partitions = partition-table.csv \ No newline at end of file diff --git a/arch/nrf52/nrf52.ini b/arch/nrf52/nrf52.ini index d1826a96a..ee2b70d3b 100644 --- a/arch/nrf52/nrf52.ini +++ b/arch/nrf52/nrf52.ini @@ -15,7 +15,7 @@ build_src_filter = lib_deps= ${arduino_base.lib_deps} - jgromes/RadioLib@^6.1.0 + jgromes/RadioLib@ 6.2.0 lib_ignore = BluetoothOTA \ No newline at end of file diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index e4a60306b..d50fbb9ed 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -22,7 +22,7 @@ lib_deps = ${env.lib_deps} ${networking_base.lib_deps} rweather/Crypto@^0.4.0 - jgromes/RadioLib@6.1.0 + jgromes/RadioLib@6.2.0 build_flags = ${arduino_base.build_flags} diff --git a/arch/rp2040/rp2040.ini b/arch/rp2040/rp2040.ini index 495b52a86..f173d0af6 100644 --- a/arch/rp2040/rp2040.ini +++ b/arch/rp2040/rp2040.ini @@ -20,5 +20,5 @@ lib_ignore = lib_deps = ${arduino_base.lib_deps} ${environmental_base.lib_deps} - jgromes/RadioLib@^6.1.0 + jgromes/RadioLib@ 6.2.0 rweather/Crypto \ No newline at end of file diff --git a/arch/stm32/stm32wl5e.ini b/arch/stm32/stm32wl5e.ini index 524edd6b9..ba92e0370 100644 --- a/arch/stm32/stm32wl5e.ini +++ b/arch/stm32/stm32wl5e.ini @@ -20,7 +20,7 @@ upload_protocol = stlink lib_deps = ${env.lib_deps} - jgromes/RadioLib@^6.1.0 + jgromes/RadioLib@ 6.2.0 https://github.com/kokke/tiny-AES-c.git#f06ac37fc31dfdaca2e0d9bec83f90d5663c319b https://github.com/littlefs-project/littlefs.git#v2.5.1 https://github.com/stm32duino/STM32FreeRTOS.git#10.3.1 From 39743832adf8b642813797a9f11b12b52e8318a1 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Wed, 29 Nov 2023 19:50:44 -0600 Subject: [PATCH 013/472] Revert Portduino RadioLib to 6.1.0 --- arch/portduino/portduino.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index d50fbb9ed..e4a60306b 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -22,7 +22,7 @@ lib_deps = ${env.lib_deps} ${networking_base.lib_deps} rweather/Crypto@^0.4.0 - jgromes/RadioLib@6.2.0 + jgromes/RadioLib@6.1.0 build_flags = ${arduino_base.build_flags} From 6fa026a78b81d89617b8bf822ce8a42aacc8b49f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Thu, 30 Nov 2023 10:59:01 +0100 Subject: [PATCH 014/472] fix radiolib API for 6.3.0 release --- arch/esp32/esp32.ini | 2 +- src/mesh/RadioLibRF95.cpp | 10 ++-------- src/mesh/SX126xInterface.cpp | 4 ++-- 3 files changed, 5 insertions(+), 11 deletions(-) diff --git a/arch/esp32/esp32.ini b/arch/esp32/esp32.ini index ab18e5500..db4b8e0b5 100644 --- a/arch/esp32/esp32.ini +++ b/arch/esp32/esp32.ini @@ -39,7 +39,7 @@ lib_deps = ${environmental_base.lib_deps} https://github.com/meshtastic/esp32_https_server.git#23665b3adc080a311dcbb586ed5941b5f94d6ea2 h2zero/NimBLE-Arduino@^1.4.1 - jgromes/RadioLib@ 6.2.0 + jgromes/RadioLib@^6.2.0 https://github.com/lewisxhe/XPowersLib.git#84b7373faea3118b6c37954d52f98b8a337148d6 https://github.com/meshtastic/ESP32_Codec2.git#633326c78ac251c059ab3a8c430fcdf25b41672f diff --git a/src/mesh/RadioLibRF95.cpp b/src/mesh/RadioLibRF95.cpp index eca2509aa..f84ec28b7 100644 --- a/src/mesh/RadioLibRF95.cpp +++ b/src/mesh/RadioLibRF95.cpp @@ -1,9 +1,6 @@ #include "RadioLibRF95.h" #include "configuration.h" -#define RF95_CHIP_VERSION 0x12 -#define RF95_ALT_VERSION 0x11 // Supposedly some versions of the chip have id 0x11 - // From datasheet but radiolib doesn't know anything about this #define SX127X_REG_TCXO 0x4B @@ -13,11 +10,8 @@ int16_t RadioLibRF95::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_ uint8_t gain) { // execute common part - int16_t state = SX127x::begin(RF95_CHIP_VERSION, syncWord, preambleLength); - if (state != RADIOLIB_ERR_NONE) { - LOG_WARN("Initial probe for RF95 failed with %d, trying again with alternative hardware version\n", state); - state = SX127x::begin(RF95_ALT_VERSION, syncWord, preambleLength); - } + uint8_t rf95versions[2] = {0x12, 0x11}; + int16_t state = SX127x::begin(rf95versions, sizeof(rf95versions), syncWord, preambleLength); RADIOLIB_ASSERT(state); // current limit was removed from module' ctor diff --git a/src/mesh/SX126xInterface.cpp b/src/mesh/SX126xInterface.cpp index 5083eeb53..30951cd16 100644 --- a/src/mesh/SX126xInterface.cpp +++ b/src/mesh/SX126xInterface.cpp @@ -250,7 +250,7 @@ template void SX126xInterface::startReceive() // We use a 16 bit preamble so this should save some power by letting radio sit in standby mostly. // Furthermore, we need the PREAMBLE_DETECTED and HEADER_VALID IRQ flag to detect whether we are actively receiving int err = lora.startReceiveDutyCycleAuto(preambleLength, 8, - RADIOLIB_SX126X_IRQ_RX_DEFAULT | RADIOLIB_SX126X_IRQ_RADIOLIB_PREAMBLE_DETECTED | + RADIOLIB_SX126X_IRQ_RX_DEFAULT | RADIOLIB_SX126X_IRQ_PREAMBLE_DETECTED | RADIOLIB_SX126X_IRQ_HEADER_VALID); assert(err == RADIOLIB_ERR_NONE); @@ -284,7 +284,7 @@ template bool SX126xInterface::isActivelyReceiving() // received and handled the interrupt for reading the packet/handling errors. uint16_t irq = lora.getIrqStatus(); - bool detected = (irq & (RADIOLIB_SX126X_IRQ_HEADER_VALID | RADIOLIB_SX126X_IRQ_RADIOLIB_PREAMBLE_DETECTED)); + bool detected = (irq & (RADIOLIB_SX126X_IRQ_HEADER_VALID | RADIOLIB_SX126X_IRQ_PREAMBLE_DETECTED)); // Handle false detections if (detected) { uint32_t now = millis(); From 5df7f07f9570e628671c5214497ba46093192926 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Thu, 30 Nov 2023 11:10:43 +0100 Subject: [PATCH 015/472] unpin radiolib --- arch/nrf52/nrf52.ini | 2 +- arch/portduino/portduino.ini | 2 +- arch/rp2040/rp2040.ini | 2 +- arch/stm32/stm32wl5e.ini | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/arch/nrf52/nrf52.ini b/arch/nrf52/nrf52.ini index ee2b70d3b..1a3631420 100644 --- a/arch/nrf52/nrf52.ini +++ b/arch/nrf52/nrf52.ini @@ -15,7 +15,7 @@ build_src_filter = lib_deps= ${arduino_base.lib_deps} - jgromes/RadioLib@ 6.2.0 + jgromes/RadioLib@^6.2.0 lib_ignore = BluetoothOTA \ No newline at end of file diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index e4a60306b..cdba520d3 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -22,7 +22,7 @@ lib_deps = ${env.lib_deps} ${networking_base.lib_deps} rweather/Crypto@^0.4.0 - jgromes/RadioLib@6.1.0 + jgromes/RadioLib@^6.1.0 build_flags = ${arduino_base.build_flags} diff --git a/arch/rp2040/rp2040.ini b/arch/rp2040/rp2040.ini index f173d0af6..38acde1e0 100644 --- a/arch/rp2040/rp2040.ini +++ b/arch/rp2040/rp2040.ini @@ -20,5 +20,5 @@ lib_ignore = lib_deps = ${arduino_base.lib_deps} ${environmental_base.lib_deps} - jgromes/RadioLib@ 6.2.0 + jgromes/RadioLib@^6.2.0 rweather/Crypto \ No newline at end of file diff --git a/arch/stm32/stm32wl5e.ini b/arch/stm32/stm32wl5e.ini index ba92e0370..f563eec18 100644 --- a/arch/stm32/stm32wl5e.ini +++ b/arch/stm32/stm32wl5e.ini @@ -20,7 +20,7 @@ upload_protocol = stlink lib_deps = ${env.lib_deps} - jgromes/RadioLib@ 6.2.0 + jgromes/RadioLib@^6.2.0 https://github.com/kokke/tiny-AES-c.git#f06ac37fc31dfdaca2e0d9bec83f90d5663c319b https://github.com/littlefs-project/littlefs.git#v2.5.1 https://github.com/stm32duino/STM32FreeRTOS.git#10.3.1 From 238cf8cdebda32051e6c4c25f13710f01d67ea34 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Thu, 30 Nov 2023 11:26:48 +0100 Subject: [PATCH 016/472] fix portduino --- arch/portduino/portduino.ini | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index cdba520d3..3de602f6a 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -27,4 +27,5 @@ lib_deps = build_flags = ${arduino_base.build_flags} -fPIC - -Isrc/platform/portduino \ No newline at end of file + -Isrc/platform/portduino + -DRADIOLIB_EEPROM_UNSUPPORTED // Portduino does not implement EEPROM \ No newline at end of file From 8e742f2f8011caad4f7e5340756599fc6142eb0b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Thu, 30 Nov 2023 11:31:08 +0100 Subject: [PATCH 017/472] Update portduino.ini --- arch/portduino/portduino.ini | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index 3de602f6a..8b4ab5d4b 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -28,4 +28,5 @@ build_flags = ${arduino_base.build_flags} -fPIC -Isrc/platform/portduino - -DRADIOLIB_EEPROM_UNSUPPORTED // Portduino does not implement EEPROM \ No newline at end of file + -DRADIOLIB_EEPROM_UNSUPPORTED + From fb89482129315069bf7551a78f76a3ea30272528 Mon Sep 17 00:00:00 2001 From: S5NC <145265251+S5NC@users.noreply.github.com> Date: Thu, 30 Nov 2023 12:39:46 +0000 Subject: [PATCH 018/472] Set default LoRa SPI pins individually on ESP32 architecture (#2971) * Each pin individually * Correction --------- Co-authored-by: Jonathan Bennett Co-authored-by: Ben Meadors --- src/platform/esp32/architecture.h | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/src/platform/esp32/architecture.h b/src/platform/esp32/architecture.h index 781d41678..0686aa59f 100644 --- a/src/platform/esp32/architecture.h +++ b/src/platform/esp32/architecture.h @@ -127,12 +127,20 @@ // LoRa SPI // ----------------------------------------------------------------------------- -// NRF52 boards will define this in variant.h +// If an SPI-related pin used by the LoRa module isn't defined, use the conventional pin number for it. +// FIXME: these pins should really be defined in each variant.h file to prevent breakages if the defaults change, currently many +// ESP32 variants don't define these pins in their variant.h file. #ifndef LORA_SCK #define LORA_SCK 5 +#endif +#ifndef LORA_MISO #define LORA_MISO 19 +#endif +#ifndef LORA_MOSI #define LORA_MOSI 27 +#endif +#ifndef LORA_CS #define LORA_CS 18 #endif -#define SERIAL0_RX_GPIO 3 // Always GPIO3 on ESP32 \ No newline at end of file +#define SERIAL0_RX_GPIO 3 // Always GPIO3 on ESP32 // FIXME: may be different on ESP32-S3, etc. \ No newline at end of file From 209fb585b0acb32f5785f29f84ef3a920ef590f8 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 30 Nov 2023 20:49:00 -0600 Subject: [PATCH 019/472] Default to what G2 comes with --- src/mesh/NodeDB.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 2e6c8131e..262a19263 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -248,6 +248,12 @@ void NodeDB::installDefaultModuleConfig() #ifdef T_WATCH_S3 // Don't worry about the other settings, we'll use the DRV2056 behavior for notifications moduleConfig.external_notification.enabled = true; +#endif +#ifdef NANO_G2_ULTRA + moduleConfig.external_notification.enabled = true; + moduleConfig.external_notification.alert_message = true; + moduleConfig.external_notification.output_ms = 100; + moduleConfig.external_notification.active true; #endif moduleConfig.has_canned_message = true; From def4ec5822331ab57b07aedd873fe5b92a1e1929 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 1 Dec 2023 07:00:19 -0600 Subject: [PATCH 020/472] Always set user (nodeinfo) role to device config's current role (#2973) --- protobufs | 2 +- src/mesh/NodeDB.cpp | 3 ++- src/mesh/generated/meshtastic/deviceonly.pb.h | 4 ++-- src/mesh/generated/meshtastic/mesh.pb.h | 15 ++++++++++----- 4 files changed, 15 insertions(+), 9 deletions(-) diff --git a/protobufs b/protobufs index c845b7848..9148427a3 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit c845b7848eebb11150ca0427773303bf8758e533 +Subproject commit 9148427a3be535c9e3f17e846ecbb64ce04b6521 diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 2e6c8131e..59b6e4bf1 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -370,7 +370,6 @@ void NodeDB::installDefaultDeviceState() pickNewNodeNum(); // based on macaddr now snprintf(owner.long_name, sizeof(owner.long_name), "Meshtastic %02x%02x", ourMacAddr[4], ourMacAddr[5]); snprintf(owner.short_name, sizeof(owner.short_name), "%02x%02x", ourMacAddr[4], ourMacAddr[5]); - snprintf(owner.id, sizeof(owner.id), "!%08x", getNodeNum()); // Default node ID now based on nodenum memcpy(owner.macaddr, ourMacAddr, sizeof(owner.macaddr)); } @@ -395,6 +394,8 @@ void NodeDB::init() // Set our board type so we can share it with others owner.hw_model = HW_VENDOR; + // Ensure user (nodeinfo) role is set to whatever we're configured to + owner.role = config.device.role; // Include our owner in the node db under our nodenum meshtastic_NodeInfoLite *info = getOrCreateMeshNode(getNodeNum()); diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index ace142773..b099a3eab 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -313,8 +313,8 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg; /* Maximum encoded size of messages (where known) */ #define meshtastic_ChannelFile_size 638 -#define meshtastic_DeviceState_size 16854 -#define meshtastic_NodeInfoLite_size 151 +#define meshtastic_DeviceState_size 17056 +#define meshtastic_NodeInfoLite_size 153 #define meshtastic_NodeRemoteHardwarePin_size 29 #define meshtastic_OEMStore_size 3231 #define meshtastic_PositionLite_size 28 diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index dfaf693fc..59005db48 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -402,6 +402,8 @@ typedef struct _meshtastic_User { If this user is a licensed operator, set this flag. Also, "long_name" should be their licence number. */ bool is_licensed; + /* Indicates that the user's role in the mesh */ + meshtastic_Config_DeviceConfig_Role role; } meshtastic_User; /* A message used in our Dynamic Source Routing protocol (RFC 4728 based) */ @@ -826,6 +828,7 @@ extern "C" { #define meshtastic_Position_altitude_source_ENUMTYPE meshtastic_Position_AltSource #define meshtastic_User_hw_model_ENUMTYPE meshtastic_HardwareModel +#define meshtastic_User_role_ENUMTYPE meshtastic_Config_DeviceConfig_Role #define meshtastic_Routing_variant_error_reason_ENUMTYPE meshtastic_Routing_Error @@ -854,7 +857,7 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_Position_init_default {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN, _meshtastic_Position_AltSource_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} -#define meshtastic_User_init_default {"", "", "", {0}, _meshtastic_HardwareModel_MIN, 0} +#define meshtastic_User_init_default {"", "", "", {0}, _meshtastic_HardwareModel_MIN, 0, _meshtastic_Config_DeviceConfig_Role_MIN} #define meshtastic_RouteDiscovery_init_default {0, {0, 0, 0, 0, 0, 0, 0, 0}} #define meshtastic_Routing_init_default {0, {meshtastic_RouteDiscovery_init_default}} #define meshtastic_Data_init_default {_meshtastic_PortNum_MIN, {0, {0}}, 0, 0, 0, 0, 0, 0} @@ -872,7 +875,7 @@ extern "C" { #define meshtastic_Neighbor_init_default {0, 0, 0, 0} #define meshtastic_DeviceMetadata_init_default {"", 0, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_Role_MIN, 0, _meshtastic_HardwareModel_MIN, 0} #define meshtastic_Position_init_zero {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN, _meshtastic_Position_AltSource_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} -#define meshtastic_User_init_zero {"", "", "", {0}, _meshtastic_HardwareModel_MIN, 0} +#define meshtastic_User_init_zero {"", "", "", {0}, _meshtastic_HardwareModel_MIN, 0, _meshtastic_Config_DeviceConfig_Role_MIN} #define meshtastic_RouteDiscovery_init_zero {0, {0, 0, 0, 0, 0, 0, 0, 0}} #define meshtastic_Routing_init_zero {0, {meshtastic_RouteDiscovery_init_zero}} #define meshtastic_Data_init_zero {_meshtastic_PortNum_MIN, {0, {0}}, 0, 0, 0, 0, 0, 0} @@ -919,6 +922,7 @@ extern "C" { #define meshtastic_User_macaddr_tag 4 #define meshtastic_User_hw_model_tag 5 #define meshtastic_User_is_licensed_tag 6 +#define meshtastic_User_role_tag 7 #define meshtastic_RouteDiscovery_route_tag 1 #define meshtastic_Routing_route_request_tag 1 #define meshtastic_Routing_route_reply_tag 2 @@ -1047,7 +1051,8 @@ X(a, STATIC, SINGULAR, STRING, long_name, 2) \ X(a, STATIC, SINGULAR, STRING, short_name, 3) \ X(a, STATIC, SINGULAR, FIXED_LENGTH_BYTES, macaddr, 4) \ X(a, STATIC, SINGULAR, UENUM, hw_model, 5) \ -X(a, STATIC, SINGULAR, BOOL, is_licensed, 6) +X(a, STATIC, SINGULAR, BOOL, is_licensed, 6) \ +X(a, STATIC, SINGULAR, UENUM, role, 7) #define meshtastic_User_CALLBACK NULL #define meshtastic_User_DEFAULT NULL @@ -1280,13 +1285,13 @@ extern const pb_msgdesc_t meshtastic_DeviceMetadata_msg; #define meshtastic_MyNodeInfo_size 18 #define meshtastic_NeighborInfo_size 258 #define meshtastic_Neighbor_size 22 -#define meshtastic_NodeInfo_size 261 +#define meshtastic_NodeInfo_size 263 #define meshtastic_Position_size 137 #define meshtastic_QueueStatus_size 23 #define meshtastic_RouteDiscovery_size 40 #define meshtastic_Routing_size 42 #define meshtastic_ToRadio_size 504 -#define meshtastic_User_size 77 +#define meshtastic_User_size 79 #define meshtastic_Waypoint_size 165 #ifdef __cplusplus From a05bab35ad3b163871880c9d3c00dd53b7be8567 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 1 Dec 2023 07:17:38 -0600 Subject: [PATCH 021/472] = --- src/mesh/NodeDB.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index f2505bb0d..cb5c27b49 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -253,7 +253,7 @@ void NodeDB::installDefaultModuleConfig() moduleConfig.external_notification.enabled = true; moduleConfig.external_notification.alert_message = true; moduleConfig.external_notification.output_ms = 100; - moduleConfig.external_notification.active true; + moduleConfig.external_notification.active = true; #endif moduleConfig.has_canned_message = true; From 6e967421a5a12da3c41365c968ce980898edabd8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Tue, 22 Aug 2023 16:23:02 +0200 Subject: [PATCH 022/472] UI/UX: Display delivered message on incoming ACK. Needs more work --- src/modules/CannedMessageModule.cpp | 28 ++++++++++++++++++++++++++-- src/modules/CannedMessageModule.h | 28 +++++++++++++++++++++++++--- 2 files changed, 51 insertions(+), 5 deletions(-) diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index ade9d0e5a..f85a7b1fd 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -244,7 +244,8 @@ int32_t CannedMessageModule::runOnce() } // LOG_DEBUG("Check status\n"); UIFrameEvent e = {false, true}; - if (this->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE) { + if ((this->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE) || + (this->runState == CANNED_MESSAGE_RUN_STATE_ACK_RECEIVED)) { // TODO: might have some feedback of sendig state this->runState = CANNED_MESSAGE_RUN_STATE_INACTIVE; e.frameChanged = true; @@ -483,7 +484,12 @@ void CannedMessageModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *st { char buffer[50]; - if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE) { + if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_ACK_RECEIVED) { + display->setTextAlignment(TEXT_ALIGN_CENTER); + display->setFont(FONT_MEDIUM); + display->drawStringf(display->getWidth() / 2 + x, 0 + y + 12, buffer, "Delivered to %s", + cannedMessageModule->getNodeName(this->incoming)); + } else if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE) { display->setTextAlignment(TEXT_ALIGN_CENTER); display->setFont(FONT_MEDIUM); display->drawString(display->getWidth() / 2 + x, 0 + y + 12, "Sending..."); @@ -546,6 +552,24 @@ void CannedMessageModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *st } } +ProcessMessage CannedMessageModule::handleReceived(const meshtastic_MeshPacket &mp) +{ + if (mp.decoded.portnum == meshtastic_PortNum_ROUTING_APP) { + // look for a request_id + if (mp.decoded.request_id != 0) { + UIFrameEvent e = {false, true}; + e.frameChanged = true; + this->runState = CANNED_MESSAGE_RUN_STATE_ACK_RECEIVED; + this->incoming = mp.decoded.request_id; + this->notifyObservers(&e); + // run the next time 2 seconds later + setIntervalFromNow(2000); + } + } + + return ProcessMessage::CONTINUE; +} + void CannedMessageModule::loadProtoForModule() { if (!nodeDB.loadProto(cannedMessagesConfigFile, meshtastic_CannedMessageModuleConfig_size, diff --git a/src/modules/CannedMessageModule.h b/src/modules/CannedMessageModule.h index 98467215e..a2abcff89 100644 --- a/src/modules/CannedMessageModule.h +++ b/src/modules/CannedMessageModule.h @@ -9,6 +9,7 @@ enum cannedMessageModuleRunState { CANNED_MESSAGE_RUN_STATE_ACTIVE, CANNED_MESSAGE_RUN_STATE_FREETEXT, CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE, + CANNED_MESSAGE_RUN_STATE_ACK_RECEIVED, CANNED_MESSAGE_RUN_STATE_ACTION_SELECT, CANNED_MESSAGE_RUN_STATE_ACTION_UP, CANNED_MESSAGE_RUN_STATE_ACTION_DOWN, @@ -37,15 +38,29 @@ class CannedMessageModule : public SinglePortModule, public Observabledecoded.portnum) { + case meshtastic_PortNum_TEXT_MESSAGE_APP: + case meshtastic_PortNum_ROUTING_APP: + return true; + default: + return false; + } + } + protected: virtual int32_t runOnce() override; @@ -63,6 +78,12 @@ class CannedMessageModule : public SinglePortModule, public Observable Date: Tue, 22 Aug 2023 20:29:52 +0200 Subject: [PATCH 023/472] Distinguish between ACK/NAK by checking for error reason --- src/modules/CannedMessageModule.cpp | 12 ++++++++++-- src/modules/CannedMessageModule.h | 3 ++- 2 files changed, 12 insertions(+), 3 deletions(-) diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index f85a7b1fd..3bca5edaa 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -487,7 +487,12 @@ void CannedMessageModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *st if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_ACK_RECEIVED) { display->setTextAlignment(TEXT_ALIGN_CENTER); display->setFont(FONT_MEDIUM); - display->drawStringf(display->getWidth() / 2 + x, 0 + y + 12, buffer, "Delivered to %s", + String displayString; + if (this->ack) + displayString = "Delivered to\n%s"; + else + displayString = "Delivery failed\nto %s"; + display->drawStringf(display->getWidth() / 2 + x, 0 + y + 12, buffer, displayString, cannedMessageModule->getNodeName(this->incoming)); } else if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE) { display->setTextAlignment(TEXT_ALIGN_CENTER); @@ -561,6 +566,9 @@ ProcessMessage CannedMessageModule::handleReceived(const meshtastic_MeshPacket & e.frameChanged = true; this->runState = CANNED_MESSAGE_RUN_STATE_ACK_RECEIVED; this->incoming = mp.decoded.request_id; + meshtastic_Routing decoded = meshtastic_Routing_init_default; + pb_decode_from_bytes(mp.decoded.payload.bytes, mp.decoded.payload.size, meshtastic_Routing_fields, &decoded); + this->ack = decoded.error_reason == meshtastic_Routing_Error_NONE; this->notifyObservers(&e); // run the next time 2 seconds later setIntervalFromNow(2000); @@ -674,4 +682,4 @@ String CannedMessageModule::drawWithCursor(String text, int cursor) return result; } -#endif +#endif \ No newline at end of file diff --git a/src/modules/CannedMessageModule.h b/src/modules/CannedMessageModule.h index a2abcff89..8a53d392e 100644 --- a/src/modules/CannedMessageModule.h +++ b/src/modules/CannedMessageModule.h @@ -97,6 +97,7 @@ class CannedMessageModule : public SinglePortModule, public Observable Date: Sat, 2 Dec 2023 12:30:00 +0000 Subject: [PATCH 024/472] Update Power.cpp (#2979) --- src/Power.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/Power.cpp b/src/Power.cpp index 0a56a1ba2..0fa97b7f0 100644 --- a/src/Power.cpp +++ b/src/Power.cpp @@ -435,7 +435,7 @@ void Power::shutdown() ledOff(PIN_LED2); #endif #ifdef PIN_LED3 - ledOff(PIN_LED2); + ledOff(PIN_LED3); #endif doDeepSleep(DELAY_FOREVER, false); #endif @@ -897,4 +897,4 @@ bool Power::axpChipInit() #else return false; #endif -} \ No newline at end of file +} From 1b6c11c5f1701f8a7cf04daadbfe82b2c386d7c6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sat, 2 Dec 2023 14:00:20 +0100 Subject: [PATCH 025/472] tryfix crash (#2964) * tryfix crash * only use this when wifi is not enabled. (poking around) --------- Co-authored-by: Ben Meadors --- src/mesh/MeshService.cpp | 4 +++- src/nimble/NimbleBluetooth.cpp | 8 +++++--- 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/src/mesh/MeshService.cpp b/src/mesh/MeshService.cpp index 44094f1bb..4fd9523c0 100644 --- a/src/mesh/MeshService.cpp +++ b/src/mesh/MeshService.cpp @@ -320,7 +320,9 @@ meshtastic_NodeInfoLite *MeshService::refreshLocalMeshNode() position.time = getValidTime(RTCQualityFromNet); - updateBatteryLevel(powerStatus->getBatteryChargePercent()); + if (powerStatus->getHasBattery() == 1) { + updateBatteryLevel(powerStatus->getBatteryChargePercent()); + } return node; } diff --git a/src/nimble/NimbleBluetooth.cpp b/src/nimble/NimbleBluetooth.cpp index 3175e0f09..0b2a806c9 100644 --- a/src/nimble/NimbleBluetooth.cpp +++ b/src/nimble/NimbleBluetooth.cpp @@ -186,7 +186,7 @@ void NimbleBluetooth::setupService() // Setup the battery service NimBLEService *batteryService = bleServer->createService(NimBLEUUID((uint16_t)0x180f)); // 0x180F is the Battery Service BatteryCharacteristic = batteryService->createCharacteristic( // 0x2A19 is the Battery Level characteristic) - (uint16_t)0x2a19, NIMBLE_PROPERTY::READ | NIMBLE_PROPERTY::NOTIFY); + (uint16_t)0x2a19, NIMBLE_PROPERTY::READ | NIMBLE_PROPERTY::NOTIFY, 1); NimBLE2904 *batteryLevelDescriptor = (NimBLE2904 *)BatteryCharacteristic->createDescriptor((uint16_t)0x2904); batteryLevelDescriptor->setFormat(NimBLE2904::FORMAT_UINT8); @@ -208,8 +208,10 @@ void NimbleBluetooth::startAdvertising() /// Given a level between 0-100, update the BLE attribute void updateBatteryLevel(uint8_t level) { - BatteryCharacteristic->setValue(&level, 1); - BatteryCharacteristic->notify(); + if ((config.bluetooth.enabled == true) && bleServer && nimbleBluetooth->isConnected()) { + BatteryCharacteristic->setValue(&level, 1); + BatteryCharacteristic->notify(); + } } void NimbleBluetooth::clearBonds() From 2544733ad40769b8dec528309ae7d3c2459f8c2a Mon Sep 17 00:00:00 2001 From: S5NC <145265251+S5NC@users.noreply.github.com> Date: Sat, 2 Dec 2023 13:40:31 +0000 Subject: [PATCH 026/472] Standardise order for setting GPIO pin default values (#2942) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Update SX126xInterface.cpp * Update GPS.cpp * Update TFTDisplay.cpp * Update SX128xInterface.cpp * Update EInkDisplay2.cpp * trunk fmt --------- Co-authored-by: Ben Meadors Co-authored-by: Thomas Göttgens --- src/gps/GPS.cpp | 12 ++++++------ src/graphics/EInkDisplay2.cpp | 6 +++--- src/graphics/TFTDisplay.cpp | 8 ++++---- src/mesh/SX126xInterface.cpp | 2 +- src/mesh/SX128xInterface.cpp | 6 +++--- 5 files changed, 17 insertions(+), 17 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 7ea36c860..f51fb0588 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -495,14 +495,14 @@ void GPS::setGPSPower(bool on, bool standbyOnly, uint32_t sleepTime) #ifdef PIN_GPS_STANDBY // Specifically the standby pin for L76K and clones if (on) { LOG_INFO("Waking GPS"); - digitalWrite(PIN_GPS_STANDBY, 1); pinMode(PIN_GPS_STANDBY, OUTPUT); + digitalWrite(PIN_GPS_STANDBY, 1); return; } else { LOG_INFO("GPS entering sleep"); // notifyGPSSleep.notifyObservers(NULL); - digitalWrite(PIN_GPS_STANDBY, 0); pinMode(PIN_GPS_STANDBY, OUTPUT); + digitalWrite(PIN_GPS_STANDBY, 0); return; } #endif @@ -920,8 +920,8 @@ GPS *GPS::createGps() if (_en_gpio != 0) { LOG_DEBUG("Setting %d to output.\n", _en_gpio); - digitalWrite(_en_gpio, !GPS_EN_ACTIVE); pinMode(_en_gpio, OUTPUT); + digitalWrite(_en_gpio, !GPS_EN_ACTIVE); } #ifdef PIN_GPS_PPS @@ -941,8 +941,8 @@ GPS *GPS::createGps() new_gps->setGPSPower(true, false, 0); #ifdef PIN_GPS_RESET - digitalWrite(PIN_GPS_RESET, GPS_RESET_MODE); // assert for 10ms pinMode(PIN_GPS_RESET, OUTPUT); + digitalWrite(PIN_GPS_RESET, GPS_RESET_MODE); // assert for 10ms delay(10); digitalWrite(PIN_GPS_RESET, !GPS_RESET_MODE); #endif @@ -987,8 +987,8 @@ bool GPS::factoryReset() { #ifdef PIN_GPS_REINIT // The L76K GNSS on the T-Echo requires the RESET pin to be pulled LOW - digitalWrite(PIN_GPS_REINIT, 0); pinMode(PIN_GPS_REINIT, OUTPUT); + digitalWrite(PIN_GPS_REINIT, 0); delay(150); // The L76K datasheet calls for at least 100MS delay digitalWrite(PIN_GPS_REINIT, 1); #endif @@ -1268,4 +1268,4 @@ int32_t GPS::disable() setAwake(false); return INT32_MAX; -} \ No newline at end of file +} diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index 61d0eea5a..3b97dd723 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -46,7 +46,7 @@ #define TECHO_DISPLAY_MODEL GxEPD2_154_M09 #elif defined(HELTEC_WIRELESS_PAPER) -//#define TECHO_DISPLAY_MODEL GxEPD2_213_T5D +// #define TECHO_DISPLAY_MODEL GxEPD2_213_T5D #define TECHO_DISPLAY_MODEL GxEPD2_213_BN #endif @@ -193,14 +193,14 @@ bool EInkDisplay::connect() LOG_INFO("Doing EInk init\n"); #ifdef PIN_EINK_PWR_ON - digitalWrite(PIN_EINK_PWR_ON, HIGH); // If we need to assert a pin to power external peripherals pinMode(PIN_EINK_PWR_ON, OUTPUT); + digitalWrite(PIN_EINK_PWR_ON, HIGH); // If we need to assert a pin to power external peripherals #endif #ifdef PIN_EINK_EN // backlight power, HIGH is backlight on, LOW is off - digitalWrite(PIN_EINK_EN, LOW); pinMode(PIN_EINK_EN, OUTPUT); + digitalWrite(PIN_EINK_EN, LOW); #endif #if defined(TTGO_T_ECHO) diff --git a/src/graphics/TFTDisplay.cpp b/src/graphics/TFTDisplay.cpp index 63db8120a..618880a5c 100644 --- a/src/graphics/TFTDisplay.cpp +++ b/src/graphics/TFTDisplay.cpp @@ -478,8 +478,8 @@ bool TFTDisplay::connect() LOG_INFO("Doing TFT init\n"); #ifdef TFT_BL - digitalWrite(TFT_BL, TFT_BACKLIGHT_ON); pinMode(TFT_BL, OUTPUT); + digitalWrite(TFT_BL, TFT_BACKLIGHT_ON); // pinMode(PIN_3V3_EN, OUTPUT); // digitalWrite(PIN_3V3_EN, HIGH); LOG_INFO("Power to TFT Backlight\n"); @@ -487,11 +487,11 @@ bool TFTDisplay::connect() #ifdef ST7735_BACKLIGHT_EN_V03 if (heltec_version == 3) { - digitalWrite(ST7735_BACKLIGHT_EN_V03, TFT_BACKLIGHT_ON); pinMode(ST7735_BACKLIGHT_EN_V03, OUTPUT); + digitalWrite(ST7735_BACKLIGHT_EN_V03, TFT_BACKLIGHT_ON); } else { - digitalWrite(ST7735_BACKLIGHT_EN_V05, TFT_BACKLIGHT_ON); pinMode(ST7735_BACKLIGHT_EN_V05, OUTPUT); + digitalWrite(ST7735_BACKLIGHT_EN_V05, TFT_BACKLIGHT_ON); } #endif @@ -515,4 +515,4 @@ bool TFTDisplay::connect() return true; } -#endif \ No newline at end of file +#endif diff --git a/src/mesh/SX126xInterface.cpp b/src/mesh/SX126xInterface.cpp index 30951cd16..0692d1ef1 100644 --- a/src/mesh/SX126xInterface.cpp +++ b/src/mesh/SX126xInterface.cpp @@ -26,8 +26,8 @@ SX126xInterface::SX126xInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs template bool SX126xInterface::init() { #ifdef SX126X_POWER_EN - digitalWrite(SX126X_POWER_EN, HIGH); pinMode(SX126X_POWER_EN, OUTPUT); + digitalWrite(SX126X_POWER_EN, HIGH); #endif // FIXME: correct logic to default to not using TCXO if no voltage is specified for SX126X_DIO3_TCXO_VOLTAGE diff --git a/src/mesh/SX128xInterface.cpp b/src/mesh/SX128xInterface.cpp index 1916c8042..0c5c4dcfa 100644 --- a/src/mesh/SX128xInterface.cpp +++ b/src/mesh/SX128xInterface.cpp @@ -22,8 +22,8 @@ SX128xInterface::SX128xInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs template bool SX128xInterface::init() { #ifdef SX128X_POWER_EN - digitalWrite(SX128X_POWER_EN, HIGH); pinMode(SX128X_POWER_EN, OUTPUT); + digitalWrite(SX128X_POWER_EN, HIGH); #endif #ifdef RF95_FAN_EN @@ -32,12 +32,12 @@ template bool SX128xInterface::init() #endif #if defined(SX128X_RXEN) && (SX128X_RXEN != RADIOLIB_NC) // set not rx or tx mode - digitalWrite(SX128X_RXEN, LOW); // Set low before becoming an output pinMode(SX128X_RXEN, OUTPUT); + digitalWrite(SX128X_RXEN, LOW); // Set low before becoming an output #endif #if defined(SX128X_TXEN) && (SX128X_TXEN != RADIOLIB_NC) - digitalWrite(SX128X_TXEN, LOW); pinMode(SX128X_TXEN, OUTPUT); + digitalWrite(SX128X_TXEN, LOW); #endif RadioLibInterface::init(); From 9e90b4af027daa618ada9c7fa25043ac04d139e8 Mon Sep 17 00:00:00 2001 From: S5NC <145265251+S5NC@users.noreply.github.com> Date: Sat, 2 Dec 2023 13:46:25 +0000 Subject: [PATCH 027/472] Update variant.h (#2930) Co-authored-by: Ben Meadors --- variants/diy/hydra/variant.h | 1 + 1 file changed, 1 insertion(+) diff --git a/variants/diy/hydra/variant.h b/variants/diy/hydra/variant.h index a51b21653..60bb60beb 100644 --- a/variants/diy/hydra/variant.h +++ b/variants/diy/hydra/variant.h @@ -18,6 +18,7 @@ // Radio #define USE_SX1262 // E22-900M30S uses SX1262 +#define USE_SX1268 // E22-400M30S uses SX1268 #define SX126X_MAX_POWER \ 22 // Outputting 22dBm from SX1262 results in ~30dBm E22-900M30S output (module only uses last stage of the YP2233W PA) #define SX126X_DIO3_TCXO_VOLTAGE 1.8 // E22 series TCXO reference voltage is 1.8V From 6ff61b3e04ec583f679db658772fe6ed37315e69 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Sat, 2 Dec 2023 21:47:52 +0100 Subject: [PATCH 028/472] Pico W: Initial Wi-Fi support (#2980) * Pico W: Initial WiFi support: connects, but freezes after a while * Update arduino-pico core to fix hang with Wi-Fi * Add `picow` to workflow since it's different from `pico` now --- .github/workflows/main_matrix.yml | 1 + arch/nrf52/nrf52.ini | 2 +- arch/portduino/portduino.ini | 1 + arch/rp2040/rp2040.ini | 6 +- arch/stm32/stm32wl5e.ini | 2 +- src/graphics/Screen.cpp | 11 +- src/main.cpp | 11 +- src/mesh/NodeDB.cpp | 2 +- src/mesh/api/WiFiServerAPI.h | 2 +- src/mesh/http/ContentHandler.cpp | 2 +- src/mesh/http/ContentHandler.h | 3 +- src/mesh/http/ContentHelper.cpp | 4 +- src/mesh/http/WebServer.cpp | 4 +- src/mesh/{http => wifi}/WiFiAPClient.cpp | 194 +++++++++++++---------- src/mesh/{http => wifi}/WiFiAPClient.h | 4 +- src/modules/AdminModule.h | 6 +- src/mqtt/MQTT.cpp | 2 +- src/platform/esp32/main-esp32.cpp | 2 +- src/sleep.cpp | 2 +- variants/rpipicow/platformio.ini | 6 +- variants/rpipicow/variant.h | 6 +- 21 files changed, 154 insertions(+), 119 deletions(-) rename src/mesh/{http => wifi}/WiFiAPClient.cpp (94%) rename src/mesh/{http => wifi}/WiFiAPClient.h (79%) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 6b6ff1ad7..e53c35bd2 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -123,6 +123,7 @@ jobs: matrix: include: - board: pico + - board: picow - board: rak11310 uses: ./.github/workflows/build_rpi2040.yml with: diff --git a/arch/nrf52/nrf52.ini b/arch/nrf52/nrf52.ini index 1a3631420..5da571cce 100644 --- a/arch/nrf52/nrf52.ini +++ b/arch/nrf52/nrf52.ini @@ -11,7 +11,7 @@ build_flags = -Isrc/platform/nrf52 build_src_filter = - ${arduino_base.build_src_filter} - - - - - - - - + ${arduino_base.build_src_filter} - - - - - - - - - lib_deps= ${arduino_base.lib_deps} diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index 8b4ab5d4b..c4b6d5377 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -10,6 +10,7 @@ build_src_filter = - - - + - - - - diff --git a/arch/rp2040/rp2040.ini b/arch/rp2040/rp2040.ini index 38acde1e0..7674fbd52 100644 --- a/arch/rp2040/rp2040.ini +++ b/arch/rp2040/rp2040.ini @@ -1,8 +1,8 @@ ; Common settings for rp2040 Processor based targets [rp2040_base] -platform = https://github.com/maxgerhardt/platform-raspberrypi.git#0c33219f53faa035e188925ea1324f472e8b93d2 +platform = https://github.com/maxgerhardt/platform-raspberrypi.git#612de5399d68b359053f1307ed223d400aea975c extends = arduino_base -platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#3.2.2 +platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#d2461a14ad5aa920e44508d236c2f459e3befbf8 board_build.core = earlephilhower board_build.filesystem_size = 0.5m @@ -12,7 +12,7 @@ build_flags = -D__PLAT_RP2040__ # -D _POSIX_THREADS build_src_filter = - ${arduino_base.build_src_filter} - - - - - - - - + ${arduino_base.build_src_filter} - - - - - - - - lib_ignore = BluetoothOTA diff --git a/arch/stm32/stm32wl5e.ini b/arch/stm32/stm32wl5e.ini index f563eec18..cac7110f2 100644 --- a/arch/stm32/stm32wl5e.ini +++ b/arch/stm32/stm32wl5e.ini @@ -13,7 +13,7 @@ build_flags = -DVECT_TAB_OFFSET=0x08000000 build_src_filter = - ${arduino_base.build_src_filter} - - - - - - - - - - - - + ${arduino_base.build_src_filter} - - - - - - - - - - - - - board_upload.offset_address = 0x08000000 upload_protocol = stlink diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 2e144e41a..e75a432d4 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -45,7 +45,7 @@ along with this program. If not, see . #ifdef ARCH_ESP32 #include "esp_task_wdt.h" -#include "mesh/http/WiFiAPClient.h" +#include "mesh/wifi/WiFiAPClient.h" #include "modules/esp32/StoreForwardModule.h" #endif @@ -1618,12 +1618,19 @@ void DebugInfo::drawFrameWiFi(OLEDDisplay *display, OLEDDisplayUiState *state, i display->drawString(x, y + FONT_HEIGHT_SMALL * 1, "Connection Failed"); } else if (WiFi.status() == WL_IDLE_STATUS) { display->drawString(x, y + FONT_HEIGHT_SMALL * 1, "Idle ... Reconnecting"); - } else { + } +#ifdef ARCH_ESP32 + else { // Codes: // https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-guides/wifi.html#wi-fi-reason-code display->drawString(x, y + FONT_HEIGHT_SMALL * 1, WiFi.disconnectReasonName(static_cast(getWifiDisconnectReason()))); } +#else + else { + display->drawString(x, y + FONT_HEIGHT_SMALL * 1, "Unkown status: " + String(WiFi.status())); + } +#endif display->drawString(x, y + FONT_HEIGHT_SMALL * 2, "SSID: " + String(wifiName)); diff --git a/src/main.cpp b/src/main.cpp index 5cea142bc..b3671c020 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -32,9 +32,6 @@ #include // #include -#include "mesh/eth/ethClient.h" -#include "mesh/http/WiFiAPClient.h" - #ifdef ARCH_ESP32 #include "mesh/http/WebServer.h" #include "nimble/NimbleBluetooth.h" @@ -48,10 +45,12 @@ NRF52Bluetooth *nrf52Bluetooth; #if HAS_WIFI #include "mesh/api/WiFiServerAPI.h" +#include "mesh/wifi/WiFiAPClient.h" #endif #if HAS_ETHERNET #include "mesh/api/ethServerAPI.h" +#include "mesh/eth/ethClient.h" #endif #include "mqtt/MQTT.h" @@ -835,11 +834,15 @@ void setup() #ifndef ARCH_PORTDUINO // Initialize Wifi +#if HAS_WIFI initWifi(); +#endif +#if HAS_ETHERNET // Initialize Ethernet initEthernet(); #endif +#endif #ifdef ARCH_ESP32 // Start web server thread. @@ -938,4 +941,4 @@ void loop() mainDelay.delay(delayMsec); } // if (didWake) LOG_DEBUG("wake!\n"); -} \ No newline at end of file +} diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index cb5c27b49..bb079e5c0 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -21,7 +21,7 @@ #include #ifdef ARCH_ESP32 -#include "mesh/http/WiFiAPClient.h" +#include "mesh/wifi/WiFiAPClient.h" #include "modules/esp32/StoreForwardModule.h" #include #include diff --git a/src/mesh/api/WiFiServerAPI.h b/src/mesh/api/WiFiServerAPI.h index 11b494d23..e436a177d 100644 --- a/src/mesh/api/WiFiServerAPI.h +++ b/src/mesh/api/WiFiServerAPI.h @@ -22,4 +22,4 @@ class WiFiServerPort : public APIServerPort explicit WiFiServerPort(int port); }; -void initApiServer(int port = 4403); +void initApiServer(int port = 4403); \ No newline at end of file diff --git a/src/mesh/http/ContentHandler.cpp b/src/mesh/http/ContentHandler.cpp index 2ea2a76a5..4ca37a256 100644 --- a/src/mesh/http/ContentHandler.cpp +++ b/src/mesh/http/ContentHandler.cpp @@ -5,7 +5,7 @@ #include "main.h" #include "mesh/http/ContentHelper.h" #include "mesh/http/WebServer.h" -#include "mesh/http/WiFiAPClient.h" +#include "mesh/wifi/WiFiAPClient.h" #include "mqtt/JSON.h" #include "power.h" #include "sleep.h" diff --git a/src/mesh/http/ContentHandler.h b/src/mesh/http/ContentHandler.h index 903d5ee08..987e3ffef 100644 --- a/src/mesh/http/ContentHandler.h +++ b/src/mesh/http/ContentHandler.h @@ -1,5 +1,4 @@ #pragma once - void registerHandlers(HTTPServer *insecureServer, HTTPSServer *secureServer); // Declare some handler functions for the various URLs on the server @@ -34,4 +33,4 @@ class HttpAPI : public PhoneAPI protected: /// Check the current underlying physical link to see if the client is currently connected virtual bool checkIsConnected() override { return true; } // FIXME, be smarter about this -}; +}; \ No newline at end of file diff --git a/src/mesh/http/ContentHelper.cpp b/src/mesh/http/ContentHelper.cpp index 249dcbde6..8f283932b 100644 --- a/src/mesh/http/ContentHelper.cpp +++ b/src/mesh/http/ContentHelper.cpp @@ -1,6 +1,6 @@ #include "mesh/http/ContentHelper.h" -//#include -//#include "main.h" +// #include +// #include "main.h" void replaceAll(std::string &str, const std::string &from, const std::string &to) { diff --git a/src/mesh/http/WebServer.cpp b/src/mesh/http/WebServer.cpp index 2b045c0be..7814f2c29 100644 --- a/src/mesh/http/WebServer.cpp +++ b/src/mesh/http/WebServer.cpp @@ -2,7 +2,7 @@ #include "NodeDB.h" #include "graphics/Screen.h" #include "main.h" -#include "mesh/http/WiFiAPClient.h" +#include "mesh/wifi/WiFiAPClient.h" #include "sleep.h" #include #include @@ -210,4 +210,4 @@ void initWebServer() } else { LOG_ERROR("Web Servers Failed! ;-( \n"); } -} +} \ No newline at end of file diff --git a/src/mesh/http/WiFiAPClient.cpp b/src/mesh/wifi/WiFiAPClient.cpp similarity index 94% rename from src/mesh/http/WiFiAPClient.cpp rename to src/mesh/wifi/WiFiAPClient.cpp index cc8d4b168..06573fd60 100644 --- a/src/mesh/http/WiFiAPClient.cpp +++ b/src/mesh/wifi/WiFiAPClient.cpp @@ -1,17 +1,22 @@ -#include "mesh/http/WiFiAPClient.h" +#include "mesh/wifi/WiFiAPClient.h" #include "NodeDB.h" #include "RTC.h" #include "concurrency/Periodic.h" #include "configuration.h" #include "main.h" #include "mesh/api/WiFiServerAPI.h" -#include "mesh/http/WebServer.h" #include "mqtt/MQTT.h" #include "target_specific.h" -#include #include #include +#ifndef ARCH_RP2040 +#include "mesh/http/WebServer.h" +#include #include +static void WiFiEvent(WiFiEvent_t event); +#else +#include +#endif #ifndef DISABLE_NTP #include @@ -19,8 +24,6 @@ using namespace concurrency; -static void WiFiEvent(WiFiEvent_t event); - // NTP WiFiUDP ntpUDP; @@ -44,78 +47,6 @@ Syslog syslog(syslogClient); Periodic *wifiReconnect; -static int32_t reconnectWiFi() -{ - const char *wifiName = config.network.wifi_ssid; - const char *wifiPsw = config.network.wifi_psk; - - if (config.network.wifi_enabled && needReconnect) { - - if (!*wifiPsw) // Treat empty password as no password - wifiPsw = NULL; - - needReconnect = false; - - // Make sure we clear old connection credentials - WiFi.disconnect(false, true); - LOG_INFO("Reconnecting to WiFi access point %s\n", wifiName); - - delay(5000); - - if (!WiFi.isConnected()) { - WiFi.begin(wifiName, wifiPsw); - } - } - -#ifndef DISABLE_NTP - if (WiFi.isConnected() && (((millis() - lastrun_ntp) > 43200000) || (lastrun_ntp == 0))) { // every 12 hours - LOG_DEBUG("Updating NTP time from %s\n", config.network.ntp_server); - if (timeClient.update()) { - LOG_DEBUG("NTP Request Success - Setting RTCQualityNTP if needed\n"); - - struct timeval tv; - tv.tv_sec = timeClient.getEpochTime(); - tv.tv_usec = 0; - - perhapsSetRTC(RTCQualityNTP, &tv); - lastrun_ntp = millis(); - - } else { - LOG_DEBUG("NTP Update failed\n"); - } - } -#endif - - if (config.network.wifi_enabled && !WiFi.isConnected()) { - return 1000; // check once per second - } else { - return 300000; // every 5 minutes - } -} - -bool isWifiAvailable() -{ - - if (config.network.wifi_enabled && (config.network.wifi_ssid[0])) { - return true; - } else { - return false; - } -} - -// Disable WiFi -void deinitWifi() -{ - LOG_INFO("WiFi deinit\n"); - - if (isWifiAvailable()) { - WiFi.disconnect(true); - WiFi.mode(WIFI_MODE_NULL); - LOG_INFO("WiFi Turned Off\n"); - // WiFi.printDiag(Serial); - } -} - static void onNetworkConnected() { if (!APStartupComplete) { @@ -158,7 +89,9 @@ static void onNetworkConnected() syslog.enable(); } +#ifndef ARCH_RP2040 initWebServer(); +#endif initApiServer(); APStartupComplete = true; @@ -169,6 +102,89 @@ static void onNetworkConnected() mqtt->reconnect(); } +static int32_t reconnectWiFi() +{ + const char *wifiName = config.network.wifi_ssid; + const char *wifiPsw = config.network.wifi_psk; + + if (config.network.wifi_enabled && needReconnect) { + + if (!*wifiPsw) // Treat empty password as no password + wifiPsw = NULL; + + needReconnect = false; + + // Make sure we clear old connection credentials +#ifdef ARCH_ESP32 + WiFi.disconnect(false, true); +#else + WiFi.disconnect(false); +#endif + LOG_INFO("Reconnecting to WiFi access point %s\n", wifiName); + + delay(5000); + + if (!WiFi.isConnected()) { + WiFi.begin(wifiName, wifiPsw); + } + } + +#ifndef DISABLE_NTP + if (WiFi.isConnected() && (((millis() - lastrun_ntp) > 43200000) || (lastrun_ntp == 0))) { // every 12 hours + LOG_DEBUG("Updating NTP time from %s\n", config.network.ntp_server); + if (timeClient.update()) { + LOG_DEBUG("NTP Request Success - Setting RTCQualityNTP if needed\n"); + + struct timeval tv; + tv.tv_sec = timeClient.getEpochTime(); + tv.tv_usec = 0; + + perhapsSetRTC(RTCQualityNTP, &tv); + lastrun_ntp = millis(); + + } else { + LOG_DEBUG("NTP Update failed\n"); + } + } +#endif + + if (config.network.wifi_enabled && !WiFi.isConnected()) { + return 1000; // check once per second + } else { +#ifdef ARCH_RP2040 + onNetworkConnected(); // will only do anything once +#endif + return 300000; // every 5 minutes + } +} + +bool isWifiAvailable() +{ + + if (config.network.wifi_enabled && (config.network.wifi_ssid[0])) { + return true; + } else { + return false; + } +} + +// Disable WiFi +void deinitWifi() +{ + LOG_INFO("WiFi deinit\n"); + + if (isWifiAvailable()) { +#ifdef ARCH_ESP32 + WiFi.disconnect(true, false); +#else + WiFi.disconnect(true); +#endif + WiFi.mode(WIFI_OFF); + LOG_INFO("WiFi Turned Off\n"); + // WiFi.printDiag(Serial); + } +} + // Startup WiFi bool initWifi() { @@ -177,10 +193,10 @@ bool initWifi() const char *wifiName = config.network.wifi_ssid; const char *wifiPsw = config.network.wifi_psk; - createSSLCert(); - +#ifndef ARCH_RP2040 + createSSLCert(); // For WebServer esp_wifi_set_storage(WIFI_STORAGE_RAM); // Disable flash storage for WiFi credentials - +#endif if (!*wifiPsw) // Treat empty password as no password wifiPsw = NULL; @@ -189,17 +205,17 @@ bool initWifi() getMacAddr(dmac); snprintf(ourHost, sizeof(ourHost), "Meshtastic-%02x%02x", dmac[4], dmac[5]); - WiFi.mode(WIFI_MODE_STA); + WiFi.mode(WIFI_STA); WiFi.setHostname(ourHost); - WiFi.onEvent(WiFiEvent); - WiFi.setAutoReconnect(true); - WiFi.setSleep(false); if (config.network.address_mode == meshtastic_Config_NetworkConfig_AddressMode_STATIC && config.network.ipv4_config.ip != 0) { WiFi.config(config.network.ipv4_config.ip, config.network.ipv4_config.gateway, config.network.ipv4_config.subnet, - config.network.ipv4_config.dns, - config.network.ipv4_config.dns); // Wifi wants two DNS servers... set both to the same value + config.network.ipv4_config.dns); } +#ifndef ARCH_RP2040 + WiFi.onEvent(WiFiEvent); + WiFi.setAutoReconnect(true); + WiFi.setSleep(false); // This is needed to improve performance. esp_wifi_set_ps(WIFI_PS_NONE); // Disable radio power saving @@ -218,7 +234,7 @@ bool initWifi() wifiDisconnectReason = info.wifi_sta_disconnected.reason; }, WiFiEvent_t::ARDUINO_EVENT_WIFI_STA_DISCONNECTED); - +#endif LOG_DEBUG("JOINING WIFI soon: ssid=%s\n", wifiName); wifiReconnect = new Periodic("WifiConnect", reconnectWiFi); } @@ -229,6 +245,7 @@ bool initWifi() } } +#ifndef ARCH_RP2040 // Called by the Espressif SDK to static void WiFiEvent(WiFiEvent_t event) { @@ -369,8 +386,9 @@ static void WiFiEvent(WiFiEvent_t event) break; } } +#endif uint8_t getWifiDisconnectReason() { return wifiDisconnectReason; -} +} \ No newline at end of file diff --git a/src/mesh/http/WiFiAPClient.h b/src/mesh/wifi/WiFiAPClient.h similarity index 79% rename from src/mesh/http/WiFiAPClient.h rename to src/mesh/wifi/WiFiAPClient.h index 0c08c567b..6625d3e46 100644 --- a/src/mesh/http/WiFiAPClient.h +++ b/src/mesh/wifi/WiFiAPClient.h @@ -5,7 +5,7 @@ #include #include -#ifdef ARCH_ESP32 +#if defined(HAS_WIFI) && !defined(ARCH_PORTDUINO) #include #endif @@ -19,4 +19,4 @@ void deinitWifi(); bool isWifiAvailable(); -uint8_t getWifiDisconnectReason(); +uint8_t getWifiDisconnectReason(); \ No newline at end of file diff --git a/src/modules/AdminModule.h b/src/modules/AdminModule.h index eb06e7b83..6ecc88829 100644 --- a/src/modules/AdminModule.h +++ b/src/modules/AdminModule.h @@ -1,7 +1,7 @@ #pragma once #include "ProtobufModule.h" -#ifdef ARCH_ESP32 -#include "mesh/http/WiFiAPClient.h" +#if HAS_WIFI +#include "mesh/wifi/WiFiAPClient.h" #endif /** @@ -50,4 +50,4 @@ class AdminModule : public ProtobufModule void reboot(int32_t seconds); }; -extern AdminModule *adminModule; +extern AdminModule *adminModule; \ No newline at end of file diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 29a634922..a97aa5255 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -7,9 +7,9 @@ #include "mesh/Router.h" #include "mesh/generated/meshtastic/mqtt.pb.h" #include "mesh/generated/meshtastic/telemetry.pb.h" -#include "mesh/http/WiFiAPClient.h" #include "sleep.h" #if HAS_WIFI +#include "mesh/wifi/WiFiAPClient.h" #include #endif #include "mqtt/JSON.h" diff --git a/src/platform/esp32/main-esp32.cpp b/src/platform/esp32/main-esp32.cpp index 833e058d8..7da41512e 100644 --- a/src/platform/esp32/main-esp32.cpp +++ b/src/platform/esp32/main-esp32.cpp @@ -7,7 +7,7 @@ #include "nimble/NimbleBluetooth.h" #endif #include "BleOta.h" -#include "mesh/http/WiFiAPClient.h" +#include "mesh/wifi/WiFiAPClient.h" #include "meshUtils.h" #include "sleep.h" diff --git a/src/sleep.cpp b/src/sleep.cpp index b0f4aec88..464486d00 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -11,7 +11,7 @@ #ifdef ARCH_ESP32 #include "esp32/pm.h" #include "esp_pm.h" -#include "mesh/http/WiFiAPClient.h" +#include "mesh/wifi/WiFiAPClient.h" #include "rom/rtc.h" #include #include diff --git a/variants/rpipicow/platformio.ini b/variants/rpipicow/platformio.ini index 3228e4c24..4c8cf992d 100644 --- a/variants/rpipicow/platformio.ini +++ b/variants/rpipicow/platformio.ini @@ -8,8 +8,10 @@ upload_protocol = picotool build_flags = ${rp2040_base.build_flags} -DRPI_PICO -Ivariants/rpipicow - -DDEBUG_RP2040_PORT=Serial -DHW_SPI1_DEVICE -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m0plus" + -fexceptions # for exception handling in MQTT +build_src_filter = ${rp2040_base.build_src_filter} + lib_deps = - ${rp2040_base.lib_deps} \ No newline at end of file + ${rp2040_base.lib_deps} + ${networking_base.lib_deps} \ No newline at end of file diff --git a/variants/rpipicow/variant.h b/variants/rpipicow/variant.h index abbd1c465..c48b901ac 100644 --- a/variants/rpipicow/variant.h +++ b/variants/rpipicow/variant.h @@ -4,6 +4,10 @@ #define ARDUINO_ARCH_AVR +#ifndef HAS_WIFI +#define HAS_WIFI 1 +#endif + #define USE_SH1106 1 // default I2C pins: @@ -46,4 +50,4 @@ #define SX126X_RESET LORA_RESET #define SX126X_DIO2_AS_RF_SWITCH #define SX126X_DIO3_TCXO_VOLTAGE 1.8 -#endif +#endif \ No newline at end of file From 31c4693c662dee0a6cab08db9ef9cfbad015ac0d Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sat, 2 Dec 2023 15:50:17 -0600 Subject: [PATCH 029/472] Missed the version bump apparently --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 972a6f6de..8830a26a5 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 2 -build = 14 +build = 15 From 1f931a5e55a7a48ab62e2140d69e5ed6e0e9a3f3 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sat, 2 Dec 2023 17:19:29 -0600 Subject: [PATCH 030/472] [create-pull-request] automated change (#2981) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 8830a26a5..c95d5701a 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 2 -build = 15 +build = 16 From 1c22d2c885194d267f4174eb8f6884ecc0f8af4e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sun, 3 Dec 2023 10:56:13 +0100 Subject: [PATCH 031/472] switch onebutton back to PIO registry, since they finally updated the lib there --- arch/stm32/stm32wl5e.ini | 2 +- platformio.ini | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/arch/stm32/stm32wl5e.ini b/arch/stm32/stm32wl5e.ini index cac7110f2..4e47be8c3 100644 --- a/arch/stm32/stm32wl5e.ini +++ b/arch/stm32/stm32wl5e.ini @@ -26,4 +26,4 @@ lib_deps = https://github.com/stm32duino/STM32FreeRTOS.git#10.3.1 lib_ignore = - https://github.com/mathertel/OneButton#2.1.0 \ No newline at end of file + mathertel/OneButton \ No newline at end of file diff --git a/platformio.ini b/platformio.ini index 451fe3f1a..f176823d1 100644 --- a/platformio.ini +++ b/platformio.ini @@ -69,7 +69,7 @@ monitor_speed = 115200 lib_deps = https://github.com/meshtastic/esp8266-oled-ssd1306.git#b38094e03dfa964fbc0e799bc374e91a605c1223 ; ESP8266_SSD1306 - https://github.com/mathertel/OneButton#2.1.0 ; OneButton library for non-blocking button debounce + mathertel/OneButton@^2.5.0 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 https://github.com/meshtastic/TinyGPSPlus.git#076e8d2c8fb702d9be5b08c55b93ff76f8af7e61 https://github.com/meshtastic/ArduinoThread.git#72921ac222eed6f526ba1682023cee290d9aa1b3 From 07fc5df9c1b46b98ee6c80bb71e021033add3751 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sun, 3 Dec 2023 13:02:14 +0100 Subject: [PATCH 032/472] update trunk and linters to latest version --- .trunk/trunk.yaml | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/.trunk/trunk.yaml b/.trunk/trunk.yaml index e31b026f4..645d3863a 100644 --- a/.trunk/trunk.yaml +++ b/.trunk/trunk.yaml @@ -1,25 +1,25 @@ version: 0.1 cli: - version: 1.17.1 + version: 1.17.2 plugins: sources: - id: trunk - ref: v1.2.6 + ref: v1.3.0 uri: https://github.com/trunk-io/plugins lint: enabled: - bandit@1.7.5 - - checkov@3.0.16 - - terrascan@1.18.3 - - trivy@0.46.1 - - trufflehog@3.62.1 + - checkov@3.1.9 + - terrascan@1.18.5 + - trivy@0.47.0 + - trufflehog@3.63.2-rc0 - taplo@0.8.1 - - ruff@0.1.3 - - yamllint@1.32.0 + - ruff@0.1.6 + - yamllint@1.33.0 - isort@5.12.0 - markdownlint@0.37.0 - oxipng@9.0.0 - - svgo@3.0.2 + - svgo@3.0.5 - actionlint@1.6.26 - flake8@6.1.0 - hadolint@2.12.0 @@ -27,9 +27,9 @@ lint: - shellcheck@0.9.0 - black@23.9.1 - git-diff-check - - gitleaks@8.18.0 + - gitleaks@8.18.1 - clang-format@16.0.3 - - prettier@3.0.3 + - prettier@3.1.0 runtimes: enabled: - python@3.10.8 From 72b4fe51b104ea64277a2724abb70d867d0e4bde Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Mon, 4 Dec 2023 11:05:45 +0100 Subject: [PATCH 033/472] radiolib is stable just use one definition for all targets --- arch/esp32/esp32.ini | 1 - arch/nrf52/nrf52.ini | 1 - arch/portduino/portduino.ini | 1 - arch/rp2040/rp2040.ini | 1 - arch/stm32/stm32wl5e.ini | 1 - platformio.ini | 1 + 6 files changed, 1 insertion(+), 5 deletions(-) diff --git a/arch/esp32/esp32.ini b/arch/esp32/esp32.ini index db4b8e0b5..1f28ba6df 100644 --- a/arch/esp32/esp32.ini +++ b/arch/esp32/esp32.ini @@ -39,7 +39,6 @@ lib_deps = ${environmental_base.lib_deps} https://github.com/meshtastic/esp32_https_server.git#23665b3adc080a311dcbb586ed5941b5f94d6ea2 h2zero/NimBLE-Arduino@^1.4.1 - jgromes/RadioLib@^6.2.0 https://github.com/lewisxhe/XPowersLib.git#84b7373faea3118b6c37954d52f98b8a337148d6 https://github.com/meshtastic/ESP32_Codec2.git#633326c78ac251c059ab3a8c430fcdf25b41672f diff --git a/arch/nrf52/nrf52.ini b/arch/nrf52/nrf52.ini index 5da571cce..04ca89a54 100644 --- a/arch/nrf52/nrf52.ini +++ b/arch/nrf52/nrf52.ini @@ -15,7 +15,6 @@ build_src_filter = lib_deps= ${arduino_base.lib_deps} - jgromes/RadioLib@^6.2.0 lib_ignore = BluetoothOTA \ No newline at end of file diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index c4b6d5377..5933850e7 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -23,7 +23,6 @@ lib_deps = ${env.lib_deps} ${networking_base.lib_deps} rweather/Crypto@^0.4.0 - jgromes/RadioLib@^6.1.0 build_flags = ${arduino_base.build_flags} diff --git a/arch/rp2040/rp2040.ini b/arch/rp2040/rp2040.ini index 7674fbd52..2190125fa 100644 --- a/arch/rp2040/rp2040.ini +++ b/arch/rp2040/rp2040.ini @@ -20,5 +20,4 @@ lib_ignore = lib_deps = ${arduino_base.lib_deps} ${environmental_base.lib_deps} - jgromes/RadioLib@^6.2.0 rweather/Crypto \ No newline at end of file diff --git a/arch/stm32/stm32wl5e.ini b/arch/stm32/stm32wl5e.ini index 4e47be8c3..4483ff526 100644 --- a/arch/stm32/stm32wl5e.ini +++ b/arch/stm32/stm32wl5e.ini @@ -20,7 +20,6 @@ upload_protocol = stlink lib_deps = ${env.lib_deps} - jgromes/RadioLib@^6.2.0 https://github.com/kokke/tiny-AES-c.git#f06ac37fc31dfdaca2e0d9bec83f90d5663c319b https://github.com/littlefs-project/littlefs.git#v2.5.1 https://github.com/stm32duino/STM32FreeRTOS.git#10.3.1 diff --git a/platformio.ini b/platformio.ini index f176823d1..d7ad05337 100644 --- a/platformio.ini +++ b/platformio.ini @@ -68,6 +68,7 @@ build_flags = -Wno-missing-field-initializers monitor_speed = 115200 lib_deps = + jgromes/RadioLib@^6.3.0 https://github.com/meshtastic/esp8266-oled-ssd1306.git#b38094e03dfa964fbc0e799bc374e91a605c1223 ; ESP8266_SSD1306 mathertel/OneButton@^2.5.0 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 From 62329ad11f873da96c2512ef4b0a13d0747549e7 Mon Sep 17 00:00:00 2001 From: Ken McGuire Date: Mon, 4 Dec 2023 11:35:26 -0700 Subject: [PATCH 034/472] Fix typo in GNSS_MODEL defination and usages for the UC6580 (#2988) Correct the $CFGSYS init string for the UC6580 to init the receiver for: GPS L1 & L5 + BDS B1I & B2a + GLONASS L1 + GALILEO E1 & E5a + SBAS --- src/gps/GPS.cpp | 8 ++++---- src/gps/GPS.h | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index f51fb0588..afd8fb127 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -293,7 +293,7 @@ bool GPS::setup() gnssModel = GNSS_MODEL_UNKNOWN; } #else - gnssModel = GNSS_MODEL_UC6850; + gnssModel = GNSS_MODEL_UC6580; #endif if (gnssModel == GNSS_MODEL_MTK) { @@ -311,10 +311,10 @@ bool GPS::setup() // Switch to Vehicle Mode, since SoftRF enables Aviation < 2g _serial_gps->write("$PCAS11,3*1E\r\n"); delay(250); - } else if (gnssModel == GNSS_MODEL_UC6850) { + } else if (gnssModel == GNSS_MODEL_UC6580) { - // use GPS + GLONASS - _serial_gps->write("$CFGSYS,h15\r\n"); + // use GPS L1 & L5 + BDS B1I & B2a + GLONASS L1 + GALILEO E1 & E5a + SBAS + _serial_gps->write("$CFGSYS,h25155\r\n"); delay(250); } else if (gnssModel == GNSS_MODEL_UBLOX) { // Configure GNSS system to GPS+SBAS+GLONASS (Module may restart after this command) diff --git a/src/gps/GPS.h b/src/gps/GPS.h index d52c79182..4cbdae06b 100644 --- a/src/gps/GPS.h +++ b/src/gps/GPS.h @@ -23,7 +23,7 @@ struct uBloxGnssModelInfo { typedef enum { GNSS_MODEL_MTK, GNSS_MODEL_UBLOX, - GNSS_MODEL_UC6850, + GNSS_MODEL_UC6580, GNSS_MODEL_UNKNOWN, } GnssModel_t; From 46d02affe85ca8e2ea1c331ef3e325c619dad2be Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Mon, 4 Dec 2023 22:45:07 +0100 Subject: [PATCH 035/472] Pico W: Wi-Fi improvements (#2989) * Pico W: Initial WiFi support: connects, but freezes after a while * Update arduino-pico core to fix hang with Wi-Fi * Add `picow` to workflow since it's different from `pico` now * Show Wi-Fi frame on screen for all devices with Wi-Fi * Pico W: Disable mDNS as it's unsupported with FreeRTOS * Fix printing IP address * Fix Raspbian build --- src/graphics/Screen.cpp | 7 +++++-- src/mesh/wifi/WiFiAPClient.cpp | 18 ++++++++++-------- 2 files changed, 15 insertions(+), 10 deletions(-) diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index e75a432d4..417a6e454 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -43,9 +43,12 @@ along with this program. If not, see . #include "sleep.h" #include "target_specific.h" +#if HAS_WIFI && !defined(ARCH_RASPBERRY_PI) +#include "mesh/wifi/WiFiAPClient.h" +#endif + #ifdef ARCH_ESP32 #include "esp_task_wdt.h" -#include "mesh/wifi/WiFiAPClient.h" #include "modules/esp32/StoreForwardModule.h" #endif @@ -1294,7 +1297,7 @@ void Screen::setFrames() // call a method on debugInfoScreen object (for more details) normalFrames[numframes++] = &Screen::drawDebugInfoSettingsTrampoline; -#ifdef ARCH_ESP32 +#if HAS_WIFI && !defined(ARCH_RASPBERRY_PI) if (isWifiAvailable()) { // call a method on debugInfoScreen object (for more details) normalFrames[numframes++] = &Screen::drawDebugInfoWiFiTrampoline; diff --git a/src/mesh/wifi/WiFiAPClient.cpp b/src/mesh/wifi/WiFiAPClient.cpp index 06573fd60..fb29f54e3 100644 --- a/src/mesh/wifi/WiFiAPClient.cpp +++ b/src/mesh/wifi/WiFiAPClient.cpp @@ -9,13 +9,11 @@ #include "target_specific.h" #include #include -#ifndef ARCH_RP2040 +#ifdef ARCH_ESP32 #include "mesh/http/WebServer.h" #include #include static void WiFiEvent(WiFiEvent_t event); -#else -#include #endif #ifndef DISABLE_NTP @@ -53,6 +51,7 @@ static void onNetworkConnected() // Start web server LOG_INFO("Starting network services\n"); +#ifdef ARCH_ESP32 // start mdns if (!MDNS.begin("Meshtastic")) { LOG_ERROR("Error setting up MDNS responder!\n"); @@ -62,6 +61,9 @@ static void onNetworkConnected() MDNS.addService("http", "tcp", 80); MDNS.addService("https", "tcp", 443); } +#else // ESP32 handles this in WiFiEvent + LOG_INFO("Obtained IP address: %s\n", WiFi.localIP().toString().c_str()); +#endif #ifndef DISABLE_NTP LOG_INFO("Starting NTP time client\n"); @@ -89,7 +91,7 @@ static void onNetworkConnected() syslog.enable(); } -#ifndef ARCH_RP2040 +#ifdef ARCH_ESP32 initWebServer(); #endif initApiServer(); @@ -245,7 +247,7 @@ bool initWifi() } } -#ifndef ARCH_RP2040 +#ifdef ARCH_ESP32 // Called by the Espressif SDK to static void WiFiEvent(WiFiEvent_t event) { @@ -279,11 +281,11 @@ static void WiFiEvent(WiFiEvent_t event) LOG_INFO("Authentication mode of access point has changed\n"); break; case ARDUINO_EVENT_WIFI_STA_GOT_IP: - LOG_INFO("Obtained IP address: ", WiFi.localIPv6()); + LOG_INFO("Obtained IP address: %s\n", WiFi.localIP().toString().c_str()); onNetworkConnected(); break; case ARDUINO_EVENT_WIFI_STA_GOT_IP6: - LOG_INFO("Obtained IP6 address: %s", WiFi.localIPv6()); + LOG_INFO("Obtained IP6 address: %s\n", WiFi.localIPv6().toString().c_str()); break; case ARDUINO_EVENT_WIFI_STA_LOST_IP: LOG_INFO("Lost IP address and IP address is reset to 0\n"); @@ -391,4 +393,4 @@ static void WiFiEvent(WiFiEvent_t event) uint8_t getWifiDisconnectReason() { return wifiDisconnectReason; -} \ No newline at end of file +} From 89f0464233cce0949fb35494fa83053cb5b982b2 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Wed, 6 Dec 2023 06:17:50 -0600 Subject: [PATCH 036/472] [create-pull-request] automated change (#2991) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/config.pb.h | 26 +++++++++++++++++------ 2 files changed, 21 insertions(+), 7 deletions(-) diff --git a/protobufs b/protobufs index 9148427a3..1eda884c3 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 9148427a3be535c9e3f17e846ecbb64ce04b6521 +Subproject commit 1eda884c3962b7647aa6a2a3f98a23568cfcff1e diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index 53e92a948..8406dc887 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -43,7 +43,18 @@ typedef enum _meshtastic_Config_DeviceConfig_Role { Used for nodes dedicated for connection to an ATAK EUD. Turns off many of the routine broadcasts to favor CoT packet stream from the Meshtastic ATAK plugin -> IMeshService -> Node */ - meshtastic_Config_DeviceConfig_Role_TAK = 7 + meshtastic_Config_DeviceConfig_Role_TAK = 7, + /* Client Hidden device role + Used for nodes that "only speak when spoken to" + Turns all of the routine broadcasts but allows for ad-hoc communication + Still rebroadcasts, but with local only rebroadcast mode (known meshes only) + Can be used for clandestine operation or to dramatically reduce airtime / power consumption */ + meshtastic_Config_DeviceConfig_Role_CLIENT_HIDDEN = 8, + /* Lost and Found device role + Used to automatically send a text message to the mesh + with the current position of the device on a frequent interval: + "I'm lost! Position: lat / long" */ + meshtastic_Config_DeviceConfig_Role_LOST_AND_FOUND = 9 } meshtastic_Config_DeviceConfig_Role; /* Defines the device's behavior for how messages are rebroadcast */ @@ -56,7 +67,10 @@ typedef enum _meshtastic_Config_DeviceConfig_RebroadcastMode { meshtastic_Config_DeviceConfig_RebroadcastMode_ALL_SKIP_DECODING = 1, /* Ignores observed messages from foreign meshes that are open or those which it cannot decrypt. Only rebroadcasts message on the nodes local primary / secondary channels. */ - meshtastic_Config_DeviceConfig_RebroadcastMode_LOCAL_ONLY = 2 + meshtastic_Config_DeviceConfig_RebroadcastMode_LOCAL_ONLY = 2, + /* Ignores observed messages from foreign meshes like LOCAL_ONLY, + but takes it step further by also ignoring messages from nodenums not in the node's known list (NodeDB) */ + meshtastic_Config_DeviceConfig_RebroadcastMode_KNOWN_ONLY = 3 } meshtastic_Config_DeviceConfig_RebroadcastMode; /* Bit field of boolean configuration options, indicating which optional @@ -479,12 +493,12 @@ extern "C" { /* Helper constants for enums */ #define _meshtastic_Config_DeviceConfig_Role_MIN meshtastic_Config_DeviceConfig_Role_CLIENT -#define _meshtastic_Config_DeviceConfig_Role_MAX meshtastic_Config_DeviceConfig_Role_TAK -#define _meshtastic_Config_DeviceConfig_Role_ARRAYSIZE ((meshtastic_Config_DeviceConfig_Role)(meshtastic_Config_DeviceConfig_Role_TAK+1)) +#define _meshtastic_Config_DeviceConfig_Role_MAX meshtastic_Config_DeviceConfig_Role_LOST_AND_FOUND +#define _meshtastic_Config_DeviceConfig_Role_ARRAYSIZE ((meshtastic_Config_DeviceConfig_Role)(meshtastic_Config_DeviceConfig_Role_LOST_AND_FOUND+1)) #define _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN meshtastic_Config_DeviceConfig_RebroadcastMode_ALL -#define _meshtastic_Config_DeviceConfig_RebroadcastMode_MAX meshtastic_Config_DeviceConfig_RebroadcastMode_LOCAL_ONLY -#define _meshtastic_Config_DeviceConfig_RebroadcastMode_ARRAYSIZE ((meshtastic_Config_DeviceConfig_RebroadcastMode)(meshtastic_Config_DeviceConfig_RebroadcastMode_LOCAL_ONLY+1)) +#define _meshtastic_Config_DeviceConfig_RebroadcastMode_MAX meshtastic_Config_DeviceConfig_RebroadcastMode_KNOWN_ONLY +#define _meshtastic_Config_DeviceConfig_RebroadcastMode_ARRAYSIZE ((meshtastic_Config_DeviceConfig_RebroadcastMode)(meshtastic_Config_DeviceConfig_RebroadcastMode_KNOWN_ONLY+1)) #define _meshtastic_Config_PositionConfig_PositionFlags_MIN meshtastic_Config_PositionConfig_PositionFlags_UNSET #define _meshtastic_Config_PositionConfig_PositionFlags_MAX meshtastic_Config_PositionConfig_PositionFlags_SPEED From 28502a762fd02c42d528c76b2a9e10a776040a41 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 6 Dec 2023 14:02:41 -0600 Subject: [PATCH 037/472] Added Known-Only rebroadcast mode behavior (#2993) --- src/mesh/Router.cpp | 6 ++++++ src/modules/RoutingModule.cpp | 3 ++- 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp index b2d8d585d..ff657fd11 100644 --- a/src/mesh/Router.cpp +++ b/src/mesh/Router.cpp @@ -299,6 +299,12 @@ bool perhapsDecode(meshtastic_MeshPacket *p) config.device.rebroadcast_mode == meshtastic_Config_DeviceConfig_RebroadcastMode_ALL_SKIP_DECODING) return false; + if (config.device.rebroadcast_mode == meshtastic_Config_DeviceConfig_RebroadcastMode_KNOWN_ONLY && + !nodeDB.getMeshNode(p->from)->has_user) { + LOG_DEBUG("Node 0x%x not in NodeDB. Rebroadcast mode KNOWN_ONLY will ignore packet\n", p->from); + return false; + } + if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) return true; // If packet was already decoded just return diff --git a/src/modules/RoutingModule.cpp b/src/modules/RoutingModule.cpp index d81311481..edeb1fb86 100644 --- a/src/modules/RoutingModule.cpp +++ b/src/modules/RoutingModule.cpp @@ -46,5 +46,6 @@ void RoutingModule::sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketI RoutingModule::RoutingModule() : ProtobufModule("routing", meshtastic_PortNum_ROUTING_APP, &meshtastic_Routing_msg) { isPromiscuous = true; - encryptedOk = config.device.rebroadcast_mode != meshtastic_Config_DeviceConfig_RebroadcastMode_LOCAL_ONLY; + encryptedOk = config.device.rebroadcast_mode != meshtastic_Config_DeviceConfig_RebroadcastMode_LOCAL_ONLY && + config.device.rebroadcast_mode != meshtastic_Config_DeviceConfig_RebroadcastMode_KNOWN_ONLY; } From b4ad6b0f418cf5b39ca4fc6721741ee8b0c14f03 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 6 Dec 2023 14:04:09 -0600 Subject: [PATCH 038/472] Added client-hidden role behavior (#2992) * Added client-hidden role behavior * Trunkt * That line got all boogered up --- src/mesh/NodeDB.cpp | 9 +++++++++ src/modules/NodeInfoModule.cpp | 2 +- src/modules/Telemetry/DeviceTelemetry.cpp | 3 ++- 3 files changed, 12 insertions(+), 2 deletions(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index bb079e5c0..9c623d973 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -302,6 +302,15 @@ void NodeDB::installRoleDefaults(meshtastic_Config_DeviceConfig_Role role) (meshtastic_Config_PositionConfig_PositionFlags_ALTITUDE | meshtastic_Config_PositionConfig_PositionFlags_SPEED | meshtastic_Config_PositionConfig_PositionFlags_HEADING | meshtastic_Config_PositionConfig_PositionFlags_DOP); moduleConfig.telemetry.device_update_interval = ONE_DAY; + } else if (role == meshtastic_Config_DeviceConfig_Role_CLIENT_HIDDEN) { + config.device.rebroadcast_mode = meshtastic_Config_DeviceConfig_RebroadcastMode_LOCAL_ONLY; + config.device.node_info_broadcast_secs = UINT32_MAX; + config.position.position_broadcast_smart_enabled = false; + config.position.position_broadcast_secs = UINT32_MAX; + moduleConfig.neighbor_info.update_interval = UINT32_MAX; + moduleConfig.telemetry.device_update_interval = UINT32_MAX; + moduleConfig.telemetry.environment_update_interval = UINT32_MAX; + moduleConfig.telemetry.air_quality_interval = UINT32_MAX; } } diff --git a/src/modules/NodeInfoModule.cpp b/src/modules/NodeInfoModule.cpp index 855ba9cde..799f6ec7c 100644 --- a/src/modules/NodeInfoModule.cpp +++ b/src/modules/NodeInfoModule.cpp @@ -89,7 +89,7 @@ int32_t NodeInfoModule::runOnce() bool requestReplies = currentGeneration != radioGeneration; currentGeneration = radioGeneration; - if (airTime->isTxAllowedAirUtil()) { + if (airTime->isTxAllowedAirUtil() && config.device.role != meshtastic_Config_DeviceConfig_Role_CLIENT_HIDDEN) { LOG_INFO("Sending our nodeinfo to mesh (wantReplies=%d)\n", requestReplies); sendOurNodeInfo(NODENUM_BROADCAST, requestReplies); // Send our info (don't request replies) } diff --git a/src/modules/Telemetry/DeviceTelemetry.cpp b/src/modules/Telemetry/DeviceTelemetry.cpp index bc6c03c52..a6eecda80 100644 --- a/src/modules/Telemetry/DeviceTelemetry.cpp +++ b/src/modules/Telemetry/DeviceTelemetry.cpp @@ -18,7 +18,8 @@ int32_t DeviceTelemetryModule::runOnce() if (((lastSentToMesh == 0) || ((now - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.telemetry.device_update_interval))) && airTime->isTxAllowedChannelUtil() && airTime->isTxAllowedAirUtil() && - config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER) { + config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER && + config.device.role != meshtastic_Config_DeviceConfig_Role_CLIENT_HIDDEN) { sendTelemetry(); lastSentToMesh = now; } else if (service.isToPhoneQueueEmpty()) { From ba021c97b2c3512b5552b3ee8671984fb905e42d Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Wed, 6 Dec 2023 22:49:56 +0100 Subject: [PATCH 039/472] Pico W: Handle Wi-Fi reconnects and update core (#2994) * Fix time lost on the Pico W right after NTP Shouldn't check for `#ifdef` as it will always be defined, but might be set to 0 * Handle reconnect for Wi-Fi on RP2040 * Update arduino-core for Wi-Fi + FreeRTOS fixes --------- Co-authored-by: Ben Meadors --- arch/rp2040/rp2040.ini | 2 +- src/gps/RTC.cpp | 4 ++-- src/mesh/wifi/WiFiAPClient.cpp | 5 +++++ 3 files changed, 8 insertions(+), 3 deletions(-) diff --git a/arch/rp2040/rp2040.ini b/arch/rp2040/rp2040.ini index 2190125fa..48fe0dae6 100644 --- a/arch/rp2040/rp2040.ini +++ b/arch/rp2040/rp2040.ini @@ -2,7 +2,7 @@ [rp2040_base] platform = https://github.com/maxgerhardt/platform-raspberrypi.git#612de5399d68b359053f1307ed223d400aea975c extends = arduino_base -platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#d2461a14ad5aa920e44508d236c2f459e3befbf8 +platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#3.6.2 board_build.core = earlephilhower board_build.filesystem_size = 0.5m diff --git a/src/gps/RTC.cpp b/src/gps/RTC.cpp index ef438a7dd..10e9e0331 100644 --- a/src/gps/RTC.cpp +++ b/src/gps/RTC.cpp @@ -152,7 +152,7 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv) #endif // nrf52 doesn't have a readable RTC (yet - software not written) -#ifdef HAS_RTC +#if HAS_RTC readFromRTC(); #endif @@ -208,4 +208,4 @@ uint32_t getTime() uint32_t getValidTime(RTCQuality minQuality) { return (currentQuality >= minQuality) ? getTime() : 0; -} \ No newline at end of file +} diff --git a/src/mesh/wifi/WiFiAPClient.cpp b/src/mesh/wifi/WiFiAPClient.cpp index fb29f54e3..1e521e033 100644 --- a/src/mesh/wifi/WiFiAPClient.cpp +++ b/src/mesh/wifi/WiFiAPClient.cpp @@ -151,6 +151,11 @@ static int32_t reconnectWiFi() #endif if (config.network.wifi_enabled && !WiFi.isConnected()) { +#ifdef ARCH_RP2040 // (ESP32 handles this in WiFiEvent) + /* If APStartupComplete, but we're not connected, try again. + Shouldn't try again before APStartupComplete. */ + needReconnect = APStartupComplete; +#endif return 1000; // check once per second } else { #ifdef ARCH_RP2040 From 17f1a450b29a3799874b2411f73f6890bef139c0 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Wed, 6 Dec 2023 18:14:41 -0600 Subject: [PATCH 040/472] [create-pull-request] automated change (#2995) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/mesh.pb.h | 4 ++++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/protobufs b/protobufs index 1eda884c3..a34b2c680 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 1eda884c3962b7647aa6a2a3f98a23568cfcff1e +Subproject commit a34b2c680e2c1c240643c515e57c5532b29c91a7 diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index 59005db48..ae80b3fe5 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -67,6 +67,10 @@ typedef enum _meshtastic_HardwareModel { meshtastic_HardwareModel_STATION_G1 = 25, /* RAK11310 (RP2040 + SX1262) */ meshtastic_HardwareModel_RAK11310 = 26, + /* Makerfabs SenseLoRA Receiver (RP2040 + RFM96) */ + meshtastic_HardwareModel_SENSELORA_RP2040 = 27, + /* Makerfabs SenseLoRA Industrial Monitor (ESP32-S3 + RFM96) */ + meshtastic_HardwareModel_SENSELORA_S3 = 28, /* --------------------------------------------------------------------------- Less common/prototype boards listed here (needs one more byte over the air) --------------------------------------------------------------------------- */ From 9188a9a1f27afb89cfd591a0d137e21e500d60d6 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 6 Dec 2023 21:42:06 -0600 Subject: [PATCH 041/472] Makersense RP2040 support (#2996) * WIP * Do the right things * Add to build matrix * Yaml lint has annoyed me for the final time --- .github/workflows/main_matrix.yml | 1 + .trunk/trunk.yaml | 1 - src/platform/esp32/architecture.h | 4 +++ src/platform/rp2040/architecture.h | 2 ++ variants/senselora_rp2040/platformio.ini | 14 +++++++++ variants/senselora_rp2040/variant.h | 38 ++++++++++++++++++++++++ 6 files changed, 59 insertions(+), 1 deletion(-) create mode 100644 variants/senselora_rp2040/platformio.ini create mode 100644 variants/senselora_rp2040/variant.h diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index e53c35bd2..9f1de95c5 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -125,6 +125,7 @@ jobs: - board: pico - board: picow - board: rak11310 + - board: senselora_rp2040 uses: ./.github/workflows/build_rpi2040.yml with: board: ${{ matrix.board }} diff --git a/.trunk/trunk.yaml b/.trunk/trunk.yaml index 645d3863a..da8face9a 100644 --- a/.trunk/trunk.yaml +++ b/.trunk/trunk.yaml @@ -15,7 +15,6 @@ lint: - trufflehog@3.63.2-rc0 - taplo@0.8.1 - ruff@0.1.6 - - yamllint@1.33.0 - isort@5.12.0 - markdownlint@0.37.0 - oxipng@9.0.0 diff --git a/src/platform/esp32/architecture.h b/src/platform/esp32/architecture.h index 0686aa59f..451d7ffbe 100644 --- a/src/platform/esp32/architecture.h +++ b/src/platform/esp32/architecture.h @@ -121,6 +121,10 @@ #define HW_VENDOR meshtastic_HardwareModel_PICOMPUTER_S3 #elif defined(HELTEC_HT62) #define HW_VENDOR meshtastic_HardwareModel_HELTEC_HT62 +#elif defined(SENSELORA_S3) +#define HW_VENDOR meshtastic_HardwareModel_SENSELORA_S3 +#elif defined(HELTEC_HT62) +#define HW_VENDOR meshtastic_HardwareModel_HELTEC_HT62 #endif // ----------------------------------------------------------------------------- diff --git a/src/platform/rp2040/architecture.h b/src/platform/rp2040/architecture.h index 762a2dc83..61eb1bbe8 100644 --- a/src/platform/rp2040/architecture.h +++ b/src/platform/rp2040/architecture.h @@ -25,4 +25,6 @@ #define HW_VENDOR meshtastic_HardwareModel_RPI_PICO #elif defined(RAK11310) #define HW_VENDOR meshtastic_HardwareModel_RAK11310 +#elif defined(SENSELORA_RP2040) +#define HW_VENDOR meshtastic_HardwareModel_SENSELORA_RP2040 #endif \ No newline at end of file diff --git a/variants/senselora_rp2040/platformio.ini b/variants/senselora_rp2040/platformio.ini new file mode 100644 index 000000000..abf28559e --- /dev/null +++ b/variants/senselora_rp2040/platformio.ini @@ -0,0 +1,14 @@ +[env:senselora_rp2040] +extends = rp2040_base +board = rpipico +upload_protocol = picotool + +# add our variants files to the include and src paths +build_flags = ${rp2040_base.build_flags} + -DSENSELORA_RP2040 + -Ivariants/rpipico + -DDEBUG_RP2040_PORT=Serial + -DHW_SPI1_DEVICE + -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m0plus" +lib_deps = + ${rp2040_base.lib_deps} \ No newline at end of file diff --git a/variants/senselora_rp2040/variant.h b/variants/senselora_rp2040/variant.h new file mode 100644 index 000000000..78f3e8f14 --- /dev/null +++ b/variants/senselora_rp2040/variant.h @@ -0,0 +1,38 @@ +// #define RADIOLIB_CUSTOM_ARDUINO 1 +// #define RADIOLIB_TONE_UNSUPPORTED 1 +// #define RADIOLIB_SOFTWARE_SERIAL_UNSUPPORTED 1 + +#define ARDUINO_ARCH_AVR + +#define USE_SSD1306 1 + +#define BUTTON_PIN 2 + +#define I2C_SDA1 6 +#define I2C_SCL1 7 + +#define PIN_SPI_MISO (16u) +#define PIN_SPI_MOSI (19u) +#define PIN_SPI_SCK (18u) +#define PIN_SPI_SS (17u) + +#define LED_PIN PIN_LED + +#undef BATTERY_PIN + +#undef LORA_SCK +#undef LORA_MISO +#undef LORA_MOSI +#undef LORA_CS + +#define USE_RF95 +#define LORA_SCK PIN_SPI_SCK +#define LORA_MISO PIN_SPI_MISO +#define LORA_MOSI PIN_SPI_MOSI +#define LORA_CS PIN_SPI_SS + +#define LORA_DIO0 21 +#define LORA_DIO1 22 +#define LORA_DIO2 23 +#define LORA_DIO5 24 +#define LORA_RST 20 From a54e3826e97e0cc9680d4f85eeda19bc5af7e50d Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 7 Dec 2023 07:14:41 -0600 Subject: [PATCH 042/472] Remove truffle-hog tool for now since it's breaking CI --- .trunk/trunk.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.trunk/trunk.yaml b/.trunk/trunk.yaml index da8face9a..81a35f8f1 100644 --- a/.trunk/trunk.yaml +++ b/.trunk/trunk.yaml @@ -12,7 +12,7 @@ lint: - checkov@3.1.9 - terrascan@1.18.5 - trivy@0.47.0 - - trufflehog@3.63.2-rc0 + #- trufflehog@3.63.2-rc0 - taplo@0.8.1 - ruff@0.1.6 - isort@5.12.0 From 8f57cfaaf494662664552d7c84c10440fa2acfe4 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 7 Dec 2023 17:12:51 -0600 Subject: [PATCH 043/472] Makersense rp2040 variant fixes (#2997) * WIP * Do the right things * Add to build matrix * Yaml lint has annoyed me for the final time * Fixes to variant --- variants/senselora_rp2040/pins_arduino.h | 50 ++++++++++++++++++++++++ variants/senselora_rp2040/platformio.ini | 3 +- variants/senselora_rp2040/variant.h | 28 ++++--------- 3 files changed, 59 insertions(+), 22 deletions(-) create mode 100644 variants/senselora_rp2040/pins_arduino.h diff --git a/variants/senselora_rp2040/pins_arduino.h b/variants/senselora_rp2040/pins_arduino.h new file mode 100644 index 000000000..bb0ee637e --- /dev/null +++ b/variants/senselora_rp2040/pins_arduino.h @@ -0,0 +1,50 @@ +#pragma once + +#define PIN_A0 (26u) +#define PIN_A1 (27u) +#define PIN_A2 (28u) +#define PIN_A3 (29u) + +static const uint8_t A0 = PIN_A0; +static const uint8_t A1 = PIN_A1; +static const uint8_t A2 = PIN_A2; +static const uint8_t A3 = PIN_A3; + +// LEDs +#define PIN_LED (23u) +#define PIN_LED1 PIN_LED +#define LED_BUILTIN PIN_LED + +#define ADC_RESOLUTION 12 + +// Serial +#define PIN_SERIAL1_TX (0ul) +#define PIN_SERIAL1_RX (1ul) + +#define PIN_SERIAL2_TX (4ul) +#define PIN_SERIAL2_RX (5ul) + +// SPI +#define PIN_SPI0_MISO (16u) +#define PIN_SPI0_MOSI (19u) +#define PIN_SPI0_SCK (18u) +#define PIN_SPI0_SS (17u) + +// Wire +#define PIN_WIRE0_SDA (6u) +#define PIN_WIRE0_SCL (7u) + +#define PIN_WIRE1_SDA (-1) +#define PIN_WIRE1_SCL (-1) + +#define SERIAL_HOWMANY (3u) +#define SPI_HOWMANY (2u) +#define WIRE_HOWMANY (1u) + +static const uint8_t SS = PIN_SPI0_SS; +static const uint8_t MOSI = PIN_SPI0_MOSI; +static const uint8_t MISO = PIN_SPI0_MISO; +static const uint8_t SCK = PIN_SPI0_SCK; + +static const uint8_t SDA = PIN_WIRE0_SDA; +static const uint8_t SCL = PIN_WIRE0_SCL; \ No newline at end of file diff --git a/variants/senselora_rp2040/platformio.ini b/variants/senselora_rp2040/platformio.ini index abf28559e..3b3253ee8 100644 --- a/variants/senselora_rp2040/platformio.ini +++ b/variants/senselora_rp2040/platformio.ini @@ -6,9 +6,8 @@ upload_protocol = picotool # add our variants files to the include and src paths build_flags = ${rp2040_base.build_flags} -DSENSELORA_RP2040 - -Ivariants/rpipico + -Ivariants/senselora_rp2040 -DDEBUG_RP2040_PORT=Serial - -DHW_SPI1_DEVICE -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m0plus" lib_deps = ${rp2040_base.lib_deps} \ No newline at end of file diff --git a/variants/senselora_rp2040/variant.h b/variants/senselora_rp2040/variant.h index 78f3e8f14..9eda65521 100644 --- a/variants/senselora_rp2040/variant.h +++ b/variants/senselora_rp2040/variant.h @@ -1,20 +1,9 @@ -// #define RADIOLIB_CUSTOM_ARDUINO 1 -// #define RADIOLIB_TONE_UNSUPPORTED 1 -// #define RADIOLIB_SOFTWARE_SERIAL_UNSUPPORTED 1 - #define ARDUINO_ARCH_AVR -#define USE_SSD1306 1 +#define USE_SSD1306 #define BUTTON_PIN 2 - -#define I2C_SDA1 6 -#define I2C_SCL1 7 - -#define PIN_SPI_MISO (16u) -#define PIN_SPI_MOSI (19u) -#define PIN_SPI_SCK (18u) -#define PIN_SPI_SS (17u) +#define BUTTON_NEED_PULLUP #define LED_PIN PIN_LED @@ -26,13 +15,12 @@ #undef LORA_CS #define USE_RF95 -#define LORA_SCK PIN_SPI_SCK -#define LORA_MISO PIN_SPI_MISO -#define LORA_MOSI PIN_SPI_MOSI -#define LORA_CS PIN_SPI_SS +#define LORA_SCK PIN_SPI0_SCK +#define LORA_MISO PIN_SPI0_MISO +#define LORA_MOSI PIN_SPI0_MOSI +#define LORA_CS PIN_SPI0_SS #define LORA_DIO0 21 #define LORA_DIO1 22 -#define LORA_DIO2 23 -#define LORA_DIO5 24 -#define LORA_RST 20 +#define LORA_DIO2 RADIOLIB_NC +#define LORA_RESET 20 \ No newline at end of file From 8ea19d665af8142ecd661b96bc14c37b4423776f Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 7 Dec 2023 20:22:22 -0600 Subject: [PATCH 044/472] Update pull-request-artifacts --- .github/workflows/main_matrix.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 9f1de95c5..a3ea7dbb0 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -285,14 +285,14 @@ jobs: - name: Create request artifacts continue-on-error: true # FIXME: Why are we getting 502, but things still work? if: ${{ github.event_name == 'pull_request_target' || github.event_name == 'pull_request' }} - uses: gavv/pull-request-artifacts@v1.1.0 + uses: gavv/pull-request-artifacts@v2.1.0 with: commit: ${{ (github.event.pull_request_target || github.event.pull_request).head.sha }} repo-token: ${{ secrets.GITHUB_TOKEN }} artifacts-token: ${{ secrets.ARTIFACTS_TOKEN }} artifacts-repo: meshtastic/artifacts artifacts-branch: device - artifacts-dir: pr + artifacts-prefix: pr artifacts: ./firmware-${{ steps.version.outputs.version }}.zip release-artifacts: From 671112f47d79a2ec7c778ca1cd635bcdc84922fb Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 7 Dec 2023 21:22:30 -0600 Subject: [PATCH 045/472] Update pull-request-artifacts config --- .github/workflows/main_matrix.yml | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index a3ea7dbb0..056938b90 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -212,6 +212,13 @@ jobs: repository: ${{github.event.pull_request.head.repo.full_name}} gather-artifacts: + permissions: + # Required to upload/save artifact, otherwise you'll get + # "Error: Resource not accessible by integration" + contents: write + # Required to post comment, otherwise you'll get + # "Error: Resource not accessible by integration" + pull-requests: write runs-on: ubuntu-latest needs: [ @@ -292,7 +299,6 @@ jobs: artifacts-token: ${{ secrets.ARTIFACTS_TOKEN }} artifacts-repo: meshtastic/artifacts artifacts-branch: device - artifacts-prefix: pr artifacts: ./firmware-${{ steps.version.outputs.version }}.zip release-artifacts: From 5eac227550accac64f89a53d22b04c5f4bd1f883 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 7 Dec 2023 21:29:04 -0600 Subject: [PATCH 046/472] Fix whitespace in workflow --- .github/workflows/main_matrix.yml | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 056938b90..a2aa11288 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -213,12 +213,8 @@ jobs: gather-artifacts: permissions: - # Required to upload/save artifact, otherwise you'll get - # "Error: Resource not accessible by integration" - contents: write - # Required to post comment, otherwise you'll get - # "Error: Resource not accessible by integration" - pull-requests: write + contents: write + pull-requests: write runs-on: ubuntu-latest needs: [ From abaa37133d503a9b5732064bdddbef71fbf7300c Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 8 Dec 2023 11:13:15 -0600 Subject: [PATCH 047/472] Repeater and other power optimizations (#2999) * End wire if we find no i2c devices * Set tx-power to 0 on nrf bluetooth shutdown * Change polling interval of PowerFSM to 100ms instead of 10ms * Guard 3v3 --- src/PowerFSMThread.h | 2 +- src/main.cpp | 20 +++++++++++++++----- src/platform/nrf52/NRF52Bluetooth.cpp | 3 ++- 3 files changed, 18 insertions(+), 7 deletions(-) diff --git a/src/PowerFSMThread.h b/src/PowerFSMThread.h index 541522f43..b757f3abb 100644 --- a/src/PowerFSMThread.h +++ b/src/PowerFSMThread.h @@ -33,7 +33,7 @@ class PowerFSMThread : public OSThread powerFSM.trigger(EVENT_SHUTDOWN); } - return 10; + return 100; } }; diff --git a/src/main.cpp b/src/main.cpp index b3671c020..c8fc61e4c 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -432,6 +432,10 @@ void setup() auto i2cCount = i2cScanner->countDevices(); if (i2cCount == 0) { LOG_INFO("No I2C devices found\n"); + Wire.end(); +#ifdef I2C_SDA1 + Wire1.end(); +#endif } else { LOG_INFO("%i I2C devices found\n", i2cCount); } @@ -576,10 +580,13 @@ void setup() // but we need to do this after main cpu init (esp32setup), because we need the random seed set nodeDB.init(); - // If we're taking on the repeater role, use flood router - if (config.device.role == meshtastic_Config_DeviceConfig_Role_REPEATER) + // If we're taking on the repeater role, use flood router and turn off 3V3_S rail because peripherals are not needed + if (config.device.role == meshtastic_Config_DeviceConfig_Role_REPEATER) { router = new FloodingRouter(); - else +#ifdef PIN_3V3_EN + digitalWrite(PIN_3V3_EN, LOW); +#endif + } else router = new ReliableRouter(); #if HAS_BUTTON || defined(ARCH_RASPBERRY_PI) @@ -653,7 +660,10 @@ void setup() readFromRTC(); // read the main CPU RTC at first (in case we can't get GPS time) - gps = GPS::createGps(); + // If we're taking on the repeater role, ignore GPS + if (config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER) { + gps = GPS::createGps(); + } if (gps) { gpsStatus->observe(&gps->newStatus); } else { @@ -941,4 +951,4 @@ void loop() mainDelay.delay(delayMsec); } // if (didWake) LOG_DEBUG("wake!\n"); -} +} \ No newline at end of file diff --git a/src/platform/nrf52/NRF52Bluetooth.cpp b/src/platform/nrf52/NRF52Bluetooth.cpp index c29739542..dd81929c8 100644 --- a/src/platform/nrf52/NRF52Bluetooth.cpp +++ b/src/platform/nrf52/NRF52Bluetooth.cpp @@ -211,6 +211,7 @@ void NRF52Bluetooth::shutdown() // Shutdown bluetooth for minimum power draw LOG_INFO("Disable NRF52 bluetooth\n"); Bluefruit.Advertising.stop(); + Bluefruit.setTxPower(0); // Minimum power } bool NRF52Bluetooth::isConnected() @@ -333,4 +334,4 @@ void NRF52Bluetooth::onPairingCompleted(uint16_t conn_handle, uint8_t auth_statu LOG_INFO("BLE pairing failed\n"); screen->stopBluetoothPinScreen(); -} +} \ No newline at end of file From 4de6eb2e1d76278356e236955e272ec0a0e564a9 Mon Sep 17 00:00:00 2001 From: Ken McGuire Date: Fri, 8 Dec 2023 13:51:50 -0700 Subject: [PATCH 048/472] Reduce Serial Traffic on Heltec Wireless Trackers GNSS port (#3004) * Fix typo in GNSS_MODEL defination and usages for the UC6580 Correct the $CFGSYS init string for the UC6580 to init the receiver for: GPS L1 & L5 + BDS B1I & B2a + GLONASS L1 + GALILEO E1 & E5a + SBAS * Reduce GNSS serial traffic on Helted Wireless Tracker Turn off GSV and NOTIFY __TXT messages as neither are necessary to Meshtastic operation. --- src/gps/GPS.cpp | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index afd8fb127..d5cd9b682 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -312,10 +312,22 @@ bool GPS::setup() _serial_gps->write("$PCAS11,3*1E\r\n"); delay(250); } else if (gnssModel == GNSS_MODEL_UC6580) { - + // The Unicore UC6580 can use a lot of sat systems, enable it to // use GPS L1 & L5 + BDS B1I & B2a + GLONASS L1 + GALILEO E1 & E5a + SBAS + // This will reset the receiver, so wait a bit afterwards + // The paranoid will wait for the OK*04 confirmation response after each command. _serial_gps->write("$CFGSYS,h25155\r\n"); + delay(750); + // Must be done after the CFGSYS command + // Turn off GSV messages, we don't really care about which and where the sats are, maybe someday. + _serial_gps->write("$CFGMSG,0,3,0\r\n"); delay(250); + // Turn off NOTICE __TXT messages, these may provide Unicore some info but we don't care. + _serial_gps->write("$CFGMSG,6,0,0\r\n"); + delay(250); + _serial_gps->write("$CFGMSG,6,1,0\r\n"); + delay(250); + } else if (gnssModel == GNSS_MODEL_UBLOX) { // Configure GNSS system to GPS+SBAS+GLONASS (Module may restart after this command) // We need set it because by default it is GPS only, and we want to use GLONASS too From 14b31d4d1461af53818668cb9046b825fee66333 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 8 Dec 2023 19:26:37 -0600 Subject: [PATCH 049/472] Fix INA sensor dual use between environment telem and device battery reading (#3002) --- src/modules/Telemetry/EnvironmentTelemetry.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/Telemetry/EnvironmentTelemetry.cpp b/src/modules/Telemetry/EnvironmentTelemetry.cpp index 1047ade1d..9c7b406e9 100644 --- a/src/modules/Telemetry/EnvironmentTelemetry.cpp +++ b/src/modules/Telemetry/EnvironmentTelemetry.cpp @@ -97,9 +97,9 @@ int32_t EnvironmentTelemetryModule::runOnce() result = lps22hbSensor.runOnce(); if (sht31Sensor.hasSensor()) result = sht31Sensor.runOnce(); - if (ina219Sensor.hasSensor() && !ina219Sensor.isInitialized()) + if (ina219Sensor.hasSensor()) result = ina219Sensor.runOnce(); - if (ina260Sensor.hasSensor() && !ina260Sensor.isInitialized()) + if (ina260Sensor.hasSensor()) result = ina260Sensor.runOnce(); } return result; From d552ee35564951d785f12b5c2b44f5759bc994a5 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sat, 9 Dec 2023 19:12:51 -0600 Subject: [PATCH 050/472] Add heltec-ht62 to CI (#3007) --- .github/workflows/main_matrix.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index a2aa11288..8b28090ca 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -66,6 +66,7 @@ jobs: - board: tlora-v2-1-1_6 - board: tlora-v2-1-1_8 - board: tbeam + - board: heltec-ht62-esp32c3-sx1262 - board: heltec-v1 - board: heltec-v2_0 - board: heltec-v2_1 From 796592b5869ed3655d1143d91d8ca1008db4f488 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Tue, 22 Aug 2023 16:23:02 +0200 Subject: [PATCH 051/472] UI/UX: Display delivered message on incoming ACK. Needs more work --- src/modules/CannedMessageModule.cpp | 28 ++++++++++++++++++++++++++-- src/modules/CannedMessageModule.h | 28 +++++++++++++++++++++++++--- 2 files changed, 51 insertions(+), 5 deletions(-) diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index ade9d0e5a..f85a7b1fd 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -244,7 +244,8 @@ int32_t CannedMessageModule::runOnce() } // LOG_DEBUG("Check status\n"); UIFrameEvent e = {false, true}; - if (this->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE) { + if ((this->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE) || + (this->runState == CANNED_MESSAGE_RUN_STATE_ACK_RECEIVED)) { // TODO: might have some feedback of sendig state this->runState = CANNED_MESSAGE_RUN_STATE_INACTIVE; e.frameChanged = true; @@ -483,7 +484,12 @@ void CannedMessageModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *st { char buffer[50]; - if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE) { + if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_ACK_RECEIVED) { + display->setTextAlignment(TEXT_ALIGN_CENTER); + display->setFont(FONT_MEDIUM); + display->drawStringf(display->getWidth() / 2 + x, 0 + y + 12, buffer, "Delivered to %s", + cannedMessageModule->getNodeName(this->incoming)); + } else if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE) { display->setTextAlignment(TEXT_ALIGN_CENTER); display->setFont(FONT_MEDIUM); display->drawString(display->getWidth() / 2 + x, 0 + y + 12, "Sending..."); @@ -546,6 +552,24 @@ void CannedMessageModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *st } } +ProcessMessage CannedMessageModule::handleReceived(const meshtastic_MeshPacket &mp) +{ + if (mp.decoded.portnum == meshtastic_PortNum_ROUTING_APP) { + // look for a request_id + if (mp.decoded.request_id != 0) { + UIFrameEvent e = {false, true}; + e.frameChanged = true; + this->runState = CANNED_MESSAGE_RUN_STATE_ACK_RECEIVED; + this->incoming = mp.decoded.request_id; + this->notifyObservers(&e); + // run the next time 2 seconds later + setIntervalFromNow(2000); + } + } + + return ProcessMessage::CONTINUE; +} + void CannedMessageModule::loadProtoForModule() { if (!nodeDB.loadProto(cannedMessagesConfigFile, meshtastic_CannedMessageModuleConfig_size, diff --git a/src/modules/CannedMessageModule.h b/src/modules/CannedMessageModule.h index 98467215e..a2abcff89 100644 --- a/src/modules/CannedMessageModule.h +++ b/src/modules/CannedMessageModule.h @@ -9,6 +9,7 @@ enum cannedMessageModuleRunState { CANNED_MESSAGE_RUN_STATE_ACTIVE, CANNED_MESSAGE_RUN_STATE_FREETEXT, CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE, + CANNED_MESSAGE_RUN_STATE_ACK_RECEIVED, CANNED_MESSAGE_RUN_STATE_ACTION_SELECT, CANNED_MESSAGE_RUN_STATE_ACTION_UP, CANNED_MESSAGE_RUN_STATE_ACTION_DOWN, @@ -37,15 +38,29 @@ class CannedMessageModule : public SinglePortModule, public Observabledecoded.portnum) { + case meshtastic_PortNum_TEXT_MESSAGE_APP: + case meshtastic_PortNum_ROUTING_APP: + return true; + default: + return false; + } + } + protected: virtual int32_t runOnce() override; @@ -63,6 +78,12 @@ class CannedMessageModule : public SinglePortModule, public Observable Date: Tue, 22 Aug 2023 20:29:52 +0200 Subject: [PATCH 052/472] Distinguish between ACK/NAK by checking for error reason --- src/modules/CannedMessageModule.cpp | 12 ++++++++++-- src/modules/CannedMessageModule.h | 3 ++- 2 files changed, 12 insertions(+), 3 deletions(-) diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index f85a7b1fd..3bca5edaa 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -487,7 +487,12 @@ void CannedMessageModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *st if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_ACK_RECEIVED) { display->setTextAlignment(TEXT_ALIGN_CENTER); display->setFont(FONT_MEDIUM); - display->drawStringf(display->getWidth() / 2 + x, 0 + y + 12, buffer, "Delivered to %s", + String displayString; + if (this->ack) + displayString = "Delivered to\n%s"; + else + displayString = "Delivery failed\nto %s"; + display->drawStringf(display->getWidth() / 2 + x, 0 + y + 12, buffer, displayString, cannedMessageModule->getNodeName(this->incoming)); } else if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE) { display->setTextAlignment(TEXT_ALIGN_CENTER); @@ -561,6 +566,9 @@ ProcessMessage CannedMessageModule::handleReceived(const meshtastic_MeshPacket & e.frameChanged = true; this->runState = CANNED_MESSAGE_RUN_STATE_ACK_RECEIVED; this->incoming = mp.decoded.request_id; + meshtastic_Routing decoded = meshtastic_Routing_init_default; + pb_decode_from_bytes(mp.decoded.payload.bytes, mp.decoded.payload.size, meshtastic_Routing_fields, &decoded); + this->ack = decoded.error_reason == meshtastic_Routing_Error_NONE; this->notifyObservers(&e); // run the next time 2 seconds later setIntervalFromNow(2000); @@ -674,4 +682,4 @@ String CannedMessageModule::drawWithCursor(String text, int cursor) return result; } -#endif +#endif \ No newline at end of file diff --git a/src/modules/CannedMessageModule.h b/src/modules/CannedMessageModule.h index a2abcff89..8a53d392e 100644 --- a/src/modules/CannedMessageModule.h +++ b/src/modules/CannedMessageModule.h @@ -97,6 +97,7 @@ class CannedMessageModule : public SinglePortModule, public Observable Date: Mon, 11 Dec 2023 15:11:10 +0100 Subject: [PATCH 053/472] Look into tophone queue for the received packet. - only works if we don't have a phone connected, but that is probably dsired - this will send a copy of device-originating text messgaes to a connected phone. Breaking change. - this will iterate the tophone queue by deconstructing and reconstructing it every time we look for an ID. Probably also mangles the queue oder since it aborts when a ID is found. - Can we navigate the packet pool instead? If so, how? - Let's keep this in draft state for now --- src/mesh/MeshService.cpp | 16 ++++++++++++++++ src/mesh/MeshService.h | 3 +++ src/mesh/TypedQueue.h | 4 ++++ src/modules/CannedMessageModule.cpp | 17 ++++++++++------- src/modules/CannedMessageModule.h | 2 +- 5 files changed, 34 insertions(+), 8 deletions(-) diff --git a/src/mesh/MeshService.cpp b/src/mesh/MeshService.cpp index 4fd9523c0..231ba3ac2 100644 --- a/src/mesh/MeshService.cpp +++ b/src/mesh/MeshService.cpp @@ -140,6 +140,22 @@ void MeshService::reloadOwner(bool shouldSave) } } +// search the queue for a request id and return the matching nodenum +NodeNum MeshService::getNodenumFromRequestId(uint32_t request_id) +{ + NodeNum nodenum = 0; + for (int i = 0; i < toPhoneQueue.numUsed(); i++) { + meshtastic_MeshPacket *p = toPhoneQueue.dequeuePtr(0); + // put it right back on the queue + toPhoneQueue.enqueue(p, 0); + if (p->id == request_id) { + nodenum = p->to; + break; + } + } + return nodenum; +} + /** * Given a ToRadio buffer parse it and properly handle it (setup radio, owner or send packet into the mesh) * Called by PhoneAPI.handleToRadio. Note: p is a scratch buffer, this function is allowed to write to it but it can not keep a diff --git a/src/mesh/MeshService.h b/src/mesh/MeshService.h index eb40b7712..6d73c076a 100644 --- a/src/mesh/MeshService.h +++ b/src/mesh/MeshService.h @@ -82,6 +82,9 @@ class MeshService /// Return the next MqttClientProxyMessage packet destined to the phone. meshtastic_MqttClientProxyMessage *getMqttClientProxyMessageForPhone() { return toPhoneMqttProxyQueue.dequeuePtr(0); } + // search the queue for a request id and return the matching nodenum + NodeNum getNodenumFromRequestId(uint32_t request_id); + // Release QueueStatus packet to pool void releaseQueueStatusToPool(meshtastic_QueueStatus *p) { queueStatusPool.release(p); } diff --git a/src/mesh/TypedQueue.h b/src/mesh/TypedQueue.h index c08f9183b..c96edae8e 100644 --- a/src/mesh/TypedQueue.h +++ b/src/mesh/TypedQueue.h @@ -27,6 +27,8 @@ template class TypedQueue bool isEmpty() { return uxQueueMessagesWaiting(h) == 0; } + int numUsed() { return uxQueueMessagesWaiting(h); } + /** euqueue a packet. Also, maxWait used to default to portMAX_DELAY, but we now want to callers to THINK about what blocking * they want */ bool enqueue(T x, TickType_t maxWait) @@ -80,6 +82,8 @@ template class TypedQueue bool isEmpty() { return q.empty(); } + int numUsed() { return q.size(); } + bool enqueue(T x, TickType_t maxWait = portMAX_DELAY) { if (reader) { diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index 3bca5edaa..dedfdb850 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -233,7 +233,9 @@ void CannedMessageModule::sendText(NodeNum dest, const char *message, bool wantR LOG_INFO("Sending message id=%d, dest=%x, msg=%.*s\n", p->id, p->to, p->decoded.payload.size, p->decoded.payload.bytes); - service.sendToMesh(p); + service.sendToMesh( + p, RX_SRC_LOCAL, + true); // send to mesh, cc to phone. Even if there's no phone connected, this stores the message to match ACKs } int32_t CannedMessageModule::runOnce() @@ -245,7 +247,7 @@ int32_t CannedMessageModule::runOnce() // LOG_DEBUG("Check status\n"); UIFrameEvent e = {false, true}; if ((this->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE) || - (this->runState == CANNED_MESSAGE_RUN_STATE_ACK_RECEIVED)) { + (this->runState == CANNED_MESSAGE_RUN_STATE_ACK_NACK_RECEIVED)) { // TODO: might have some feedback of sendig state this->runState = CANNED_MESSAGE_RUN_STATE_INACTIVE; e.frameChanged = true; @@ -484,14 +486,15 @@ void CannedMessageModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *st { char buffer[50]; - if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_ACK_RECEIVED) { + if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_ACK_NACK_RECEIVED) { display->setTextAlignment(TEXT_ALIGN_CENTER); display->setFont(FONT_MEDIUM); String displayString; - if (this->ack) + if (this->ack) { displayString = "Delivered to\n%s"; - else + } else { displayString = "Delivery failed\nto %s"; + } display->drawStringf(display->getWidth() / 2 + x, 0 + y + 12, buffer, displayString, cannedMessageModule->getNodeName(this->incoming)); } else if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE) { @@ -564,8 +567,8 @@ ProcessMessage CannedMessageModule::handleReceived(const meshtastic_MeshPacket & if (mp.decoded.request_id != 0) { UIFrameEvent e = {false, true}; e.frameChanged = true; - this->runState = CANNED_MESSAGE_RUN_STATE_ACK_RECEIVED; - this->incoming = mp.decoded.request_id; + this->runState = CANNED_MESSAGE_RUN_STATE_ACK_NACK_RECEIVED; + this->incoming = service.getNodenumFromRequestId(mp.decoded.request_id); meshtastic_Routing decoded = meshtastic_Routing_init_default; pb_decode_from_bytes(mp.decoded.payload.bytes, mp.decoded.payload.size, meshtastic_Routing_fields, &decoded); this->ack = decoded.error_reason == meshtastic_Routing_Error_NONE; diff --git a/src/modules/CannedMessageModule.h b/src/modules/CannedMessageModule.h index 8a53d392e..b41fba045 100644 --- a/src/modules/CannedMessageModule.h +++ b/src/modules/CannedMessageModule.h @@ -9,7 +9,7 @@ enum cannedMessageModuleRunState { CANNED_MESSAGE_RUN_STATE_ACTIVE, CANNED_MESSAGE_RUN_STATE_FREETEXT, CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE, - CANNED_MESSAGE_RUN_STATE_ACK_RECEIVED, + CANNED_MESSAGE_RUN_STATE_ACK_NACK_RECEIVED, CANNED_MESSAGE_RUN_STATE_ACTION_SELECT, CANNED_MESSAGE_RUN_STATE_ACTION_UP, CANNED_MESSAGE_RUN_STATE_ACTION_DOWN, From 385b29c9776900d107029c4a63770abdc9a342b4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Mon, 11 Dec 2023 15:35:22 +0100 Subject: [PATCH 054/472] we don't use the static MemoryPool anywhere, ditch dead code. --- src/mesh/MemoryPool.h | 55 ------------------------------------------- 1 file changed, 55 deletions(-) diff --git a/src/mesh/MemoryPool.h b/src/mesh/MemoryPool.h index 84cac7eff..d30404b9f 100644 --- a/src/mesh/MemoryPool.h +++ b/src/mesh/MemoryPool.h @@ -73,58 +73,3 @@ template class MemoryDynamic : public Allocator return p; } }; - -/** - * A pool based allocator - * - */ -template class MemoryPool : public Allocator -{ - PointerQueue dead; - - T *buf; // our large raw block of memory - - size_t maxElements; - - public: - explicit MemoryPool(size_t _maxElements) : dead(_maxElements), maxElements(_maxElements) - { - buf = new T[maxElements]; - - // prefill dead - for (size_t i = 0; i < maxElements; i++) - release(&buf[i]); - } - - ~MemoryPool() { delete[] buf; } - - /// Return a buffer for use by others - void release(T *p) - { - assert(p >= buf && - (size_t)(p - buf) < - maxElements); // sanity check to make sure a programmer didn't free something that didn't come from this pool - assert(dead.enqueue(p, 0)); - } - -#ifdef HAS_FREE_RTOS - /// Return a buffer from an ISR, if higherPriWoken is set to true you have some work to do ;-) - void releaseFromISR(T *p, BaseType_t *higherPriWoken) - { - assert(p >= buf && - (size_t)(p - buf) < - maxElements); // sanity check to make sure a programmer didn't free something that didn't come from this pool - assert(dead.enqueueFromISR(p, higherPriWoken)); - } -#endif - - protected: - /// Return a queable object which has been prefilled with zeros - allow timeout to wait for available buffers (you - /// probably don't want this version). - virtual T *alloc(TickType_t maxWait) - { - T *p = dead.dequeuePtr(maxWait); - assert(p); - return p; - } -}; From d952da8b1e1a2b1184dcc42c265574537858909f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Mon, 11 Dec 2023 15:44:32 +0100 Subject: [PATCH 055/472] make sure the queue stays in te same order the memory pool can NOT be iterated easily, since it's not a linear object. --- src/mesh/MeshService.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/mesh/MeshService.cpp b/src/mesh/MeshService.cpp index 231ba3ac2..9101712d1 100644 --- a/src/mesh/MeshService.cpp +++ b/src/mesh/MeshService.cpp @@ -146,12 +146,12 @@ NodeNum MeshService::getNodenumFromRequestId(uint32_t request_id) NodeNum nodenum = 0; for (int i = 0; i < toPhoneQueue.numUsed(); i++) { meshtastic_MeshPacket *p = toPhoneQueue.dequeuePtr(0); - // put it right back on the queue - toPhoneQueue.enqueue(p, 0); if (p->id == request_id) { nodenum = p->to; - break; + // make sure to continue this to make one full loop } + // put it right back on the queue + toPhoneQueue.enqueue(p, 0); } return nodenum; } From d14d2c89c3aa8f73fef7e1e2fa2fda83b6f9964d Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Tue, 12 Dec 2023 08:36:37 -0600 Subject: [PATCH 056/472] RTTTL ringtones on T-Deck / T-Watch S3 and potentially more I2S audio enabled devices (#2917) * WIP * ESP8266 SAM fun * I2S audio / ext. notification module * Remove * Protos * Add use_i2s_as_buzzer from protos * Fixes * Stuff * Thing * Ext. Notification working(ish) * Remove SAM commented code * Trunk upgrade * Trunk * Fixes * Slow not fast... :-| * T-Deck and T-Watch don't use normal buttons * Stop ext. notification nagging with touchscreen as well * Add button gpio back for T-Deck, but guard against long-press during ext. notification * Ext. notification wrap up * Better place to guard against long-press false positives * Adjust default gain and guard against non-i2s devices referencing audio-thread * Simplify guard logic with a boolean * Supress uninitMemberVar * Protos merge got out of wack * Trunk resolution * Remove extra crap * Cleanup and thread-interval * Default to alert message buzzer and add nag timeout * Formatting --- src/AudioThread.h | 77 ++++++++++++++++++++++ src/ButtonThread.h | 7 ++ src/input/TouchScreenImpl1.cpp | 7 +- src/main.cpp | 12 +++- src/main.h | 6 ++ src/mesh/NodeDB.cpp | 7 +- src/modules/ExternalNotificationModule.cpp | 51 ++++++++++++-- suppressions.txt | 3 +- variants/t-deck/platformio.ini | 8 ++- variants/t-deck/variant.h | 6 ++ variants/t-watch-s3/platformio.ini | 6 +- variants/t-watch-s3/variant.h | 7 +- 12 files changed, 179 insertions(+), 18 deletions(-) create mode 100644 src/AudioThread.h diff --git a/src/AudioThread.h b/src/AudioThread.h new file mode 100644 index 000000000..c9f253440 --- /dev/null +++ b/src/AudioThread.h @@ -0,0 +1,77 @@ +#pragma once +#include "PowerFSM.h" +#include "concurrency/OSThread.h" +#include "configuration.h" +#include "main.h" +#include "sleep.h" + +#ifdef HAS_I2S +#include +#include +#include +#include + +#define AUDIO_THREAD_INTERVAL_MS 100 + +class AudioThread : public concurrency::OSThread +{ + public: + AudioThread() : OSThread("AudioThread") { initOutput(); } + + void beginRttl(const void *data, uint32_t len) + { + setCPUFast(true); + rtttlFile = new AudioFileSourcePROGMEM(data, len); + i2sRtttl = new AudioGeneratorRTTTL(); + i2sRtttl->begin(rtttlFile, audioOut); + } + + bool isPlaying() + { + if (i2sRtttl != nullptr) { + return i2sRtttl->isRunning() && i2sRtttl->loop(); + } + return false; + } + + void stop() + { + if (i2sRtttl != nullptr) { + i2sRtttl->stop(); + delete i2sRtttl; + i2sRtttl = nullptr; + } + if (rtttlFile != nullptr) { + delete rtttlFile; + rtttlFile = nullptr; + } + + setCPUFast(false); + } + + protected: + int32_t runOnce() override + { + canSleep = true; // Assume we should not keep the board awake + + // if (i2sRtttl != nullptr && i2sRtttl->isRunning()) { + // i2sRtttl->loop(); + // } + return AUDIO_THREAD_INTERVAL_MS; + } + + private: + void initOutput() + { + audioOut = new AudioOutputI2S(1, AudioOutputI2S::EXTERNAL_I2S); + audioOut->SetPinout(DAC_I2S_BCK, DAC_I2S_WS, DAC_I2S_DOUT); + audioOut->SetGain(0.2); + }; + + AudioGeneratorRTTTL *i2sRtttl = nullptr; + AudioOutputI2S *audioOut; + + AudioFileSourcePROGMEM *rtttlFile; +}; + +#endif diff --git a/src/ButtonThread.h b/src/ButtonThread.h index a60b7730a..5f68aa5b6 100644 --- a/src/ButtonThread.h +++ b/src/ButtonThread.h @@ -5,6 +5,7 @@ #include "configuration.h" #include "graphics/Screen.h" #include "main.h" +#include "modules/ExternalNotificationModule.h" #include "power.h" #include @@ -205,6 +206,12 @@ class ButtonThread : public concurrency::OSThread static void userButtonPressedLongStart() { +#ifdef T_DECK + // False positive long-press triggered on T-Deck with i2s audio, so short circuit + if (moduleConfig.external_notification.enabled && (externalNotificationModule->nagCycleCutoff != UINT32_MAX)) { + return; + } +#endif if (millis() > 30 * 1000) { LOG_DEBUG("Long press start!\n"); longPressTime = millis(); diff --git a/src/input/TouchScreenImpl1.cpp b/src/input/TouchScreenImpl1.cpp index b3152c88a..e38d6c324 100644 --- a/src/input/TouchScreenImpl1.cpp +++ b/src/input/TouchScreenImpl1.cpp @@ -2,6 +2,7 @@ #include "InputBroker.h" #include "PowerFSM.h" #include "configuration.h" +#include "modules/ExternalNotificationModule.h" TouchScreenImpl1 *touchScreenImpl1; @@ -63,7 +64,11 @@ void TouchScreenImpl1::onEvent(const TouchEvent &event) break; } case TOUCH_ACTION_TAP: { - powerFSM.trigger(EVENT_INPUT); + if (moduleConfig.external_notification.enabled && (externalNotificationModule->nagCycleCutoff != UINT32_MAX)) { + externalNotificationModule->stopNow(); + } else { + powerFSM.trigger(EVENT_INPUT); + } break; } default: diff --git a/src/main.cpp b/src/main.cpp index c8fc61e4c..505c1c804 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -84,6 +84,11 @@ NRF52Bluetooth *nrf52Bluetooth; #include "AmbientLightingThread.h" #endif +#ifdef HAS_I2S +#include "AudioThread.h" +AudioThread *audioThread; +#endif + using namespace concurrency; // We always create a screen object, but we only init it if we find the hardware @@ -122,6 +127,7 @@ ATECCX08A atecc; #ifdef T_WATCH_S3 Adafruit_DRV2605 drv; #endif + bool isVibrating = false; bool eink_found = true; @@ -671,6 +677,11 @@ void setup() } nodeStatus->observe(&nodeDB.newStatus); +#ifdef HAS_I2S + LOG_DEBUG("Starting audio thread\n"); + audioThread = new AudioThread(); +#endif + service.init(); // Now that the mesh service is created, create any modules @@ -880,7 +891,6 @@ void setup() // This must be _after_ service.init because we need our preferences loaded from flash to have proper timeout values PowerFSM_setup(); // we will transition to ON in a couple of seconds, FIXME, only do this for cold boots, not waking from SDS powerFSMthread = new PowerFSMThread(); - setCPUFast(false); // 80MHz is fine for our slow peripherals } diff --git a/src/main.h b/src/main.h index 5c9de1b81..52e9a4271 100644 --- a/src/main.h +++ b/src/main.h @@ -42,6 +42,12 @@ extern ATECCX08A atecc; #include extern Adafruit_DRV2605 drv; #endif + +#ifdef HAS_I2S +#include "AudioThread.h" +extern AudioThread *audioThread; +#endif + extern bool isVibrating; extern int TCPPort; // set by Portduino diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 9c623d973..0fc69f8aa 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -245,9 +245,12 @@ void NodeDB::installDefaultModuleConfig() moduleConfig.external_notification.output_ms = 1000; moduleConfig.external_notification.nag_timeout = 60; #endif -#ifdef T_WATCH_S3 - // Don't worry about the other settings, we'll use the DRV2056 behavior for notifications +#ifdef HAS_I2S + // Don't worry about the other settings for T-Watch, we'll also use the DRV2056 behavior for notifications moduleConfig.external_notification.enabled = true; + moduleConfig.external_notification.use_i2s_as_buzzer = true; + moduleConfig.external_notification.alert_message_buzzer = true; + moduleConfig.external_notification.nag_timeout = 60; #endif #ifdef NANO_G2_ULTRA moduleConfig.external_notification.enabled = true; diff --git a/src/modules/ExternalNotificationModule.cpp b/src/modules/ExternalNotificationModule.cpp index 6a7641b04..bdbe044b5 100644 --- a/src/modules/ExternalNotificationModule.cpp +++ b/src/modules/ExternalNotificationModule.cpp @@ -20,11 +20,10 @@ #include "Router.h" #include "buzz/buzz.h" #include "configuration.h" +#include "main.h" #include "mesh/generated/meshtastic/rtttl.pb.h" #include -#include "main.h" - #ifdef HAS_NCP5623 #include @@ -54,6 +53,8 @@ bool ascending = true; #endif #define EXT_NOTIFICATION_MODULE_OUTPUT_MS 1000 +#define EXT_NOTIFICATION_DEFAULT_THREAD_MS 25 + #define ASCII_BELL 0x07 meshtastic_RTTTLConfig rtttlConfig; @@ -71,7 +72,12 @@ int32_t ExternalNotificationModule::runOnce() if (!moduleConfig.external_notification.enabled) { return INT32_MAX; // we don't need this thread here... } else { - if ((nagCycleCutoff < millis()) && !rtttl::isPlaying()) { + + bool isPlaying = rtttl::isPlaying(); +#ifdef HAS_I2S + isPlaying = rtttl::isPlaying() || audioThread->isPlaying(); +#endif + if ((nagCycleCutoff < millis()) && !isPlaying) { // let the song finish if we reach timeout nagCycleCutoff = UINT32_MAX; LOG_INFO("Turning off external notification: "); @@ -132,6 +138,16 @@ int32_t ExternalNotificationModule::runOnce() #endif } + // Play RTTTL over i2s audio interface if enabled as buzzer +#ifdef HAS_I2S + if (moduleConfig.external_notification.use_i2s_as_buzzer) { + if (audioThread->isPlaying()) { + // Continue playing + } else if (isNagging && (nagCycleCutoff >= millis())) { + audioThread->beginRttl(rtttlConfig.ringtone, strlen_P(rtttlConfig.ringtone)); + } + } +#endif // now let the PWM buzzer play if (moduleConfig.external_notification.use_pwm) { if (rtttl::isPlaying()) { @@ -142,7 +158,7 @@ int32_t ExternalNotificationModule::runOnce() } } - return 25; + return EXT_NOTIFICATION_DEFAULT_THREAD_MS; } } @@ -175,6 +191,7 @@ void ExternalNotificationModule::setExternalOn(uint8_t index) digitalWrite(output, (moduleConfig.external_notification.active ? true : false)); break; } + #ifdef HAS_NCP5623 if (rgb_found.type == ScanI2C::NCP5623) { rgb.setColor(red, green, blue); @@ -226,6 +243,9 @@ bool ExternalNotificationModule::getExternal(uint8_t index) void ExternalNotificationModule::stopNow() { rtttl::stop(); +#ifdef HAS_I2S + audioThread->stop(); +#endif nagCycleCutoff = 1; // small value isNagging = false; setIntervalFromNow(0); @@ -246,6 +266,7 @@ ExternalNotificationModule::ExternalNotificationModule() // moduleConfig.external_notification.alert_message = true; // moduleConfig.external_notification.alert_message_buzzer = true; // moduleConfig.external_notification.alert_message_vibra = true; + // moduleConfig.external_notification.use_i2s_as_buzzer = true; // moduleConfig.external_notification.active = true; // moduleConfig.external_notification.alert_bell = 1; @@ -255,6 +276,13 @@ ExternalNotificationModule::ExternalNotificationModule() // moduleConfig.external_notification.output_vibra = 28; // RAK4631 IO7 // moduleConfig.external_notification.nag_timeout = 300; + // T-Watch / T-Deck i2s audio as buzzer: + // moduleConfig.external_notification.enabled = true; + // moduleConfig.external_notification.nag_timeout = 300; + // moduleConfig.external_notification.output_ms = 1000; + // moduleConfig.external_notification.use_i2s_as_buzzer = true; + // moduleConfig.external_notification.alert_message_buzzer = true; + if (moduleConfig.external_notification.enabled) { if (!nodeDB.loadProto(rtttlConfigFile, meshtastic_RTTTLConfig_size, sizeof(meshtastic_RTTTLConfig), &meshtastic_RTTTLConfig_msg, &rtttlConfig)) { @@ -309,14 +337,13 @@ ExternalNotificationModule::ExternalNotificationModule() ProcessMessage ExternalNotificationModule::handleReceived(const meshtastic_MeshPacket &mp) { if (moduleConfig.external_notification.enabled) { -#if T_WATCH_S3 +#ifdef T_WATCH_S3 drv.setWaveform(0, 75); drv.setWaveform(1, 56); drv.setWaveform(2, 0); drv.go(); #endif if (getFrom(&mp) != nodeDB.getNodeNum()) { - // Check if the message contains a bell character. Don't do this loop for every pin, just once. auto &p = mp.decoded; bool containsBell = false; @@ -359,7 +386,11 @@ ProcessMessage ExternalNotificationModule::handleReceived(const meshtastic_MeshP if (!moduleConfig.external_notification.use_pwm) { setExternalOn(2); } else { +#ifdef HAS_I2S + audioThread->beginRttl(rtttlConfig.ringtone, strlen_P(rtttlConfig.ringtone)); +#else rtttl::begin(config.device.buzzer_gpio, rtttlConfig.ringtone); +#endif } if (moduleConfig.external_notification.nag_timeout) { nagCycleCutoff = millis() + moduleConfig.external_notification.nag_timeout * 1000; @@ -394,10 +425,16 @@ ProcessMessage ExternalNotificationModule::handleReceived(const meshtastic_MeshP if (moduleConfig.external_notification.alert_message_buzzer) { LOG_INFO("externalNotificationModule - Notification Module (Buzzer)\n"); isNagging = true; - if (!moduleConfig.external_notification.use_pwm) { + if (!moduleConfig.external_notification.use_pwm && !moduleConfig.external_notification.use_i2s_as_buzzer) { setExternalOn(2); } else { +#ifdef HAS_I2S + if (moduleConfig.external_notification.use_i2s_as_buzzer) { + audioThread->beginRttl(rtttlConfig.ringtone, strlen_P(rtttlConfig.ringtone)); + } +#else rtttl::begin(config.device.buzzer_gpio, rtttlConfig.ringtone); +#endif } if (moduleConfig.external_notification.nag_timeout) { nagCycleCutoff = millis() + moduleConfig.external_notification.nag_timeout * 1000; diff --git a/suppressions.txt b/suppressions.txt index e65afc0bf..6cbd38d47 100644 --- a/suppressions.txt +++ b/suppressions.txt @@ -49,4 +49,5 @@ virtualCallInConstructor passedByValue:*/RedirectablePrint.h -internalAstError:*/CrossPlatformCryptoEngine.cpp \ No newline at end of file +internalAstError:*/CrossPlatformCryptoEngine.cpp +uninitMemberVar:*/AudioThread.h \ No newline at end of file diff --git a/variants/t-deck/platformio.ini b/variants/t-deck/platformio.ini index 38e334a30..cb6033300 100644 --- a/variants/t-deck/platformio.ini +++ b/variants/t-deck/platformio.ini @@ -2,8 +2,8 @@ [env:t-deck] extends = esp32s3_base board = t-deck -upload_protocol = esp-builtin -debug_tool = esp-builtin +upload_protocol = esptool +#upload_port = COM29 build_flags = ${esp32_base.build_flags} -DT_DECK @@ -12,4 +12,6 @@ build_flags = ${esp32_base.build_flags} -Ivariants/t-deck lib_deps = ${esp32s3_base.lib_deps} - lovyan03/LovyanGFX@^1.1.9 \ No newline at end of file + lovyan03/LovyanGFX@^1.1.9 + earlephilhower/ESP8266Audio@^1.9.7 + earlephilhower/ESP8266SAM@^1.0.1 \ No newline at end of file diff --git a/variants/t-deck/variant.h b/variants/t-deck/variant.h index 446e22732..62ac0a373 100644 --- a/variants/t-deck/variant.h +++ b/variants/t-deck/variant.h @@ -65,6 +65,12 @@ #define ES7210_LRCK 21 #define ES7210_MCLK 48 +// dac / amp +#define HAS_I2S +#define DAC_I2S_BCK 7 +#define DAC_I2S_WS 5 +#define DAC_I2S_DOUT 6 + // LoRa #define USE_SX1262 #define USE_SX1268 diff --git a/variants/t-watch-s3/platformio.ini b/variants/t-watch-s3/platformio.ini index 162384bfd..d03273ed4 100644 --- a/variants/t-watch-s3/platformio.ini +++ b/variants/t-watch-s3/platformio.ini @@ -3,6 +3,8 @@ extends = esp32s3_base board = t-watch-s3 upload_protocol = esptool +upload_speed = 115200 +upload_port = /dev/tty.usbmodem3485188D636C1 build_flags = ${esp32_base.build_flags} -DT_WATCH_S3 @@ -12,4 +14,6 @@ build_flags = ${esp32_base.build_flags} lib_deps = ${esp32s3_base.lib_deps} lovyan03/LovyanGFX@^1.1.9 lewisxhe/PCF8563_Library@1.0.1 - adafruit/Adafruit DRV2605 Library@^1.2.2 \ No newline at end of file + adafruit/Adafruit DRV2605 Library@^1.2.2 + earlephilhower/ESP8266Audio@^1.9.7 + earlephilhower/ESP8266SAM@^1.0.1 \ No newline at end of file diff --git a/variants/t-watch-s3/variant.h b/variants/t-watch-s3/variant.h index c30224034..c66fac5ef 100644 --- a/variants/t-watch-s3/variant.h +++ b/variants/t-watch-s3/variant.h @@ -30,6 +30,11 @@ #define TFT_BL ST7789_BACKLIGHT_EN +#define HAS_I2S +#define DAC_I2S_BCK 48 +#define DAC_I2S_WS 15 +#define DAC_I2S_DOUT 46 + #define HAS_AXP2101 #define HAS_RTC 1 @@ -37,8 +42,6 @@ #define I2C_SDA 10 // For QMC6310 sensors and screens #define I2C_SCL 11 // For QMC6310 sensors and screens -#define BUTTON_PIN 0 - #define BMA4XX_INT 14 // Interrupt for BMA_423 axis sensor #define HAS_GPS 0 From 2ebaea317a23565323ab09254b27647438623208 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Tue, 12 Dec 2023 20:27:31 -0600 Subject: [PATCH 057/472] Refactor display handling add Raspbian TFT display (#2998) * Refactor display handling add Raspbian TFT display * Add missed change * Add static casts * Add missed TFT refactor for RAK14014 * Add missed GPIO configuration * Adds Native keyboard input option * Get the ifdefs right * CannedMessage send via queue, not run immediately. * Fixup systemd service file * Add display blanking for Raspberry Pi * Add a couple missed key definitions --------- Co-authored-by: Ben Meadors --- arch/portduino/portduino.ini | 5 +- bin/config-dist.yaml | 36 ++++- bin/meshtasticd.service | 9 +- src/graphics/Screen.cpp | 170 +++++++++++++-------- src/graphics/Screen.h | 18 +-- src/graphics/TFTDisplay.cpp | 153 +++++++++++++++---- src/graphics/TFTDisplay.h | 3 +- src/graphics/images.h | 4 +- src/input/LinuxInput.cpp | 179 +++++++++++++++++++++++ src/input/LinuxInput.h | 64 ++++++++ src/input/LinuxInputImpl.cpp | 14 ++ src/input/LinuxInputImpl.h | 21 +++ src/input/TouchScreenImpl1.cpp | 13 +- src/main.cpp | 4 + src/mesh/NodeDB.cpp | 10 ++ src/modules/CannedMessageModule.cpp | 20 ++- src/modules/Modules.cpp | 11 +- src/platform/portduino/PortduinoGlue.cpp | 47 +++++- src/platform/portduino/PortduinoGlue.h | 30 +++- variants/portduino/platformio.ini | 1 + variants/portduino/variant.h | 1 + 21 files changed, 682 insertions(+), 131 deletions(-) create mode 100644 src/input/LinuxInput.cpp create mode 100644 src/input/LinuxInput.h create mode 100644 src/input/LinuxInputImpl.cpp create mode 100644 src/input/LinuxInputImpl.h diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index 5933850e7..e739d7066 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -1,6 +1,6 @@ ; The Portduino based sim environment on top of any host OS, all hardware will be simulated [portduino_base] -platform = https://github.com/meshtastic/platform-native.git#05255283879a0c65a7d3eba6c468b9186438bb14 +platform = https://github.com/meshtastic/platform-native.git#ff5da1d203b5c1163cfcda858d5f84920187f030 framework = arduino build_src_filter = @@ -28,5 +28,4 @@ build_flags = ${arduino_base.build_flags} -fPIC -Isrc/platform/portduino - -DRADIOLIB_EEPROM_UNSUPPORTED - + -DRADIOLIB_EEPROM_UNSUPPORTED \ No newline at end of file diff --git a/bin/config-dist.yaml b/bin/config-dist.yaml index cde45d1f8..266a9ae20 100644 --- a/bin/config-dist.yaml +++ b/bin/config-dist.yaml @@ -1,5 +1,5 @@ -# Define your devices here using Broadcom pin numbering -# Uncomment the block that corresponds to your hardware +### Define your devices here using Broadcom pin numbering +### Uncomment the block that corresponds to your hardware --- Lora: # Module: sx1262 # Waveshare SX126X XXXM @@ -25,16 +25,40 @@ Lora: # CS: 7 # IRQ: 25 -# Set gpio chip to use in /dev/. Defaults to 0. -# Notably the Raspberry Pi 5 puts the GPIO header on gpiochip4 +### Set gpio chip to use in /dev/. Defaults to 0. +### Notably the Raspberry Pi 5 puts the GPIO header on gpiochip4 # gpiochip: 4 -# Define GPIO buttons here: +### Define GPIO buttons here: GPIO: # User: 6 -# Define GPS +### Define GPS GPS: # SerialPath: /dev/ttyS0 + +### Set up SPI displays here. Note that I2C displays are generally auto-detected. + +Display: + +### Waveshare 2.8inch RPi LCD +# Panel: ST7789 +# CS: 8 +# DC: 22 # Data/Command pin +# Backlight: 18 +# Width: 240 +# Height: 320 +# Reset: 27 +# Rotate: true + +Touchscreen: +# Module: XPT2046 +# CS: 7 +# IRQ: 17 + +### Configure device for direct keyboard input + +Input: +# KeyboardDevice: /dev/input/event0 diff --git a/bin/meshtasticd.service b/bin/meshtasticd.service index 4ed1bfd8f..f15fdc871 100644 --- a/bin/meshtasticd.service +++ b/bin/meshtasticd.service @@ -1,9 +1,12 @@ -[unit] -description=Meshtastic Native Daemon +[Unit] +Description=Meshtastic Native Daemon +After=network-online.target [Service] +User=root +Group=root Type=simple ExecStart=/usr/sbin/meshtasticd [Install] -WantedBy=multi-user.target +WantedBy=multi-user.target \ No newline at end of file diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 417a6e454..a7fcd0c34 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -52,6 +52,10 @@ along with this program. If not, see . #include "modules/esp32/StoreForwardModule.h" #endif +#if ARCH_RASPBERRY_PI +#include "platform/portduino/PortduinoGlue.h" +#endif + #ifdef OLED_RU #include "fonts/OLEDDisplayFontsRU.h" #endif @@ -909,10 +913,40 @@ static void drawNodeInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_ } Screen::Screen(ScanI2C::DeviceAddress address, meshtastic_Config_DisplayConfig_OledType screenType, OLEDDISPLAY_GEOMETRY geometry) - : concurrency::OSThread("Screen"), address_found(address), model(screenType), geometry(geometry), cmdQueue(32), - dispdev(address.address, -1, -1, geometry, (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE), - ui(&dispdev) + : concurrency::OSThread("Screen"), address_found(address), model(screenType), geometry(geometry), cmdQueue(32) { +#if defined(USE_SH1106) || defined(USE_SH1107) || defined(USE_SH1107_128_64) + dispdev = new SH1106Wire(address.address, -1, -1, geometry, + (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); +#elif defined(USE_SSD1306) + dispdev = new SSD1306Wire(address.address, -1, -1, geometry, + (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); +#elif defined(ST7735_CS) || defined(ILI9341_DRIVER) || defined(ST7789_CS) || defined(RAK14014) + dispdev = new TFTDisplay(address.address, -1, -1, geometry, + (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); +#elif defined(USE_EINK) + dispdev = new EInkDisplay(address.address, -1, -1, geometry, + (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); +#elif defined(USE_ST7567) + dispdev = new ST7567Wire(address.address, -1, -1, geometry, + (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); +#elif ARCH_RASPBERRY_PI + if (settingsMap[displayPanel] == st7789) { + LOG_DEBUG("Making TFTDisplay!\n"); + dispdev = new TFTDisplay(address.address, -1, -1, geometry, + (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); + } else { + dispdev = new AutoOLEDWire(address.address, -1, -1, geometry, + (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); + isAUTOOled = true; + } +#else + dispdev = new AutoOLEDWire(address.address, -1, -1, geometry, + (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); + isAUTOOled = true; +#endif + + ui = new OLEDDisplayUi(dispdev); cmdQueue.setReader(this); } @@ -925,8 +959,8 @@ void Screen::doDeepSleep() #ifdef USE_EINK static FrameCallback sleepFrames[] = {drawSleepScreen}; static const int sleepFrameCount = sizeof(sleepFrames) / sizeof(sleepFrames[0]); - ui.setFrames(sleepFrames, sleepFrameCount); - ui.update(); + ui->setFrames(sleepFrames, sleepFrameCount); + ui->update(); #endif setOn(false); } @@ -942,14 +976,16 @@ void Screen::handleSetOn(bool on) #ifdef T_WATCH_S3 PMU->enablePowerOutput(XPOWERS_ALDO2); #endif - dispdev.displayOn(); - dispdev.displayOn(); +#if !ARCH_RASPBERRY_PI + dispdev->displayOn(); +#endif + dispdev->displayOn(); enabled = true; setInterval(0); // Draw ASAP runASAP = true; } else { LOG_INFO("Turning off screen\n"); - dispdev.displayOff(); + dispdev->displayOff(); #ifdef T_WATCH_S3 PMU->disablePowerOutput(XPOWERS_ALDO2); #endif @@ -966,32 +1002,33 @@ void Screen::setup() useDisplay = true; #ifdef AutoOLEDWire_h - dispdev.setDetected(model); + if (isAUTOOled) + static_cast(dispdev)->setDetected(model); #endif #ifdef USE_SH1107_128_64 - dispdev.setSubtype(7); + static_cast(dispdev)->setSubtype(7); #endif // Initialising the UI will init the display too. - ui.init(); + ui->init(); - displayWidth = dispdev.width(); - displayHeight = dispdev.height(); + displayWidth = dispdev->width(); + displayHeight = dispdev->height(); - ui.setTimePerTransition(0); + ui->setTimePerTransition(0); - ui.setIndicatorPosition(BOTTOM); + ui->setIndicatorPosition(BOTTOM); // Defines where the first frame is located in the bar. - ui.setIndicatorDirection(LEFT_RIGHT); - ui.setFrameAnimation(SLIDE_LEFT); + ui->setIndicatorDirection(LEFT_RIGHT); + ui->setFrameAnimation(SLIDE_LEFT); // Don't show the page swipe dots while in boot screen. - ui.disableAllIndicators(); + ui->disableAllIndicators(); // Store a pointer to Screen so we can get to it from static functions. - ui.getUiState()->userData = this; + ui->getUiState()->userData = this; // Set the utf8 conversion function - dispdev.setFontTableLookupFunction(customFontTableLookup); + dispdev->setFontTableLookupFunction(customFontTableLookup); if (strlen(oemStore.oem_text) > 0) logo_timeout *= 2; @@ -999,23 +1036,23 @@ void Screen::setup() // Add frames. static FrameCallback bootFrames[] = {drawBootScreen}; static const int bootFrameCount = sizeof(bootFrames) / sizeof(bootFrames[0]); - ui.setFrames(bootFrames, bootFrameCount); + ui->setFrames(bootFrames, bootFrameCount); // No overlays. - ui.setOverlays(nullptr, 0); + ui->setOverlays(nullptr, 0); // Require presses to switch between frames. - ui.disableAutoTransition(); + ui->disableAutoTransition(); // Set up a log buffer with 3 lines, 32 chars each. - dispdev.setLogBuffer(3, 32); + dispdev->setLogBuffer(3, 32); #ifdef SCREEN_MIRROR - dispdev.mirrorScreen(); + dispdev->mirrorScreen(); #else // Standard behaviour is to FLIP the screen (needed on T-Beam). If this config item is set, unflip it, and thereby logically // flip it. If you have a headache now, you're welcome. if (!config.display.flip_screen) { - dispdev.flipScreenVertically(); + dispdev->flipScreenVertically(); } #endif @@ -1023,20 +1060,30 @@ void Screen::setup() uint8_t dmac[6]; getMacAddr(dmac); snprintf(ourId, sizeof(ourId), "%02x%02x", dmac[4], dmac[5]); +#if ARCH_RASPBERRY_PI + handleSetOn(false); // force clean init +#endif // Turn on the display. handleSetOn(true); // On some ssd1306 clones, the first draw command is discarded, so draw it // twice initially. Skip this for EINK Displays to save a few seconds during boot - ui.update(); + ui->update(); #ifndef USE_EINK - ui.update(); + ui->update(); #endif serialSinceMsec = millis(); -#if HAS_TOUCHSCREEN - touchScreenImpl1 = new TouchScreenImpl1(dispdev.getWidth(), dispdev.getHeight(), dispdev.getTouch); +#if ARCH_RASPBERRY_PI + if (settingsMap[touchscreenModule]) { + touchScreenImpl1 = + new TouchScreenImpl1(dispdev->getWidth(), dispdev->getHeight(), static_cast(dispdev)->getTouch); + touchScreenImpl1->init(); + } +#elif HAS_TOUCHSCREEN + touchScreenImpl1 = + new TouchScreenImpl1(dispdev->getWidth(), dispdev->getHeight(), static_cast(dispdev)->getTouch); touchScreenImpl1->init(); #endif @@ -1057,7 +1104,7 @@ void Screen::forceDisplay() { // Nasty hack to force epaper updates for 'key' frames. FIXME, cleanup. #ifdef USE_EINK - dispdev.forceDisplay(); + static_cast(dispdev)->forceDisplay(); #endif } @@ -1088,10 +1135,10 @@ int32_t Screen::runOnce() // Change frames. static FrameCallback bootOEMFrames[] = {drawOEMBootScreen}; static const int bootOEMFrameCount = sizeof(bootOEMFrames) / sizeof(bootOEMFrames[0]); - ui.setFrames(bootOEMFrames, bootOEMFrameCount); - ui.update(); + ui->setFrames(bootOEMFrames, bootOEMFrameCount); + ui->update(); #ifndef USE_EINK - ui.update(); + ui->update(); #endif showingOEMBootScreen = false; } @@ -1164,16 +1211,16 @@ int32_t Screen::runOnce() // this must be before the frameState == FIXED check, because we always // want to draw at least one FIXED frame before doing forceDisplay - ui.update(); + ui->update(); // Switch to a low framerate (to save CPU) when we are not in transition // but we should only call setTargetFPS when framestate changes, because // otherwise that breaks animations. - if (targetFramerate != IDLE_FRAMERATE && ui.getUiState()->frameState == FIXED) { - // oldFrameState = ui.getUiState()->frameState; + if (targetFramerate != IDLE_FRAMERATE && ui->getUiState()->frameState == FIXED) { + // oldFrameState = ui->getUiState()->frameState; targetFramerate = IDLE_FRAMERATE; - ui.setTargetFPS(targetFramerate); + ui->setTargetFPS(targetFramerate); forceDisplay(); } @@ -1189,7 +1236,7 @@ int32_t Screen::runOnce() } // LOG_DEBUG("want fps %d, fixed=%d\n", targetFramerate, - // ui.getUiState()->frameState); If we are scrolling we need to be called + // ui->getUiState()->frameState); If we are scrolling we need to be called // soon, otherwise just 1 fps (to save CPU) We also ask to be called twice // as fast as we really need so that any rounding errors still result with // the correct framerate @@ -1221,8 +1268,8 @@ void Screen::setSSLFrames() if (address_found.address) { // LOG_DEBUG("showing SSL frames\n"); static FrameCallback sslFrames[] = {drawSSLScreen}; - ui.setFrames(sslFrames, 1); - ui.update(); + ui->setFrames(sslFrames, 1); + ui->update(); } } @@ -1306,8 +1353,8 @@ void Screen::setFrames() LOG_DEBUG("Finished building frames. numframes: %d\n", numframes); - ui.setFrames(normalFrames, numframes); - ui.enableAllIndicators(); + ui->setFrames(normalFrames, numframes); + ui->enableAllIndicators(); prevFrame = -1; // Force drawNodeInfo to pick a new node (because our list // just changed) @@ -1327,8 +1374,8 @@ void Screen::handleStartBluetoothPinScreen(uint32_t pin) void Screen::setFrameImmediateDraw(FrameCallback *drawFrames) { - ui.disableAllIndicators(); - ui.setFrames(drawFrames, 1); + ui->disableAllIndicators(); + ui->setFrames(drawFrames, 1); setFastFramerate(); } @@ -1370,17 +1417,17 @@ void Screen::blink() { setFastFramerate(); uint8_t count = 10; - dispdev.setBrightness(254); + dispdev->setBrightness(254); while (count > 0) { - dispdev.fillRect(0, 0, SCREEN_WIDTH, SCREEN_HEIGHT); - dispdev.display(); + dispdev->fillRect(0, 0, SCREEN_WIDTH, SCREEN_HEIGHT); + dispdev->display(); delay(50); - dispdev.clear(); - dispdev.display(); + dispdev->clear(); + dispdev->display(); delay(50); count = count - 1; } - dispdev.setBrightness(brightness); + dispdev->setBrightness(brightness); } std::string Screen::drawTimeDelta(uint32_t days, uint32_t hours, uint32_t minutes, uint32_t seconds) @@ -1408,15 +1455,15 @@ void Screen::handlePrint(const char *text) if (!useDisplay || !showingNormalScreen) return; - dispdev.print(text); + dispdev->print(text); } void Screen::handleOnPress() { // If screen was off, just wake it, otherwise advance to next frame // If we are in a transition, the press must have bounced, drop it. - if (ui.getUiState()->frameState == FIXED) { - ui.nextFrame(); + if (ui->getUiState()->frameState == FIXED) { + ui->nextFrame(); lastScreenTransition = millis(); setFastFramerate(); } @@ -1426,8 +1473,8 @@ void Screen::handleShowPrevFrame() { // If screen was off, just wake it, otherwise go back to previous frame // If we are in a transition, the press must have bounced, drop it. - if (ui.getUiState()->frameState == FIXED) { - ui.previousFrame(); + if (ui->getUiState()->frameState == FIXED) { + ui->previousFrame(); lastScreenTransition = millis(); setFastFramerate(); } @@ -1437,8 +1484,8 @@ void Screen::handleShowNextFrame() { // If screen was off, just wake it, otherwise advance to next frame // If we are in a transition, the press must have bounced, drop it. - if (ui.getUiState()->frameState == FIXED) { - ui.nextFrame(); + if (ui->getUiState()->frameState == FIXED) { + ui->nextFrame(); lastScreenTransition = millis(); setFastFramerate(); } @@ -1453,7 +1500,7 @@ void Screen::setFastFramerate() // We are about to start a transition so speed up fps targetFramerate = SCREEN_TRANSITION_FRAMERATE; - ui.setTargetFPS(targetFramerate); + ui->setTargetFPS(targetFramerate); setInterval(0); // redraw ASAP runASAP = true; } @@ -1540,7 +1587,8 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16 } #endif } else { -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \ + // TODO: Raspberry Pi supports more than just the one screen size +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS) || ARCH_RASPBERRY_PI) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) display->drawFastImage(x + SCREEN_WIDTH - 14 - display->getStringWidth(ourId), y + 3 + FONT_HEIGHT_SMALL, 12, 8, imgInfoL1); @@ -1780,7 +1828,7 @@ int Screen::handleUIFrameEvent(const UIFrameEvent *event) setFastFramerate(); // TODO: We might also want switch to corresponding frame, // but we don't know the exact frame number. - // ui.switchToFrame(0); + // ui->switchToFrame(0); } } diff --git a/src/graphics/Screen.h b/src/graphics/Screen.h index 554fa0aeb..baee4b140 100644 --- a/src/graphics/Screen.h +++ b/src/graphics/Screen.h @@ -324,6 +324,8 @@ class Screen : public concurrency::OSThread // Called periodically from the main loop. int32_t runOnce() final; + bool isAUTOOled = false; + private: struct ScreenCmd { Cmd cmd; @@ -385,22 +387,10 @@ class Screen : public concurrency::OSThread DebugInfo debugInfo; /// Display device + OLEDDisplay *dispdev; -#if defined(USE_SH1106) || defined(USE_SH1107) || defined(USE_SH1107_128_64) - SH1106Wire dispdev; -#elif defined(USE_SSD1306) - SSD1306Wire dispdev; -#elif defined(ST7735_CS) || defined(ILI9341_DRIVER) || defined(ST7789_CS) || defined(RAK14014) - TFTDisplay dispdev; -#elif defined(USE_EINK) - EInkDisplay dispdev; -#elif defined(USE_ST7567) - ST7567Wire dispdev; -#else - AutoOLEDWire dispdev; -#endif /// UI helper for rendering to frames and switching between them - OLEDDisplayUi ui; + OLEDDisplayUi *ui; }; } // namespace graphics diff --git a/src/graphics/TFTDisplay.cpp b/src/graphics/TFTDisplay.cpp index 618880a5c..fe98882b4 100644 --- a/src/graphics/TFTDisplay.cpp +++ b/src/graphics/TFTDisplay.cpp @@ -1,5 +1,8 @@ #include "configuration.h" #include "main.h" +#if ARCH_RASPBERRY_PI +#include "platform/portduino/PortduinoGlue.h" +#endif #ifndef TFT_BACKLIGHT_ON #define TFT_BACKLIGHT_ON HIGH @@ -103,11 +106,11 @@ class LGFX : public lgfx::LGFX_Device } }; -static LGFX tft; +static LGFX *tft = nullptr; #elif defined(RAK14014) #include -TFT_eSPI tft = TFT_eSPI(); +TFT_eSPI *tft = nullptr; #elif defined(ST7789_CS) #include // Graphics and font library for ST7735 driver chip @@ -233,7 +236,7 @@ class LGFX : public lgfx::LGFX_Device } }; -static LGFX tft; +static LGFX *tft = nullptr; #elif defined(ILI9341_DRIVER) @@ -322,23 +325,96 @@ class LGFX : public lgfx::LGFX_Device } }; -static LGFX tft; +static LGFX *tft = nullptr; #elif defined(ST7735_CS) #include // Graphics and font library for ILI9341 driver chip -static TFT_eSPI tft = TFT_eSPI(); // Invoke library, pins defined in User_Setup.h +static TFT_eSPI *tft = nullptr; // Invoke library, pins defined in User_Setup.h +#elif ARCH_RASPBERRY_PI +#include // Graphics and font library for ST7735 driver chip +class LGFX : public lgfx::LGFX_Device +{ + lgfx::Panel_LCD *_panel_instance; + lgfx::Bus_SPI _bus_instance; + + lgfx::ITouch *_touch_instance; + + public: + LGFX(void) + { + + _panel_instance = new lgfx::Panel_ST7789; + auto buscfg = _bus_instance.config(); + buscfg.spi_mode = 0; + + buscfg.pin_dc = settingsMap[displayDC]; // Set SPI DC pin number (-1 = disable) + + _bus_instance.config(buscfg); // applies the set value to the bus. + _panel_instance->setBus(&_bus_instance); // set the bus on the panel. + + auto cfg = _panel_instance->config(); // Gets a structure for display panel settings. + LOG_DEBUG("Height: %d, Width: %d \n", settingsMap[displayHeight], settingsMap[displayWidth]); + cfg.pin_cs = settingsMap[displayCS]; // Pin number where CS is connected (-1 = disable) + cfg.panel_width = settingsMap[displayWidth]; // actual displayable width + cfg.panel_height = settingsMap[displayHeight]; // actual displayable height + cfg.offset_x = 0; // Panel offset amount in X direction + cfg.offset_y = 0; // Panel offset amount in Y direction + cfg.offset_rotation = 0; // Rotation direction value offset 0~7 (4~7 is mirrored) + cfg.dummy_read_pixel = 9; // Number of bits for dummy read before pixel readout + cfg.dummy_read_bits = 1; // Number of bits for dummy read before non-pixel data read + cfg.readable = true; // Set to true if data can be read + cfg.invert = true; // Set to true if the light/darkness of the panel is reversed + cfg.rgb_order = false; // Set to true if the panel's red and blue are swapped + cfg.dlen_16bit = false; // Set to true for panels that transmit data length in 16-bit units with 16-bit parallel or SPI + cfg.bus_shared = true; // If the bus is shared with the SD card, set to true (bus control with drawJpgFile etc.) + + _panel_instance->config(cfg); + + // Configure settings for touch control. + if (settingsMap[touchscreenModule]) { + if (settingsMap[touchscreenModule] == xpt2046) { + _touch_instance = new lgfx::Touch_XPT2046; + } + auto touch_cfg = _touch_instance->config(); + + touch_cfg.pin_cs = settingsMap[touchscreenCS]; + touch_cfg.x_min = 0; + touch_cfg.x_max = settingsMap[displayHeight] - 1; + touch_cfg.y_min = 0; + touch_cfg.y_max = settingsMap[displayWidth] - 1; + touch_cfg.pin_int = settingsMap[touchscreenIRQ]; + touch_cfg.bus_shared = true; + touch_cfg.offset_rotation = 1; + + _touch_instance->config(touch_cfg); + _panel_instance->setTouch(_touch_instance); + } + + setPanel(_panel_instance); // Sets the panel to use. + } +}; + +static LGFX *tft = nullptr; #endif -#if defined(ST7735_CS) || defined(ST7789_CS) || defined(ILI9341_DRIVER) || defined(RAK14014) +#if defined(ST7735_CS) || defined(ST7789_CS) || defined(ILI9341_DRIVER) || defined(RAK14014) || ARCH_RASPBERRY_PI #include "SPILock.h" #include "TFTDisplay.h" #include TFTDisplay::TFTDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY geometry, HW_I2C i2cBus) { -#ifdef SCREEN_ROTATE + LOG_DEBUG("TFTDisplay!\n"); +#if ARCH_RASPBERRY_PI + if (settingsMap[displayRotate]) { + setGeometry(GEOMETRY_RAWMODE, settingsMap[configNames::displayHeight], settingsMap[configNames::displayWidth]); + } else { + setGeometry(GEOMETRY_RAWMODE, settingsMap[configNames::displayWidth], settingsMap[configNames::displayHeight]); + } + +#elif defined(SCREEN_ROTATE) setGeometry(GEOMETRY_RAWMODE, TFT_HEIGHT, TFT_WIDTH); #else setGeometry(GEOMETRY_RAWMODE, TFT_WIDTH, TFT_HEIGHT); @@ -346,19 +422,25 @@ TFTDisplay::TFTDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY g } // Write the buffer to the display memory -void TFTDisplay::display(void) +void TFTDisplay::display(bool fromBlank) { + if (fromBlank) + tft->clear(); concurrency::LockGuard g(spiLock); uint16_t x, y; for (y = 0; y < displayHeight; y++) { for (x = 0; x < displayWidth; x++) { - // get src pixel in the page based ordering the OLED lib uses FIXME, super inefficent auto isset = buffer[x + (y / 8) * displayWidth] & (1 << (y & 7)); - auto dblbuf_isset = buffer_back[x + (y / 8) * displayWidth] & (1 << (y & 7)); - if (isset != dblbuf_isset) { - tft.drawPixel(x, y, isset ? TFT_MESH : TFT_BLACK); + if (!fromBlank) { + // get src pixel in the page based ordering the OLED lib uses FIXME, super inefficent + auto dblbuf_isset = buffer_back[x + (y / 8) * displayWidth] & (1 << (y & 7)); + if (isset != dblbuf_isset) { + tft->drawPixel(x, y, isset ? TFT_MESH : TFT_BLACK); + } + } else if (isset) { + tft->drawPixel(x, y, TFT_MESH); } } } @@ -377,7 +459,11 @@ void TFTDisplay::sendCommand(uint8_t com) // handle display on/off directly switch (com) { case DISPLAYON: { -#if defined(ST7735_BACKLIGHT_EN_V03) && defined(TFT_BACKLIGHT_ON) +#if ARCH_RASPBERRY_PI + display(true); + if (settingsMap[displayBacklight] > 0) + digitalWrite(settingsMap[displayBacklight], TFT_BACKLIGHT_ON); +#elif defined(ST7735_BACKLIGHT_EN_V03) && defined(TFT_BACKLIGHT_ON) if (heltec_version == 3) { digitalWrite(ST7735_BACKLIGHT_EN_V03, TFT_BACKLIGHT_ON); } else { @@ -400,12 +486,16 @@ void TFTDisplay::sendCommand(uint8_t com) #ifdef RAK14014 #elif !defined(M5STACK) - tft.setBrightness(128); + tft->setBrightness(128); #endif break; } case DISPLAYOFF: { -#if defined(ST7735_BACKLIGHT_EN_V03) && defined(TFT_BACKLIGHT_ON) +#if ARCH_RASPBERRY_PI + tft->clear(); + if (settingsMap[displayBacklight] > 0) + digitalWrite(settingsMap[displayBacklight], !TFT_BACKLIGHT_ON); +#elif defined(ST7735_BACKLIGHT_EN_V03) && defined(TFT_BACKLIGHT_ON) if (heltec_version == 3) { digitalWrite(ST7735_BACKLIGHT_EN_V03, !TFT_BACKLIGHT_ON); } else { @@ -427,7 +517,7 @@ void TFTDisplay::sendCommand(uint8_t com) #endif #ifdef RAK14014 #elif !defined(M5STACK) - tft.setBrightness(0); + tft->setBrightness(0); #endif break; } @@ -442,7 +532,7 @@ void TFTDisplay::flipScreenVertically() { #if defined(T_WATCH_S3) LOG_DEBUG("Flip TFT vertically\n"); // T-Watch S3 right-handed orientation - tft.setRotation(0); + tft->setRotation(0); #endif } @@ -450,7 +540,7 @@ bool TFTDisplay::hasTouch(void) { #ifdef RAK14014 #elif !defined(M5STACK) - return tft.touch() != nullptr; + return tft->touch() != nullptr; #else return false; #endif @@ -460,7 +550,7 @@ bool TFTDisplay::getTouch(int16_t *x, int16_t *y) { #ifdef RAK14014 #elif !defined(M5STACK) - return tft.getTouch(x, y); + return tft->getTouch(x, y); #else return false; #endif @@ -476,6 +566,11 @@ bool TFTDisplay::connect() { concurrency::LockGuard g(spiLock); LOG_INFO("Doing TFT init\n"); +#ifdef RAK14014 + tft = new TFT_eSPI; +#else + tft = new LGFX; +#endif #ifdef TFT_BL pinMode(TFT_BL, OUTPUT); @@ -495,24 +590,24 @@ bool TFTDisplay::connect() } #endif - tft.init(); + tft->init(); #if defined(M5STACK) - tft.setRotation(0); + tft->setRotation(0); #elif defined(RAK14014) - tft.setRotation(1); - tft.setSwapBytes(true); -// tft.fillScreen(TFT_BLACK); + tft->setRotation(1); + tft->setSwapBytes(true); +// tft->fillScreen(TFT_BLACK); #elif defined(T_DECK) || defined(PICOMPUTER_S3) - tft.setRotation(1); // T-Deck has the TFT in landscape + tft->setRotation(1); // T-Deck has the TFT in landscape #elif defined(T_WATCH_S3) - tft.setRotation(2); // T-Watch S3 left-handed orientation + tft->setRotation(2); // T-Watch S3 left-handed orientation #else - tft.setRotation(3); // Orient horizontal and wide underneath the silkscreen name label + tft->setRotation(3); // Orient horizontal and wide underneath the silkscreen name label #endif - tft.fillScreen(TFT_BLACK); + tft->fillScreen(TFT_BLACK); return true; } -#endif +#endif \ No newline at end of file diff --git a/src/graphics/TFTDisplay.h b/src/graphics/TFTDisplay.h index 8c9a9b62e..3d6ea6cc6 100644 --- a/src/graphics/TFTDisplay.h +++ b/src/graphics/TFTDisplay.h @@ -20,7 +20,8 @@ class TFTDisplay : public OLEDDisplay TFTDisplay(uint8_t, int, int, OLEDDISPLAY_GEOMETRY, HW_I2C); // Write the buffer to the display memory - virtual void display(void) override; + virtual void display() override { display(false); }; + virtual void display(bool fromBlank); // Turn the display upside down virtual void flipScreenVertically(); diff --git a/src/graphics/images.h b/src/graphics/images.h index a1191076b..7f3cd46fc 100644 --- a/src/graphics/images.h +++ b/src/graphics/images.h @@ -14,7 +14,7 @@ const uint8_t imgUser[] PROGMEM = {0x3C, 0x42, 0x99, 0xA5, 0xA5, 0x99, 0x42, 0x3 const uint8_t imgPositionEmpty[] PROGMEM = {0x20, 0x30, 0x28, 0x24, 0x42, 0xFF}; const uint8_t imgPositionSolid[] PROGMEM = {0x20, 0x30, 0x38, 0x3C, 0x7E, 0xFF}; -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \ +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS) || ARCH_RASPBERRY_PI) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) const uint8_t imgQuestionL1[] PROGMEM = {0xff, 0x01, 0x01, 0x32, 0x7b, 0x49, 0x49, 0x6f, 0x26, 0x01, 0x01, 0xff}; const uint8_t imgQuestionL2[] PROGMEM = {0x0f, 0x08, 0x08, 0x08, 0x06, 0x0f, 0x0f, 0x06, 0x08, 0x08, 0x08, 0x0f}; @@ -30,4 +30,4 @@ const uint8_t imgQuestion[] PROGMEM = {0xbf, 0x41, 0xc0, 0x8b, 0xdb, 0x70, 0xa1, const uint8_t imgSF[] PROGMEM = {0xd2, 0xb7, 0xad, 0xbb, 0x92, 0x01, 0xfd, 0xfd, 0x15, 0x85, 0xf5}; #endif -#include "img/icon.xbm" +#include "img/icon.xbm" \ No newline at end of file diff --git a/src/input/LinuxInput.cpp b/src/input/LinuxInput.cpp new file mode 100644 index 000000000..4b6150949 --- /dev/null +++ b/src/input/LinuxInput.cpp @@ -0,0 +1,179 @@ +#if ARCH_RASPBERRY_PI +#include "LinuxInput.h" +#include "configuration.h" + +#include "platform/portduino/PortduinoGlue.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// Inspired by https://github.com/librerpi/rpi-tools/blob/master/keyboard-proxy/main.c which is GPL-v2 + +LinuxInput::LinuxInput(const char *name) : concurrency::OSThread(name) +{ + this->_originName = name; +} + +int32_t LinuxInput::runOnce() +{ + + if (firstTime) { + if (settingsStrings[keyboardDevice] == "") + return disable(); + fd = open(settingsStrings[keyboardDevice].c_str(), O_RDWR); + if (fd < 0) + return disable(); + ret = ioctl(fd, EVIOCGRAB, (void *)1); + if (ret != 0) + return disable(); + + epollfd = epoll_create1(0); + assert(epollfd >= 0); + + ev.events = EPOLLIN; + ev.data.fd = fd; + if (epoll_ctl(epollfd, EPOLL_CTL_ADD, fd, &ev)) { + perror("unable to epoll add"); + return disable(); + } + // This is the first time the OSThread library has called this function, so do port setup + firstTime = 0; + } + + int nfds = epoll_wait(epollfd, events, MAX_EVENTS, 1); + if (nfds < 0) { + printf("%d ", nfds); + perror("epoll_wait failed"); + return disable(); + } else if (nfds == 0) { + return 50; + } + + int keys = 0; + memset(report, 0, 8); + for (int i = 0; i < nfds; i++) { + + struct input_event ev[64]; + int rd = read(events[i].data.fd, ev, sizeof(ev)); + assert(rd > ((signed int)sizeof(struct input_event))); + for (int j = 0; j < rd / ((signed int)sizeof(struct input_event)); j++) { + InputEvent e; + e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE; + e.source = this->_originName; + e.kbchar = 0; + unsigned int type, code; + type = ev[j].type; + code = ev[j].code; + int value = ev[j].value; + // printf("Event: time %ld.%06ld, ", ev[j].time.tv_sec, ev[j].time.tv_usec); + + if (type == EV_KEY) { + uint8_t mod = 0; + + switch (code) { + case KEY_LEFTCTRL: + mod = 0x01; + break; + case KEY_RIGHTCTRL: + mod = 0x10; + break; + case KEY_LEFTSHIFT: + mod = 0x02; + break; + case KEY_RIGHTSHIFT: + mod = 0x20; + break; + case KEY_LEFTALT: + mod = 0x04; + break; + case KEY_RIGHTALT: + mod = 0x40; + break; + case KEY_LEFTMETA: + mod = 0x08; + break; + } + if (value == 1) { + switch (code) { + case KEY_LEFTCTRL: + mod = 0x01; + break; + case KEY_RIGHTCTRL: + mod = 0x10; + break; + case KEY_LEFTSHIFT: + mod = 0x02; + break; + case KEY_RIGHTSHIFT: + mod = 0x20; + break; + case KEY_LEFTALT: + mod = 0x04; + break; + case KEY_RIGHTALT: + mod = 0x40; + break; + case KEY_LEFTMETA: + mod = 0x08; + break; + case KEY_ESC: // ESC + e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_CANCEL; + break; + case KEY_BACK: // Back + e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_BACK; + // e.kbchar = key; + break; + + case KEY_UP: // Up + e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_UP; + break; + case KEY_DOWN: // Down + e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_DOWN; + break; + case KEY_LEFT: // Left + e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_LEFT; + break; + e.kbchar = 0xb4; + case KEY_RIGHT: // Right + e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_RIGHT; + break; + e.kbchar = 0xb7; + case KEY_ENTER: // Enter + e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_SELECT; + break; + default: // all other keys + if (keymap[code]) { + e.inputEvent = ANYKEY; + e.kbchar = keymap[code]; + } + break; + } + } + if (ev[j].value) { + modifiers |= mod; + } else { + modifiers &= ~mod; + } + report[0] = modifiers; + } + if (e.inputEvent != meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE) { + if (e.inputEvent == ANYKEY && (modifiers && 0x22)) + e.kbchar = uppers[e.kbchar]; // doesn't get punctuation. Meh. + this->notifyObservers(&e); + } + } + } + + return 50; // Keyscan every 50msec to avoid key bounce +} + +#endif \ No newline at end of file diff --git a/src/input/LinuxInput.h b/src/input/LinuxInput.h new file mode 100644 index 000000000..c21fb4c36 --- /dev/null +++ b/src/input/LinuxInput.h @@ -0,0 +1,64 @@ +#pragma once +#if ARCH_RASPBERRY_PI +#include "InputBroker.h" +#include "concurrency/OSThread.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define MAX_EVENTS 10 + +class LinuxInput : public Observable, public concurrency::OSThread +{ + public: + explicit LinuxInput(const char *name); + + protected: + virtual int32_t runOnce() override; + + private: + const char *_originName; + bool firstTime = 1; + int shift = 0; + char key = 0; + char prevkey = 0; + + InputEvent eventqueue[50]; // The Linux API will return multiple keypresses at a time. Queue them to not miss any. + int queue_length = 0; + int queue_progress = 0; + + struct epoll_event events[MAX_EVENTS]; + int fd; + int ret; + uint8_t report[8]; + int epollfd; + struct epoll_event ev; + uint8_t modifiers = 0; + std::map keymap{ + {KEY_A, 'a'}, {KEY_B, 'b'}, {KEY_C, 'c'}, {KEY_D, 'd'}, {KEY_E, 'e'}, + {KEY_F, 'f'}, {KEY_G, 'g'}, {KEY_H, 'h'}, {KEY_I, 'i'}, {KEY_J, 'j'}, + {KEY_K, 'k'}, {KEY_L, 'l'}, {KEY_M, 'm'}, {KEY_N, 'n'}, {KEY_O, 'o'}, + {KEY_P, 'p'}, {KEY_Q, 'q'}, {KEY_R, 'r'}, {KEY_S, 's'}, {KEY_T, 't'}, + {KEY_U, 'u'}, {KEY_V, 'v'}, {KEY_W, 'w'}, {KEY_X, 'x'}, {KEY_Y, 'y'}, + {KEY_Z, 'z'}, {KEY_BACKSPACE, 0x08}, {KEY_SPACE, ' '}, {KEY_1, '1'}, {KEY_2, '2'}, + {KEY_3, '3'}, {KEY_4, '4'}, {KEY_5, '5'}, {KEY_6, '6'}, {KEY_7, '7'}, + {KEY_8, '8'}, {KEY_9, '9'}, {KEY_0, '0'}, {KEY_DOT, '.'}, {KEY_COMMA, ','}, + {KEY_MINUS, '-'}, {KEY_EQUAL, '='}, {KEY_LEFTBRACE, '['}, {KEY_RIGHTBRACE, ']'}, {KEY_BACKSLASH, '\\'}, + {KEY_SEMICOLON, ';'}, {KEY_APOSTROPHE, '\''}, {KEY_SLASH, '/'}, {KEY_TAB, 0x09}}; + std::map uppers{{'a', 'A'}, {'b', 'B'}, {'c', 'C'}, {'d', 'D'}, {'e', 'E'}, {'f', 'F'}, {'g', 'G'}, {'h', 'H'}, + {'i', 'I'}, {'j', 'J'}, {'k', 'K'}, {'l', 'L'}, {'m', 'M'}, {'n', 'N'}, {'o', 'O'}, {'p', 'P'}, + {'q', 'Q'}, {'r', 'R'}, {'s', 'S'}, {'t', 'T'}, {'u', 'U'}, {'v', 'V'}, {'w', 'W'}, {'x', 'X'}, + {'y', 'Y'}, {'z', 'Z'}, {'1', '!'}, {'2', '@'}, {'3', '#'}, {'4', '$'}, {'5', '%'}, {'6', '^'}, + {'7', '&'}, {'8', '*'}, {'9', '('}, {'0', ')'}, {'.', '>'}, {',', '<'}, {'-', '_'}, {'=', '+'}, + {'[', '{'}, {']', '}'}, {'\\', '|'}, {';', ':'}, {'\'', '"'}, {'/', '?'}}; +}; +#endif \ No newline at end of file diff --git a/src/input/LinuxInputImpl.cpp b/src/input/LinuxInputImpl.cpp new file mode 100644 index 000000000..d12f457ec --- /dev/null +++ b/src/input/LinuxInputImpl.cpp @@ -0,0 +1,14 @@ +#if ARCH_RASPBERRY_PI +#include "LinuxInputImpl.h" +#include "InputBroker.h" + +LinuxInputImpl *aLinuxInputImpl; + +LinuxInputImpl::LinuxInputImpl() : LinuxInput("LinuxInput") {} + +void LinuxInputImpl::init() +{ + inputBroker->registerSource(this); +} + +#endif \ No newline at end of file diff --git a/src/input/LinuxInputImpl.h b/src/input/LinuxInputImpl.h new file mode 100644 index 000000000..b5bfdc4c2 --- /dev/null +++ b/src/input/LinuxInputImpl.h @@ -0,0 +1,21 @@ +#ifdef ARCH_RASPBERRY_PI +#pragma once +#include "LinuxInput.h" +#include "main.h" + +/** + * @brief The idea behind this class to have static methods for the event handlers. + * Check attachInterrupt() at RotaryEncoderInteruptBase.cpp + * Technically you can have as many rotary encoders hardver attached + * to your device as you wish, but you always need to have separate event + * handlers, thus you need to have a RotaryEncoderInterrupt implementation. + */ + +class LinuxInputImpl : public LinuxInput +{ + public: + LinuxInputImpl(); + void init(); +}; +extern LinuxInputImpl *aLinuxInputImpl; +#endif \ No newline at end of file diff --git a/src/input/TouchScreenImpl1.cpp b/src/input/TouchScreenImpl1.cpp index e38d6c324..145033c95 100644 --- a/src/input/TouchScreenImpl1.cpp +++ b/src/input/TouchScreenImpl1.cpp @@ -4,6 +4,10 @@ #include "configuration.h" #include "modules/ExternalNotificationModule.h" +#ifdef ARCH_RASPBERRY_PI +#include "platform/portduino/PortduinoGlue.h" +#endif + TouchScreenImpl1 *touchScreenImpl1; TouchScreenImpl1::TouchScreenImpl1(uint16_t width, uint16_t height, bool (*getTouch)(int16_t *, int16_t *)) @@ -13,7 +17,14 @@ TouchScreenImpl1::TouchScreenImpl1(uint16_t width, uint16_t height, bool (*getTo void TouchScreenImpl1::init() { -#if !HAS_TOUCHSCREEN +#if ARCH_RASPBERRY_PI + if (settingsMap[touchscreenModule]) { + TouchScreenBase::init(true); + inputBroker->registerSource(this); + } else { + TouchScreenBase::init(false); + } +#elif !HAS_TOUCHSCREEN TouchScreenBase::init(false); return; #else diff --git a/src/main.cpp b/src/main.cpp index 505c1c804..9c67cc0ac 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -697,6 +697,10 @@ void setup() // the current region name) #if defined(ST7735_CS) || defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7789_CS) screen->setup(); +#elif ARCH_RASPBERRY_PI + if (screen_found.port != ScanI2C::I2CPort::NO_I2C || settingsMap[displayPanel]) { + screen->setup(); + } #else if (screen_found.port != ScanI2C::I2CPort::NO_I2C) screen->setup(); diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 0fc69f8aa..c963fff5b 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -27,6 +27,10 @@ #include #endif +#ifdef ARCH_RASPBERRY_PI +#include "platform/portduino/PortduinoGlue.h" +#endif + #ifdef ARCH_NRF52 #include #include @@ -191,6 +195,12 @@ void NodeDB::installDefaultConfig() config.bluetooth.fixed_pin = defaultBLEPin; #if defined(ST7735_CS) || defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7789_CS) bool hasScreen = true; +#elif ARCH_RASPBERRY_PI + bool hasScreen = false; + if (settingsMap[displayPanel]) + hasScreen = true; + else + hasScreen = screen_found.port != ScanI2C::I2CPort::NO_I2C; #else bool hasScreen = screen_found.port != ScanI2C::I2CPort::NO_I2C; #endif diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index dedfdb850..79cb5eee6 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -1,4 +1,7 @@ #include "configuration.h" +#if ARCH_RASPBERRY_PI +#include "PortduinoGlue.h" +#endif #if HAS_SCREEN #include "CannedMessageModule.h" #include "FSCommon.h" @@ -163,9 +166,14 @@ int CannedMessageModule::handleInputEvent(const InputEvent *event) } if (event->inputEvent == static_cast(meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_CANCEL)) { LOG_DEBUG("Canned message event Cancel\n"); - // emulate a timeout. Same result - this->lastTouchMillis = 0; - validEvent = true; + UIFrameEvent e = {false, true}; + e.frameChanged = true; + this->currentMessageIndex = -1; + this->freetext = ""; // clear freetext + this->cursor = 0; + this->destSelect = false; + this->runState = CANNED_MESSAGE_RUN_STATE_INACTIVE; + this->notifyObservers(&e); } if ((event->inputEvent == static_cast(meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_BACK)) || (event->inputEvent == static_cast(meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_LEFT)) || @@ -212,7 +220,11 @@ int CannedMessageModule::handleInputEvent(const InputEvent *event) if (validEvent) { // Let runOnce to be called immediately. - setIntervalFromNow(0); + if (this->runState == CANNED_MESSAGE_RUN_STATE_ACTION_SELECT) { + setIntervalFromNow(0); // on fast keypresses, this isn't fast enough. + } else { + runOnce(); + } } return 0; diff --git a/src/modules/Modules.cpp b/src/modules/Modules.cpp index 526a1c7d8..19d6b76d4 100644 --- a/src/modules/Modules.cpp +++ b/src/modules/Modules.cpp @@ -17,6 +17,9 @@ #include "modules/TextMessageModule.h" #include "modules/TraceRouteModule.h" #include "modules/WaypointModule.h" +#if ARCH_RASPBERRY_PI +#include "input/LinuxInputImpl.h" +#endif #if HAS_TELEMETRY #include "modules/Telemetry/DeviceTelemetry.h" #endif @@ -44,7 +47,7 @@ void setupModules() { if (config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER) { -#if HAS_BUTTON +#if HAS_BUTTON || ARCH_RASPBERRY_PI inputBroker = new InputBroker(); #endif adminModule = new AdminModule(); @@ -61,7 +64,7 @@ void setupModules() new RemoteHardwareModule(); new ReplyModule(); -#if HAS_BUTTON +#if HAS_BUTTON || ARCH_RASPBERRY_PI rotaryEncoderInterruptImpl1 = new RotaryEncoderInterruptImpl1(); if (!rotaryEncoderInterruptImpl1->init()) { delete rotaryEncoderInterruptImpl1; @@ -79,6 +82,10 @@ void setupModules() kbMatrixImpl->init(); #endif // INPUTBROKER_MATRIX_TYPE #endif // HAS_BUTTON +#if ARCH_RASPBERRY_PI + aLinuxInputImpl = new LinuxInputImpl(); + aLinuxInputImpl->init(); +#endif #if HAS_TRACKBALL trackballInterruptImpl1 = new TrackballInterruptImpl1(); trackballInterruptImpl1->init(); diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index 06e18eb91..b8e9dd9e6 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -17,7 +17,8 @@ #include #include -std::map settingsMap; +std::map settingsMap; +std::map settingsStrings; #else #include @@ -154,6 +155,28 @@ void portduinoSetup() settingsMap[has_gps] = 1; } } + settingsMap[displayPanel] = no_screen; + if (yamlConfig["Display"]) { + if (yamlConfig["Display"]["Panel"].as("") == "ST7789") + settingsMap[displayPanel] = st7789; + settingsMap[displayHeight] = yamlConfig["Display"]["Height"].as(0); + settingsMap[displayWidth] = yamlConfig["Display"]["Width"].as(0); + settingsMap[displayDC] = yamlConfig["Display"]["DC"].as(-1); + settingsMap[displayCS] = yamlConfig["Display"]["CS"].as(-1); + settingsMap[displayBacklight] = yamlConfig["Display"]["Backlight"].as(-1); + settingsMap[displayReset] = yamlConfig["Display"]["Reset"].as(-1); + settingsMap[displayRotate] = yamlConfig["Display"]["Rotate"].as(false); + } + settingsMap[touchscreenModule] = no_touchscreen; + if (yamlConfig["Touchscreen"]) { + if (yamlConfig["Touchscreen"]["Module"].as("") == "XPT2046") + settingsMap[touchscreenModule] = xpt2046; + settingsMap[touchscreenCS] = yamlConfig["Touchscreen"]["CS"].as(-1); + settingsMap[touchscreenIRQ] = yamlConfig["Touchscreen"]["IRQ"].as(-1); + } + if (yamlConfig["Input"]) { + settingsStrings[keyboardDevice] = (yamlConfig["Input"]["KeyboardDevice"]).as(""); + } } catch (YAML::Exception e) { std::cout << "*** Exception " << e.what() << std::endl; @@ -191,6 +214,23 @@ void portduinoSetup() } } + if (settingsMap[displayPanel] != no_screen) { + if (settingsMap[displayCS] > 0) + initGPIOPin(settingsMap[displayCS], gpioChipName); + if (settingsMap[displayDC] > 0) + initGPIOPin(settingsMap[displayDC], gpioChipName); + if (settingsMap[displayBacklight] > 0) + initGPIOPin(settingsMap[displayBacklight], gpioChipName); + if (settingsMap[displayReset] > 0) + initGPIOPin(settingsMap[displayReset], gpioChipName); + } + if (settingsMap[touchscreenModule] != no_touchscreen) { + if (settingsMap[touchscreenCS] > 0) + initGPIOPin(settingsMap[touchscreenCS], gpioChipName); + if (settingsMap[touchscreenIRQ] > 0) + initGPIOPin(settingsMap[touchscreenIRQ], gpioChipName); + } + return; #endif @@ -250,8 +290,9 @@ int initGPIOPin(int pinNum, std::string gpioChipName) csPin->setSilent(); gpioBind(csPin); return ERRNO_OK; - } catch (std::invalid_argument &e) { - std::cout << "Warning, cannot claim pin" << gpio_name << std::endl; + } catch (...) { + std::exception_ptr p = std::current_exception(); + std::cout << "Warning, cannot claim pin " << gpio_name << (p ? p.__cxa_exception_type()->name() : "null") << std::endl; return ERRNO_DISABLED; } } diff --git a/src/platform/portduino/PortduinoGlue.h b/src/platform/portduino/PortduinoGlue.h index b942ab46a..046c5d097 100644 --- a/src/platform/portduino/PortduinoGlue.h +++ b/src/platform/portduino/PortduinoGlue.h @@ -2,9 +2,35 @@ #ifdef ARCH_RASPBERRY_PI #include -extern std::map settingsMap; +enum configNames { + use_sx1262, + cs, + irq, + busy, + reset, + dio2_as_rf_switch, + use_rf95, + user, + gpiochip, + has_gps, + touchscreenModule, + touchscreenCS, + touchscreenIRQ, + displayPanel, + displayWidth, + displayHeight, + displayCS, + displayDC, + displayBacklight, + displayReset, + displayRotate, + keyboardDevice +}; +enum { no_screen, st7789 }; +enum { no_touchscreen, xpt2046 }; -enum { use_sx1262, cs, irq, busy, reset, dio2_as_rf_switch, use_rf95, user, gpiochip, has_gps }; +extern std::map settingsMap; +extern std::map settingsStrings; int initGPIOPin(int pinNum, std::string gpioChipname); #endif \ No newline at end of file diff --git a/variants/portduino/platformio.ini b/variants/portduino/platformio.ini index 5e9428d4e..cdc32fae5 100644 --- a/variants/portduino/platformio.ini +++ b/variants/portduino/platformio.ini @@ -19,4 +19,5 @@ extends = portduino_base build_flags = ${portduino_base.build_flags} -O0 -lgpiod -I variants/portduino -DARCH_RASPBERRY_PI -lpigpio -lyaml-cpp board = linux_arm lib_deps = ${portduino_base.lib_deps} + https://github.com/jp-bennett/LovyanGFX.git#jp-bennett-patch-1 ; lovyan03/LovyanGFX@^1.1.9 build_src_filter = ${portduino_base.build_src_filter} \ No newline at end of file diff --git a/variants/portduino/variant.h b/variants/portduino/variant.h index 23066276b..3493f704f 100644 --- a/variants/portduino/variant.h +++ b/variants/portduino/variant.h @@ -1,6 +1,7 @@ #if defined(ARCH_RASPBERRY_PI) #define HAS_WIRE 1 #define HAS_SCREEN 1 +#define CANNED_MESSAGE_MODULE_ENABLE 1 #else // Pine64 mode. From 4b7fbeca29909ba01159608dff93a792c9fbd763 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Mon, 11 Dec 2023 16:00:26 +0100 Subject: [PATCH 058/472] only ever emit the up/down action if we have actual messages stored --- src/modules/CannedMessageModule.cpp | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index 79cb5eee6..419507952 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -144,14 +144,18 @@ int CannedMessageModule::handleInputEvent(const InputEvent *event) bool validEvent = false; if (event->inputEvent == static_cast(meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_UP)) { - // LOG_DEBUG("Canned message event UP\n"); - this->runState = CANNED_MESSAGE_RUN_STATE_ACTION_UP; - validEvent = true; + if (this->messagesCount > 0) { + // LOG_DEBUG("Canned message event UP\n"); + this->runState = CANNED_MESSAGE_RUN_STATE_ACTION_UP; + validEvent = true; + } } if (event->inputEvent == static_cast(meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_DOWN)) { - // LOG_DEBUG("Canned message event DOWN\n"); - this->runState = CANNED_MESSAGE_RUN_STATE_ACTION_DOWN; - validEvent = true; + if (this->messagesCount > 0) { + // LOG_DEBUG("Canned message event DOWN\n"); + this->runState = CANNED_MESSAGE_RUN_STATE_ACTION_DOWN; + validEvent = true; + } } if (event->inputEvent == static_cast(meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_SELECT)) { LOG_DEBUG("Canned message event Select\n"); From dad05d7873a84abb76b4fb186b146c1e551dbaa1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Mon, 11 Dec 2023 23:49:33 +0100 Subject: [PATCH 059/472] Select Node and channel in Canned Message module. --- src/modules/CannedMessageModule.cpp | 84 ++++++++++++++++++++++------- src/modules/CannedMessageModule.h | 15 ++++-- 2 files changed, 77 insertions(+), 22 deletions(-) diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index 419507952..554326057 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -4,6 +4,7 @@ #endif #if HAS_SCREEN #include "CannedMessageModule.h" +#include "Channels.h" #include "FSCommon.h" #include "MeshService.h" #include "NodeDB.h" @@ -187,10 +188,10 @@ int CannedMessageModule::handleInputEvent(const InputEvent *event) if (!event->kbchar) { if (event->inputEvent == static_cast(meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_LEFT)) { this->payload = 0xb4; - this->destSelect = true; + this->destSelect = CANNED_MESSAGE_DESTINATION_TYPE_NODE; } else if (event->inputEvent == static_cast(meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_RIGHT)) { this->payload = 0xb7; - this->destSelect = true; + this->destSelect = CANNED_MESSAGE_DESTINATION_TYPE_NODE; } } else { // pass the pressed key @@ -234,10 +235,11 @@ int CannedMessageModule::handleInputEvent(const InputEvent *event) return 0; } -void CannedMessageModule::sendText(NodeNum dest, const char *message, bool wantReplies) +void CannedMessageModule::sendText(NodeNum dest, ChannelIndex channel, const char *message, bool wantReplies) { meshtastic_MeshPacket *p = allocDataPacket(); p->to = dest; + p->channel = channel; p->want_ack = true; p->decoded.payload.size = strlen(message); memcpy(p->decoded.payload.bytes, message, p->decoded.payload.size); @@ -270,7 +272,7 @@ int32_t CannedMessageModule::runOnce() this->currentMessageIndex = -1; this->freetext = ""; // clear freetext this->cursor = 0; - this->destSelect = false; + this->destSelect = CANNED_MESSAGE_DESTINATION_TYPE_NONE; this->notifyObservers(&e); } else if (((this->runState == CANNED_MESSAGE_RUN_STATE_ACTIVE) || (this->runState == CANNED_MESSAGE_RUN_STATE_FREETEXT)) && ((millis() - this->lastTouchMillis) > INACTIVATE_AFTER_MS)) { @@ -280,13 +282,13 @@ int32_t CannedMessageModule::runOnce() this->currentMessageIndex = -1; this->freetext = ""; // clear freetext this->cursor = 0; - this->destSelect = false; + this->destSelect = CANNED_MESSAGE_DESTINATION_TYPE_NONE; this->runState = CANNED_MESSAGE_RUN_STATE_INACTIVE; this->notifyObservers(&e); } else if (this->runState == CANNED_MESSAGE_RUN_STATE_ACTION_SELECT) { if (this->payload == CANNED_MESSAGE_RUN_STATE_FREETEXT) { if (this->freetext.length() > 0) { - sendText(this->dest, this->freetext.c_str(), true); + sendText(this->dest, indexChannels[this->channel], this->freetext.c_str(), true); this->runState = CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE; } else { LOG_DEBUG("Reset message is empty.\n"); @@ -298,7 +300,7 @@ int32_t CannedMessageModule::runOnce() powerFSM.trigger(EVENT_PRESS); return INT32_MAX; } else { - sendText(NODENUM_BROADCAST, this->messages[this->currentMessageIndex], true); + sendText(NODENUM_BROADCAST, channels.getPrimaryIndex(), this->messages[this->currentMessageIndex], true); } this->runState = CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE; } else { @@ -310,7 +312,7 @@ int32_t CannedMessageModule::runOnce() this->currentMessageIndex = -1; this->freetext = ""; // clear freetext this->cursor = 0; - this->destSelect = false; + this->destSelect = CANNED_MESSAGE_DESTINATION_TYPE_NONE; this->notifyObservers(&e); return 2000; } else if ((this->runState != CANNED_MESSAGE_RUN_STATE_FREETEXT) && (this->currentMessageIndex == -1)) { @@ -323,7 +325,7 @@ int32_t CannedMessageModule::runOnce() this->currentMessageIndex = getPrevIndex(); this->freetext = ""; // clear freetext this->cursor = 0; - this->destSelect = false; + this->destSelect = CANNED_MESSAGE_DESTINATION_TYPE_NONE; this->runState = CANNED_MESSAGE_RUN_STATE_ACTIVE; LOG_DEBUG("MOVE UP (%d):%s\n", this->currentMessageIndex, this->getCurrentMessage()); } @@ -332,14 +334,14 @@ int32_t CannedMessageModule::runOnce() this->currentMessageIndex = this->getNextIndex(); this->freetext = ""; // clear freetext this->cursor = 0; - this->destSelect = false; + this->destSelect = CANNED_MESSAGE_DESTINATION_TYPE_NONE; this->runState = CANNED_MESSAGE_RUN_STATE_ACTIVE; LOG_DEBUG("MOVE DOWN (%d):%s\n", this->currentMessageIndex, this->getCurrentMessage()); } } else if (this->runState == CANNED_MESSAGE_RUN_STATE_FREETEXT || this->runState == CANNED_MESSAGE_RUN_STATE_ACTIVE) { switch (this->payload) { case 0xb4: // left - if (this->destSelect) { + if (this->destSelect == CANNED_MESSAGE_DESTINATION_TYPE_NODE) { size_t numMeshNodes = nodeDB.getNumMeshNodes(); if (this->dest == NODENUM_BROADCAST) { this->dest = nodeDB.getNodeNum(); @@ -354,6 +356,19 @@ int32_t CannedMessageModule::runOnce() if (this->dest == nodeDB.getNodeNum()) { this->dest = NODENUM_BROADCAST; } + } else if (this->destSelect == CANNED_MESSAGE_DESTINATION_TYPE_CHANNEL) { + for (unsigned int i = 0; i < channels.getNumChannels(); i++) { + if ((channels.getByIndex(i).role == meshtastic_Channel_Role_SECONDARY) || + (channels.getByIndex(i).role == meshtastic_Channel_Role_PRIMARY)) { + indexChannels[numChannels] = i; + numChannels++; + } + } + if (this->channel == 0) { + this->channel = numChannels - 1; + } else { + this->channel--; + } } else { if (this->cursor > 0) { this->cursor--; @@ -361,7 +376,7 @@ int32_t CannedMessageModule::runOnce() } break; case 0xb7: // right - if (this->destSelect) { + if (this->destSelect == CANNED_MESSAGE_DESTINATION_TYPE_NODE) { size_t numMeshNodes = nodeDB.getNumMeshNodes(); if (this->dest == NODENUM_BROADCAST) { this->dest = nodeDB.getNodeNum(); @@ -376,6 +391,19 @@ int32_t CannedMessageModule::runOnce() if (this->dest == nodeDB.getNodeNum()) { this->dest = NODENUM_BROADCAST; } + } else if (this->destSelect == CANNED_MESSAGE_DESTINATION_TYPE_CHANNEL) { + for (unsigned int i = 0; i < channels.getNumChannels(); i++) { + if ((channels.getByIndex(i).role == meshtastic_Channel_Role_SECONDARY) || + (channels.getByIndex(i).role == meshtastic_Channel_Role_PRIMARY)) { + indexChannels[numChannels] = i; + numChannels++; + } + } + if (this->channel == numChannels - 1) { + this->channel = 0; + } else { + this->channel++; + } } else { if (this->cursor < this->freetext.length()) { this->cursor++; @@ -400,10 +428,12 @@ int32_t CannedMessageModule::runOnce() } break; case 0x09: // tab - if (this->destSelect) { - this->destSelect = false; + if (this->destSelect == CANNED_MESSAGE_DESTINATION_TYPE_CHANNEL) { + this->destSelect = CANNED_MESSAGE_DESTINATION_TYPE_NONE; + } else if (this->destSelect == CANNED_MESSAGE_DESTINATION_TYPE_NODE) { + this->destSelect = CANNED_MESSAGE_DESTINATION_TYPE_CHANNEL; } else { - this->destSelect = true; + this->destSelect = CANNED_MESSAGE_DESTINATION_TYPE_NODE; } break; case 0xb4: // left @@ -524,18 +554,34 @@ void CannedMessageModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *st } else if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_FREETEXT) { display->setTextAlignment(TEXT_ALIGN_LEFT); display->setFont(FONT_SMALL); - if (this->destSelect) { + if (this->destSelect != CANNED_MESSAGE_DESTINATION_TYPE_NONE) { display->fillRect(0 + x, 0 + y, x + display->getWidth(), y + FONT_HEIGHT_SMALL); display->setColor(BLACK); - display->drawStringf(1 + x, 0 + y, buffer, "To: %s", cannedMessageModule->getNodeName(this->dest)); } - display->drawStringf(0 + x, 0 + y, buffer, "To: %s", cannedMessageModule->getNodeName(this->dest)); + switch (this->destSelect) { + case CANNED_MESSAGE_DESTINATION_TYPE_NODE: + display->drawStringf(1 + x, 0 + y, buffer, "To: >%s<@%s", cannedMessageModule->getNodeName(this->dest), + channels.getName(indexChannels[this->channel])); + display->drawStringf(0 + x, 0 + y, buffer, "To: >%s<@%s", cannedMessageModule->getNodeName(this->dest), + channels.getName(indexChannels[this->channel])); + break; + case CANNED_MESSAGE_DESTINATION_TYPE_CHANNEL: + display->drawStringf(1 + x, 0 + y, buffer, "To: %s@>%s<", cannedMessageModule->getNodeName(this->dest), + channels.getName(indexChannels[this->channel])); + display->drawStringf(0 + x, 0 + y, buffer, "To: %s@>%s<", cannedMessageModule->getNodeName(this->dest), + channels.getName(indexChannels[this->channel])); + break; + default: + display->drawStringf(0 + x, 0 + y, buffer, "To: %s@%s", cannedMessageModule->getNodeName(this->dest), + channels.getName(indexChannels[this->channel])); + break; + } // used chars right aligned uint16_t charsLeft = meshtastic_Constants_DATA_PAYLOAD_LEN - this->freetext.length() - (moduleConfig.canned_message.send_bell ? 1 : 0); snprintf(buffer, sizeof(buffer), "%d left", charsLeft); display->drawString(x + display->getWidth() - display->getStringWidth(buffer), y + 0, buffer); - if (this->destSelect) { + if (this->destSelect != CANNED_MESSAGE_DESTINATION_TYPE_NONE) { display->drawString(x + display->getWidth() - display->getStringWidth(buffer) - 1, y + 0, buffer); } display->setColor(WHITE); diff --git a/src/modules/CannedMessageModule.h b/src/modules/CannedMessageModule.h index b41fba045..4802be078 100644 --- a/src/modules/CannedMessageModule.h +++ b/src/modules/CannedMessageModule.h @@ -15,6 +15,12 @@ enum cannedMessageModuleRunState { CANNED_MESSAGE_RUN_STATE_ACTION_DOWN, }; +enum cannedMessageDestinationType { + CANNED_MESSAGE_DESTINATION_TYPE_NONE, + CANNED_MESSAGE_DESTINATION_TYPE_NODE, + CANNED_MESSAGE_DESTINATION_TYPE_CHANNEL +}; + #define CANNED_MESSAGE_MODULE_MESSAGE_MAX_COUNT 50 /** * Sum of CannedMessageModuleConfig part sizes. @@ -64,7 +70,7 @@ class CannedMessageModule : public SinglePortModule, public Observable Date: Tue, 12 Dec 2023 22:28:50 +0100 Subject: [PATCH 060/472] remove char counter when changing destination shorten destination to make room for char counter, only on small displays. --- src/modules/CannedMessageModule.cpp | 22 +++++++++++++--------- 1 file changed, 13 insertions(+), 9 deletions(-) diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index 554326057..f8669d1df 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -572,17 +572,21 @@ void CannedMessageModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *st channels.getName(indexChannels[this->channel])); break; default: - display->drawStringf(0 + x, 0 + y, buffer, "To: %s@%s", cannedMessageModule->getNodeName(this->dest), - channels.getName(indexChannels[this->channel])); + if (display->getWidth() > 128) { + display->drawStringf(0 + x, 0 + y, buffer, "To: %s@%s", cannedMessageModule->getNodeName(this->dest), + channels.getName(indexChannels[this->channel])); + } else { + display->drawStringf(0 + x, 0 + y, buffer, "To: %.5s@%.5s", cannedMessageModule->getNodeName(this->dest), + channels.getName(indexChannels[this->channel])); + } break; } - // used chars right aligned - uint16_t charsLeft = - meshtastic_Constants_DATA_PAYLOAD_LEN - this->freetext.length() - (moduleConfig.canned_message.send_bell ? 1 : 0); - snprintf(buffer, sizeof(buffer), "%d left", charsLeft); - display->drawString(x + display->getWidth() - display->getStringWidth(buffer), y + 0, buffer); - if (this->destSelect != CANNED_MESSAGE_DESTINATION_TYPE_NONE) { - display->drawString(x + display->getWidth() - display->getStringWidth(buffer) - 1, y + 0, buffer); + // used chars right aligned, only when not editing the destination + if (this->destSelect == CANNED_MESSAGE_DESTINATION_TYPE_NONE) { + uint16_t charsLeft = + meshtastic_Constants_DATA_PAYLOAD_LEN - this->freetext.length() - (moduleConfig.canned_message.send_bell ? 1 : 0); + snprintf(buffer, sizeof(buffer), "%d left", charsLeft); + display->drawString(x + display->getWidth() - display->getStringWidth(buffer), y + 0, buffer); } display->setColor(WHITE); display->drawStringMaxWidth( From dd96848becf152ee91ebbc9d7e810b669b550a97 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Tue, 12 Dec 2023 20:53:14 -0600 Subject: [PATCH 061/472] Change type to fix compilation in new code --- src/modules/CannedMessageModule.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index f8669d1df..45d2083b7 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -176,7 +176,7 @@ int CannedMessageModule::handleInputEvent(const InputEvent *event) this->currentMessageIndex = -1; this->freetext = ""; // clear freetext this->cursor = 0; - this->destSelect = false; + this->destSelect = CANNED_MESSAGE_DESTINATION_TYPE_NONE; this->runState = CANNED_MESSAGE_RUN_STATE_INACTIVE; this->notifyObservers(&e); } From 9f85279e74c1ccab7a564179a1ee1a60f0bd57f0 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 13 Dec 2023 17:43:20 -0600 Subject: [PATCH 062/472] Lost and found mode (#3012) * Lost and found WIP * 5 minutes * ASCII bell character correction * Memory --- src/mesh/NodeDB.cpp | 3 +++ src/modules/PositionModule.cpp | 18 ++++++++++++++++++ src/modules/PositionModule.h | 1 + 3 files changed, 22 insertions(+) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index c963fff5b..6f1ba5583 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -306,6 +306,9 @@ void NodeDB::installRoleDefaults(meshtastic_Config_DeviceConfig_Role role) } else if (role == meshtastic_Config_DeviceConfig_Role_SENSOR) { moduleConfig.telemetry.environment_measurement_enabled = true; moduleConfig.telemetry.environment_update_interval = 300; + } else if (role == meshtastic_Config_DeviceConfig_Role_LOST_AND_FOUND) { + config.position.position_broadcast_smart_enabled = false; + config.position.position_broadcast_secs = 300; // Every 5 minutes } else if (role == meshtastic_Config_DeviceConfig_Role_TAK) { config.device.node_info_broadcast_secs = ONE_DAY; config.position.position_broadcast_smart_enabled = false; diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index 69cd4848e..212961dc4 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -225,6 +225,9 @@ int32_t PositionModule::runOnce() LOG_INFO("Sending pos@%x:6 to mesh (wantReplies=%d)\n", localPosition.timestamp, requestReplies); sendOurPosition(NODENUM_BROADCAST, requestReplies); + if (config.device.role == meshtastic_Config_DeviceConfig_Role_LOST_AND_FOUND) { + sendLostAndFoundText(); + } } } else if (config.position.position_broadcast_smart_enabled) { const meshtastic_NodeInfoLite *node2 = service.refreshLocalMeshNode(); // should guarantee there is now a position @@ -261,6 +264,21 @@ int32_t PositionModule::runOnce() return RUNONCE_INTERVAL; // to save power only wake for our callback occasionally } +void PositionModule::sendLostAndFoundText() +{ + meshtastic_MeshPacket *p = allocDataPacket(); + p->to = NODENUM_BROADCAST; + char *message = new char[60]; + sprintf(message, "🚨I'm lost! Lat / Lon: %f, %f\a", (lastGpsLatitude * 1e-7), (lastGpsLongitude * 1e-7)); + p->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_APP; + p->want_ack = false; + p->decoded.payload.size = strlen(message); + memcpy(p->decoded.payload.bytes, message, p->decoded.payload.size); + + service.sendToMesh(p, RX_SRC_LOCAL, true); + delete[] message; +} + struct SmartPosition PositionModule::getDistanceTraveledSinceLastSend(meshtastic_PositionLite currentPosition) { // The minimum distance to travel before we are able to send a new position packet. diff --git a/src/modules/PositionModule.h b/src/modules/PositionModule.h index 1b7eca800..983fcdf8f 100644 --- a/src/modules/PositionModule.h +++ b/src/modules/PositionModule.h @@ -52,6 +52,7 @@ class PositionModule : public ProtobufModule, private concu /** Only used in power saving trackers for now */ void clearPosition(); + void sendLostAndFoundText(); }; struct SmartPosition { From 1af3e0ddaa6722c41cf985a2d8e15d83374571ee Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Thu, 14 Dec 2023 13:40:22 +0100 Subject: [PATCH 063/472] ESP32-S2 fix ESP32-S2 does not have bluetooth --- src/modules/AdminModule.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index dce33ad48..fa2059f33 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -622,12 +622,12 @@ void AdminModule::handleGetDeviceConnectionStatus(const meshtastic_MeshPacket &r #if HAS_BLUETOOTH conn.has_bluetooth = true; conn.bluetooth.pin = config.bluetooth.fixed_pin; -#endif #ifdef ARCH_ESP32 conn.bluetooth.is_connected = nimbleBluetooth->isConnected(); conn.bluetooth.rssi = nimbleBluetooth->getRssi(); #elif defined(ARCH_NRF52) conn.bluetooth.is_connected = nrf52Bluetooth->isConnected(); +#endif #endif conn.has_serial = true; // No serial-less devices conn.serial.is_connected = powerFSM.getState() == &stateSERIAL; @@ -699,4 +699,4 @@ AdminModule::AdminModule() : ProtobufModule("Admin", meshtastic_PortNum_ADMIN_AP { // restrict to the admin channel for rx boundChannel = Channels::adminChannel; -} \ No newline at end of file +} From 4720b2874f8c5699de5be8c73cd68e17e36c5c3d Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 14 Dec 2023 07:35:46 -0600 Subject: [PATCH 064/472] Cpp-check warnings cleanup (#3014) * cpp-check warnings cleanup * Supressions and more fixes --- src/AccelerometerThread.h | 2 +- src/AmbientLightingThread.h | 2 +- src/Power.cpp | 5 +---- src/PowerFSMThread.h | 2 +- src/mesh/Channels.cpp | 2 +- src/meshUtils.cpp | 7 ++++--- src/modules/NeighborInfoModule.cpp | 4 ++-- src/mqtt/MQTT.cpp | 2 +- suppressions.txt | 5 ++++- 9 files changed, 16 insertions(+), 15 deletions(-) diff --git a/src/AccelerometerThread.h b/src/AccelerometerThread.h index da5695368..744f0ad64 100644 --- a/src/AccelerometerThread.h +++ b/src/AccelerometerThread.h @@ -42,7 +42,7 @@ namespace concurrency class AccelerometerThread : public concurrency::OSThread { public: - AccelerometerThread(ScanI2C::DeviceType type = ScanI2C::DeviceType::NONE) : OSThread("AccelerometerThread") + explicit AccelerometerThread(ScanI2C::DeviceType type) : OSThread("AccelerometerThread") { if (accelerometer_found.port == ScanI2C::I2CPort::NO_I2C) { LOG_DEBUG("AccelerometerThread disabling due to no sensors found\n"); diff --git a/src/AmbientLightingThread.h b/src/AmbientLightingThread.h index 0dd0fdf4a..98ccedde4 100644 --- a/src/AmbientLightingThread.h +++ b/src/AmbientLightingThread.h @@ -10,7 +10,7 @@ namespace concurrency class AmbientLightingThread : public concurrency::OSThread { public: - AmbientLightingThread(ScanI2C::DeviceType type) : OSThread("AmbientLightingThread") + explicit AmbientLightingThread(ScanI2C::DeviceType type) : OSThread("AmbientLightingThread") { // Uncomment to test module // moduleConfig.ambient_lighting.led_state = true; diff --git a/src/Power.cpp b/src/Power.cpp index 0fa97b7f0..12e92b3f1 100644 --- a/src/Power.cpp +++ b/src/Power.cpp @@ -402,11 +402,8 @@ bool Power::analogInit() */ bool Power::setup() { - bool found = axpChipInit(); + bool found = axpChipInit() || analogInit(); - if (!found) { - found = analogInit(); - } enabled = found; low_voltage_counter = 0; diff --git a/src/PowerFSMThread.h b/src/PowerFSMThread.h index b757f3abb..584c955aa 100644 --- a/src/PowerFSMThread.h +++ b/src/PowerFSMThread.h @@ -21,7 +21,7 @@ class PowerFSMThread : public OSThread /// If we are in power state we force the CPU to wake every 10ms to check for serial characters (we don't yet wake /// cpu for serial rx - FIXME) - const auto state = powerFSM.getState(); + const State *state = powerFSM.getState(); canSleep = (state != &statePOWER) && (state != &stateSERIAL); if (powerStatus->getHasUSB()) { diff --git a/src/mesh/Channels.cpp b/src/mesh/Channels.cpp index 9974297fa..f3c692e34 100644 --- a/src/mesh/Channels.cpp +++ b/src/mesh/Channels.cpp @@ -184,7 +184,7 @@ void Channels::onConfigChanged() { // Make sure the phone hasn't mucked anything up for (int i = 0; i < channelFile.channels_count; i++) { - meshtastic_Channel &ch = fixupChannel(i); + const meshtastic_Channel &ch = fixupChannel(i); if (ch.role == meshtastic_Channel_Role_PRIMARY) primaryIndex = i; diff --git a/src/meshUtils.cpp b/src/meshUtils.cpp index cab05e54b..59d4e6714 100644 --- a/src/meshUtils.cpp +++ b/src/meshUtils.cpp @@ -39,10 +39,11 @@ */ char *strnstr(const char *s, const char *find, size_t slen) { - char c, sc; - size_t len; - + char c; if ((c = *find++) != '\0') { + char sc; + size_t len; + len = strlen(find); do { do { diff --git a/src/modules/NeighborInfoModule.cpp b/src/modules/NeighborInfoModule.cpp index cf2276f0e..4541958fa 100644 --- a/src/modules/NeighborInfoModule.cpp +++ b/src/modules/NeighborInfoModule.cpp @@ -118,7 +118,7 @@ uint32_t NeighborInfoModule::collectNeighborInfo(meshtastic_NeighborInfo *neighb int num_neighbors = cleanUpNeighbors(); for (int i = 0; i < num_neighbors; i++) { - meshtastic_Neighbor *dbEntry = getNeighborByIndex(i); + const meshtastic_Neighbor *dbEntry = getNeighborByIndex(i); if ((neighborInfo->neighbors_count < MAX_NUM_NEIGHBORS) && (dbEntry->node_id != my_node_id)) { neighborInfo->neighbors[neighborInfo->neighbors_count].node_id = dbEntry->node_id; neighborInfo->neighbors[neighborInfo->neighbors_count].snr = dbEntry->snr; @@ -146,7 +146,7 @@ size_t NeighborInfoModule::cleanUpNeighbors() // Find neighbors to remove std::vector indices_to_remove; for (int i = 0; i < num_neighbors; i++) { - meshtastic_Neighbor *dbEntry = getNeighborByIndex(i); + const meshtastic_Neighbor *dbEntry = getNeighborByIndex(i); // We will remove a neighbor if we haven't heard from them in twice the broadcast interval if ((now - dbEntry->last_rx_time > dbEntry->node_broadcast_interval_secs * 2) && (dbEntry->node_id != my_node_id)) { indices_to_remove.push_back(i); diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index a97aa5255..8c20bfd2f 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -519,10 +519,10 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp) // the created jsonObj is immutable after creation, so // we need to do the heavy lifting before assembling it. std::string msgType; - JSONObject msgPayload; JSONObject jsonObj; if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag) { + JSONObject msgPayload; switch (mp->decoded.portnum) { case meshtastic_PortNum_TEXT_MESSAGE_APP: { msgType = "text"; diff --git a/suppressions.txt b/suppressions.txt index 6cbd38d47..04937523d 100644 --- a/suppressions.txt +++ b/suppressions.txt @@ -50,4 +50,7 @@ virtualCallInConstructor passedByValue:*/RedirectablePrint.h internalAstError:*/CrossPlatformCryptoEngine.cpp -uninitMemberVar:*/AudioThread.h \ No newline at end of file +uninitMemberVar:*/AudioThread.h +// False positive +constVariableReference:*/Channels.cpp +constParameterPointer:*/unishox2.c \ No newline at end of file From 6c1db94ae7843053cb71389c87beb679ef1405e3 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 14 Dec 2023 19:53:42 -0600 Subject: [PATCH 065/472] Add raspbian reboot and shutdown behavior --- arch/portduino/portduino.ini | 2 +- src/input/LinuxInput.cpp | 5 +++++ src/input/LinuxInput.h | 1 + src/mesh/api/WiFiServerAPI.cpp | 6 +++++- src/mesh/api/WiFiServerAPI.h | 3 ++- src/shutdown.h | 12 +++++++++++- 6 files changed, 25 insertions(+), 4 deletions(-) diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index e739d7066..98bb309b9 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -1,6 +1,6 @@ ; The Portduino based sim environment on top of any host OS, all hardware will be simulated [portduino_base] -platform = https://github.com/meshtastic/platform-native.git#ff5da1d203b5c1163cfcda858d5f84920187f030 +platform = https://github.com/meshtastic/platform-native.git#8a66ef82cf38a4135d85cbb5043d0e8ebbb8ba17 framework = arduino build_src_filter = diff --git a/src/input/LinuxInput.cpp b/src/input/LinuxInput.cpp index 4b6150949..ea588c4bf 100644 --- a/src/input/LinuxInput.cpp +++ b/src/input/LinuxInput.cpp @@ -23,6 +23,11 @@ LinuxInput::LinuxInput(const char *name) : concurrency::OSThread(name) this->_originName = name; } +void LinuxInput::deInit() +{ + close(fd); +} + int32_t LinuxInput::runOnce() { diff --git a/src/input/LinuxInput.h b/src/input/LinuxInput.h index c21fb4c36..c7f011379 100644 --- a/src/input/LinuxInput.h +++ b/src/input/LinuxInput.h @@ -21,6 +21,7 @@ class LinuxInput : public Observable, public concurrency::OS { public: explicit LinuxInput(const char *name); + void deInit(); // Strictly for cleanly "rebooting" the binary on native protected: virtual int32_t runOnce() override; diff --git a/src/mesh/api/WiFiServerAPI.cpp b/src/mesh/api/WiFiServerAPI.cpp index 5f86dbe85..ba31f76e5 100644 --- a/src/mesh/api/WiFiServerAPI.cpp +++ b/src/mesh/api/WiFiServerAPI.cpp @@ -15,6 +15,10 @@ void initApiServer(int port) apiPort->init(); } } +void deInitApiServer() +{ + delete apiPort; +} WiFiServerAPI::WiFiServerAPI(WiFiClient &_client) : ServerAPI(_client) { @@ -22,4 +26,4 @@ WiFiServerAPI::WiFiServerAPI(WiFiClient &_client) : ServerAPI(_client) } WiFiServerPort::WiFiServerPort(int port) : APIServerPort(port) {} -#endif +#endif \ No newline at end of file diff --git a/src/mesh/api/WiFiServerAPI.h b/src/mesh/api/WiFiServerAPI.h index e436a177d..7a3d2967f 100644 --- a/src/mesh/api/WiFiServerAPI.h +++ b/src/mesh/api/WiFiServerAPI.h @@ -22,4 +22,5 @@ class WiFiServerPort : public APIServerPort explicit WiFiServerPort(int port); }; -void initApiServer(int port = 4403); \ No newline at end of file +void initApiServer(int port = 4403); +void deInitApiServer(); \ No newline at end of file diff --git a/src/shutdown.h b/src/shutdown.h index f36a7f8dd..113bfc541 100644 --- a/src/shutdown.h +++ b/src/shutdown.h @@ -1,6 +1,8 @@ +#include "api/WiFiServerAPI.h" #include "buzz.h" #include "configuration.h" #include "graphics/Screen.h" +#include "input/LinuxInputImpl.h" #include "main.h" #include "power.h" @@ -15,7 +17,13 @@ void powerCommandsCheck() #elif defined(ARCH_RP2040) rp2040.reboot(); #elif defined(ARCH_RASPBERRY_PI) - exit(EXIT_SUCCESS); + deInitApiServer(); + if (aLinuxInputImpl) + aLinuxInputImpl->deInit(); + SPI.end(); + Wire.end(); + Serial1.end(); + reboot(); #else rebootAtMsec = -1; LOG_WARN("FIXME implement reboot for this platform. Note that some settings require a restart to be applied.\n"); @@ -33,6 +41,8 @@ void powerCommandsCheck() #if defined(ARCH_NRF52) || defined(ARCH_ESP32) playShutdownMelody(); power->shutdown(); +#elif ARCH_RASPBERRY_PI + exit(EXIT_SUCCESS); #else LOG_WARN("FIXME implement shutdown for this platform"); #endif From fc365a1fee412519bba887606dd9052b298ad4f9 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 14 Dec 2023 20:16:36 -0600 Subject: [PATCH 066/472] Keep WiFi defines out of platforms without WiFi --- src/shutdown.h | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/src/shutdown.h b/src/shutdown.h index 113bfc541..9488ad241 100644 --- a/src/shutdown.h +++ b/src/shutdown.h @@ -1,10 +1,13 @@ -#include "api/WiFiServerAPI.h" #include "buzz.h" #include "configuration.h" #include "graphics/Screen.h" -#include "input/LinuxInputImpl.h" #include "main.h" #include "power.h" +#if ARCH_RASPBERRY_PI +#include "api/WiFiServerAPI.h" +#include "input/LinuxInputImpl.h" + +#endif void powerCommandsCheck() { From c6ae66dcaa255173f31f34707eb1175fcf0df34b Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 14 Dec 2023 21:03:21 -0600 Subject: [PATCH 067/472] Add fallthrough option to avoid a GPS stuck off. --- src/gps/GPS.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index d5cd9b682..60eeeb3bb 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -575,15 +575,20 @@ void GPS::setAwake(bool on) if ((int32_t)getSleepTime() - averageLockTime > 15 * 60 * 1000) { // 15 minutes is probably long enough to make a complete poweroff worth it. setGPSPower(on, false, getSleepTime() - averageLockTime); + return; } else if ((int32_t)getSleepTime() - averageLockTime > 10000) { // 10 seconds is enough for standby #ifdef GPS_UC6580 setGPSPower(on, false, getSleepTime() - averageLockTime); #else setGPSPower(on, true, getSleepTime() - averageLockTime); #endif - } else if (averageLockTime > 20000) { + return; + } + if (averageLockTime > 20000) { averageLockTime -= 1000; // eventually want to sleep again. } + if (on) + setGPSPower(true, true, 0); // make sure we don't have a fallthrough where GPS is stuck off } } From 1c6acfd73495c2613eb937f56a0856dc2b34e9a0 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sat, 16 Dec 2023 06:57:01 -0600 Subject: [PATCH 068/472] Set NRF cpu brownout at 2.4V instead of running down to the limit (#3016) --- src/platform/nrf52/main-nrf52.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/platform/nrf52/main-nrf52.cpp b/src/platform/nrf52/main-nrf52.cpp index 65b45f1e9..cab6a63b9 100644 --- a/src/platform/nrf52/main-nrf52.cpp +++ b/src/platform/nrf52/main-nrf52.cpp @@ -51,7 +51,7 @@ void getMacAddr(uint8_t *dmac) static void initBrownout() { - auto vccthresh = POWER_POFCON_THRESHOLD_V17; + auto vccthresh = POWER_POFCON_THRESHOLD_V24; auto err_code = sd_power_pof_enable(POWER_POFCON_POF_Enabled); assert(err_code == NRF_SUCCESS); From 45f90fb39b9bb66b45c25dfe7ae7d825ccd43a41 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sat, 16 Dec 2023 19:21:54 -0600 Subject: [PATCH 069/472] [create-pull-request] automated change (#3018) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index c95d5701a..9e5ea17c6 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 2 -build = 16 +build = 17 From 71c072683863d3e6e8a158e9ef1bf55a6eb660d7 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sat, 16 Dec 2023 22:20:53 -0600 Subject: [PATCH 070/472] Ignore keyboard input while sending CannedMessages packet --- src/modules/CannedMessageModule.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index 45d2083b7..cc6d8e39d 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -142,7 +142,9 @@ int CannedMessageModule::handleInputEvent(const InputEvent *event) // source at all) return 0; } - + if (this->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE) { + return 0; // Ignore input while sending + } bool validEvent = false; if (event->inputEvent == static_cast(meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_UP)) { if (this->messagesCount > 0) { From 24c4ee9bfa918a6e0224eb75104f0c3b4fd8cb84 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sun, 17 Dec 2023 16:28:48 +0100 Subject: [PATCH 071/472] local variable and class variable may not be named the same --- src/modules/NodeInfoModule.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/modules/NodeInfoModule.cpp b/src/modules/NodeInfoModule.cpp index 799f6ec7c..c266f235c 100644 --- a/src/modules/NodeInfoModule.cpp +++ b/src/modules/NodeInfoModule.cpp @@ -83,8 +83,6 @@ NodeInfoModule::NodeInfoModule() int32_t NodeInfoModule::runOnce() { - static uint32_t currentGeneration; - // If we changed channels, ask everyone else for their latest info bool requestReplies = currentGeneration != radioGeneration; currentGeneration = radioGeneration; From bbe21766be81ce8959426265a4c0bcebc4f4b5a1 Mon Sep 17 00:00:00 2001 From: caveman99 Date: Sun, 17 Dec 2023 17:29:49 +0000 Subject: [PATCH 072/472] [create-pull-request] automated change --- protobufs | 2 +- src/mesh/generated/meshtastic/admin.pb.h | 8 ++- src/mesh/generated/meshtastic/deviceonly.pb.h | 2 +- src/mesh/generated/meshtastic/localonly.pb.h | 14 +++-- .../generated/meshtastic/module_config.pb.c | 3 + .../generated/meshtastic/module_config.pb.h | 28 ++++++++- src/mesh/generated/meshtastic/paxcount.pb.c | 12 ++++ src/mesh/generated/meshtastic/paxcount.pb.h | 57 +++++++++++++++++++ src/mesh/generated/meshtastic/portnums.pb.h | 3 + 9 files changed, 119 insertions(+), 10 deletions(-) create mode 100644 src/mesh/generated/meshtastic/paxcount.pb.c create mode 100644 src/mesh/generated/meshtastic/paxcount.pb.h diff --git a/protobufs b/protobufs index a34b2c680..c1e179ecf 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit a34b2c680e2c1c240643c515e57c5532b29c91a7 +Subproject commit c1e179ecfd86c88deaf1140e7a9c6902b763cc3d diff --git a/src/mesh/generated/meshtastic/admin.pb.h b/src/mesh/generated/meshtastic/admin.pb.h index 9978c5591..f5f362789 100644 --- a/src/mesh/generated/meshtastic/admin.pb.h +++ b/src/mesh/generated/meshtastic/admin.pb.h @@ -59,7 +59,9 @@ typedef enum _meshtastic_AdminMessage_ModuleConfigType { /* TODO: REPLACE */ meshtastic_AdminMessage_ModuleConfigType_AMBIENTLIGHTING_CONFIG = 10, /* TODO: REPLACE */ - meshtastic_AdminMessage_ModuleConfigType_DETECTIONSENSOR_CONFIG = 11 + meshtastic_AdminMessage_ModuleConfigType_DETECTIONSENSOR_CONFIG = 11, + /* TODO: REPLACE */ + meshtastic_AdminMessage_ModuleConfigType_PAXCOUNTER_CONFIG = 12 } meshtastic_AdminMessage_ModuleConfigType; /* Struct definitions */ @@ -180,8 +182,8 @@ extern "C" { #define _meshtastic_AdminMessage_ConfigType_ARRAYSIZE ((meshtastic_AdminMessage_ConfigType)(meshtastic_AdminMessage_ConfigType_BLUETOOTH_CONFIG+1)) #define _meshtastic_AdminMessage_ModuleConfigType_MIN meshtastic_AdminMessage_ModuleConfigType_MQTT_CONFIG -#define _meshtastic_AdminMessage_ModuleConfigType_MAX meshtastic_AdminMessage_ModuleConfigType_DETECTIONSENSOR_CONFIG -#define _meshtastic_AdminMessage_ModuleConfigType_ARRAYSIZE ((meshtastic_AdminMessage_ModuleConfigType)(meshtastic_AdminMessage_ModuleConfigType_DETECTIONSENSOR_CONFIG+1)) +#define _meshtastic_AdminMessage_ModuleConfigType_MAX meshtastic_AdminMessage_ModuleConfigType_PAXCOUNTER_CONFIG +#define _meshtastic_AdminMessage_ModuleConfigType_ARRAYSIZE ((meshtastic_AdminMessage_ModuleConfigType)(meshtastic_AdminMessage_ModuleConfigType_PAXCOUNTER_CONFIG+1)) #define meshtastic_AdminMessage_payload_variant_get_config_request_ENUMTYPE meshtastic_AdminMessage_ConfigType #define meshtastic_AdminMessage_payload_variant_get_module_config_request_ENUMTYPE meshtastic_AdminMessage_ModuleConfigType diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index b099a3eab..ef5045e2e 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -316,7 +316,7 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg; #define meshtastic_DeviceState_size 17056 #define meshtastic_NodeInfoLite_size 153 #define meshtastic_NodeRemoteHardwarePin_size 29 -#define meshtastic_OEMStore_size 3231 +#define meshtastic_OEMStore_size 3241 #define meshtastic_PositionLite_size 28 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/localonly.pb.h b/src/mesh/generated/meshtastic/localonly.pb.h index 7dc96e79a..3f8751653 100644 --- a/src/mesh/generated/meshtastic/localonly.pb.h +++ b/src/mesh/generated/meshtastic/localonly.pb.h @@ -81,6 +81,9 @@ typedef struct _meshtastic_LocalModuleConfig { /* The part of the config that is specific to the Detection Sensor module */ bool has_detection_sensor; meshtastic_ModuleConfig_DetectionSensorConfig detection_sensor; + /* Paxcounter Config */ + bool has_paxcounter; + meshtastic_ModuleConfig_PaxcounterConfig paxcounter; } meshtastic_LocalModuleConfig; @@ -90,9 +93,9 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_LocalConfig_init_default {false, meshtastic_Config_DeviceConfig_init_default, false, meshtastic_Config_PositionConfig_init_default, false, meshtastic_Config_PowerConfig_init_default, false, meshtastic_Config_NetworkConfig_init_default, false, meshtastic_Config_DisplayConfig_init_default, false, meshtastic_Config_LoRaConfig_init_default, false, meshtastic_Config_BluetoothConfig_init_default, 0} -#define meshtastic_LocalModuleConfig_init_default {false, meshtastic_ModuleConfig_MQTTConfig_init_default, false, meshtastic_ModuleConfig_SerialConfig_init_default, false, meshtastic_ModuleConfig_ExternalNotificationConfig_init_default, false, meshtastic_ModuleConfig_StoreForwardConfig_init_default, false, meshtastic_ModuleConfig_RangeTestConfig_init_default, false, meshtastic_ModuleConfig_TelemetryConfig_init_default, false, meshtastic_ModuleConfig_CannedMessageConfig_init_default, 0, false, meshtastic_ModuleConfig_AudioConfig_init_default, false, meshtastic_ModuleConfig_RemoteHardwareConfig_init_default, false, meshtastic_ModuleConfig_NeighborInfoConfig_init_default, false, meshtastic_ModuleConfig_AmbientLightingConfig_init_default, false, meshtastic_ModuleConfig_DetectionSensorConfig_init_default} +#define meshtastic_LocalModuleConfig_init_default {false, meshtastic_ModuleConfig_MQTTConfig_init_default, false, meshtastic_ModuleConfig_SerialConfig_init_default, false, meshtastic_ModuleConfig_ExternalNotificationConfig_init_default, false, meshtastic_ModuleConfig_StoreForwardConfig_init_default, false, meshtastic_ModuleConfig_RangeTestConfig_init_default, false, meshtastic_ModuleConfig_TelemetryConfig_init_default, false, meshtastic_ModuleConfig_CannedMessageConfig_init_default, 0, false, meshtastic_ModuleConfig_AudioConfig_init_default, false, meshtastic_ModuleConfig_RemoteHardwareConfig_init_default, false, meshtastic_ModuleConfig_NeighborInfoConfig_init_default, false, meshtastic_ModuleConfig_AmbientLightingConfig_init_default, false, meshtastic_ModuleConfig_DetectionSensorConfig_init_default, false, meshtastic_ModuleConfig_PaxcounterConfig_init_default} #define meshtastic_LocalConfig_init_zero {false, meshtastic_Config_DeviceConfig_init_zero, false, meshtastic_Config_PositionConfig_init_zero, false, meshtastic_Config_PowerConfig_init_zero, false, meshtastic_Config_NetworkConfig_init_zero, false, meshtastic_Config_DisplayConfig_init_zero, false, meshtastic_Config_LoRaConfig_init_zero, false, meshtastic_Config_BluetoothConfig_init_zero, 0} -#define meshtastic_LocalModuleConfig_init_zero {false, meshtastic_ModuleConfig_MQTTConfig_init_zero, false, meshtastic_ModuleConfig_SerialConfig_init_zero, false, meshtastic_ModuleConfig_ExternalNotificationConfig_init_zero, false, meshtastic_ModuleConfig_StoreForwardConfig_init_zero, false, meshtastic_ModuleConfig_RangeTestConfig_init_zero, false, meshtastic_ModuleConfig_TelemetryConfig_init_zero, false, meshtastic_ModuleConfig_CannedMessageConfig_init_zero, 0, false, meshtastic_ModuleConfig_AudioConfig_init_zero, false, meshtastic_ModuleConfig_RemoteHardwareConfig_init_zero, false, meshtastic_ModuleConfig_NeighborInfoConfig_init_zero, false, meshtastic_ModuleConfig_AmbientLightingConfig_init_zero, false, meshtastic_ModuleConfig_DetectionSensorConfig_init_zero} +#define meshtastic_LocalModuleConfig_init_zero {false, meshtastic_ModuleConfig_MQTTConfig_init_zero, false, meshtastic_ModuleConfig_SerialConfig_init_zero, false, meshtastic_ModuleConfig_ExternalNotificationConfig_init_zero, false, meshtastic_ModuleConfig_StoreForwardConfig_init_zero, false, meshtastic_ModuleConfig_RangeTestConfig_init_zero, false, meshtastic_ModuleConfig_TelemetryConfig_init_zero, false, meshtastic_ModuleConfig_CannedMessageConfig_init_zero, 0, false, meshtastic_ModuleConfig_AudioConfig_init_zero, false, meshtastic_ModuleConfig_RemoteHardwareConfig_init_zero, false, meshtastic_ModuleConfig_NeighborInfoConfig_init_zero, false, meshtastic_ModuleConfig_AmbientLightingConfig_init_zero, false, meshtastic_ModuleConfig_DetectionSensorConfig_init_zero, false, meshtastic_ModuleConfig_PaxcounterConfig_init_zero} /* Field tags (for use in manual encoding/decoding) */ #define meshtastic_LocalConfig_device_tag 1 @@ -116,6 +119,7 @@ extern "C" { #define meshtastic_LocalModuleConfig_neighbor_info_tag 11 #define meshtastic_LocalModuleConfig_ambient_lighting_tag 12 #define meshtastic_LocalModuleConfig_detection_sensor_tag 13 +#define meshtastic_LocalModuleConfig_paxcounter_tag 14 /* Struct field encoding specification for nanopb */ #define meshtastic_LocalConfig_FIELDLIST(X, a) \ @@ -150,7 +154,8 @@ X(a, STATIC, OPTIONAL, MESSAGE, audio, 9) \ X(a, STATIC, OPTIONAL, MESSAGE, remote_hardware, 10) \ X(a, STATIC, OPTIONAL, MESSAGE, neighbor_info, 11) \ X(a, STATIC, OPTIONAL, MESSAGE, ambient_lighting, 12) \ -X(a, STATIC, OPTIONAL, MESSAGE, detection_sensor, 13) +X(a, STATIC, OPTIONAL, MESSAGE, detection_sensor, 13) \ +X(a, STATIC, OPTIONAL, MESSAGE, paxcounter, 14) #define meshtastic_LocalModuleConfig_CALLBACK NULL #define meshtastic_LocalModuleConfig_DEFAULT NULL #define meshtastic_LocalModuleConfig_mqtt_MSGTYPE meshtastic_ModuleConfig_MQTTConfig @@ -165,6 +170,7 @@ X(a, STATIC, OPTIONAL, MESSAGE, detection_sensor, 13) #define meshtastic_LocalModuleConfig_neighbor_info_MSGTYPE meshtastic_ModuleConfig_NeighborInfoConfig #define meshtastic_LocalModuleConfig_ambient_lighting_MSGTYPE meshtastic_ModuleConfig_AmbientLightingConfig #define meshtastic_LocalModuleConfig_detection_sensor_MSGTYPE meshtastic_ModuleConfig_DetectionSensorConfig +#define meshtastic_LocalModuleConfig_paxcounter_MSGTYPE meshtastic_ModuleConfig_PaxcounterConfig extern const pb_msgdesc_t meshtastic_LocalConfig_msg; extern const pb_msgdesc_t meshtastic_LocalModuleConfig_msg; @@ -175,7 +181,7 @@ extern const pb_msgdesc_t meshtastic_LocalModuleConfig_msg; /* Maximum encoded size of messages (where known) */ #define meshtastic_LocalConfig_size 464 -#define meshtastic_LocalModuleConfig_size 621 +#define meshtastic_LocalModuleConfig_size 631 #ifdef __cplusplus } /* extern "C" */ diff --git a/src/mesh/generated/meshtastic/module_config.pb.c b/src/mesh/generated/meshtastic/module_config.pb.c index 7318d34f7..38965f3e2 100644 --- a/src/mesh/generated/meshtastic/module_config.pb.c +++ b/src/mesh/generated/meshtastic/module_config.pb.c @@ -24,6 +24,9 @@ PB_BIND(meshtastic_ModuleConfig_DetectionSensorConfig, meshtastic_ModuleConfig_D PB_BIND(meshtastic_ModuleConfig_AudioConfig, meshtastic_ModuleConfig_AudioConfig, AUTO) +PB_BIND(meshtastic_ModuleConfig_PaxcounterConfig, meshtastic_ModuleConfig_PaxcounterConfig, AUTO) + + PB_BIND(meshtastic_ModuleConfig_SerialConfig, meshtastic_ModuleConfig_SerialConfig, AUTO) diff --git a/src/mesh/generated/meshtastic/module_config.pb.h b/src/mesh/generated/meshtastic/module_config.pb.h index b9f43e352..edfd56e4c 100644 --- a/src/mesh/generated/meshtastic/module_config.pb.h +++ b/src/mesh/generated/meshtastic/module_config.pb.h @@ -170,6 +170,13 @@ typedef struct _meshtastic_ModuleConfig_AudioConfig { uint8_t i2s_sck; } meshtastic_ModuleConfig_AudioConfig; +/* Config for the Paxcounter Module */ +typedef struct _meshtastic_ModuleConfig_PaxcounterConfig { + /* Enable the Paxcounter Module */ + bool enabled; + uint32_t paxcounter_update_interval; +} meshtastic_ModuleConfig_PaxcounterConfig; + /* Serial Config */ typedef struct _meshtastic_ModuleConfig_SerialConfig { /* Preferences for the SerialModule */ @@ -384,6 +391,8 @@ typedef struct _meshtastic_ModuleConfig { meshtastic_ModuleConfig_AmbientLightingConfig ambient_lighting; /* TODO: REPLACE */ meshtastic_ModuleConfig_DetectionSensorConfig detection_sensor; + /* TODO: REPLACE */ + meshtastic_ModuleConfig_PaxcounterConfig paxcounter; } payload_variant; } meshtastic_ModuleConfig; @@ -420,6 +429,7 @@ extern "C" { #define meshtastic_ModuleConfig_AudioConfig_bitrate_ENUMTYPE meshtastic_ModuleConfig_AudioConfig_Audio_Baud + #define meshtastic_ModuleConfig_SerialConfig_baud_ENUMTYPE meshtastic_ModuleConfig_SerialConfig_Serial_Baud #define meshtastic_ModuleConfig_SerialConfig_mode_ENUMTYPE meshtastic_ModuleConfig_SerialConfig_Serial_Mode @@ -442,6 +452,7 @@ extern "C" { #define meshtastic_ModuleConfig_NeighborInfoConfig_init_default {0, 0} #define meshtastic_ModuleConfig_DetectionSensorConfig_init_default {0, 0, 0, 0, "", 0, 0, 0} #define meshtastic_ModuleConfig_AudioConfig_init_default {0, 0, _meshtastic_ModuleConfig_AudioConfig_Audio_Baud_MIN, 0, 0, 0, 0} +#define meshtastic_ModuleConfig_PaxcounterConfig_init_default {0, 0} #define meshtastic_ModuleConfig_SerialConfig_init_default {0, 0, 0, 0, _meshtastic_ModuleConfig_SerialConfig_Serial_Baud_MIN, 0, _meshtastic_ModuleConfig_SerialConfig_Serial_Mode_MIN, 0} #define meshtastic_ModuleConfig_ExternalNotificationConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_StoreForwardConfig_init_default {0, 0, 0, 0, 0} @@ -456,6 +467,7 @@ extern "C" { #define meshtastic_ModuleConfig_NeighborInfoConfig_init_zero {0, 0} #define meshtastic_ModuleConfig_DetectionSensorConfig_init_zero {0, 0, 0, 0, "", 0, 0, 0} #define meshtastic_ModuleConfig_AudioConfig_init_zero {0, 0, _meshtastic_ModuleConfig_AudioConfig_Audio_Baud_MIN, 0, 0, 0, 0} +#define meshtastic_ModuleConfig_PaxcounterConfig_init_zero {0, 0} #define meshtastic_ModuleConfig_SerialConfig_init_zero {0, 0, 0, 0, _meshtastic_ModuleConfig_SerialConfig_Serial_Baud_MIN, 0, _meshtastic_ModuleConfig_SerialConfig_Serial_Mode_MIN, 0} #define meshtastic_ModuleConfig_ExternalNotificationConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_StoreForwardConfig_init_zero {0, 0, 0, 0, 0} @@ -492,6 +504,8 @@ extern "C" { #define meshtastic_ModuleConfig_AudioConfig_i2s_sd_tag 5 #define meshtastic_ModuleConfig_AudioConfig_i2s_din_tag 6 #define meshtastic_ModuleConfig_AudioConfig_i2s_sck_tag 7 +#define meshtastic_ModuleConfig_PaxcounterConfig_enabled_tag 1 +#define meshtastic_ModuleConfig_PaxcounterConfig_paxcounter_update_interval_tag 2 #define meshtastic_ModuleConfig_SerialConfig_enabled_tag 1 #define meshtastic_ModuleConfig_SerialConfig_echo_tag 2 #define meshtastic_ModuleConfig_SerialConfig_rxd_tag 3 @@ -567,6 +581,7 @@ extern "C" { #define meshtastic_ModuleConfig_neighbor_info_tag 10 #define meshtastic_ModuleConfig_ambient_lighting_tag 11 #define meshtastic_ModuleConfig_detection_sensor_tag 12 +#define meshtastic_ModuleConfig_paxcounter_tag 13 /* Struct field encoding specification for nanopb */ #define meshtastic_ModuleConfig_FIELDLIST(X, a) \ @@ -581,7 +596,8 @@ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,audio,payload_variant.audio) X(a, STATIC, ONEOF, MESSAGE, (payload_variant,remote_hardware,payload_variant.remote_hardware), 9) \ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,neighbor_info,payload_variant.neighbor_info), 10) \ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,ambient_lighting,payload_variant.ambient_lighting), 11) \ -X(a, STATIC, ONEOF, MESSAGE, (payload_variant,detection_sensor,payload_variant.detection_sensor), 12) +X(a, STATIC, ONEOF, MESSAGE, (payload_variant,detection_sensor,payload_variant.detection_sensor), 12) \ +X(a, STATIC, ONEOF, MESSAGE, (payload_variant,paxcounter,payload_variant.paxcounter), 13) #define meshtastic_ModuleConfig_CALLBACK NULL #define meshtastic_ModuleConfig_DEFAULT NULL #define meshtastic_ModuleConfig_payload_variant_mqtt_MSGTYPE meshtastic_ModuleConfig_MQTTConfig @@ -596,6 +612,7 @@ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,detection_sensor,payload_var #define meshtastic_ModuleConfig_payload_variant_neighbor_info_MSGTYPE meshtastic_ModuleConfig_NeighborInfoConfig #define meshtastic_ModuleConfig_payload_variant_ambient_lighting_MSGTYPE meshtastic_ModuleConfig_AmbientLightingConfig #define meshtastic_ModuleConfig_payload_variant_detection_sensor_MSGTYPE meshtastic_ModuleConfig_DetectionSensorConfig +#define meshtastic_ModuleConfig_payload_variant_paxcounter_MSGTYPE meshtastic_ModuleConfig_PaxcounterConfig #define meshtastic_ModuleConfig_MQTTConfig_FIELDLIST(X, a) \ X(a, STATIC, SINGULAR, BOOL, enabled, 1) \ @@ -647,6 +664,12 @@ X(a, STATIC, SINGULAR, UINT32, i2s_sck, 7) #define meshtastic_ModuleConfig_AudioConfig_CALLBACK NULL #define meshtastic_ModuleConfig_AudioConfig_DEFAULT NULL +#define meshtastic_ModuleConfig_PaxcounterConfig_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, BOOL, enabled, 1) \ +X(a, STATIC, SINGULAR, UINT32, paxcounter_update_interval, 2) +#define meshtastic_ModuleConfig_PaxcounterConfig_CALLBACK NULL +#define meshtastic_ModuleConfig_PaxcounterConfig_DEFAULT NULL + #define meshtastic_ModuleConfig_SerialConfig_FIELDLIST(X, a) \ X(a, STATIC, SINGULAR, BOOL, enabled, 1) \ X(a, STATIC, SINGULAR, BOOL, echo, 2) \ @@ -745,6 +768,7 @@ extern const pb_msgdesc_t meshtastic_ModuleConfig_RemoteHardwareConfig_msg; extern const pb_msgdesc_t meshtastic_ModuleConfig_NeighborInfoConfig_msg; extern const pb_msgdesc_t meshtastic_ModuleConfig_DetectionSensorConfig_msg; extern const pb_msgdesc_t meshtastic_ModuleConfig_AudioConfig_msg; +extern const pb_msgdesc_t meshtastic_ModuleConfig_PaxcounterConfig_msg; extern const pb_msgdesc_t meshtastic_ModuleConfig_SerialConfig_msg; extern const pb_msgdesc_t meshtastic_ModuleConfig_ExternalNotificationConfig_msg; extern const pb_msgdesc_t meshtastic_ModuleConfig_StoreForwardConfig_msg; @@ -761,6 +785,7 @@ extern const pb_msgdesc_t meshtastic_RemoteHardwarePin_msg; #define meshtastic_ModuleConfig_NeighborInfoConfig_fields &meshtastic_ModuleConfig_NeighborInfoConfig_msg #define meshtastic_ModuleConfig_DetectionSensorConfig_fields &meshtastic_ModuleConfig_DetectionSensorConfig_msg #define meshtastic_ModuleConfig_AudioConfig_fields &meshtastic_ModuleConfig_AudioConfig_msg +#define meshtastic_ModuleConfig_PaxcounterConfig_fields &meshtastic_ModuleConfig_PaxcounterConfig_msg #define meshtastic_ModuleConfig_SerialConfig_fields &meshtastic_ModuleConfig_SerialConfig_msg #define meshtastic_ModuleConfig_ExternalNotificationConfig_fields &meshtastic_ModuleConfig_ExternalNotificationConfig_msg #define meshtastic_ModuleConfig_StoreForwardConfig_fields &meshtastic_ModuleConfig_StoreForwardConfig_msg @@ -778,6 +803,7 @@ extern const pb_msgdesc_t meshtastic_RemoteHardwarePin_msg; #define meshtastic_ModuleConfig_ExternalNotificationConfig_size 42 #define meshtastic_ModuleConfig_MQTTConfig_size 222 #define meshtastic_ModuleConfig_NeighborInfoConfig_size 8 +#define meshtastic_ModuleConfig_PaxcounterConfig_size 8 #define meshtastic_ModuleConfig_RangeTestConfig_size 10 #define meshtastic_ModuleConfig_RemoteHardwareConfig_size 96 #define meshtastic_ModuleConfig_SerialConfig_size 28 diff --git a/src/mesh/generated/meshtastic/paxcount.pb.c b/src/mesh/generated/meshtastic/paxcount.pb.c new file mode 100644 index 000000000..57d5f5be9 --- /dev/null +++ b/src/mesh/generated/meshtastic/paxcount.pb.c @@ -0,0 +1,12 @@ +/* Automatically generated nanopb constant definitions */ +/* Generated by nanopb-0.4.7 */ + +#include "meshtastic/paxcount.pb.h" +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +PB_BIND(meshtastic_Paxcount, meshtastic_Paxcount, AUTO) + + + diff --git a/src/mesh/generated/meshtastic/paxcount.pb.h b/src/mesh/generated/meshtastic/paxcount.pb.h new file mode 100644 index 000000000..4b643293c --- /dev/null +++ b/src/mesh/generated/meshtastic/paxcount.pb.h @@ -0,0 +1,57 @@ +/* Automatically generated nanopb header */ +/* Generated by nanopb-0.4.7 */ + +#ifndef PB_MESHTASTIC_MESHTASTIC_PAXCOUNT_PB_H_INCLUDED +#define PB_MESHTASTIC_MESHTASTIC_PAXCOUNT_PB_H_INCLUDED +#include + +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +/* Struct definitions */ +/* TODO: REPLACE */ +typedef struct _meshtastic_Paxcount { + /* seen Wifi devices */ + uint32_t wifi; + /* Seen BLE devices */ + uint32_t ble; + /* Uptime in seconds */ + uint32_t uptime; +} meshtastic_Paxcount; + + +#ifdef __cplusplus +extern "C" { +#endif + +/* Initializer values for message structs */ +#define meshtastic_Paxcount_init_default {0, 0, 0} +#define meshtastic_Paxcount_init_zero {0, 0, 0} + +/* Field tags (for use in manual encoding/decoding) */ +#define meshtastic_Paxcount_wifi_tag 1 +#define meshtastic_Paxcount_ble_tag 2 +#define meshtastic_Paxcount_uptime_tag 3 + +/* Struct field encoding specification for nanopb */ +#define meshtastic_Paxcount_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, UINT32, wifi, 1) \ +X(a, STATIC, SINGULAR, UINT32, ble, 2) \ +X(a, STATIC, SINGULAR, UINT32, uptime, 3) +#define meshtastic_Paxcount_CALLBACK NULL +#define meshtastic_Paxcount_DEFAULT NULL + +extern const pb_msgdesc_t meshtastic_Paxcount_msg; + +/* Defines for backwards compatibility with code written before nanopb-0.4.0 */ +#define meshtastic_Paxcount_fields &meshtastic_Paxcount_msg + +/* Maximum encoded size of messages (where known) */ +#define meshtastic_Paxcount_size 18 + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif diff --git a/src/mesh/generated/meshtastic/portnums.pb.h b/src/mesh/generated/meshtastic/portnums.pb.h index c94349d47..4fad85b86 100644 --- a/src/mesh/generated/meshtastic/portnums.pb.h +++ b/src/mesh/generated/meshtastic/portnums.pb.h @@ -79,6 +79,9 @@ typedef enum _meshtastic_PortNum { /* Used for the python IP tunnel feature ENCODING: IP Packet. Handled by the python API, firmware ignores this one and pases on. */ meshtastic_PortNum_IP_TUNNEL_APP = 33, + /* Paxcounter lib included in the firmware + ENCODING: protobuf */ + meshtastic_PortNum_PAXCOUNTER_APP = 34, /* Provides a hardware serial interface to send and receive from the Meshtastic network. Connect to the RX/TX pins of a device with 38400 8N1. Packets received from the Meshtastic network is forwarded to the RX pin while sending a packet to TX will go out to the Mesh network. From add78a459bbbb2a569e6ed9864d18625833d54dd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sun, 17 Dec 2023 16:00:57 +0100 Subject: [PATCH 073/472] Include Libpax - WIP --- arch/esp32/esp32.ini | 4 ++ src/modules/Modules.cpp | 7 +- src/modules/esp32/AudioModule.cpp | 4 +- src/modules/esp32/AudioModule.h | 2 +- src/modules/esp32/PaxcounterModule.cpp | 91 ++++++++++++++++++++++++++ src/modules/esp32/PaxcounterModule.h | 29 ++++++++ 6 files changed, 133 insertions(+), 4 deletions(-) create mode 100644 src/modules/esp32/PaxcounterModule.cpp create mode 100644 src/modules/esp32/PaxcounterModule.h diff --git a/arch/esp32/esp32.ini b/arch/esp32/esp32.ini index 1f28ba6df..bf84dd939 100644 --- a/arch/esp32/esp32.ini +++ b/arch/esp32/esp32.ini @@ -31,6 +31,9 @@ build_flags = -DCONFIG_BT_NIMBLE_HOST_TASK_STACK_SIZE=5120 -DESP_OPENSSL_SUPPRESS_LEGACY_WARNING -DSERIAL_BUFFER_SIZE=4096 + -DLIBPAX_ARDUINO + -DLIBPAX_WIFI + -DLIBPAX_BLE ;-DDEBUG_HEAP lib_deps = @@ -39,6 +42,7 @@ lib_deps = ${environmental_base.lib_deps} https://github.com/meshtastic/esp32_https_server.git#23665b3adc080a311dcbb586ed5941b5f94d6ea2 h2zero/NimBLE-Arduino@^1.4.1 + https://github.com/dbSuS/libpax.git#7bcd3fcab75037505be9b122ab2b24cc5176b587 https://github.com/lewisxhe/XPowersLib.git#84b7373faea3118b6c37954d52f98b8a337148d6 https://github.com/meshtastic/ESP32_Codec2.git#633326c78ac251c059ab3a8c430fcdf25b41672f diff --git a/src/modules/Modules.cpp b/src/modules/Modules.cpp index 19d6b76d4..5ed49a4d8 100644 --- a/src/modules/Modules.cpp +++ b/src/modules/Modules.cpp @@ -31,7 +31,10 @@ #include "modules/Telemetry/PowerTelemetry.h" #endif #ifdef ARCH_ESP32 +#ifdef USE_SX1280 #include "modules/esp32/AudioModule.h" +#endif +#include "modules/esp32/PaxcounterModule.h" #include "modules/esp32/StoreForwardModule.h" #endif #if defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040) @@ -111,9 +114,11 @@ void setupModules() #endif #ifdef ARCH_ESP32 // Only run on an esp32 based device. +#ifdef USE_SX1280 audioModule = new AudioModule(); - +#endif storeForwardModule = new StoreForwardModule(); + paxcounterModule = new PaxcounterModule(); #endif #if defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040) externalNotificationModule = new ExternalNotificationModule(); diff --git a/src/modules/esp32/AudioModule.cpp b/src/modules/esp32/AudioModule.cpp index a2e43347a..bc104df11 100644 --- a/src/modules/esp32/AudioModule.cpp +++ b/src/modules/esp32/AudioModule.cpp @@ -1,6 +1,6 @@ #include "configuration.h" -#if defined(ARCH_ESP32) +#if defined(ARCH_ESP32) && defined(USE_SX1280) #include "AudioModule.h" #include "FSCommon.h" #include "MeshService.h" @@ -145,7 +145,7 @@ AudioModule::AudioModule() : SinglePortModule("AudioModule", meshtastic_PortNum_ encode_frame_num = (meshtastic_Constants_DATA_PAYLOAD_LEN - sizeof(tx_header)) / encode_codec_size; encode_frame_size = encode_frame_num * encode_codec_size; // max 233 bytes + 4 header bytes adc_buffer_size = codec2_samples_per_frame(codec2); - LOG_INFO(" using %d frames of %d bytes for a total payload length of %d bytes\n", encode_frame_num, encode_codec_size, + LOG_INFO("using %d frames of %d bytes for a total payload length of %d bytes\n", encode_frame_num, encode_codec_size, encode_frame_size); xTaskCreate(&run_codec2, "codec2_task", 30000, NULL, 5, &codec2HandlerTask); } else { diff --git a/src/modules/esp32/AudioModule.h b/src/modules/esp32/AudioModule.h index 8bf8c3f55..b6762706a 100644 --- a/src/modules/esp32/AudioModule.h +++ b/src/modules/esp32/AudioModule.h @@ -3,7 +3,7 @@ #include "SinglePortModule.h" #include "concurrency/NotifiedWorkerThread.h" #include "configuration.h" -#if defined(ARCH_ESP32) +#if defined(ARCH_ESP32) && defined(USE_SX1280) #include "NodeDB.h" #include #include diff --git a/src/modules/esp32/PaxcounterModule.cpp b/src/modules/esp32/PaxcounterModule.cpp new file mode 100644 index 000000000..41970008f --- /dev/null +++ b/src/modules/esp32/PaxcounterModule.cpp @@ -0,0 +1,91 @@ +#include "configuration.h" +#if defined(ARCH_ESP32) +#include "MeshService.h" +#include "PaxcounterModule.h" + +#include + +PaxcounterModule *paxcounterModule; + +void NullFunc(){}; + +// paxcounterModule->sendInfo(NODENUM_BROADCAST); + +PaxcounterModule::PaxcounterModule() + : concurrency::OSThread("PaxcounterModule"), + ProtobufModule("paxcounter", meshtastic_PortNum_PAXCOUNTER_APP, &meshtastic_Paxcount_msg), + +{ +} + +bool PaxcounterModule::sendInfo(NodeNum dest) +{ + libpax_counter_count(&count_from_libpax); + LOG_INFO("(Sending): pax: wifi=%d; ble=%d; uptime=%d\n", count_from_libpax.wifi_count, count_from_libpax.ble_count, + millis() / 1000); + + meshtastic_Paxcount pl = meshtastic_Paxcount_init_default; + pl.wifi = count_from_libpax.wifi_count; + pl.ble = count_from_libpax.ble_count; + pl.uptime = millis() / 1000; + + meshtastic_MeshPacket *p = allocDataProtobuf(pl); + p->to = dest; + p->decoded.want_response = false; + p->priority = meshtastic_MeshPacket_Priority_MIN; + + service.sendToMesh(p, RX_SRC_LOCAL, true); + return true; +} + +bool PaxcounterModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_Paxcount *p) +{ + return false; // Let others look at this message also if they want. We don't do anything with received packets. +} + +meshtastic_MeshPacket *PaxcounterModule::allocReply() +{ + if (ignoreRequest) { + return NULL; + } + + meshtastic_Paxcount pl = meshtastic_Paxcount_init_default; + pl.wifi = count_from_libpax.wifi_count; + pl.ble = count_from_libpax.ble_count; + pl.uptime = millis() / 1000; + return allocDataProtobuf(pl); +} + +int32_t PaxcounterModule::runOnce() +{ + if (moduleConfig.paxcounter.enabled && !config.bluetooth.enabled && !config.network.wifi_enabled) { + if (firstTime) { + firstTime = false; + LOG_DEBUG( + "Paxcounter starting up with interval of %d seconds\n", + getConfiguredOrDefault(moduleConfig.paxcounter.paxcounter_update_interval, default_broadcast_interval_secs)); + struct libpax_config_t configuration; + libpax_default_config(&configuration); + + configuration.blecounter = 1; + configuration.blescantime = 0; // infinit + configuration.wificounter = 1; + configuration.wifi_channel_map = WIFI_CHANNEL_ALL; + configuration.wifi_channel_switch_interval = 50; + configuration.wifi_rssi_threshold = -80; + configuration.ble_rssi_threshold = -80; + libpax_update_config(&configuration); + + // internal processing initialization + libpax_counter_init(NullFunc, &count_from_libpax, UINT16_MAX, 1); + libpax_counter_start(); + } else { + sendInfo(NODENUM_BROADCAST); + } + return getConfiguredOrDefaultMs(moduleConfig.paxcounter.paxcounter_update_interval, default_broadcast_interval_secs); + } else { + return disable(); + } +} + +#endif \ No newline at end of file diff --git a/src/modules/esp32/PaxcounterModule.h b/src/modules/esp32/PaxcounterModule.h new file mode 100644 index 000000000..a3759be3f --- /dev/null +++ b/src/modules/esp32/PaxcounterModule.h @@ -0,0 +1,29 @@ +#pragma once + +#include "ProtobufModule.h" +#include "configuration.h" +#if defined(ARCH_ESP32) +#include "../mesh/generated/meshtastic/paxcount.pb.h" +#include "NodeDB.h" +#include + +/** + * A simple example module that just replies with "Message received" to any message it receives. + */ +class PaxcounterModule : private concurrency::OSThread, public ProtobufModule +{ + bool firstTime = true; + + public: + PaxcounterModule(); + + protected: + struct count_payload_t count_from_libpax; + virtual int32_t runOnce() override; + bool sendInfo(NodeNum dest = NODENUM_BROADCAST); + virtual bool handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_Paxcount *p) override; + virtual meshtastic_MeshPacket *allocReply() override; +}; + +extern PaxcounterModule *paxcounterModule; +#endif \ No newline at end of file From c5a2dc758f5613ec9d1ef2102ef8504b564601d0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sun, 17 Dec 2023 16:10:26 +0100 Subject: [PATCH 074/472] rule of thumb, last minute changes are dumb. --- src/modules/esp32/PaxcounterModule.cpp | 3 +-- src/modules/esp32/PaxcounterModule.h | 2 +- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/src/modules/esp32/PaxcounterModule.cpp b/src/modules/esp32/PaxcounterModule.cpp index 41970008f..f3df7ffdf 100644 --- a/src/modules/esp32/PaxcounterModule.cpp +++ b/src/modules/esp32/PaxcounterModule.cpp @@ -13,8 +13,7 @@ void NullFunc(){}; PaxcounterModule::PaxcounterModule() : concurrency::OSThread("PaxcounterModule"), - ProtobufModule("paxcounter", meshtastic_PortNum_PAXCOUNTER_APP, &meshtastic_Paxcount_msg), - + ProtobufModule("paxcounter", meshtastic_PortNum_PAXCOUNTER_APP, &meshtastic_Paxcount_msg) { } diff --git a/src/modules/esp32/PaxcounterModule.h b/src/modules/esp32/PaxcounterModule.h index a3759be3f..0aa9be68d 100644 --- a/src/modules/esp32/PaxcounterModule.h +++ b/src/modules/esp32/PaxcounterModule.h @@ -18,7 +18,7 @@ class PaxcounterModule : private concurrency::OSThread, public ProtobufModule Date: Sun, 17 Dec 2023 17:11:45 +0100 Subject: [PATCH 075/472] admin getters and setters --- src/mesh/PhoneAPI.cpp | 4 ++++ src/modules/AdminModule.cpp | 10 ++++++++++ 2 files changed, 14 insertions(+) diff --git a/src/mesh/PhoneAPI.cpp b/src/mesh/PhoneAPI.cpp index a01647bfa..10e8ac2dc 100644 --- a/src/mesh/PhoneAPI.cpp +++ b/src/mesh/PhoneAPI.cpp @@ -298,6 +298,10 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf) fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_ambient_lighting_tag; fromRadioScratch.moduleConfig.payload_variant.ambient_lighting = moduleConfig.ambient_lighting; break; + case meshtastic_ModuleConfig_paxcounter_tag: + fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_paxcounter_tag; + fromRadioScratch.moduleConfig.payload_variant.paxcounter = moduleConfig.paxcounter; + break; default: LOG_ERROR("Unknown module config type %d\n", config_state); } diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index fa2059f33..b33877b8d 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -389,6 +389,11 @@ void AdminModule::handleSetModuleConfig(const meshtastic_ModuleConfig &c) moduleConfig.has_ambient_lighting = true; moduleConfig.ambient_lighting = c.payload_variant.ambient_lighting; break; + case meshtastic_ModuleConfig_paxcounter_tag: + LOG_INFO("Setting module config: Paxcounter\n"); + moduleConfig.has_paxcounter = true; + moduleConfig.paxcounter = c.payload_variant.paxcounter; + break; } saveChanges(SEGMENT_MODULECONFIG); @@ -539,6 +544,11 @@ void AdminModule::handleGetModuleConfig(const meshtastic_MeshPacket &req, const res.get_module_config_response.which_payload_variant = meshtastic_ModuleConfig_ambient_lighting_tag; res.get_module_config_response.payload_variant.ambient_lighting = moduleConfig.ambient_lighting; break; + case meshtastic_AdminMessage_ModuleConfigType_PAXCOUNTER_CONFIG: + LOG_INFO("Getting module config: Paxcounter\n"); + res.get_module_config_response.which_payload_variant = meshtastic_ModuleConfig_paxcounter_tag; + res.get_module_config_response.payload_variant.paxcounter = moduleConfig.paxcounter; + break; } // NOTE: The phone app needs to know the ls_secsvalue so it can properly expect sleep behavior. From 16a3a32f2a1592e05be4d42fa8c6b716e251f923 Mon Sep 17 00:00:00 2001 From: Mark Trevor Birss Date: Mon, 18 Dec 2023 02:05:04 +0200 Subject: [PATCH 076/472] [Add] SX1280 to linux native Portduino (#3023) * Update PortduinoGlue.cpp * Update PortduinoGlue.h * Update main.cpp * Update config-dist.yaml * Update config-dist.yaml * Fix whitespace in main.cpp --------- Co-authored-by: Jonathan Bennett --- bin/config-dist.yaml | 6 ++++++ src/main.cpp | 16 +++++++++++++++- src/platform/portduino/PortduinoGlue.cpp | 5 ++++- src/platform/portduino/PortduinoGlue.h | 3 ++- 4 files changed, 27 insertions(+), 3 deletions(-) diff --git a/bin/config-dist.yaml b/bin/config-dist.yaml index 266a9ae20..4079e7676 100644 --- a/bin/config-dist.yaml +++ b/bin/config-dist.yaml @@ -25,6 +25,12 @@ Lora: # CS: 7 # IRQ: 25 +# Module: sx1280 # SX1280 +# CS: 21 +# IRQ: 16 +# Busy: 20 +# Reset: 18 + ### Set gpio chip to use in /dev/. Defaults to 0. ### Notably the Raspberry Pi 5 puts the GPIO header on gpiochip4 # gpiochip: 4 diff --git a/src/main.cpp b/src/main.cpp index 9c67cc0ac..ecb2b0b48 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -742,6 +742,20 @@ void setup() LOG_INFO("RF95 Radio init succeeded, using RF95 radio\n"); } } + } else if (settingsMap[use_sx1280]) { + if (!rIf) { + LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(SPI, spiSettings); + rIf = new SX1280Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset], + settingsMap[busy]); + if (!rIf->init()) { + LOG_ERROR("Failed to find SX1280 radio\n"); + delete rIf; + rIf = NULL; + exit(EXIT_FAILURE); + } else { + LOG_INFO("SX1280 Radio init succeeded, using SX1280 radio\n"); + } + } } #elif defined(HW_SPI1_DEVICE) @@ -965,4 +979,4 @@ void loop() mainDelay.delay(delayMsec); } // if (didWake) LOG_DEBUG("wake!\n"); -} \ No newline at end of file +} diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index b8e9dd9e6..5464c6c49 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -131,11 +131,14 @@ void portduinoSetup() if (yamlConfig["Lora"]) { settingsMap[use_sx1262] = false; settingsMap[use_rf95] = false; + settingsMap[use_sx1280] = false; if (yamlConfig["Lora"]["Module"] && yamlConfig["Lora"]["Module"].as("") == "sx1262") { settingsMap[use_sx1262] = true; } else if (yamlConfig["Lora"]["Module"] && yamlConfig["Lora"]["Module"].as("") == "RF95") { settingsMap[use_rf95] = true; + } else if (yamlConfig["Lora"]["Module"] && yamlConfig["Lora"]["Module"].as("") == "sx1280") { + settingsMap[use_sx1280] = true; } settingsMap[dio2_as_rf_switch] = yamlConfig["Lora"]["DIO2_AS_RF_SWITCH"].as(false); settingsMap[cs] = yamlConfig["Lora"]["CS"].as(RADIOLIB_NC); @@ -296,4 +299,4 @@ int initGPIOPin(int pinNum, std::string gpioChipName) return ERRNO_DISABLED; } } -#endif \ No newline at end of file +#endif diff --git a/src/platform/portduino/PortduinoGlue.h b/src/platform/portduino/PortduinoGlue.h index 046c5d097..ed45cb457 100644 --- a/src/platform/portduino/PortduinoGlue.h +++ b/src/platform/portduino/PortduinoGlue.h @@ -10,6 +10,7 @@ enum configNames { reset, dio2_as_rf_switch, use_rf95, + use_sx1280, user, gpiochip, has_gps, @@ -33,4 +34,4 @@ extern std::map settingsMap; extern std::map settingsStrings; int initGPIOPin(int pinNum, std::string gpioChipname); -#endif \ No newline at end of file +#endif From d88baea627526268ff6ba0361ddb91f86c2ae050 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Thu, 21 Dec 2023 21:59:16 +0100 Subject: [PATCH 077/472] Make implicit ACKs work on MQTT (#3028) Don't filter out messages we originally sent via LoRa --- src/mqtt/MQTT.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 8c20bfd2f..717e1818e 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -143,8 +143,8 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length) p->channel = ch.index; } - // ignore messages sent by us or if we don't have the channel key - if (router && p->from != nodeDB.getNodeNum() && perhapsDecode(p)) + // ignore messages if we don't have the channel key + if (router && perhapsDecode(p)) router->enqueueReceivedMessage(p); else packetPool.release(p); From db8f8db8e87f253ef2d8d7fc2d65d37879a94a6d Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Thu, 21 Dec 2023 21:59:45 +0100 Subject: [PATCH 078/472] Don't disconnect WiFi when we're actively reconnecting (#3026) WiFiEvents may happen asynchronously --- src/mesh/wifi/WiFiAPClient.cpp | 27 +++++++++++++++++---------- 1 file changed, 17 insertions(+), 10 deletions(-) diff --git a/src/mesh/wifi/WiFiAPClient.cpp b/src/mesh/wifi/WiFiAPClient.cpp index 1e521e033..b0b033ba0 100644 --- a/src/mesh/wifi/WiFiAPClient.cpp +++ b/src/mesh/wifi/WiFiAPClient.cpp @@ -38,7 +38,8 @@ bool APStartupComplete = 0; unsigned long lastrun_ntp = 0; -bool needReconnect = true; // If we create our reconnector, run it once at the beginning +bool needReconnect = true; // If we create our reconnector, run it once at the beginning +bool isReconnecting = false; // If we are currently reconnecting WiFiUDP syslogClient; Syslog syslog(syslogClient); @@ -115,6 +116,7 @@ static int32_t reconnectWiFi() wifiPsw = NULL; needReconnect = false; + isReconnecting = true; // Make sure we clear old connection credentials #ifdef ARCH_ESP32 @@ -129,6 +131,7 @@ static int32_t reconnectWiFi() if (!WiFi.isConnected()) { WiFi.begin(wifiName, wifiPsw); } + isReconnecting = false; } #ifndef DISABLE_NTP @@ -277,10 +280,12 @@ static void WiFiEvent(WiFiEvent_t event) break; case ARDUINO_EVENT_WIFI_STA_DISCONNECTED: LOG_INFO("Disconnected from WiFi access point\n"); - WiFi.disconnect(false, true); - syslog.disable(); - needReconnect = true; - wifiReconnect->setIntervalFromNow(1000); + if (!isReconnecting) { + WiFi.disconnect(false, true); + syslog.disable(); + needReconnect = true; + wifiReconnect->setIntervalFromNow(1000); + } break; case ARDUINO_EVENT_WIFI_STA_AUTHMODE_CHANGE: LOG_INFO("Authentication mode of access point has changed\n"); @@ -294,10 +299,12 @@ static void WiFiEvent(WiFiEvent_t event) break; case ARDUINO_EVENT_WIFI_STA_LOST_IP: LOG_INFO("Lost IP address and IP address is reset to 0\n"); - WiFi.disconnect(false, true); - syslog.disable(); - needReconnect = true; - wifiReconnect->setIntervalFromNow(1000); + if (!isReconnecting) { + WiFi.disconnect(false, true); + syslog.disable(); + needReconnect = true; + wifiReconnect->setIntervalFromNow(1000); + } break; case ARDUINO_EVENT_WPS_ER_SUCCESS: LOG_INFO("WiFi Protected Setup (WPS): succeeded in enrollee mode\n"); @@ -398,4 +405,4 @@ static void WiFiEvent(WiFiEvent_t event) uint8_t getWifiDisconnectReason() { return wifiDisconnectReason; -} +} \ No newline at end of file From ba98da55a7aaccb1a48f2ced69544948716ea105 Mon Sep 17 00:00:00 2001 From: Wolfgang Nagele Date: Mon, 25 Dec 2023 16:47:19 +0100 Subject: [PATCH 079/472] Align glibc with Debian builder (#3034) --- Dockerfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Dockerfile b/Dockerfile index 8e3cd2154..03e823117 100644 --- a/Dockerfile +++ b/Dockerfile @@ -27,7 +27,7 @@ RUN wget https://raw.githubusercontent.com/platformio/platformio-core-installer/ source ~/.platformio/penv/bin/activate && \ ./bin/build-native.sh -FROM frolvlad/alpine-glibc +FROM frolvlad/alpine-glibc:glibc-2.31 RUN apk --update add --no-cache g++ shadow && \ groupadd -g 1000 mesh && useradd -ml -u 1000 -g 1000 mesh From 7334ee73495e2bac1e9afb069ae88ba42b0fba6e Mon Sep 17 00:00:00 2001 From: Wolfgang Nagele Date: Mon, 25 Dec 2023 23:40:16 +0100 Subject: [PATCH 080/472] Time Fix (#3035) Co-authored-by: Ben Meadors --- src/modules/PositionModule.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index 212961dc4..1113bc976 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -61,7 +61,7 @@ bool PositionModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes p.altitude_geoidal_separation, p.PDOP, p.HDOP, p.VDOP, p.sats_in_view, p.fix_quality, p.fix_type, p.timestamp, p.time); - if (p.time) { + if (p.time && channels.getByIndex(mp.channel).role == meshtastic_Channel_Role_PRIMARY) { struct timeval tv; uint32_t secs = p.time; @@ -87,6 +87,7 @@ bool PositionModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes meshtastic_MeshPacket *PositionModule::allocReply() { if (ignoreRequest) { + ignoreRequest = false; // Reset for next request return nullptr; } @@ -150,6 +151,7 @@ meshtastic_MeshPacket *PositionModule::allocReply() LOG_INFO("Stripping time %u from position send\n", p.time); p.time = 0; } else { + p.time = getValidTime(RTCQualityDevice); LOG_INFO("Providing time to mesh %u\n", p.time); } @@ -166,7 +168,7 @@ void PositionModule::sendOurPosition(NodeNum dest, bool wantReplies, uint8_t cha meshtastic_MeshPacket *p = allocReply(); if (p == nullptr) { - LOG_WARN("allocReply returned a nullptr"); + LOG_WARN("allocReply returned a nullptr\n"); return; } From 8d37d93e05609eb92ee289f217598f6b3ec7d2b2 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Tue, 26 Dec 2023 13:21:09 -0600 Subject: [PATCH 081/472] Hash function needs uint32_t for some platforms. (#3038) --- src/mesh/RadioInterface.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/mesh/RadioInterface.cpp b/src/mesh/RadioInterface.cpp index c66f0e1d3..c6d5e8a78 100644 --- a/src/mesh/RadioInterface.cpp +++ b/src/mesh/RadioInterface.cpp @@ -328,9 +328,9 @@ int RadioInterface::notifyDeepSleepCb(void *unused) * djb2 by Dan Bernstein. * http://www.cse.yorku.ca/~oz/hash.html */ -unsigned long hash(const char *str) +uint32_t hash(const char *str) { - unsigned long hash = 5381; + uint32_t hash = 5381; int c; while ((c = *str++) != 0) @@ -548,4 +548,4 @@ size_t RadioInterface::beginSending(meshtastic_MeshPacket *p) sendingPacket = p; return p->encrypted.size + sizeof(PacketHeader); -} +} \ No newline at end of file From 16c18d0da96acec0073d66dc8cd663d26e3d2be7 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Wed, 27 Dec 2023 15:14:25 +0100 Subject: [PATCH 082/472] Add Traceroute, DetectionSensor and Paxcounter to MQTT JSON (#3043) * Add Traceroute, DetectionSensor and Paxcounter to MQTT JSON * Guard Paxcounter for ESP32 only --- src/mqtt/MQTT.cpp | 63 +++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 63 insertions(+) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 717e1818e..bc788ed37 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -7,6 +7,9 @@ #include "mesh/Router.h" #include "mesh/generated/meshtastic/mqtt.pb.h" #include "mesh/generated/meshtastic/telemetry.pb.h" +#if defined(ARCH_ESP32) +#include "../mesh/generated/meshtastic/paxcount.pb.h" +#endif #include "sleep.h" #if HAS_WIFI #include "mesh/wifi/WiFiAPClient.h" @@ -684,6 +687,66 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp) } break; } + case meshtastic_PortNum_TRACEROUTE_APP: { + if (mp->decoded.request_id) { // Only report the traceroute response + msgType = "traceroute"; + meshtastic_RouteDiscovery scratch; + meshtastic_RouteDiscovery *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_RouteDiscovery_msg, + &scratch)) { + decoded = &scratch; + JSONArray route; // Route this message took + // Lambda function for adding a long name to the route + auto addToRoute = [](JSONArray *route, NodeNum num) { + char long_name[40] = "Unknown"; + meshtastic_NodeInfoLite *node = nodeDB.getMeshNode(num); + bool name_known = node ? node->has_user : false; + if (name_known) + memcpy(long_name, node->user.long_name, sizeof(long_name)); + route->push_back(new JSONValue(long_name)); + }; + addToRoute(&route, mp->to); // Started at the original transmitter (destination of response) + for (uint8_t i = 0; i < decoded->route_count; i++) { + addToRoute(&route, decoded->route[i]); + } + addToRoute(&route, mp->from); // Ended at the original destination (source of response) + + msgPayload["route"] = new JSONValue(route); + jsonObj["payload"] = new JSONValue(msgPayload); + } else { + LOG_ERROR("Error decoding protobuf for traceroute message!\n"); + } + } + break; + } + case meshtastic_PortNum_DETECTION_SENSOR_APP: { + msgType = "detection"; + char payloadStr[(mp->decoded.payload.size) + 1]; + memcpy(payloadStr, mp->decoded.payload.bytes, mp->decoded.payload.size); + payloadStr[mp->decoded.payload.size] = 0; // null terminated string + msgPayload["text"] = new JSONValue(payloadStr); + jsonObj["payload"] = new JSONValue(msgPayload); + break; + } +#ifdef ARCH_ESP32 + case meshtastic_PortNum_PAXCOUNTER_APP: { + msgType = "paxcounter"; + meshtastic_Paxcount scratch; + meshtastic_Paxcount *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Paxcount_msg, &scratch)) { + decoded = &scratch; + msgPayload["wifi_count"] = new JSONValue((uint)decoded->wifi); + msgPayload["ble_count"] = new JSONValue((uint)decoded->ble); + msgPayload["uptime"] = new JSONValue((uint)decoded->uptime); + jsonObj["payload"] = new JSONValue(msgPayload); + } else { + LOG_ERROR("Error decoding protobuf for Paxcount message!\n"); + } + break; + } +#endif // add more packet types here if needed default: break; From 06b4638f6b3af1e1defdbb6f1a008d9fa22662aa Mon Sep 17 00:00:00 2001 From: Wolfgang Nagele Date: Wed, 27 Dec 2023 15:14:55 +0100 Subject: [PATCH 083/472] Allow override of HWID using environment variable (#3036) Co-authored-by: Ben Meadors --- Dockerfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Dockerfile b/Dockerfile index 03e823117..63eccc4b4 100644 --- a/Dockerfile +++ b/Dockerfile @@ -36,6 +36,6 @@ COPY --from=builder /tmp/firmware/release/meshtasticd_linux_amd64 /home/mesh/ USER mesh WORKDIR /home/mesh -CMD sh -cx "./meshtasticd_linux_amd64 --hwid '$RANDOM'" +CMD sh -cx "./meshtasticd_linux_amd64 --hwid '${HWID:-$RANDOM}'" HEALTHCHECK NONE From d318d34c3cfeebc44ccb9e992195058dc8cc72b5 Mon Sep 17 00:00:00 2001 From: Mictronics Date: Wed, 27 Dec 2023 15:15:38 +0100 Subject: [PATCH 084/472] Fix #3032 (#3040) * Fixed bug #3023 in upstream master. Wire.begin doesn't accept two arguments in RP2040 framework. * Fix typo. --------- Co-authored-by: Ben Meadors --- src/main.cpp | 26 ++++++++++++++++++++++---- 1 file changed, 22 insertions(+), 4 deletions(-) diff --git a/src/main.cpp b/src/main.cpp index ecb2b0b48..38c35cf15 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -369,11 +369,19 @@ void setup() #endif -#ifdef I2C_SDA1 +#if defined(I2C_SDA1) && defined(ARCH_RP2040) + Wire1.setSDA(I2C_SDA1); + Wire1.setSCL(I2C_SCL1); + Wire1.begin(); +#elif defined(I2C_SDA1) && !defined(ARCH_RP2040) Wire1.begin(I2C_SDA1, I2C_SCL1); #endif -#ifdef I2C_SDA +#if defined(I2C_SDA) && defined(ARCH_RP2040) + Wire.setSDA(I2C_SDA); + Wire.setSCL(I2C_SCL); + Wire.begin(); +#elif defined(I2C_SDA) && !defined(ARCH_RP2040) Wire.begin(I2C_SDA, I2C_SCL); #elif HAS_WIRE Wire.begin(); @@ -423,12 +431,22 @@ void setup() LOG_INFO("Scanning for i2c devices...\n"); -#ifdef I2C_SDA1 +#if defined(I2C_SDA1) && defined(ARCH_RP2040) + Wire1.setSDA(I2C_SDA1); + Wire1.setSCL(I2C_SCL1); + Wire1.begin(); + i2cScanner->scanPort(ScanI2C::I2CPort::WIRE1); +#elif defined(I2C_SDA1) && !defined(ARCH_RP2040) Wire1.begin(I2C_SDA1, I2C_SCL1); i2cScanner->scanPort(ScanI2C::I2CPort::WIRE1); #endif -#ifdef I2C_SDA +#if defined(I2C_SDA) && defined(ARCH_RP2040) + Wire.setSDA(I2C_SDA); + Wire.setSCL(I2C_SCL); + Wire.begin(); + i2cScanner->scanPort(ScanI2C::I2CPort::WIRE); +#elif defined(I2C_SDA) && !defined(ARCH_RP2040) Wire.begin(I2C_SDA, I2C_SCL); i2cScanner->scanPort(ScanI2C::I2CPort::WIRE); #elif HAS_WIRE From 2d35f72d85c0a7a9ab3256c65de7cd65f4f24450 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Wed, 27 Dec 2023 15:16:04 +0100 Subject: [PATCH 085/472] SimRadio: send queue status to phone (#3041) Co-authored-by: Ben Meadors --- src/mesh/MeshService.h | 4 ++-- src/platform/portduino/SimRadio.cpp | 4 +++- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/src/mesh/MeshService.h b/src/mesh/MeshService.h index 6d73c076a..68287efc2 100644 --- a/src/mesh/MeshService.h +++ b/src/mesh/MeshService.h @@ -129,6 +129,8 @@ class MeshService bool isToPhoneQueueEmpty(); + ErrorCode sendQueueStatusToPhone(const meshtastic_QueueStatus &qs, ErrorCode res, uint32_t mesh_packet_id); + private: /// Called when our gps position has changed - updates nodedb and sends Location message out into the mesh /// returns 0 to allow further processing @@ -138,8 +140,6 @@ class MeshService /// needs to keep the packet around it makes a copy int handleFromRadio(const meshtastic_MeshPacket *p); friend class RoutingModule; - - ErrorCode sendQueueStatusToPhone(const meshtastic_QueueStatus &qs, ErrorCode res, uint32_t mesh_packet_id); }; extern MeshService service; \ No newline at end of file diff --git a/src/platform/portduino/SimRadio.cpp b/src/platform/portduino/SimRadio.cpp index e3d56554a..d0072cf35 100644 --- a/src/platform/portduino/SimRadio.cpp +++ b/src/platform/portduino/SimRadio.cpp @@ -198,6 +198,8 @@ void SimRadio::startSend(meshtastic_MeshPacket *txp) p->decoded.payload.size = pb_encode_to_bytes(p->decoded.payload.bytes, sizeof(p->decoded.payload.bytes), &meshtastic_Compressed_msg, &c); p->decoded.portnum = meshtastic_PortNum_SIMULATOR_APP; + + service.sendQueueStatusToPhone(router->getQueueStatus(), 0, p->id); service.sendToPhone(p); // Sending back to simulator } @@ -263,4 +265,4 @@ int16_t SimRadio::readData(uint8_t *data, size_t len) } return state; -} +} \ No newline at end of file From 5110de4838e8a196c857f75cbacca9313f57ba0f Mon Sep 17 00:00:00 2001 From: Wolfgang Nagele Date: Wed, 27 Dec 2023 15:16:53 +0100 Subject: [PATCH 086/472] Portduino reboot (#3033) * Portduino reboot * separate blocks --------- Co-authored-by: Jonathan Bennett Co-authored-by: Ben Meadors --- src/shutdown.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/shutdown.h b/src/shutdown.h index 9488ad241..10283f5dd 100644 --- a/src/shutdown.h +++ b/src/shutdown.h @@ -27,6 +27,11 @@ void powerCommandsCheck() Wire.end(); Serial1.end(); reboot(); +#elif defined(ARCH_PORTDUINO) + deInitApiServer(); + SPI.end(); + Wire.end(); + reboot(); #else rebootAtMsec = -1; LOG_WARN("FIXME implement reboot for this platform. Note that some settings require a restart to be applied.\n"); From d401040e516e758ce9d9c5a4eae729c02a1e065f Mon Sep 17 00:00:00 2001 From: S5NC <145265251+S5NC@users.noreply.github.com> Date: Wed, 27 Dec 2023 14:18:26 +0000 Subject: [PATCH 087/472] Remove old SX126x and SX128x boosted gain commented-out code (#2976) * Update SX126xInterface.cpp * Update SX128xInterface.cpp --------- Co-authored-by: Ben Meadors --- src/mesh/SX126xInterface.cpp | 7 +------ src/mesh/SX128xInterface.cpp | 5 ----- 2 files changed, 1 insertion(+), 11 deletions(-) diff --git a/src/mesh/SX126xInterface.cpp b/src/mesh/SX126xInterface.cpp index 0692d1ef1..45519ff87 100644 --- a/src/mesh/SX126xInterface.cpp +++ b/src/mesh/SX126xInterface.cpp @@ -167,11 +167,6 @@ template bool SX126xInterface::reconfigure() if (err != RADIOLIB_ERR_NONE) RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING); - // Hmm - seems to lower SNR when the signal levels are high. Leaving off for now... - // TODO: Confirm gain registers are okay now - // err = lora.setRxGain(true); - // assert(err == RADIOLIB_ERR_NONE); - err = lora.setSyncWord(syncWord); assert(err == RADIOLIB_ERR_NONE); @@ -327,4 +322,4 @@ template bool SX126xInterface::sleep() #endif return true; -} \ No newline at end of file +} diff --git a/src/mesh/SX128xInterface.cpp b/src/mesh/SX128xInterface.cpp index 0c5c4dcfa..6b7b0f438 100644 --- a/src/mesh/SX128xInterface.cpp +++ b/src/mesh/SX128xInterface.cpp @@ -106,11 +106,6 @@ template bool SX128xInterface::reconfigure() if (err != RADIOLIB_ERR_NONE) RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING); - // Hmm - seems to lower SNR when the signal levels are high. Leaving off for now... - // TODO: Confirm gain registers are okay now - // err = lora.setRxGain(true); - // assert(err == RADIOLIB_ERR_NONE); - err = lora.setSyncWord(syncWord); assert(err == RADIOLIB_ERR_NONE); From 2b7eb1e48929b2f03b1008565daca833055dd305 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Wed, 27 Dec 2023 12:48:30 -0600 Subject: [PATCH 088/472] [create-pull-request] automated change (#3044) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/admin.pb.h | 5 +++++ 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/protobufs b/protobufs index c1e179ecf..8e84c2f95 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit c1e179ecfd86c88deaf1140e7a9c6902b763cc3d +Subproject commit 8e84c2f95fcc7f0e88a80645d3a88812adbda841 diff --git a/src/mesh/generated/meshtastic/admin.pb.h b/src/mesh/generated/meshtastic/admin.pb.h index f5f362789..198a076fd 100644 --- a/src/mesh/generated/meshtastic/admin.pb.h +++ b/src/mesh/generated/meshtastic/admin.pb.h @@ -131,6 +131,9 @@ typedef struct _meshtastic_AdminMessage { bool get_node_remote_hardware_pins_request; /* Respond with the mesh's nodes with their available gpio pins for RemoteHardware module use */ meshtastic_NodeRemoteHardwarePinsResponse get_node_remote_hardware_pins_response; + /* Enter (serial) DFU mode + Only implemented on NRF52 currently */ + bool enter_dfu_mode_request; /* Set the owner for this node */ meshtastic_User set_owner; /* Set channels (using the new API). @@ -224,6 +227,7 @@ extern "C" { #define meshtastic_AdminMessage_set_ham_mode_tag 18 #define meshtastic_AdminMessage_get_node_remote_hardware_pins_request_tag 19 #define meshtastic_AdminMessage_get_node_remote_hardware_pins_response_tag 20 +#define meshtastic_AdminMessage_enter_dfu_mode_request_tag 21 #define meshtastic_AdminMessage_set_owner_tag 32 #define meshtastic_AdminMessage_set_channel_tag 33 #define meshtastic_AdminMessage_set_config_tag 34 @@ -261,6 +265,7 @@ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,get_device_connection_status X(a, STATIC, ONEOF, MESSAGE, (payload_variant,set_ham_mode,set_ham_mode), 18) \ X(a, STATIC, ONEOF, BOOL, (payload_variant,get_node_remote_hardware_pins_request,get_node_remote_hardware_pins_request), 19) \ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,get_node_remote_hardware_pins_response,get_node_remote_hardware_pins_response), 20) \ +X(a, STATIC, ONEOF, BOOL, (payload_variant,enter_dfu_mode_request,enter_dfu_mode_request), 21) \ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,set_owner,set_owner), 32) \ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,set_channel,set_channel), 33) \ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,set_config,set_config), 34) \ From dbac2b1cadb7a4e114fedb665beb4646436719b1 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 27 Dec 2023 14:26:40 -0600 Subject: [PATCH 089/472] Implemented enter (Uf2 usb) DFU mode admin message on NRF52 (#3045) * Added enter DFU mode admin message * Trunk --- protobufs | 2 +- src/main.h | 2 +- src/mesh/generated/meshtastic/admin.pb.h | 2 +- src/modules/AdminModule.cpp | 7 +++++++ src/platform/nrf52/main-nrf52.cpp | 6 ++++++ 5 files changed, 16 insertions(+), 3 deletions(-) diff --git a/protobufs b/protobufs index 8e84c2f95..4a1d3766e 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 8e84c2f95fcc7f0e88a80645d3a88812adbda841 +Subproject commit 4a1d3766e888d3dd7d1acda817083295fb054c92 diff --git a/src/main.h b/src/main.h index 52e9a4271..8a646c80b 100644 --- a/src/main.h +++ b/src/main.h @@ -77,7 +77,7 @@ extern int heltec_version; // This will suppress the current delay and instead try to run ASAP. extern bool runASAP; -void nrf52Setup(), esp32Setup(), nrf52Loop(), esp32Loop(), rp2040Setup(), clearBonds(); +void nrf52Setup(), esp32Setup(), nrf52Loop(), esp32Loop(), rp2040Setup(), clearBonds(), enterDfuMode(); meshtastic_DeviceMetadata getDeviceMetadata(); diff --git a/src/mesh/generated/meshtastic/admin.pb.h b/src/mesh/generated/meshtastic/admin.pb.h index 198a076fd..48df9ba56 100644 --- a/src/mesh/generated/meshtastic/admin.pb.h +++ b/src/mesh/generated/meshtastic/admin.pb.h @@ -131,7 +131,7 @@ typedef struct _meshtastic_AdminMessage { bool get_node_remote_hardware_pins_request; /* Respond with the mesh's nodes with their available gpio pins for RemoteHardware module use */ meshtastic_NodeRemoteHardwarePinsResponse get_node_remote_hardware_pins_response; - /* Enter (serial) DFU mode + /* Enter (UF2) DFU mode Only implemented on NRF52 currently */ bool enter_dfu_mode_request; /* Set the owner for this node */ diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index b33877b8d..e2ec0c699 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -188,6 +188,13 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta reboot(DEFAULT_REBOOT_SECONDS); break; } + case meshtastic_AdminMessage_enter_dfu_mode_request_tag: { + LOG_INFO("Client is requesting to enter DFU mode.\n"); +#ifdef ARCH_NRF52 + enterDfuMode(); +#endif + break; + } #ifdef ARCH_PORTDUINO case meshtastic_AdminMessage_exit_simulator_tag: LOG_INFO("Exiting simulator\n"); diff --git a/src/platform/nrf52/main-nrf52.cpp b/src/platform/nrf52/main-nrf52.cpp index cab6a63b9..c1d3e93fb 100644 --- a/src/platform/nrf52/main-nrf52.cpp +++ b/src/platform/nrf52/main-nrf52.cpp @@ -1,4 +1,5 @@ #include "configuration.h" +#include #include #include #include @@ -214,4 +215,9 @@ void clearBonds() nrf52Bluetooth->setup(); } nrf52Bluetooth->clearBonds(); +} + +void enterDfuMode() +{ + enterUf2Dfu(); } \ No newline at end of file From 2e9cc73ebbc8daeefdd3d2342a79aef6a9051127 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Wed, 27 Dec 2023 18:40:54 -0600 Subject: [PATCH 090/472] [create-pull-request] automated change (#3046) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 9e5ea17c6..f1f958f5f 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 2 -build = 17 +build = 18 From 28951ea1e09303bf2fff338b3c5e7fbed0d16069 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Fri, 29 Dec 2023 12:35:42 -0600 Subject: [PATCH 091/472] Add libbluetooth-dev to build image --- .github/actions/setup-base/action.yml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/.github/actions/setup-base/action.yml b/.github/actions/setup-base/action.yml index 45930a94f..420ad8aca 100644 --- a/.github/actions/setup-base/action.yml +++ b/.github/actions/setup-base/action.yml @@ -16,6 +16,11 @@ runs: run: | sudo apt-get install -y cppcheck + - name: Install libbluetooth + shell: bash + run: | + sudo apt-get install -y libbluetooth-dev + - name: Setup Python uses: actions/setup-python@v4 with: From 1ae02a9a28d9c822c5a59948193c6e02b95eb3d0 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Fri, 29 Dec 2023 16:47:42 -0600 Subject: [PATCH 092/472] Add dependencies for native build --- .github/actions/setup-base/action.yml | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/.github/actions/setup-base/action.yml b/.github/actions/setup-base/action.yml index 420ad8aca..7b97e1753 100644 --- a/.github/actions/setup-base/action.yml +++ b/.github/actions/setup-base/action.yml @@ -20,6 +20,14 @@ runs: shell: bash run: | sudo apt-get install -y libbluetooth-dev + - name: Install libgpiod + shell: bash + run: | + sudo apt-get install -y libgpiod-dev + - name: Install libyaml-cpp + shell: bash + run: | + sudo apt-get install -y libyaml-cpp-dev - name: Setup Python uses: actions/setup-python@v4 From 4577646f8b964ccb5496ecb029c9109e7f097817 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Fri, 29 Dec 2023 17:49:25 -0600 Subject: [PATCH 093/472] Get rid of max-parallel build for rp2040 --- .github/workflows/main_matrix.yml | 1 - 1 file changed, 1 deletion(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 8b28090ca..bd7d5f1be 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -120,7 +120,6 @@ jobs: build-rpi2040: strategy: fail-fast: false - max-parallel: 2 matrix: include: - board: pico From 943367edd006669c179acd0e9b998602982854c7 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Wed, 3 Jan 2024 22:08:28 +0100 Subject: [PATCH 094/472] Fix "watch GPIOs" feature of Remote Hardware module (#3047) * Fix watch GPIO feature of Remote Hardware * Add Remote Hardware messages to JSON output * Add curly brackets --------- Co-authored-by: Ben Meadors --- src/modules/RemoteHardwareModule.cpp | 13 ++++++++----- src/mqtt/MQTT.cpp | 23 +++++++++++++++++++++++ 2 files changed, 31 insertions(+), 5 deletions(-) diff --git a/src/modules/RemoteHardwareModule.cpp b/src/modules/RemoteHardwareModule.cpp index 3d4d735b4..8e64b9a9c 100644 --- a/src/modules/RemoteHardwareModule.cpp +++ b/src/modules/RemoteHardwareModule.cpp @@ -56,7 +56,7 @@ bool RemoteHardwareModule::handleReceivedProtobuf(const meshtastic_MeshPacket &r LOG_INFO("Received RemoteHardware type=%d\n", p.type); switch (p.type) { - case meshtastic_HardwareMessage_Type_WRITE_GPIOS: + case meshtastic_HardwareMessage_Type_WRITE_GPIOS: { // Print notification to LCD screen screen->print("Write GPIOs\n"); @@ -69,6 +69,7 @@ bool RemoteHardwareModule::handleReceivedProtobuf(const meshtastic_MeshPacket &r pinModes(p.gpio_mask, OUTPUT); break; + } case meshtastic_HardwareMessage_Type_READ_GPIOS: { // Print notification to LCD screen @@ -92,8 +93,9 @@ bool RemoteHardwareModule::handleReceivedProtobuf(const meshtastic_MeshPacket &r watchGpios = p.gpio_mask; lastWatchMsec = 0; // Force a new publish soon previousWatch = - ~watchGpios; // generate a 'previous' value which is guaranteed to not match (to force an initial publish) - enabled = true; // Let our thread run at least once + ~watchGpios; // generate a 'previous' value which is guaranteed to not match (to force an initial publish) + enabled = true; // Let our thread run at least once + setInterval(2000); // Set a new interval so we'll run soon LOG_INFO("Now watching GPIOs 0x%llx\n", watchGpios); break; } @@ -118,6 +120,7 @@ int32_t RemoteHardwareModule::runOnce() if (now - lastWatchMsec >= WATCH_INTERVAL_MSEC) { uint64_t curVal = digitalReads(watchGpios); + lastWatchMsec = now; if (curVal != previousWatch) { previousWatch = curVal; @@ -136,5 +139,5 @@ int32_t RemoteHardwareModule::runOnce() return disable(); } - return 200; // Poll our GPIOs every 200ms (FIXME, make adjustable via protobuf arg) -} + return 2000; // Poll our GPIOs every 2000ms +} \ No newline at end of file diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index bc788ed37..ccde03147 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -10,6 +10,7 @@ #if defined(ARCH_ESP32) #include "../mesh/generated/meshtastic/paxcount.pb.h" #endif +#include "mesh/generated/meshtastic/remote_hardware.pb.h" #include "sleep.h" #if HAS_WIFI #include "mesh/wifi/WiFiAPClient.h" @@ -747,6 +748,28 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp) break; } #endif + case meshtastic_PortNum_REMOTE_HARDWARE_APP: { + meshtastic_HardwareMessage scratch; + meshtastic_HardwareMessage *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_HardwareMessage_msg, + &scratch)) { + decoded = &scratch; + if (decoded->type == meshtastic_HardwareMessage_Type_GPIOS_CHANGED) { + msgType = "gpios_changed"; + msgPayload["gpio_value"] = new JSONValue((uint)decoded->gpio_value); + jsonObj["payload"] = new JSONValue(msgPayload); + } else if (decoded->type == meshtastic_HardwareMessage_Type_READ_GPIOS_REPLY) { + msgType = "gpios_read_reply"; + msgPayload["gpio_value"] = new JSONValue((uint)decoded->gpio_value); + msgPayload["gpio_mask"] = new JSONValue((uint)decoded->gpio_mask); + jsonObj["payload"] = new JSONValue(msgPayload); + } + } else { + LOG_ERROR("Error decoding protobuf for RemoteHardware message!\n"); + } + break; + } // add more packet types here if needed default: break; From e3c768bf10b18746f98b46f2df7cac6efae8761b Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 4 Jan 2024 12:22:45 -0600 Subject: [PATCH 095/472] Update platformio.ini -- set target default to tbeam (#3054) --- platformio.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/platformio.ini b/platformio.ini index d7ad05337..b526a8fa2 100644 --- a/platformio.ini +++ b/platformio.ini @@ -2,7 +2,7 @@ ; https://docs.platformio.org/page/projectconf.html [platformio] -;default_envs = tbeam +default_envs = tbeam ;default_envs = pico ;default_envs = tbeam-s3-core ;default_envs = tbeam0.7 @@ -27,7 +27,7 @@ ;default_envs = m5stack-coreink ;default_envs = rak4631 ;default_envs = rak10701 -default_envs = wio-e5 +;default_envs = wio-e5 extra_configs = arch/*/*.ini From aa10a3ec40a854e07fd9560f6f844327058584ac Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 4 Jan 2024 18:54:44 -0600 Subject: [PATCH 096/472] [create-pull-request] automated change (#3055) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/config.pb.h | 10 +++++++--- 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/protobufs b/protobufs index 4a1d3766e..4a00cafd3 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 4a1d3766e888d3dd7d1acda817083295fb054c92 +Subproject commit 4a00cafd3e87368e7a113e37374e79ada3f0595a diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index 8406dc887..7e30dcfcd 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -201,7 +201,11 @@ typedef enum _meshtastic_Config_LoRaConfig_RegionCode { /* Ukraine 433mhz */ meshtastic_Config_LoRaConfig_RegionCode_UA_433 = 14, /* Ukraine 868mhz */ - meshtastic_Config_LoRaConfig_RegionCode_UA_868 = 15 + meshtastic_Config_LoRaConfig_RegionCode_UA_868 = 15, + /* Malaysia 433mhz */ + meshtastic_Config_LoRaConfig_RegionCode_MY_433 = 16, + /* Malaysia 919mhz */ + meshtastic_Config_LoRaConfig_RegionCode_MY_919 = 17 } meshtastic_Config_LoRaConfig_RegionCode; /* Standard predefined channel settings @@ -525,8 +529,8 @@ extern "C" { #define _meshtastic_Config_DisplayConfig_DisplayMode_ARRAYSIZE ((meshtastic_Config_DisplayConfig_DisplayMode)(meshtastic_Config_DisplayConfig_DisplayMode_COLOR+1)) #define _meshtastic_Config_LoRaConfig_RegionCode_MIN meshtastic_Config_LoRaConfig_RegionCode_UNSET -#define _meshtastic_Config_LoRaConfig_RegionCode_MAX meshtastic_Config_LoRaConfig_RegionCode_UA_868 -#define _meshtastic_Config_LoRaConfig_RegionCode_ARRAYSIZE ((meshtastic_Config_LoRaConfig_RegionCode)(meshtastic_Config_LoRaConfig_RegionCode_UA_868+1)) +#define _meshtastic_Config_LoRaConfig_RegionCode_MAX meshtastic_Config_LoRaConfig_RegionCode_MY_919 +#define _meshtastic_Config_LoRaConfig_RegionCode_ARRAYSIZE ((meshtastic_Config_LoRaConfig_RegionCode)(meshtastic_Config_LoRaConfig_RegionCode_MY_919+1)) #define _meshtastic_Config_LoRaConfig_ModemPreset_MIN meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST #define _meshtastic_Config_LoRaConfig_ModemPreset_MAX meshtastic_Config_LoRaConfig_ModemPreset_LONG_MODERATE From bacc525d0ac203430a8697a897d5b83b3382ff27 Mon Sep 17 00:00:00 2001 From: Amin Husni Date: Sat, 6 Jan 2024 05:37:31 +0800 Subject: [PATCH 097/472] Add Malaysia Region (#3053) * Add Malaysia Region Add frequency for 433MHz and 919MHz with specific power limit and limitation. * Update RadioInterface.cpp Formatting issues --- src/mesh/RadioInterface.cpp | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/src/mesh/RadioInterface.cpp b/src/mesh/RadioInterface.cpp index c6d5e8a78..91bd93bc5 100644 --- a/src/mesh/RadioInterface.cpp +++ b/src/mesh/RadioInterface.cpp @@ -107,10 +107,25 @@ const RegionInfo regions[] = { */ RDEF(UA_868, 868.0f, 868.6f, 1, 0, 14, true, false, false), + /* + Malaysia + 433 - 435 MHz at 100mW, no restrictions. + https://www.mcmc.gov.my/skmmgovmy/media/General/pdf/Short-Range-Devices-Specification.pdf + */ + RDEF(MY_433, 433.0f, 435.0f, 100, 0, 20, true, false, false), + + /* + Malaysia + 919 - 923 Mhz at 500mW, no restrictions. + 923 - 924 MHz at 500mW with 1% duty cycle OR frequency hopping. + Frequency hopping is used for 919 - 923 MHz. + https://www.mcmc.gov.my/skmmgovmy/media/General/pdf/Short-Range-Devices-Specification.pdf + */ + RDEF(MY_919, 919.0f, 924.0f, 100, 0, 27, true, true, false), + /* 2.4 GHZ WLAN Band equivalent. Only for SX128x chips. */ - RDEF(LORA_24, 2400.0f, 2483.5f, 100, 0, 10, true, false, true), /* From 674fd32349d027320a1baecbbd8f16ffe2260963 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sat, 6 Jan 2024 14:39:27 -0600 Subject: [PATCH 098/472] RP2040 Enter uf2 DFU mode (#3062) * Pico enter dfu mode * Ungaurd pico --- src/modules/AdminModule.cpp | 2 +- src/platform/rp2040/main-rp2040.cpp | 5 +++++ 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index e2ec0c699..38799d58d 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -190,7 +190,7 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta } case meshtastic_AdminMessage_enter_dfu_mode_request_tag: { LOG_INFO("Client is requesting to enter DFU mode.\n"); -#ifdef ARCH_NRF52 +#if defined(ARCH_NRF52) || defined(ARCH_RP2040) enterDfuMode(); #endif break; diff --git a/src/platform/rp2040/main-rp2040.cpp b/src/platform/rp2040/main-rp2040.cpp index 1d7f8fe70..3359263e9 100644 --- a/src/platform/rp2040/main-rp2040.cpp +++ b/src/platform/rp2040/main-rp2040.cpp @@ -35,4 +35,9 @@ void rp2040Setup() Taken from CPU cycle counter and ROSC oscillator, so should be pretty random. */ randomSeed(rp2040.hwrand32()); +} + +void enterDfuMode() +{ + reset_usb_boot(0, 0); } \ No newline at end of file From be46f9ea24d8b58a8e778f96cc202e7c62f16eb8 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sat, 6 Jan 2024 15:23:40 -0600 Subject: [PATCH 099/472] [create-pull-request] automated change (#3063) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/config.pb.h | 5 +---- 2 files changed, 2 insertions(+), 5 deletions(-) diff --git a/protobufs b/protobufs index 4a00cafd3..2ccf73428 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 4a00cafd3e87368e7a113e37374e79ada3f0595a +Subproject commit 2ccf73428da8dac87aca12a1f91ac5cd76a7442c diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index 7e30dcfcd..c86da50f9 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -285,10 +285,7 @@ typedef struct _meshtastic_Config_PositionConfig { or zero for the default of once every 30 seconds or a very large value (maxint) to update only once at boot. */ uint32_t gps_update_interval; - /* How long should we try to get our position during each gps_update_interval attempt? (in seconds) - Or if zero, use the default of 30 seconds. - If we don't get a new gps fix in that time, the gps will be put into sleep until the next gps_update_rate - window. */ + /* Deprecated in favor of using smart / regular broadcast intervals as implicit attempt time */ uint32_t gps_attempt_time; /* Bit field of boolean configuration options for POSITION messages (bitwise OR of PositionFlags) */ From 59253d9c78d84575d015ec38af79b02423484d4e Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 7 Jan 2024 07:37:13 -0600 Subject: [PATCH 100/472] Don't reboot after removing node from DB (#3065) --- src/modules/AdminModule.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index 38799d58d..0b1e72f9a 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -185,7 +185,6 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta case meshtastic_AdminMessage_remove_by_nodenum_tag: { LOG_INFO("Client is receiving a remove_nodenum command.\n"); nodeDB.removeNodeByNum(r->remove_by_nodenum); - reboot(DEFAULT_REBOOT_SECONDS); break; } case meshtastic_AdminMessage_enter_dfu_mode_request_tag: { From c2afa879b879371d7f19d5b4c088f4ba66ab8ecd Mon Sep 17 00:00:00 2001 From: Mictronics Date: Sun, 7 Jan 2024 14:40:12 +0100 Subject: [PATCH 101/472] Fix LED pinout for T-Echo board marked v1.0, date 2021-6-28 (#3051) Co-authored-by: Ben Meadors --- variants/t-echo/variant.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/variants/t-echo/variant.h b/variants/t-echo/variant.h index 6bd5091dd..8679dbde9 100644 --- a/variants/t-echo/variant.h +++ b/variants/t-echo/variant.h @@ -43,9 +43,9 @@ extern "C" { #define NUM_ANALOG_OUTPUTS (0) // LEDs -#define PIN_LED1 (0 + 14) // 13 red (confirmed on 1.0 board) -#define PIN_LED2 (0 + 15) // 14 blue -#define PIN_LED3 (0 + 13) // 15 green +#define PIN_LED1 (0 + 14) // blue (confirmed on boards marked v1.0, date 2021-6-28) +#define PIN_LED2 (32 + 1) // green +#define PIN_LED3 (32 + 3) // red #define LED_RED PIN_LED3 #define LED_BLUE PIN_LED1 @@ -232,4 +232,4 @@ External serial flash WP25R1635FZUIL0 * Arduino objects - C++ only *----------------------------------------------------------------------------*/ -#endif +#endif \ No newline at end of file From ea651c2f8fa421ad64809eb9d66b6a466471d643 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 7 Jan 2024 09:35:19 -0600 Subject: [PATCH 102/472] Remove gps_attempt_time and use broadcast interval instead (#3064) --- src/gps/GPS.cpp | 5 +++-- src/gps/GPS.h | 2 +- src/mesh/NodeDB.cpp | 3 --- src/mesh/NodeDB.h | 4 ---- 4 files changed, 4 insertions(+), 10 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 60eeeb3bb..fee9393b0 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -596,11 +596,12 @@ void GPS::setAwake(bool on) */ uint32_t GPS::getWakeTime() const { - uint32_t t = config.position.gps_attempt_time; + uint32_t t = config.position.position_broadcast_secs; if (t == UINT32_MAX) return t; // already maxint - return t * 1000; + + return getConfiguredOrDefaultMs(t, default_broadcast_interval_secs); } /** Get how long we should sleep between aqusition attempts in msecs diff --git a/src/gps/GPS.h b/src/gps/GPS.h index 4cbdae06b..d05bad950 100644 --- a/src/gps/GPS.h +++ b/src/gps/GPS.h @@ -70,7 +70,7 @@ class GPS : private concurrency::OSThread /** * hasValidLocation - indicates that the position variables contain a complete - * GPS location, valid and fresh (< gps_update_interval + gps_attempt_time) + * GPS location, valid and fresh (< gps_update_interval + position_broadcast_secs) */ bool hasValidLocation = false; // default to false, until we complete our first read diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 6f1ba5583..4de79de0b 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -223,7 +223,6 @@ void NodeDB::installDefaultConfig() void NodeDB::initConfigIntervals() { config.position.gps_update_interval = default_gps_update_interval; - config.position.gps_attempt_time = default_gps_attempt_time; config.position.position_broadcast_secs = default_broadcast_interval_secs; config.power.ls_secs = default_ls_secs; @@ -301,8 +300,6 @@ void NodeDB::installRoleDefaults(meshtastic_Config_DeviceConfig_Role role) initModuleConfigIntervals(); } else if (role == meshtastic_Config_DeviceConfig_Role_REPEATER) { config.display.screen_on_secs = 1; - } else if (role == meshtastic_Config_DeviceConfig_Role_TRACKER) { - config.position.gps_update_interval = 30; } else if (role == meshtastic_Config_DeviceConfig_Role_SENSOR) { moduleConfig.telemetry.environment_measurement_enabled = true; moduleConfig.telemetry.environment_update_interval = 300; diff --git a/src/mesh/NodeDB.h b/src/mesh/NodeDB.h index 5e4dc4885..47d143cd9 100644 --- a/src/mesh/NodeDB.h +++ b/src/mesh/NodeDB.h @@ -179,9 +179,6 @@ extern NodeDB nodeDB; prefs.gps_update_interval = oneday prefs.is_power_saving = True - - # allow up to five minutes for each new GPS lock attempt - prefs.gps_attempt_time = 300 */ // Our delay functions check for this for times that should never expire @@ -192,7 +189,6 @@ extern NodeDB nodeDB; #define ONE_DAY 24 * 60 * 60 -#define default_gps_attempt_time IF_ROUTER(5 * 60, 15 * 60) #define default_gps_update_interval IF_ROUTER(ONE_DAY, 2 * 60) #define default_broadcast_interval_secs IF_ROUTER(ONE_DAY / 2, 15 * 60) #define default_wait_bluetooth_secs IF_ROUTER(1, 60) From 613a2bfb70701ff22bd6a3ac73dec21de9bb020f Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Wed, 10 Jan 2024 02:45:03 +0100 Subject: [PATCH 103/472] Update exception decoder for other platforms (#3070) --- bin/exception_decoder.py | 145 +++++++++++++++++++++++++++------------ 1 file changed, 103 insertions(+), 42 deletions(-) diff --git a/bin/exception_decoder.py b/bin/exception_decoder.py index 8ef66b9bb..ec94ce20e 100755 --- a/bin/exception_decoder.py +++ b/bin/exception_decoder.py @@ -11,19 +11,22 @@ Meshtastic notes: * version that's checked into meshtastic repo is based on: https://github.com/me21/EspArduinoExceptionDecoder which adds in ESP32 Backtrace decoding. * this also updates the defaults to use ESP32, instead of ESP8266 and defaults to the built firmware.bin +* also updated the toolchain name, which will be set according to the platform To use, copy the "Backtrace: 0x...." line to a file, e.g., backtrace.txt, then run: $ bin/exception_decoder.py backtrace.txt +For a platform other than ESP32, use the -p option, e.g.: +$ bin/exception_decoder.py -p ESP32S3 backtrace.txt +To specify a specific .elf file, use the -e option, e.g.: +$ bin/exception_decoder.py -e firmware.elf backtrace.txt """ import argparse +import os import re import subprocess -from collections import namedtuple - import sys - -import os +from collections import namedtuple EXCEPTIONS = [ "Illegal instruction", @@ -55,24 +58,39 @@ EXCEPTIONS = [ "LoadStorePrivilege: A load or store referenced a virtual address at a ring level less than CRING", "reserved", "LoadProhibited: A load referenced a page mapped with an attribute that does not permit loads", - "StoreProhibited: A store referenced a page mapped with an attribute that does not permit stores" + "StoreProhibited: A store referenced a page mapped with an attribute that does not permit stores", ] PLATFORMS = { - "ESP8266": "lx106", - "ESP32": "esp32" + "ESP8266": "xtensa-lx106", + "ESP32": "xtensa-esp32", + "ESP32S3": "xtensa-esp32s3", + "ESP32C3": "riscv32-esp", +} +TOOLS = { + "ESP8266": "xtensa", + "ESP32": "xtensa-esp32", + "ESP32S3": "xtensa-esp32s3", + "ESP32C3": "riscv32-esp", } -BACKTRACE_REGEX = re.compile(r"(?:\s+(0x40[0-2](?:\d|[a-f]|[A-F]){5}):0x(?:\d|[a-f]|[A-F]){8})\b") +BACKTRACE_REGEX = re.compile( + r"(?:\s+(0x40[0-2](?:\d|[a-f]|[A-F]){5}):0x(?:\d|[a-f]|[A-F]){8})\b" +) EXCEPTION_REGEX = re.compile("^Exception \\((?P[0-9]*)\\):$") -COUNTER_REGEX = re.compile('^epc1=(?P0x[0-9a-f]+) epc2=(?P0x[0-9a-f]+) epc3=(?P0x[0-9a-f]+) ' - 'excvaddr=(?P0x[0-9a-f]+) depc=(?P0x[0-9a-f]+)$') +COUNTER_REGEX = re.compile( + "^epc1=(?P0x[0-9a-f]+) epc2=(?P0x[0-9a-f]+) epc3=(?P0x[0-9a-f]+) " + "excvaddr=(?P0x[0-9a-f]+) depc=(?P0x[0-9a-f]+)$" +) CTX_REGEX = re.compile("^ctx: (?P.+)$") -POINTER_REGEX = re.compile('^sp: (?P[0-9a-f]+) end: (?P[0-9a-f]+) offset: (?P[0-9a-f]+)$') -STACK_BEGIN = '>>>stack>>>' -STACK_END = '<<[0-9a-f]+) end: (?P[0-9a-f]+) offset: (?P[0-9a-f]+)$" +) +STACK_BEGIN = ">>>stack>>>" +STACK_END = "<<[0-9a-f]+):\W+(?P[0-9a-f]+) (?P[0-9a-f]+) (?P[0-9a-f]+) (?P[0-9a-f]+)(\W.*)?$') + "^(?P[0-9a-f]+):\W+(?P[0-9a-f]+) (?P[0-9a-f]+) (?P[0-9a-f]+) (?P[0-9a-f]+)(\W.*)?$" +) StackLine = namedtuple("StackLine", ["offset", "content"]) @@ -96,15 +114,18 @@ class ExceptionDataParser(object): self.stack = [] def _parse_backtrace(self, line): - if line.startswith('Backtrace:'): - self.stack = [StackLine(offset=0, content=(addr,)) for addr in BACKTRACE_REGEX.findall(line)] + if line.startswith("Backtrace:"): + self.stack = [ + StackLine(offset=0, content=(addr,)) + for addr in BACKTRACE_REGEX.findall(line) + ] return None return self._parse_backtrace def _parse_exception(self, line): match = EXCEPTION_REGEX.match(line) if match is not None: - self.exception = int(match.group('exc')) + self.exception = int(match.group("exc")) return self._parse_counters return self._parse_exception @@ -144,14 +165,22 @@ class ExceptionDataParser(object): if line != STACK_END: match = STACK_REGEX.match(line) if match is not None: - self.stack.append(StackLine(offset=match.group("off"), - content=(match.group("c1"), match.group("c2"), match.group("c3"), - match.group("c4")))) + self.stack.append( + StackLine( + offset=match.group("off"), + content=( + match.group("c1"), + match.group("c2"), + match.group("c3"), + match.group("c4"), + ), + ) + ) return self._parse_stack_line return None def parse_file(self, file, platform, stack_only=False): - if platform == 'ESP32': + if platform != "ESP8266": func = self._parse_backtrace else: func = self._parse_exception @@ -175,7 +204,9 @@ class AddressResolver(object): self._address_map = {} def _lookup(self, addresses): - cmd = [self._tool, "-aipfC", "-e", self._elf] + [addr for addr in addresses if addr is not None] + cmd = [self._tool, "-aipfC", "-e", self._elf] + [ + addr for addr in addresses if addr is not None + ] if sys.version_info[0] < 3: output = subprocess.check_output(cmd) @@ -190,19 +221,27 @@ class AddressResolver(object): match = line_regex.match(line) if match is None: - if last is not None and line.startswith('(inlined by)'): - line = line [12:].strip() - self._address_map[last] += ("\n \-> inlined by: " + line) + if last is not None and line.startswith("(inlined by)"): + line = line[12:].strip() + self._address_map[last] += "\n \-> inlined by: " + line continue - if match.group("result") == '?? ??:0': + if match.group("result") == "?? ??:0": continue self._address_map[match.group("addr")] = match.group("result") last = match.group("addr") def fill(self, parser): - addresses = [parser.epc1, parser.epc2, parser.epc3, parser.excvaddr, parser.sp, parser.end, parser.offset] + addresses = [ + parser.epc1, + parser.epc2, + parser.epc3, + parser.excvaddr, + parser.sp, + parser.end, + parser.offset, + ] for line in parser.stack: addresses.extend(line.content) @@ -257,8 +296,10 @@ def print_stack(lines, resolver): def print_result(parser, resolver, platform, full=True, stack_only=False): - if platform == 'ESP8266' and not stack_only: - print('Exception: {} ({})'.format(parser.exception, EXCEPTIONS[parser.exception])) + if platform == "ESP8266" and not stack_only: + print( + "Exception: {} ({})".format(parser.exception, EXCEPTIONS[parser.exception]) + ) print("") print_addr("epc1", parser.epc1, resolver) @@ -285,15 +326,33 @@ def print_result(parser, resolver, platform, full=True, stack_only=False): def parse_args(): parser = argparse.ArgumentParser(description="decode ESP Stacktraces.") - parser.add_argument("-p", "--platform", help="The platform to decode from", choices=PLATFORMS.keys(), - default="ESP32") - parser.add_argument("-t", "--tool", help="Path to the xtensa toolchain", - default="~/.platformio/packages/toolchain-xtensa32/") - parser.add_argument("-e", "--elf", help="path to elf file", - default=".pio/build/esp32/firmware.elf") - parser.add_argument("-f", "--full", help="Print full stack dump", action="store_true") - parser.add_argument("-s", "--stack_only", help="Decode only a stractrace", action="store_true") - parser.add_argument("file", help="The file to read the exception data from ('-' for STDIN)", default="-") + parser.add_argument( + "-p", + "--platform", + help="The platform to decode from", + choices=PLATFORMS.keys(), + default="ESP32", + ) + parser.add_argument( + "-t", + "--tool", + help="Path to the toolchain (without specific platform)", + default="~/.platformio/packages/toolchain-", + ) + parser.add_argument( + "-e", "--elf", help="path to elf file", default=".pio/build/tbeam/firmware.elf" + ) + parser.add_argument( + "-f", "--full", help="Print full stack dump", action="store_true" + ) + parser.add_argument( + "-s", "--stack_only", help="Decode only a stractrace", action="store_true" + ) + parser.add_argument( + "file", + help="The file to read the exception data from ('-' for STDIN)", + default="-", + ) return parser.parse_args() @@ -309,10 +368,12 @@ if __name__ == "__main__": sys.exit(1) file = open(args.file, "r") - addr2line = os.path.join(os.path.abspath(os.path.expanduser(args.tool)), - "bin/xtensa-" + PLATFORMS[args.platform] + "-elf-addr2line") - if os.name == 'nt': - addr2line += '.exe' + addr2line = os.path.join( + os.path.abspath(os.path.expanduser(args.tool + TOOLS[args.platform])), + "bin/" + PLATFORMS[args.platform] + "-elf-addr2line", + ) + if os.name == "nt": + addr2line += ".exe" if not os.path.exists(addr2line): print("ERROR: addr2line not found (" + addr2line + ")") From 77ff1704db0413e8f8b0b6d7614ecb71d55d0338 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Wed, 10 Jan 2024 02:45:54 +0100 Subject: [PATCH 104/472] Allow button press if CannedMessage `updown1` or `rotary1` are not enabled (#3067) `BUTTON_PIN` may be 0, which is equal to `inputbroker_pin_press` by default --- src/ButtonThread.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/ButtonThread.h b/src/ButtonThread.h index 5f68aa5b6..7138d3b6a 100644 --- a/src/ButtonThread.h +++ b/src/ButtonThread.h @@ -138,6 +138,7 @@ class ButtonThread : public concurrency::OSThread #ifdef BUTTON_PIN if (((config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN) != moduleConfig.canned_message.inputbroker_pin_press) || + !(moduleConfig.canned_message.updown1_enabled || moduleConfig.canned_message.rotary1_enabled) || !moduleConfig.canned_message.enabled) { powerFSM.trigger(EVENT_PRESS); } @@ -232,4 +233,4 @@ class ButtonThread : public concurrency::OSThread } }; -} // namespace concurrency +} // namespace concurrency \ No newline at end of file From 0d85069bec3352262cf34fad0fddd7d75ff76ab0 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Tue, 9 Jan 2024 19:48:21 -0600 Subject: [PATCH 105/472] Heltec paper (#3069) * Attempts at getting the Heltec Wireless Paper eink operational * Bogus comment * Fixing Support For Heltec Wireless Paper --------- Co-authored-by: NfN Orange --- src/graphics/EInkDisplay2.cpp | 27 ++++--- variants/heltec_wireless_paper/pins_arduino.h | 78 +++++++++++++++++++ variants/heltec_wireless_paper/platformio.ini | 5 +- variants/heltec_wireless_paper/variant.h | 11 ++- 4 files changed, 107 insertions(+), 14 deletions(-) create mode 100644 variants/heltec_wireless_paper/pins_arduino.h diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index 3b97dd723..eb716ac03 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -7,9 +7,9 @@ #include "main.h" #include -// #ifdef HELTEC_WIRELESS_PAPER -// SPIClass *hspi = NULL; -// #endif +#ifdef HELTEC_WIRELESS_PAPER +SPIClass *hspi = NULL; +#endif #define COLORED GxEPD_BLACK #define UNCOLORED GxEPD_WHITE @@ -47,7 +47,7 @@ #elif defined(HELTEC_WIRELESS_PAPER) // #define TECHO_DISPLAY_MODEL GxEPD2_213_T5D -#define TECHO_DISPLAY_MODEL GxEPD2_213_BN +#define TECHO_DISPLAY_MODEL GxEPD2_213_FC1 #endif GxEPD2_BW *adafruitDisplay; @@ -71,7 +71,7 @@ EInkDisplay::EInkDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY // setGeometry(GEOMETRY_RAWMODE, 200, 200); #elif defined(HELTEC_WIRELESS_PAPER) - // setGeometry(GEOMETRY_RAWMODE, 212, 104); + // GxEPD2_213_BN - 2.13 inch b/w 250x122 setGeometry(GEOMETRY_RAWMODE, 250, 122); #elif defined(MAKERPYTHON) // GxEPD2_290_T5D @@ -119,7 +119,6 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit) // tft.drawBitmap(0, 0, buffer, 128, 64, TFT_YELLOW, TFT_BLACK); for (uint32_t y = 0; y < displayHeight; y++) { for (uint32_t x = 0; x < displayWidth; x++) { - // get src pixel in the page based ordering the OLED lib uses FIXME, super inefficient auto b = buffer[x + (y / 8) * displayWidth]; auto isset = b & (1 << (y & 7)); @@ -148,7 +147,8 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit) #elif defined(PCA10059) || defined(M5_COREINK) adafruitDisplay->nextPage(); - +#elif defined(HELTEC_WIRELESS_PAPER) + adafruitDisplay->nextPage(); #elif defined(PRIVATE_HW) || defined(my) adafruitDisplay->nextPage(); @@ -231,13 +231,16 @@ bool EInkDisplay::connect() } #elif defined(HELTEC_WIRELESS_PAPER) { - auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); + hspi = new SPIClass(HSPI); + hspi->begin(PIN_EINK_SCLK, -1, PIN_EINK_MOSI, PIN_EINK_CS); // SCLK, MISO, MOSI, SS + delay(100); + pinMode(Vext, OUTPUT); + digitalWrite(Vext, LOW); + delay(100); + auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY, *hspi); adafruitDisplay = new GxEPD2_BW(*lowLevel); - // hspi = new SPIClass(HSPI); - // hspi->begin(PIN_EINK_SCLK, -1, PIN_EINK_MOSI, PIN_EINK_CS); // SCLK, MISO, MOSI, SS - adafruitDisplay->init(115200, true, 10, false, SPI, SPISettings(6000000, MSBFIRST, SPI_MODE0)); + adafruitDisplay->init(); adafruitDisplay->setRotation(3); - adafruitDisplay->setPartialWindow(0, 0, displayWidth, displayHeight); } #elif defined(PCA10059) { diff --git a/variants/heltec_wireless_paper/pins_arduino.h b/variants/heltec_wireless_paper/pins_arduino.h new file mode 100644 index 000000000..66d091691 --- /dev/null +++ b/variants/heltec_wireless_paper/pins_arduino.h @@ -0,0 +1,78 @@ +#ifndef Pins_Arduino_h +#define Pins_Arduino_h + +#include + +#define WIFI_Kit_32 true +#define DISPLAY_HEIGHT 64 +#define DISPLAY_WIDTH 128 + +#define EXTERNAL_NUM_INTERRUPTS 16 +#define NUM_DIGITAL_PINS 40 +#define NUM_ANALOG_INPUTS 16 + +#define analogInputToDigitalPin(p) (((p) < 20) ? (analogChannelToDigitalPin(p)) : -1) +#define digitalPinToInterrupt(p) (((p) < 40) ? (p) : -1) +#define digitalPinHasPWM(p) (p < 34) + +static const uint8_t LED_BUILTIN = 35; +#define BUILTIN_LED LED_BUILTIN // backward compatibility +#define LED_BUILTIN LED_BUILTIN + +static const uint8_t KEY_BUILTIN = 0; + +static const uint8_t TX = 43; +static const uint8_t RX = 44; + +static const uint8_t SDA = 41; +static const uint8_t SCL = 42; + +static const uint8_t SS = 8; +static const uint8_t MOSI = 10; +static const uint8_t MISO = 11; +static const uint8_t SCK = 9; + +static const uint8_t A0 = 1; +static const uint8_t A1 = 2; +static const uint8_t A2 = 3; +static const uint8_t A3 = 4; +static const uint8_t A4 = 5; +static const uint8_t A5 = 6; +static const uint8_t A6 = 7; +static const uint8_t A7 = 8; +static const uint8_t A8 = 9; +static const uint8_t A9 = 10; +static const uint8_t A10 = 11; +static const uint8_t A11 = 12; +static const uint8_t A12 = 13; +static const uint8_t A13 = 14; +static const uint8_t A14 = 15; +static const uint8_t A15 = 16; +static const uint8_t A16 = 17; +static const uint8_t A17 = 18; +static const uint8_t A18 = 19; +static const uint8_t A19 = 20; + +static const uint8_t T1 = 1; +static const uint8_t T2 = 2; +static const uint8_t T3 = 3; +static const uint8_t T4 = 4; +static const uint8_t T5 = 5; +static const uint8_t T6 = 6; +static const uint8_t T7 = 7; +static const uint8_t T8 = 8; +static const uint8_t T9 = 9; +static const uint8_t T10 = 10; +static const uint8_t T11 = 11; +static const uint8_t T12 = 12; +static const uint8_t T13 = 13; +static const uint8_t T14 = 14; + +static const uint8_t Vext = 45; +static const uint8_t LED = 18; + +static const uint8_t RST_LoRa = 12; +static const uint8_t BUSY_LoRa = 13; +static const uint8_t DIO0 = 14; + +#endif /* Pins_Arduino_h */ diff --git a/variants/heltec_wireless_paper/platformio.ini b/variants/heltec_wireless_paper/platformio.ini index 0bc7f14d1..dd93b52cb 100644 --- a/variants/heltec_wireless_paper/platformio.ini +++ b/variants/heltec_wireless_paper/platformio.ini @@ -5,4 +5,7 @@ build_flags = ${esp32s3_base.build_flags} -D HELTEC_WIRELESS_PAPER -I variants/heltec_wireless_paper lib_deps = ${esp32s3_base.lib_deps} - zinggjm/GxEPD2@^1.5.2 + https://github.com/ixt/GxEPD2#39f325b677713eb04dfcc83b8e402e77523fb8bf + adafruit/Adafruit BusIO@^1.13.2 + lewisxhe/PCF8563_Library@^1.0.1 +upload_speed = 115200 \ No newline at end of file diff --git a/variants/heltec_wireless_paper/variant.h b/variants/heltec_wireless_paper/variant.h index 88c5faaa1..4daf9a655 100644 --- a/variants/heltec_wireless_paper/variant.h +++ b/variants/heltec_wireless_paper/variant.h @@ -15,7 +15,16 @@ #define PIN_EINK_SCLK 3 #define PIN_EINK_MOSI 2 -#define VEXT_ENABLE Vext // active low, powers the oled display and the lora antenna boost +/* + * SPI interfaces + */ +#define SPI_INTERFACES_COUNT 2 + +#define PIN_SPI_MISO 10 // MISO P0.17 +#define PIN_SPI_MOSI 11 // MOSI P0.15 +#define PIN_SPI_SCK 9 // SCK P0.13 + +#define VEXT_ENABLE 45 // active low, powers the oled display and the lora antenna boost #define BUTTON_PIN 0 #define BATTERY_PIN 1 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage From ccb5485510efc03ed2a129e0b6ff8d514489d3f3 Mon Sep 17 00:00:00 2001 From: Mark Trevor Birss Date: Thu, 11 Jan 2024 18:06:02 +0200 Subject: [PATCH 106/472] Add SX1262 to M5Stack CoreInk (#3078) * Update platformio.ini * Update variant.h * Update variant.h * Update variant.h * Update variant.h * Update variant.h * Update variant.h * Update variant.h * Update variant.h --- variants/m5stack_coreink/platformio.ini | 4 ++-- variants/m5stack_coreink/variant.h | 27 +++++++++++++++++++------ 2 files changed, 23 insertions(+), 8 deletions(-) diff --git a/variants/m5stack_coreink/platformio.ini b/variants/m5stack_coreink/platformio.ini index e6aef380c..ee6d340dc 100644 --- a/variants/m5stack_coreink/platformio.ini +++ b/variants/m5stack_coreink/platformio.ini @@ -16,11 +16,11 @@ build_flags = -DM5STACK lib_deps = ${esp32_base.lib_deps} - zinggjm/GxEPD2@^1.4.9 + zinggjm/GxEPD2@^1.5.3 lewisxhe/PCF8563_Library@^1.0.1 lib_ignore = m5stack-coreink monitor_filters = esp32_exception_decoder board_build.f_cpu = 240000000L upload_protocol = esptool -;upload_port = /dev/ttyACM0 +upload_port = /dev/ttyACM0 diff --git a/variants/m5stack_coreink/variant.h b/variants/m5stack_coreink/variant.h index 0fc56477c..f19da2696 100644 --- a/variants/m5stack_coreink/variant.h +++ b/variants/m5stack_coreink/variant.h @@ -2,16 +2,12 @@ #define I2C_SDA 21 #define I2C_SCL 22 -// 7-07-2023 Or enable Secondary I2C Bus -// #define I2C_SDA1 32 -// #define I2C_SCL1 33 - #define HAS_GPS 1 #undef GPS_RX_PIN #undef GPS_TX_PIN // Use Secondary I2C Bus as GPS Serial #define GPS_RX_PIN 33 -#define GPS_TX_PIN 32 +// #define GPS_TX_PIN 32 (now used by SX1262 BUSY as GPS works with just RX) // Green LED #define LED_INVERTED 0 @@ -38,7 +34,9 @@ #undef LORA_MISO #undef LORA_MOSI #undef LORA_CS + #define USE_RF95 +// #define USE_SX1262 // #define USE_SX1280 #ifdef USE_RF95 @@ -52,6 +50,23 @@ #define LORA_DIO2 RADIOLIB_NC #endif +// https://www.waveshare.com/core1262-868m.htm +#ifdef USE_SX1262 +#define LORA_SCK 18 +#define LORA_MISO 34 +#define LORA_MOSI 23 +#define LORA_CS 14 +#define LORA_RESET 26 +#define LORA_DIO1 25 +#define LORA_DIO2 32 // 33 // (13 not working) //BUSY pin on SX1262 +#define SX126X_CS LORA_CS +#define SX126X_DIO1 LORA_DIO1 +#define SX126X_BUSY LORA_DIO2 +#define SX126X_RESET LORA_RESET +#define SX126X_DIO2_AS_RF_SWITCH +#define SX126X_DIO3_TCXO_VOLTAGE 1.8 +#endif + #ifdef USE_SX1280 #define LORA_SCK 18 #define LORA_MISO 34 @@ -90,5 +105,5 @@ // | // GND // https://github.com/m5stack/M5Core-Ink/blob/master/examples/Basics/FactoryTest/FactoryTest.ino#L58 -#define ADC_MULTIPLIER 5 // Just a guess for now... more detailed getBatVoltage above +#define ADC_MULTIPLIER 5 // https://embeddedexplorer.com/esp32-adc-esp-idf-tutorial/ From e9bde80b5736101f2329cdab828b625f6992d7cc Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 11 Jan 2024 10:06:26 -0600 Subject: [PATCH 107/472] change tft clear() to fillScreen() (#3077) Maintains compatability with ESPI driver. Co-authored-by: Jonathan Bennett --- src/graphics/TFTDisplay.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/graphics/TFTDisplay.cpp b/src/graphics/TFTDisplay.cpp index fe98882b4..df1aefb3d 100644 --- a/src/graphics/TFTDisplay.cpp +++ b/src/graphics/TFTDisplay.cpp @@ -425,7 +425,8 @@ TFTDisplay::TFTDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY g void TFTDisplay::display(bool fromBlank) { if (fromBlank) - tft->clear(); + tft->fillScreen(TFT_BLACK); + // tft->clear(); concurrency::LockGuard g(spiLock); uint16_t x, y; From 3e21e05a2c93c2a74ba955b0484fb52adbaed805 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 11 Jan 2024 11:52:01 -0600 Subject: [PATCH 108/472] [create-pull-request] automated change (#3079) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index f1f958f5f..59d4670c7 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 2 -build = 18 +build = 19 From 7e53a96ee57ce84f650f5e265e1cf5105061ec60 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 11 Jan 2024 12:44:46 -0600 Subject: [PATCH 109/472] [create-pull-request] automated change (#3082) Co-authored-by: thebentern --- protobufs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/protobufs b/protobufs index 2ccf73428..1091250d2 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 2ccf73428da8dac87aca12a1f91ac5cd76a7442c +Subproject commit 1091250d256d415df2a1b2644b4d282eab6570f4 From 4a867c81c05583a5f36259d60d38309eb8e936fe Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Fri, 12 Jan 2024 02:00:31 -0600 Subject: [PATCH 110/472] Portduino work (#3049) * Move to Portduino's getMacAddr() * Add ST7735/S screen support * Push Raspbian support into native target * Remove latent pigpio references. * CardKB defensive programming * Adds configurable spidev * Fixes to build on Fedora 40 * ENUMs are not #defines. Pull latest portduino * Add more configuration options for SPI displays * Add config.yaml option to set DIO3_TCXO_VOLTAGE * change tft clear() to fillScreen() Maintains compatability with ESPI driver. * Adds TXen and RXen pins to portduino * Add -c --config options to specify config file * Fail when a specified config file is unavailable --------- Co-authored-by: Ben Meadors --- arch/portduino/portduino.ini | 8 +- bin/config-dist.yaml | 27 ++++ src/ButtonThread.h | 12 +- src/RedirectablePrint.cpp | 4 +- src/detect/ScanI2CTwoWire.cpp | 2 +- src/gps/GPS.cpp | 6 +- src/graphics/Screen.cpp | 20 +-- src/graphics/TFTDisplay.cpp | 35 +++--- src/graphics/images.h | 2 +- src/input/LinuxInput.cpp | 5 +- src/input/LinuxInput.h | 2 +- src/input/LinuxInputImpl.cpp | 5 +- src/input/LinuxInputImpl.h | 2 +- src/input/TouchScreenImpl1.cpp | 4 +- src/input/kbI2cBase.cpp | 10 +- src/main.cpp | 48 +++---- src/main.h | 1 - src/mesh/NodeDB.cpp | 9 +- src/mesh/RF95Interface.cpp | 24 +++- src/mesh/SX126xInterface.cpp | 27 ++-- src/mesh/SX128xInterface.cpp | 52 +++++++- src/meshUtils.h | 1 + src/modules/CannedMessageModule.cpp | 2 +- src/modules/Modules.cpp | 8 +- src/platform/portduino/PortduinoGlue.cpp | 151 +++++++++-------------- src/platform/portduino/PortduinoGlue.h | 14 ++- src/platform/portduino/architecture.h | 2 +- src/shutdown.h | 11 +- variants/portduino/platformio.ini | 3 +- variants/portduino/variant.h | 32 +---- 30 files changed, 279 insertions(+), 250 deletions(-) diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index 98bb309b9..ac7ba13ba 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -1,6 +1,6 @@ ; The Portduino based sim environment on top of any host OS, all hardware will be simulated [portduino_base] -platform = https://github.com/meshtastic/platform-native.git#8a66ef82cf38a4135d85cbb5043d0e8ebbb8ba17 +platform = https://github.com/meshtastic/platform-native.git#04435d06e39916a6c019d511518d8e95c659dfbd framework = arduino build_src_filter = @@ -28,4 +28,8 @@ build_flags = ${arduino_base.build_flags} -fPIC -Isrc/platform/portduino - -DRADIOLIB_EEPROM_UNSUPPORTED \ No newline at end of file + -DRADIOLIB_EEPROM_UNSUPPORTED + -DPORTDUINO_LINUX_HARDWARE + -lbluetooth + -lgpiod + -lyaml-cpp \ No newline at end of file diff --git a/bin/config-dist.yaml b/bin/config-dist.yaml index 4079e7676..99a08ad87 100644 --- a/bin/config-dist.yaml +++ b/bin/config-dist.yaml @@ -14,6 +14,12 @@ Lora: # IRQ: 17 # Reset: 22 +# Module: sx1262 # pinedio +# CS: 0 +# IRQ: 10 +# Busy: 11 +# spidev: spidev0.1 + # Module: RF95 # Adafruit RFM9x # Reset: 25 # CS: 7 @@ -31,10 +37,19 @@ Lora: # Busy: 20 # Reset: 18 +# DIO3_TCXO_VOLTAGE: true # the Waveshare Core1262 and others are known to need this setting + +# TXen: x # TX and RX enable pins +# RXen: x + ### Set gpio chip to use in /dev/. Defaults to 0. ### Notably the Raspberry Pi 5 puts the GPIO header on gpiochip4 # gpiochip: 4 +### Specify the SPI device to use in /dev/. Defaults to spidev0.0 +### Some devices, like the pinedio, may require spidev0.1 as a workaround. +# spidev: spidev0.0 + ### Define GPIO buttons here: GPIO: @@ -58,6 +73,18 @@ Display: # Height: 320 # Reset: 27 # Rotate: true +# Invert: true + +### Waveshare 1.44inch LCD HAT +# Panel: ST7735S +# CS: 8 #Chip Select +# DC: 25 # Data/Command pin +# Backlight: 24 +# Width: 128 +# Height: 128 +# Reset: 27 +# OffsetX: 0 +# OffsetY: 0 Touchscreen: # Module: XPT2046 diff --git a/src/ButtonThread.h b/src/ButtonThread.h index 7138d3b6a..3301df097 100644 --- a/src/ButtonThread.h +++ b/src/ButtonThread.h @@ -38,7 +38,7 @@ class ButtonThread : public concurrency::OSThread #ifdef BUTTON_PIN_TOUCH OneButton userButtonTouch; #endif -#if defined(ARCH_RASPBERRY_PI) +#if defined(ARCH_PORTDUINO) OneButton userButton; #endif static bool shutdown_on_long_stop; @@ -49,8 +49,8 @@ class ButtonThread : public concurrency::OSThread // callback returns the period for the next callback invocation (or 0 if we should no longer be called) ButtonThread() : OSThread("Button") { -#if defined(ARCH_RASPBERRY_PI) || defined(BUTTON_PIN) -#if defined(ARCH_RASPBERRY_PI) +#if defined(ARCH_PORTDUINO) || defined(BUTTON_PIN) +#if defined(ARCH_PORTDUINO) if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) userButton = OneButton(settingsMap[user], true, true); #elif defined(BUTTON_PIN) @@ -68,7 +68,7 @@ class ButtonThread : public concurrency::OSThread userButton.attachMultiClick(userButtonMultiPressed); userButton.attachLongPressStart(userButtonPressedLongStart); userButton.attachLongPressStop(userButtonPressedLongStop); -#if defined(ARCH_RASPBERRY_PI) +#if defined(ARCH_PORTDUINO) if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) wakeOnIrq(settingsMap[user], FALLING); #else @@ -105,7 +105,7 @@ class ButtonThread : public concurrency::OSThread #if defined(BUTTON_PIN) userButton.tick(); canSleep &= userButton.isIdle(); -#elif defined(ARCH_RASPBERRY_PI) +#elif defined(ARCH_PORTDUINO) if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) { userButton.tick(); canSleep &= userButton.isIdle(); @@ -143,7 +143,7 @@ class ButtonThread : public concurrency::OSThread powerFSM.trigger(EVENT_PRESS); } #endif -#if defined(ARCH_RASPBERRY_PI) +#if defined(ARCH_PORTDUINO) if ((settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) && (settingsMap[user] != moduleConfig.canned_message.inputbroker_pin_press) || !moduleConfig.canned_message.enabled) { diff --git a/src/RedirectablePrint.cpp b/src/RedirectablePrint.cpp index 2d73c7c9b..dfb3af17e 100644 --- a/src/RedirectablePrint.cpp +++ b/src/RedirectablePrint.cpp @@ -100,9 +100,9 @@ size_t RedirectablePrint::log(const char *logLevel, const char *format, ...) int min = (hms % SEC_PER_HOUR) / SEC_PER_MIN; int sec = (hms % SEC_PER_HOUR) % SEC_PER_MIN; // or hms % SEC_PER_MIN - r += printf("%s | %02d:%02d:%02d %u ", logLevel, hour, min, sec, millis() / 1000); + r += ::printf("%s | %02d:%02d:%02d %u ", logLevel, hour, min, sec, millis() / 1000); } else - r += printf("%s | ??:??:?? %u ", logLevel, millis() / 1000); + r += ::printf("%s | ??:??:?? %u ", logLevel, millis() / 1000); auto thread = concurrency::OSThread::currentThread; if (thread) { diff --git a/src/detect/ScanI2CTwoWire.cpp b/src/detect/ScanI2CTwoWire.cpp index a5c932f1f..990fb36ea 100644 --- a/src/detect/ScanI2CTwoWire.cpp +++ b/src/detect/ScanI2CTwoWire.cpp @@ -2,7 +2,7 @@ #include "concurrency/LockGuard.h" #include "configuration.h" -#if defined(ARCH_RASPBERRY_PI) +#if defined(ARCH_PORTDUINO) #include "linux/LinuxHardwareI2C.h" #endif #if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index fee9393b0..0e0b5f8b6 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -16,7 +16,7 @@ #define GPS_RESET_MODE HIGH #endif -#if defined(NRF52840_XXAA) || defined(NRF52833_XXAA) || defined(ARCH_ESP32) || defined(ARCH_RASPBERRY_PI) +#if defined(NRF52840_XXAA) || defined(NRF52833_XXAA) || defined(ARCH_ESP32) || defined(aLinuxInputImpl) HardwareSerial *GPS::_serial_gps = &Serial1; #else HardwareSerial *GPS::_serial_gps = NULL; @@ -924,7 +924,7 @@ GPS *GPS::createGps() if (!_en_gpio) _en_gpio = PIN_GPS_EN; #endif -#ifdef ARCH_RASPBERRY_PI +#ifdef ARCH_PORTDUINO if (!settingsMap[has_gps]) return nullptr; #endif @@ -1286,4 +1286,4 @@ int32_t GPS::disable() setAwake(false); return INT32_MAX; -} +} \ No newline at end of file diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index a7fcd0c34..00880ad05 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -43,7 +43,7 @@ along with this program. If not, see . #include "sleep.h" #include "target_specific.h" -#if HAS_WIFI && !defined(ARCH_RASPBERRY_PI) +#if HAS_WIFI && !defined(ARCH_PORTDUINO) #include "mesh/wifi/WiFiAPClient.h" #endif @@ -52,7 +52,7 @@ along with this program. If not, see . #include "modules/esp32/StoreForwardModule.h" #endif -#if ARCH_RASPBERRY_PI +#if ARCH_PORTDUINO #include "platform/portduino/PortduinoGlue.h" #endif @@ -930,8 +930,8 @@ Screen::Screen(ScanI2C::DeviceAddress address, meshtastic_Config_DisplayConfig_O #elif defined(USE_ST7567) dispdev = new ST7567Wire(address.address, -1, -1, geometry, (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); -#elif ARCH_RASPBERRY_PI - if (settingsMap[displayPanel] == st7789) { +#elif ARCH_PORTDUINO + if (settingsMap[displayPanel] != no_screen) { LOG_DEBUG("Making TFTDisplay!\n"); dispdev = new TFTDisplay(address.address, -1, -1, geometry, (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); @@ -976,7 +976,7 @@ void Screen::handleSetOn(bool on) #ifdef T_WATCH_S3 PMU->enablePowerOutput(XPOWERS_ALDO2); #endif -#if !ARCH_RASPBERRY_PI +#if !ARCH_PORTDUINO dispdev->displayOn(); #endif dispdev->displayOn(); @@ -1060,7 +1060,7 @@ void Screen::setup() uint8_t dmac[6]; getMacAddr(dmac); snprintf(ourId, sizeof(ourId), "%02x%02x", dmac[4], dmac[5]); -#if ARCH_RASPBERRY_PI +#if ARCH_PORTDUINO handleSetOn(false); // force clean init #endif @@ -1075,7 +1075,7 @@ void Screen::setup() #endif serialSinceMsec = millis(); -#if ARCH_RASPBERRY_PI +#if ARCH_PORTDUINO if (settingsMap[touchscreenModule]) { touchScreenImpl1 = new TouchScreenImpl1(dispdev->getWidth(), dispdev->getHeight(), static_cast(dispdev)->getTouch); @@ -1344,7 +1344,7 @@ void Screen::setFrames() // call a method on debugInfoScreen object (for more details) normalFrames[numframes++] = &Screen::drawDebugInfoSettingsTrampoline; -#if HAS_WIFI && !defined(ARCH_RASPBERRY_PI) +#if HAS_WIFI && !defined(ARCH_PORTDUINO) if (isWifiAvailable()) { // call a method on debugInfoScreen object (for more details) normalFrames[numframes++] = &Screen::drawDebugInfoWiFiTrampoline; @@ -1588,7 +1588,7 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16 #endif } else { // TODO: Raspberry Pi supports more than just the one screen size -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS) || ARCH_RASPBERRY_PI) && \ +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS) || ARCH_PORTDUINO) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) display->drawFastImage(x + SCREEN_WIDTH - 14 - display->getStringWidth(ourId), y + 3 + FONT_HEIGHT_SMALL, 12, 8, imgInfoL1); @@ -1615,7 +1615,7 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16 // Jm void DebugInfo::drawFrameWiFi(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) { -#if HAS_WIFI && !defined(ARCH_RASPBERRY_PI) +#if HAS_WIFI && !defined(ARCH_PORTDUINO) const char *wifiName = config.network.wifi_ssid; display->setFont(FONT_SMALL); diff --git a/src/graphics/TFTDisplay.cpp b/src/graphics/TFTDisplay.cpp index df1aefb3d..9b107ba52 100644 --- a/src/graphics/TFTDisplay.cpp +++ b/src/graphics/TFTDisplay.cpp @@ -1,6 +1,6 @@ #include "configuration.h" #include "main.h" -#if ARCH_RASPBERRY_PI +#if ARCH_PORTDUINO #include "platform/portduino/PortduinoGlue.h" #endif @@ -331,7 +331,7 @@ static LGFX *tft = nullptr; #include // Graphics and font library for ILI9341 driver chip static TFT_eSPI *tft = nullptr; // Invoke library, pins defined in User_Setup.h -#elif ARCH_RASPBERRY_PI +#elif ARCH_PORTDUINO #include // Graphics and font library for ST7735 driver chip class LGFX : public lgfx::LGFX_Device @@ -344,8 +344,12 @@ class LGFX : public lgfx::LGFX_Device public: LGFX(void) { - - _panel_instance = new lgfx::Panel_ST7789; + if (settingsMap[displayPanel] == st7789) + _panel_instance = new lgfx::Panel_ST7789; + else if (settingsMap[displayPanel] == st7735) + _panel_instance = new lgfx::Panel_ST7735; + else if (settingsMap[displayPanel] == st7735s) + _panel_instance = new lgfx::Panel_ST7735S; auto buscfg = _bus_instance.config(); buscfg.spi_mode = 0; @@ -356,19 +360,14 @@ class LGFX : public lgfx::LGFX_Device auto cfg = _panel_instance->config(); // Gets a structure for display panel settings. LOG_DEBUG("Height: %d, Width: %d \n", settingsMap[displayHeight], settingsMap[displayWidth]); - cfg.pin_cs = settingsMap[displayCS]; // Pin number where CS is connected (-1 = disable) + cfg.pin_cs = settingsMap[displayCS]; // Pin number where CS is connected (-1 = disable) + cfg.pin_rst = settingsMap[displayReset]; cfg.panel_width = settingsMap[displayWidth]; // actual displayable width cfg.panel_height = settingsMap[displayHeight]; // actual displayable height - cfg.offset_x = 0; // Panel offset amount in X direction - cfg.offset_y = 0; // Panel offset amount in Y direction + cfg.offset_x = settingsMap[displayOffsetX]; // Panel offset amount in X direction + cfg.offset_y = settingsMap[displayOffsetY]; // Panel offset amount in Y direction cfg.offset_rotation = 0; // Rotation direction value offset 0~7 (4~7 is mirrored) - cfg.dummy_read_pixel = 9; // Number of bits for dummy read before pixel readout - cfg.dummy_read_bits = 1; // Number of bits for dummy read before non-pixel data read - cfg.readable = true; // Set to true if data can be read - cfg.invert = true; // Set to true if the light/darkness of the panel is reversed - cfg.rgb_order = false; // Set to true if the panel's red and blue are swapped - cfg.dlen_16bit = false; // Set to true for panels that transmit data length in 16-bit units with 16-bit parallel or SPI - cfg.bus_shared = true; // If the bus is shared with the SD card, set to true (bus control with drawJpgFile etc.) + cfg.invert = settingsMap[displayInvert]; // Set to true if the light/darkness of the panel is reversed _panel_instance->config(cfg); @@ -399,7 +398,7 @@ class LGFX : public lgfx::LGFX_Device static LGFX *tft = nullptr; #endif -#if defined(ST7735_CS) || defined(ST7789_CS) || defined(ILI9341_DRIVER) || defined(RAK14014) || ARCH_RASPBERRY_PI +#if defined(ST7735_CS) || defined(ST7789_CS) || defined(ILI9341_DRIVER) || defined(RAK14014) || ARCH_PORTDUINO #include "SPILock.h" #include "TFTDisplay.h" #include @@ -407,7 +406,7 @@ static LGFX *tft = nullptr; TFTDisplay::TFTDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY geometry, HW_I2C i2cBus) { LOG_DEBUG("TFTDisplay!\n"); -#if ARCH_RASPBERRY_PI +#if ARCH_PORTDUINO if (settingsMap[displayRotate]) { setGeometry(GEOMETRY_RAWMODE, settingsMap[configNames::displayHeight], settingsMap[configNames::displayWidth]); } else { @@ -460,7 +459,7 @@ void TFTDisplay::sendCommand(uint8_t com) // handle display on/off directly switch (com) { case DISPLAYON: { -#if ARCH_RASPBERRY_PI +#if ARCH_PORTDUINO display(true); if (settingsMap[displayBacklight] > 0) digitalWrite(settingsMap[displayBacklight], TFT_BACKLIGHT_ON); @@ -492,7 +491,7 @@ void TFTDisplay::sendCommand(uint8_t com) break; } case DISPLAYOFF: { -#if ARCH_RASPBERRY_PI +#if ARCH_PORTDUINO tft->clear(); if (settingsMap[displayBacklight] > 0) digitalWrite(settingsMap[displayBacklight], !TFT_BACKLIGHT_ON); diff --git a/src/graphics/images.h b/src/graphics/images.h index 7f3cd46fc..207fc3a86 100644 --- a/src/graphics/images.h +++ b/src/graphics/images.h @@ -14,7 +14,7 @@ const uint8_t imgUser[] PROGMEM = {0x3C, 0x42, 0x99, 0xA5, 0xA5, 0x99, 0x42, 0x3 const uint8_t imgPositionEmpty[] PROGMEM = {0x20, 0x30, 0x28, 0x24, 0x42, 0xFF}; const uint8_t imgPositionSolid[] PROGMEM = {0x20, 0x30, 0x38, 0x3C, 0x7E, 0xFF}; -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS) || ARCH_RASPBERRY_PI) && \ +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS) || ARCH_PORTDUINO) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) const uint8_t imgQuestionL1[] PROGMEM = {0xff, 0x01, 0x01, 0x32, 0x7b, 0x49, 0x49, 0x6f, 0x26, 0x01, 0x01, 0xff}; const uint8_t imgQuestionL2[] PROGMEM = {0x0f, 0x08, 0x08, 0x08, 0x06, 0x0f, 0x0f, 0x06, 0x08, 0x08, 0x08, 0x0f}; diff --git a/src/input/LinuxInput.cpp b/src/input/LinuxInput.cpp index ea588c4bf..d2a94e94e 100644 --- a/src/input/LinuxInput.cpp +++ b/src/input/LinuxInput.cpp @@ -1,7 +1,6 @@ -#if ARCH_RASPBERRY_PI -#include "LinuxInput.h" #include "configuration.h" - +#if ARCH_PORTDUINO +#include "LinuxInput.h" #include "platform/portduino/PortduinoGlue.h" #include #include diff --git a/src/input/LinuxInput.h b/src/input/LinuxInput.h index c7f011379..aa1e8e340 100644 --- a/src/input/LinuxInput.h +++ b/src/input/LinuxInput.h @@ -1,5 +1,5 @@ #pragma once -#if ARCH_RASPBERRY_PI +#if ARCH_PORTDUINO #include "InputBroker.h" #include "concurrency/OSThread.h" #include diff --git a/src/input/LinuxInputImpl.cpp b/src/input/LinuxInputImpl.cpp index d12f457ec..4ddda1923 100644 --- a/src/input/LinuxInputImpl.cpp +++ b/src/input/LinuxInputImpl.cpp @@ -1,6 +1,7 @@ -#if ARCH_RASPBERRY_PI -#include "LinuxInputImpl.h" +#include "configuration.h" +#if ARCH_PORTDUINO #include "InputBroker.h" +#include "LinuxInputImpl.h" LinuxInputImpl *aLinuxInputImpl; diff --git a/src/input/LinuxInputImpl.h b/src/input/LinuxInputImpl.h index b5bfdc4c2..e734b0294 100644 --- a/src/input/LinuxInputImpl.h +++ b/src/input/LinuxInputImpl.h @@ -1,4 +1,4 @@ -#ifdef ARCH_RASPBERRY_PI +#ifdef ARCH_PORTDUINO #pragma once #include "LinuxInput.h" #include "main.h" diff --git a/src/input/TouchScreenImpl1.cpp b/src/input/TouchScreenImpl1.cpp index 145033c95..3e4ed4163 100644 --- a/src/input/TouchScreenImpl1.cpp +++ b/src/input/TouchScreenImpl1.cpp @@ -4,7 +4,7 @@ #include "configuration.h" #include "modules/ExternalNotificationModule.h" -#ifdef ARCH_RASPBERRY_PI +#ifdef ARCH_PORTDUINO #include "platform/portduino/PortduinoGlue.h" #endif @@ -17,7 +17,7 @@ TouchScreenImpl1::TouchScreenImpl1(uint16_t width, uint16_t height, bool (*getTo void TouchScreenImpl1::init() { -#if ARCH_RASPBERRY_PI +#if ARCH_PORTDUINO if (settingsMap[touchscreenModule]) { TouchScreenBase::init(true); inputBroker->registerSource(this); diff --git a/src/input/kbI2cBase.cpp b/src/input/kbI2cBase.cpp index 366e7fbb1..1dba4e34d 100644 --- a/src/input/kbI2cBase.cpp +++ b/src/input/kbI2cBase.cpp @@ -187,7 +187,7 @@ int32_t KbI2cBase::runOnce() i2cBus->requestFrom((int)cardkb_found.address, 1); - while (i2cBus->available()) { + if (i2cBus->available()) { char c = i2cBus->read(); InputEvent e; e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE; @@ -222,7 +222,11 @@ int32_t KbI2cBase::runOnce() case 0x00: // nopress e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE; break; - default: // all other keys + default: // all other keys + if (c > 127) { // bogus key value + e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE; + break; + } e.inputEvent = ANYKEY; e.kbchar = c; break; @@ -238,4 +242,4 @@ int32_t KbI2cBase::runOnce() LOG_WARN("Unknown kb_model 0x%02x\n", kb_model); } return 300; -} +} \ No newline at end of file diff --git a/src/main.cpp b/src/main.cpp index 38c35cf15..a0246afe0 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -66,7 +66,7 @@ NRF52Bluetooth *nrf52Bluetooth; #include "platform/portduino/SimRadio.h" #endif -#ifdef ARCH_RASPBERRY_PI +#ifdef ARCH_PORTDUINO #include "linux/LinuxHardwareI2C.h" #include "platform/portduino/PortduinoGlue.h" #include @@ -74,7 +74,7 @@ NRF52Bluetooth *nrf52Bluetooth; #include #endif -#if HAS_BUTTON || defined(ARCH_RASPBERRY_PI) +#if HAS_BUTTON || defined(ARCH_PORTDUINO) #include "ButtonThread.h" #endif #include "PowerFSMThread.h" @@ -141,32 +141,12 @@ std::pair nodeTelemetrySensorsMap[_meshtastic_TelemetrySenso Router *router = NULL; // Users of router don't care what sort of subclass implements that API -#ifdef ARCH_RASPBERRY_PI -void getPiMacAddr(uint8_t *dmac) -{ - std::fstream macIdentity; - macIdentity.open("/sys/kernel/debug/bluetooth/hci0/identity", std::ios::in); - std::string macLine; - getline(macIdentity, macLine); - macIdentity.close(); - - dmac[0] = strtol(macLine.substr(0, 2).c_str(), NULL, 16); - dmac[1] = strtol(macLine.substr(3, 2).c_str(), NULL, 16); - dmac[2] = strtol(macLine.substr(6, 2).c_str(), NULL, 16); - dmac[3] = strtol(macLine.substr(9, 2).c_str(), NULL, 16); - dmac[4] = strtol(macLine.substr(12, 2).c_str(), NULL, 16); - dmac[5] = strtol(macLine.substr(15, 2).c_str(), NULL, 16); -} -#endif - const char *getDeviceName() { uint8_t dmac[6]; -#ifdef ARCH_RASPBERRY_PI - getPiMacAddr(dmac); -#else + getMacAddr(dmac); -#endif + // Meshtastic_ab3c or Shortname_abcd static char name[20]; snprintf(name, sizeof(name), "%02x%02x", dmac[4], dmac[5]); @@ -211,13 +191,13 @@ static int32_t ledBlinker() uint32_t timeLastPowered = 0; -#if HAS_BUTTON || defined(ARCH_RASPBERRY_PI) +#if HAS_BUTTON || defined(ARCH_PORTDUINO) bool ButtonThread::shutdown_on_long_stop = false; #endif static Periodic *ledPeriodic; static OSThread *powerFSMthread; -#if HAS_BUTTON || defined(ARCH_RASPBERRY_PI) +#if HAS_BUTTON || defined(ARCH_PORTDUINO) static OSThread *buttonThread; uint32_t ButtonThread::longPressTime = 0; #endif @@ -613,7 +593,7 @@ void setup() } else router = new ReliableRouter(); -#if HAS_BUTTON || defined(ARCH_RASPBERRY_PI) +#if HAS_BUTTON || defined(ARCH_PORTDUINO) // Buttons. Moved here cause we need NodeDB to be initialized buttonThread = new ButtonThread(); #endif @@ -664,12 +644,14 @@ void setup() pinMode(LORA_CS, OUTPUT); digitalWrite(LORA_CS, HIGH); SPI1.begin(false); -#else // HW_SPI1_DEVICE +#else // HW_SPI1_DEVICE SPI.setSCK(LORA_SCK); SPI.setTX(LORA_MOSI); SPI.setRX(LORA_MISO); SPI.begin(false); -#endif // HW_SPI1_DEVICE +#endif // HW_SPI1_DEVICE +#elif ARCH_PORTDUINO + SPI.begin(settingsStrings[spidev].c_str()); #elif !defined(ARCH_ESP32) // ARCH_RP2040 SPI.begin(); #else @@ -715,7 +697,7 @@ void setup() // the current region name) #if defined(ST7735_CS) || defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7789_CS) screen->setup(); -#elif ARCH_RASPBERRY_PI +#elif defined(ARCH_PORTDUINO) if (screen_found.port != ScanI2C::I2CPort::NO_I2C || settingsMap[displayPanel]) { screen->setup(); } @@ -732,7 +714,7 @@ void setup() digitalWrite(SX126X_ANT_SW, 1); #endif -#ifdef ARCH_RASPBERRY_PI +#ifdef ARCH_PORTDUINO if (settingsMap[use_sx1262]) { if (!rIf) { LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(SPI, spiSettings); @@ -822,7 +804,7 @@ void setup() } #endif -#if defined(USE_SX1262) && !defined(ARCH_RASPBERRY_PI) +#if defined(USE_SX1262) && !defined(ARCH_PORTDUINO) if (!rIf) { rIf = new SX1262Interface(RadioLibHAL, SX126X_CS, SX126X_DIO1, SX126X_RESET, SX126X_BUSY); if (!rIf->init()) { @@ -997,4 +979,4 @@ void loop() mainDelay.delay(delayMsec); } // if (didWake) LOG_DEBUG("wake!\n"); -} +} \ No newline at end of file diff --git a/src/main.h b/src/main.h index 8a646c80b..1a93298aa 100644 --- a/src/main.h +++ b/src/main.h @@ -62,7 +62,6 @@ extern graphics::Screen *screen; // Return a human readable string of the form "Meshtastic_ab13" const char *getDeviceName(); -void getPiMacAddr(uint8_t *dmac); extern uint32_t timeLastPowered; diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 4de79de0b..1a619f34e 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -27,7 +27,7 @@ #include #endif -#ifdef ARCH_RASPBERRY_PI +#ifdef ARCH_PORTDUINO #include "platform/portduino/PortduinoGlue.h" #endif @@ -195,7 +195,7 @@ void NodeDB::installDefaultConfig() config.bluetooth.fixed_pin = defaultBLEPin; #if defined(ST7735_CS) || defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7789_CS) bool hasScreen = true; -#elif ARCH_RASPBERRY_PI +#elif ARCH_PORTDUINO bool hasScreen = false; if (settingsMap[displayPanel]) hasScreen = true; @@ -464,11 +464,8 @@ void NodeDB::init() */ void NodeDB::pickNewNodeNum() { -#ifdef ARCH_RASPBERRY_PI - getPiMacAddr(ourMacAddr); // Make sure ourMacAddr is set -#else + getMacAddr(ourMacAddr); // Make sure ourMacAddr is set -#endif // Pick an initial nodenum based on the macaddr NodeNum nodeNum = (ourMacAddr[2] << 24) | (ourMacAddr[3] << 16) | (ourMacAddr[4] << 8) | ourMacAddr[5]; diff --git a/src/mesh/RF95Interface.cpp b/src/mesh/RF95Interface.cpp index d7f319f8e..72e0f823f 100644 --- a/src/mesh/RF95Interface.cpp +++ b/src/mesh/RF95Interface.cpp @@ -4,6 +4,10 @@ #include "configuration.h" #include "error.h" +#if ARCH_PORTDUINO +#include "PortduinoGlue.h" +#endif + #define MAX_POWER 20 // if we use 20 we are limited to 1% duty cycle or hw might overheat. For continuous operation set a limit of 17 // In theory up to 27 dBm is possible, but the modules installed in most radios can cope with a max of 20. So BIG WARNING @@ -23,10 +27,18 @@ void RF95Interface::setTransmitEnable(bool txon) { #ifdef RF95_TXEN digitalWrite(RF95_TXEN, txon ? 1 : 0); +#elif ARCH_PORTDUINO + if (settingsMap[txen] != RADIOLIB_NC) { + digitalWrite(settingsMap[txen], txon ? 1 : 0); + } #endif #ifdef RF95_RXEN digitalWrite(RF95_RXEN, txon ? 0 : 1); +#elif ARCH_PORTDUINO + if (settingsMap[rxen] != RADIOLIB_NC) { + digitalWrite(settingsMap[rxen], txon ? 0 : 1); + } #endif } @@ -62,6 +74,16 @@ bool RF95Interface::init() #ifdef RF95_RXEN pinMode(RF95_RXEN, OUTPUT); digitalWrite(RF95_RXEN, 1); +#endif +#if ARCH_PORTDUINO + if (settingsMap[txen] != RADIOLIB_NC) { + pinMode(settingsMap[txen], OUTPUT); + digitalWrite(settingsMap[txen], 0); + } + if (settingsMap[rxen] != RADIOLIB_NC) { + pinMode(settingsMap[rxen], OUTPUT); + digitalWrite(settingsMap[rxen], 0); + } #endif setTransmitEnable(false); @@ -202,4 +224,4 @@ bool RF95Interface::sleep() lora->sleep(); return true; -} +} \ No newline at end of file diff --git a/src/mesh/SX126xInterface.cpp b/src/mesh/SX126xInterface.cpp index 45519ff87..7220dd3e5 100644 --- a/src/mesh/SX126xInterface.cpp +++ b/src/mesh/SX126xInterface.cpp @@ -2,7 +2,7 @@ #include "configuration.h" #include "error.h" #include "mesh/NodeDB.h" -#ifdef ARCH_RASPBERRY_PI +#ifdef ARCH_PORTDUINO #include "PortduinoGlue.h" #endif @@ -30,18 +30,25 @@ template bool SX126xInterface::init() digitalWrite(SX126X_POWER_EN, HIGH); #endif +#if ARCH_PORTDUINO + float tcxoVoltage = 0; + if (settingsMap[dio3_tcxo_voltage]) + tcxoVoltage = 1.8; // FIXME: correct logic to default to not using TCXO if no voltage is specified for SX126X_DIO3_TCXO_VOLTAGE -#if !defined(SX126X_DIO3_TCXO_VOLTAGE) +#elif !defined(SX126X_DIO3_TCXO_VOLTAGE) float tcxoVoltage = 0; // "TCXO reference voltage to be set on DIO3. Defaults to 1.6 V, set to 0 to skip." per // https://github.com/jgromes/RadioLib/blob/690a050ebb46e6097c5d00c371e961c1caa3b52e/src/modules/SX126x/SX126x.h#L471C26-L471C104 // (DIO3 is free to be used as an IRQ) - LOG_DEBUG("SX126X_DIO3_TCXO_VOLTAGE not defined, not using DIO3 as TCXO reference voltage\n"); #else float tcxoVoltage = SX126X_DIO3_TCXO_VOLTAGE; - LOG_DEBUG("SX126X_DIO3_TCXO_VOLTAGE defined, using DIO3 as TCXO reference voltage at %f V\n", SX126X_DIO3_TCXO_VOLTAGE); // (DIO3 is not free to be used as an IRQ) #endif + if (tcxoVoltage == 0) + LOG_DEBUG("SX126X_DIO3_TCXO_VOLTAGE not defined, not using DIO3 as TCXO reference voltage\n"); + else + LOG_DEBUG("SX126X_DIO3_TCXO_VOLTAGE defined, using DIO3 as TCXO reference voltage at %f V\n", tcxoVoltage); + // FIXME: May want to set depending on a definition, currently all SX126x variant files use the DC-DC regulator option bool useRegulatorLDO = false; // Seems to depend on the connection to pin 9/DCC_SW - if an inductor DCDC? @@ -77,7 +84,7 @@ template bool SX126xInterface::init() #ifdef SX126X_DIO2_AS_RF_SWITCH LOG_DEBUG("Setting DIO2 as RF switch\n"); bool dio2AsRfSwitch = true; -#elif defined(ARCH_RASPBERRY_PI) +#elif defined(ARCH_PORTDUINO) bool dio2AsRfSwitch = false; if (settingsMap[dio2_as_rf_switch]) { LOG_DEBUG("Setting DIO2 as RF switch\n"); @@ -93,6 +100,12 @@ template bool SX126xInterface::init() // If a pin isn't defined, we set it to RADIOLIB_NC, it is safe to always do external RF switching with RADIOLIB_NC as it has // no effect +#if ARCH_PORTDUINO + if (res == RADIOLIB_ERR_NONE) { + LOG_DEBUG("Using MCU pin %i as RXEN and pin %i as TXEN to control RF switching\n", settingsMap[rxen], settingsMap[txen]); + lora.setRfSwitchPins(settingsMap[rxen], settingsMap[txen]); + } +#else #ifndef SX126X_RXEN #define SX126X_RXEN RADIOLIB_NC LOG_DEBUG("SX126X_RXEN not defined, defaulting to RADIOLIB_NC\n"); @@ -105,7 +118,7 @@ template bool SX126xInterface::init() LOG_DEBUG("Using MCU pin %i as RXEN and pin %i as TXEN to control RF switching\n", SX126X_RXEN, SX126X_TXEN); lora.setRfSwitchPins(SX126X_RXEN, SX126X_TXEN); } - +#endif if (config.lora.sx126x_rx_boosted_gain) { uint16_t result = lora.setRxBoostedGainMode(true); LOG_INFO("Set RX gain to boosted mode; result: %d\n", result); @@ -322,4 +335,4 @@ template bool SX126xInterface::sleep() #endif return true; -} +} \ No newline at end of file diff --git a/src/mesh/SX128xInterface.cpp b/src/mesh/SX128xInterface.cpp index 6b7b0f438..47a79ea52 100644 --- a/src/mesh/SX128xInterface.cpp +++ b/src/mesh/SX128xInterface.cpp @@ -3,6 +3,10 @@ #include "error.h" #include "mesh/NodeDB.h" +#if ARCH_PORTDUINO +#include "PortduinoGlue.h" +#endif + // Particular boards might define a different max power based on what their hardware can do #ifndef SX128X_MAX_POWER #define SX128X_MAX_POWER 13 @@ -31,6 +35,16 @@ template bool SX128xInterface::init() digitalWrite(RF95_FAN_EN, 1); #endif +#if ARCH_PORTDUINO + if (settingsMap[rxen] != RADIOLIB_NC) { + pinMode(settingsMap[rxen], OUTPUT); + digitalWrite(settingsMap[rxen], LOW); // Set low before becoming an output + } + if (settingsMap[txen] != RADIOLIB_NC) { + pinMode(settingsMap[txen], OUTPUT); + digitalWrite(settingsMap[txen], LOW); // Set low before becoming an output + } +#else #if defined(SX128X_RXEN) && (SX128X_RXEN != RADIOLIB_NC) // set not rx or tx mode pinMode(SX128X_RXEN, OUTPUT); digitalWrite(SX128X_RXEN, LOW); // Set low before becoming an output @@ -38,6 +52,7 @@ template bool SX128xInterface::init() #if defined(SX128X_TXEN) && (SX128X_TXEN != RADIOLIB_NC) pinMode(SX128X_TXEN, OUTPUT); digitalWrite(SX128X_TXEN, LOW); +#endif #endif RadioLibInterface::init(); @@ -75,6 +90,10 @@ template bool SX128xInterface::init() if (res == RADIOLIB_ERR_NONE) { lora.setRfSwitchPins(SX128X_RXEN, SX128X_TXEN); } +#elif ARCH_PORTDUINO + if (res == RADIOLIB_ERR_NONE && settingsMap[rxen] != RADIOLIB_NC && settingsMap[txen] != RADIOLIB_NC) { + lora.setRfSwitchPins(settingsMap[rxen], settingsMap[txen]); + } #endif if (res == RADIOLIB_ERR_NONE) @@ -148,14 +167,21 @@ template void SX128xInterface::setStandby() } assert(err == RADIOLIB_ERR_NONE); - +#if ARCH_PORTDUINO + if (settingsMap[rxen] != RADIOLIB_NC) { + digitalWrite(settingsMap[rxen], LOW); + } + if (settingsMap[txen] != RADIOLIB_NC) { + digitalWrite(settingsMap[txen], LOW); + } +#else #if defined(SX128X_RXEN) && (SX128X_RXEN != RADIOLIB_NC) // we have RXEN/TXEN control - turn off RX and TX power digitalWrite(SX128X_RXEN, LOW); #endif #if defined(SX128X_TXEN) && (SX128X_TXEN != RADIOLIB_NC) digitalWrite(SX128X_TXEN, LOW); #endif - +#endif isReceiving = false; // If we were receiving, not any more activeReceiveStart = 0; disableInterrupt(); @@ -176,11 +202,21 @@ template void SX128xInterface::addReceiveMetadata(meshtastic_Mes */ template void SX128xInterface::configHardwareForSend() { +#if ARCH_PORTDUINO + if (settingsMap[txen] != RADIOLIB_NC) { + digitalWrite(settingsMap[txen], HIGH); + } + if (settingsMap[rxen] != RADIOLIB_NC) { + digitalWrite(settingsMap[rxen], LOW); + } + +#else #if defined(SX128X_TXEN) && (SX128X_TXEN != RADIOLIB_NC) // we have RXEN/TXEN control - turn on TX power / off RX power digitalWrite(SX128X_TXEN, HIGH); #endif #if defined(SX128X_RXEN) && (SX128X_RXEN != RADIOLIB_NC) digitalWrite(SX128X_RXEN, LOW); +#endif #endif RadioLibInterface::configHardwareForSend(); @@ -197,11 +233,21 @@ template void SX128xInterface::startReceive() setStandby(); +#if ARCH_PORTDUINO + if (settingsMap[rxen] != RADIOLIB_NC) { + digitalWrite(settingsMap[rxen], HIGH); + } + if (settingsMap[txen] != RADIOLIB_NC) { + digitalWrite(settingsMap[txen], LOW); + } + +#else #if defined(SX128X_RXEN) && (SX128X_RXEN != RADIOLIB_NC) // we have RXEN/TXEN control - turn on RX power / off TX power digitalWrite(SX128X_RXEN, HIGH); #endif #if defined(SX128X_TXEN) && (SX128X_TXEN != RADIOLIB_NC) digitalWrite(SX128X_TXEN, LOW); +#endif #endif // We use the PREAMBLE_DETECTED and HEADER_VALID IRQ flag to detect whether we are actively receiving @@ -281,4 +327,4 @@ template bool SX128xInterface::sleep() #endif return true; -} +} \ No newline at end of file diff --git a/src/meshUtils.h b/src/meshUtils.h index a6436a8d5..e32ef230a 100644 --- a/src/meshUtils.h +++ b/src/meshUtils.h @@ -8,5 +8,6 @@ template constexpr const T &clamp(const T &v, const T &lo, const T &hi #if (defined(ARCH_PORTDUINO) && !defined(STRNSTR)) #define STRNSTR +#include char *strnstr(const char *s, const char *find, size_t slen); #endif \ No newline at end of file diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index cc6d8e39d..3127b0986 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -1,5 +1,5 @@ #include "configuration.h" -#if ARCH_RASPBERRY_PI +#if ARCH_PORTDUINO #include "PortduinoGlue.h" #endif #if HAS_SCREEN diff --git a/src/modules/Modules.cpp b/src/modules/Modules.cpp index 5ed49a4d8..37c7576f6 100644 --- a/src/modules/Modules.cpp +++ b/src/modules/Modules.cpp @@ -17,7 +17,7 @@ #include "modules/TextMessageModule.h" #include "modules/TraceRouteModule.h" #include "modules/WaypointModule.h" -#if ARCH_RASPBERRY_PI +#if ARCH_PORTDUINO #include "input/LinuxInputImpl.h" #endif #if HAS_TELEMETRY @@ -50,7 +50,7 @@ void setupModules() { if (config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER) { -#if HAS_BUTTON || ARCH_RASPBERRY_PI +#if HAS_BUTTON || ARCH_PORTDUINO inputBroker = new InputBroker(); #endif adminModule = new AdminModule(); @@ -67,7 +67,7 @@ void setupModules() new RemoteHardwareModule(); new ReplyModule(); -#if HAS_BUTTON || ARCH_RASPBERRY_PI +#if HAS_BUTTON || ARCH_PORTDUINO rotaryEncoderInterruptImpl1 = new RotaryEncoderInterruptImpl1(); if (!rotaryEncoderInterruptImpl1->init()) { delete rotaryEncoderInterruptImpl1; @@ -85,7 +85,7 @@ void setupModules() kbMatrixImpl->init(); #endif // INPUTBROKER_MATRIX_TYPE #endif // HAS_BUTTON -#if ARCH_RASPBERRY_PI +#if ARCH_PORTDUINO aLinuxInputImpl = new LinuxInputImpl(); aLinuxInputImpl->init(); #endif diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index 5464c6c49..a13e7eba2 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -8,10 +8,8 @@ #include #include -#ifdef ARCH_RASPBERRY_PI #include "PortduinoGlue.h" #include "linux/gpio/LinuxGPIOPin.h" -#include "pigpio.h" #include "yaml-cpp/yaml.h" #include #include @@ -19,10 +17,7 @@ std::map settingsMap; std::map settingsStrings; - -#else -#include -#endif +char *configPath = nullptr; // FIXME - move setBluetoothEnable into a HALPlatform class void setBluetoothEnable(bool on) @@ -36,34 +31,7 @@ void cpuDeepSleep(uint32_t msecs) } void updateBatteryLevel(uint8_t level) NOT_IMPLEMENTED("updateBatteryLevel"); -#ifndef ARCH_RASPBERRY_PI -/** a simulated pin for busted IRQ hardware - * Porduino helper class to do this i2c based polling: - */ -class PolledIrqPin : public GPIOPin -{ - public: - PolledIrqPin() : GPIOPin(LORA_DIO1, "loraIRQ") {} - /// Read the low level hardware for this pin - virtual PinStatus readPinHardware() - { - if (isrPinStatus < 0) - return LOW; // No interrupt handler attached, don't bother polling i2c right now - else { - extern RadioInterface *rIf; // FIXME, temporary hack until we know if we need to keep this - - assert(rIf); - RadioLibInterface *rIf95 = static_cast(rIf); - bool p = rIf95->isIRQPending(); - log(SysGPIO, LogDebug, "PolledIrqPin::readPinHardware(%s, %d, %d)", getName(), getPinNum(), p); - return p ? HIGH : LOW; - } - } -}; - -static GPIOPin *loraIrq; -#endif int TCPPort = 4403; static error_t parse_opt(int key, char *arg, struct argp_state *state) @@ -73,7 +41,10 @@ static error_t parse_opt(int key, char *arg, struct argp_state *state) if (sscanf(arg, "%d", &TCPPort) < 1) return ARGP_ERR_UNKNOWN; else - printf("Using TCP port %d\n", TCPPort); + printf("Using config file %d\n", TCPPort); + break; + case 'c': + configPath = arg; break; case ARGP_KEY_ARG: return 0; @@ -85,7 +56,9 @@ static error_t parse_opt(int key, char *arg, struct argp_state *state) void portduinoCustomInit() { - static struct argp_option options[] = {{"port", 'p', "PORT", 0, "The TCP port to use."}, {0}}; + static struct argp_option options[] = {{"port", 'p', "PORT", 0, "The TCP port to use."}, + {"config", 'c', "CONFIG_PATH", 0, "Full path of the .yaml config file to use."}, + {0}}; static void *childArguments; static char doc[] = "Meshtastic native build."; static char args_doc[] = "..."; @@ -101,14 +74,20 @@ void portduinoCustomInit() void portduinoSetup() { printf("Setting up Meshtastic on Portduino...\n"); - -#ifdef ARCH_RASPBERRY_PI gpioInit(); std::string gpioChipName = "gpiochip"; + YAML::Node yamlConfig; - if (access("config.yaml", R_OK) == 0) { + if (configPath != nullptr) { + try { + yamlConfig = YAML::LoadFile(configPath); + } catch (YAML::Exception e) { + std::cout << "Could not open " << configPath << " because of error: " << e.what() << std::endl; + exit(EXIT_FAILURE); + } + } else if (access("config.yaml", R_OK) == 0) { try { yamlConfig = YAML::LoadFile("config.yaml"); } catch (YAML::Exception e) { @@ -123,8 +102,24 @@ void portduinoSetup() exit(EXIT_FAILURE); } } else { - std::cout << "No 'config.yaml' found, exiting." << std::endl; - exit(EXIT_FAILURE); + std::cout << "No 'config.yaml' found, running simulated." << std::endl; + // Set the random seed equal to TCPPort to have a different seed per instance + randomSeed(TCPPort); + + /* Aren't all pins defaulted to simulated? + auto fakeBusy = new SimGPIOPin(SX126X_BUSY, "fakeBusy"); + fakeBusy->writePin(LOW); + fakeBusy->setSilent(true); + gpioBind(fakeBusy); + + auto cs = new SimGPIOPin(SX126X_CS, "fakeLoraCS"); + cs->setSilent(true); + gpioBind(cs); + + gpioBind(new SimGPIOPin(SX126X_RESET, "fakeLoraReset")); + gpioBind(new SimGPIOPin(LORA_DIO1, "fakeLoraIrq")); + */ + return; } try { @@ -141,12 +136,17 @@ void portduinoSetup() settingsMap[use_sx1280] = true; } settingsMap[dio2_as_rf_switch] = yamlConfig["Lora"]["DIO2_AS_RF_SWITCH"].as(false); + settingsMap[dio3_tcxo_voltage] = yamlConfig["Lora"]["DIO3_TCXO_VOLTAGE"].as(false); settingsMap[cs] = yamlConfig["Lora"]["CS"].as(RADIOLIB_NC); settingsMap[irq] = yamlConfig["Lora"]["IRQ"].as(RADIOLIB_NC); settingsMap[busy] = yamlConfig["Lora"]["Busy"].as(RADIOLIB_NC); settingsMap[reset] = yamlConfig["Lora"]["Reset"].as(RADIOLIB_NC); + settingsMap[txen] = yamlConfig["Lora"]["TXen"].as(RADIOLIB_NC); + settingsMap[rxen] = yamlConfig["Lora"]["RXen"].as(RADIOLIB_NC); settingsMap[gpiochip] = yamlConfig["Lora"]["gpiochip"].as(0); gpioChipName += std::to_string(settingsMap[gpiochip]); + + settingsStrings[spidev] = "/dev/" + yamlConfig["Lora"]["spidev"].as("spidev0.0"); } if (yamlConfig["GPIO"]) { settingsMap[user] = yamlConfig["GPIO"]["User"].as(RADIOLIB_NC); @@ -162,13 +162,20 @@ void portduinoSetup() if (yamlConfig["Display"]) { if (yamlConfig["Display"]["Panel"].as("") == "ST7789") settingsMap[displayPanel] = st7789; + else if (yamlConfig["Display"]["Panel"].as("") == "ST7735") + settingsMap[displayPanel] = st7735; + else if (yamlConfig["Display"]["Panel"].as("") == "ST7735S") + settingsMap[displayPanel] = st7735s; settingsMap[displayHeight] = yamlConfig["Display"]["Height"].as(0); settingsMap[displayWidth] = yamlConfig["Display"]["Width"].as(0); settingsMap[displayDC] = yamlConfig["Display"]["DC"].as(-1); settingsMap[displayCS] = yamlConfig["Display"]["CS"].as(-1); settingsMap[displayBacklight] = yamlConfig["Display"]["Backlight"].as(-1); settingsMap[displayReset] = yamlConfig["Display"]["Reset"].as(-1); + settingsMap[displayOffsetX] = yamlConfig["Display"]["OffsetX"].as(0); + settingsMap[displayOffsetY] = yamlConfig["Display"]["OffsetY"].as(0); settingsMap[displayRotate] = yamlConfig["Display"]["Rotate"].as(false); + settingsMap[displayInvert] = yamlConfig["Display"]["Invert"].as(false); } settingsMap[touchscreenModule] = no_touchscreen; if (yamlConfig["Touchscreen"]) { @@ -185,10 +192,6 @@ void portduinoSetup() std::cout << "*** Exception " << e.what() << std::endl; exit(EXIT_FAILURE); } - if (access("/sys/kernel/debug/bluetooth/hci0/identity", R_OK) != 0) { - std::cout << "Cannot read Bluetooth MAC Address. Please run as root" << std::endl; - exit(EXIT_FAILURE); - } // Need to bind all the configured GPIO pins so they're not simulated if (settingsMap.count(cs) > 0 && settingsMap[cs] != RADIOLIB_NC) { @@ -216,6 +219,16 @@ void portduinoSetup() settingsMap[user] = RADIOLIB_NC; } } + if (settingsMap.count(rxen) > 0 && settingsMap[rxen] != RADIOLIB_NC) { + if (initGPIOPin(settingsMap[rxen], gpioChipName) != ERRNO_OK) { + settingsMap[rxen] = RADIOLIB_NC; + } + } + if (settingsMap.count(txen) > 0 && settingsMap[txen] != RADIOLIB_NC) { + if (initGPIOPin(settingsMap[txen], gpioChipName) != ERRNO_OK) { + settingsMap[txen] = RADIOLIB_NC; + } + } if (settingsMap[displayPanel] != no_screen) { if (settingsMap[displayCS] > 0) @@ -235,55 +248,8 @@ void portduinoSetup() } return; -#endif - -#ifdef defined(PORTDUINO_LINUX_HARDWARE) - SPI.begin(); // We need to create SPI - bool usePineLora = !spiChip->isSimulated(); - if (usePineLora) { - printf("Connecting to PineLora board...\n"); - - // FIXME: remove this hack once interrupts are confirmed to work on new pine64 board - // loraIrq = new PolledIrqPin(); - loraIrq = new LinuxGPIOPin(LORA_DIO1, "ch341", "int", "loraIrq"); // or "err"? - loraIrq->setSilent(); - gpioBind(loraIrq); - - // BUSY hw was busted on current board - just use the simulated pin (which will read low) - auto busy = new LinuxGPIOPin(SX126X_BUSY, "ch341", "slct", "loraBusy"); - busy->setSilent(); - gpioBind(busy); - - gpioBind(new LinuxGPIOPin(SX126X_RESET, "ch341", "ini", "loraReset")); - - auto loraCs = new LinuxGPIOPin(SX126X_CS, "ch341", "cs0", "loraCs"); - loraCs->setSilent(); - gpioBind(loraCs); - } else -#endif -#ifndef ARCH_RASPBERRY_PI - { - // Set the random seed equal to TCPPort to have a different seed per instance - randomSeed(TCPPort); - - auto fakeBusy = new SimGPIOPin(SX126X_BUSY, "fakeBusy"); - fakeBusy->writePin(LOW); - fakeBusy->setSilent(true); - gpioBind(fakeBusy); - - auto cs = new SimGPIOPin(SX126X_CS, "fakeLoraCS"); - cs->setSilent(true); - gpioBind(cs); - - gpioBind(new SimGPIOPin(SX126X_RESET, "fakeLoraReset")); - gpioBind(new SimGPIOPin(LORA_DIO1, "fakeLoraIrq")); - } - // gpioBind((new SimGPIOPin(LORA_RESET, "LORA_RESET"))); - // gpioBind((new SimGPIOPin(LORA_CS, "LORA_CS"))->setSilent()); -#endif } -#ifdef ARCH_RASPBERRY_PI int initGPIOPin(int pinNum, std::string gpioChipName) { std::string gpio_name = "GPIO" + std::to_string(pinNum); @@ -298,5 +264,4 @@ int initGPIOPin(int pinNum, std::string gpioChipName) std::cout << "Warning, cannot claim pin " << gpio_name << (p ? p.__cxa_exception_type()->name() : "null") << std::endl; return ERRNO_DISABLED; } -} -#endif +} \ No newline at end of file diff --git a/src/platform/portduino/PortduinoGlue.h b/src/platform/portduino/PortduinoGlue.h index ed45cb457..cb85ce69a 100644 --- a/src/platform/portduino/PortduinoGlue.h +++ b/src/platform/portduino/PortduinoGlue.h @@ -1,5 +1,4 @@ #pragma once -#ifdef ARCH_RASPBERRY_PI #include enum configNames { @@ -8,11 +7,15 @@ enum configNames { irq, busy, reset, + txen, + rxen, dio2_as_rf_switch, + dio3_tcxo_voltage, use_rf95, use_sx1280, user, gpiochip, + spidev, has_gps, touchscreenModule, touchscreenCS, @@ -25,13 +28,14 @@ enum configNames { displayBacklight, displayReset, displayRotate, + displayOffsetX, + displayOffsetY, + displayInvert, keyboardDevice }; -enum { no_screen, st7789 }; +enum { no_screen, st7789, st7735, st7735s }; enum { no_touchscreen, xpt2046 }; extern std::map settingsMap; extern std::map settingsStrings; -int initGPIOPin(int pinNum, std::string gpioChipname); - -#endif +int initGPIOPin(int pinNum, std::string gpioChipname); \ No newline at end of file diff --git a/src/platform/portduino/architecture.h b/src/platform/portduino/architecture.h index a98769222..321949226 100644 --- a/src/platform/portduino/architecture.h +++ b/src/platform/portduino/architecture.h @@ -1,6 +1,6 @@ #pragma once -#define ARCH_PORTDUINO +#define ARCH_PORTDUINO 1 // // set HW_VENDOR diff --git a/src/shutdown.h b/src/shutdown.h index 10283f5dd..6449b129e 100644 --- a/src/shutdown.h +++ b/src/shutdown.h @@ -3,7 +3,7 @@ #include "graphics/Screen.h" #include "main.h" #include "power.h" -#if ARCH_RASPBERRY_PI +#if defined(ARCH_PORTDUINO) #include "api/WiFiServerAPI.h" #include "input/LinuxInputImpl.h" @@ -19,7 +19,7 @@ void powerCommandsCheck() NVIC_SystemReset(); #elif defined(ARCH_RP2040) rp2040.reboot(); -#elif defined(ARCH_RASPBERRY_PI) +#elif defined(ARCH_PORTDUINO) deInitApiServer(); if (aLinuxInputImpl) aLinuxInputImpl->deInit(); @@ -27,11 +27,6 @@ void powerCommandsCheck() Wire.end(); Serial1.end(); reboot(); -#elif defined(ARCH_PORTDUINO) - deInitApiServer(); - SPI.end(); - Wire.end(); - reboot(); #else rebootAtMsec = -1; LOG_WARN("FIXME implement reboot for this platform. Note that some settings require a restart to be applied.\n"); @@ -49,7 +44,7 @@ void powerCommandsCheck() #if defined(ARCH_NRF52) || defined(ARCH_ESP32) playShutdownMelody(); power->shutdown(); -#elif ARCH_RASPBERRY_PI +#elif defined(ARCH_PORTDUINO) exit(EXIT_SUCCESS); #else LOG_WARN("FIXME implement shutdown for this platform"); diff --git a/variants/portduino/platformio.ini b/variants/portduino/platformio.ini index cdc32fae5..2641cc136 100644 --- a/variants/portduino/platformio.ini +++ b/variants/portduino/platformio.ini @@ -3,6 +3,7 @@ extends = portduino_base build_flags = ${portduino_base.build_flags} -O0 -I variants/portduino board = cross_platform lib_deps = ${portduino_base.lib_deps} + lovyan03/LovyanGFX@^1.1.12 build_src_filter = ${portduino_base.build_src_filter} ; The Portduino based sim environment on top of a linux OS and touching linux hardware devices @@ -16,7 +17,7 @@ build_src_filter = ${portduino_base.build_src_filter} ; The Raspberry Pi actually has accessible SPI and GPIO, so we can support real hardware there. [env:raspbian] extends = portduino_base -build_flags = ${portduino_base.build_flags} -O0 -lgpiod -I variants/portduino -DARCH_RASPBERRY_PI -lpigpio -lyaml-cpp +build_flags = ${portduino_base.build_flags} -O0 -lgpiod -I variants/portduino -DARCH_RASPBERRY_PI -lyaml-cpp board = linux_arm lib_deps = ${portduino_base.lib_deps} https://github.com/jp-bennett/LovyanGFX.git#jp-bennett-patch-1 ; lovyan03/LovyanGFX@^1.1.9 diff --git a/variants/portduino/variant.h b/variants/portduino/variant.h index 3493f704f..24885d7eb 100644 --- a/variants/portduino/variant.h +++ b/variants/portduino/variant.h @@ -1,33 +1,3 @@ -#if defined(ARCH_RASPBERRY_PI) #define HAS_WIRE 1 #define HAS_SCREEN 1 -#define CANNED_MESSAGE_MODULE_ENABLE 1 - -#else // Pine64 mode. - -// Pine64 uses a common pinout for their SX1262 vs RF95 modules - both can be enabled and we will probe at runtime for RF95 and if -// not found then probe for SX1262. Currently the RF95 code is disabled because I think the RF95 module won't need to ship. -// #define USE_RF95 -#define USE_SX1262 - -// Fake SPI device selections -#define LORA_SCK 5 -#define LORA_MISO 19 -#define LORA_MOSI 27 -#define LORA_CS RADIOLIB_NC // the ch341f spi controller does CS for us - -#define LORA_DIO0 26 // a No connect on the SX1262 module -#define LORA_RESET 14 -#define LORA_DIO1 33 // SX1262 IRQ, called DIO0 on pinelora schematic, pin 7 on ch341f "ack" - FIXME, enable hwints in linux -#define LORA_DIO2 32 // SX1262 BUSY, actually connected to "DIO5" on pinelora schematic, pin 8 on ch341f "slct" -#define LORA_DIO3 RADIOLIB_NC // Not connected on PCB, but internally on the TTGO SX1262, if DIO3 is high the TXCO is enabled - -#ifdef USE_SX1262 -#define SX126X_CS 20 // CS0 on pinelora schematic, hooked to gpio D0 on ch341f -#define SX126X_DIO1 LORA_DIO1 -#define SX126X_BUSY LORA_DIO2 -#define SX126X_RESET LORA_RESET -#define SX126X_DIO2_AS_RF_SWITCH -#endif - -#endif \ No newline at end of file +#define CANNED_MESSAGE_MODULE_ENABLE 1 \ No newline at end of file From 6f96fbfb74474dd50acb141cf3784e3354152155 Mon Sep 17 00:00:00 2001 From: KodinLanewave Date: Fri, 12 Jan 2024 08:02:51 -0800 Subject: [PATCH 111/472] INA3221 library branch to support negative values (#3084) * INA3221 library branch to support negative values Original INA3221 library does not handle negative values properly due to mishandling of signed bits in sensor reading and processing. I have branched the library, changed the code, and tested with several deployed nodes to confirm functionality. * Update INA3221 library reference to use version tag Updated my library repo to reflect a version tag properly per request by meshtastic code reviewer --------- Co-authored-by: Ben Meadors --- platformio.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platformio.ini b/platformio.ini index b526a8fa2..f017dccee 100644 --- a/platformio.ini +++ b/platformio.ini @@ -115,7 +115,7 @@ lib_deps = https://github.com/boschsensortec/Bosch-BSEC2-Library#v1.5.2400 boschsensortec/BME68x Sensor Library@^1.1.40407 adafruit/Adafruit MCP9808 Library@^2.0.0 - https://github.com/Tinyu-Zhao/INA3221@^0.0.1 + https://github.com/KodinLanewave/INA3221@^1.0.0 adafruit/Adafruit INA260 Library@^1.5.0 adafruit/Adafruit INA219@^1.2.0 adafruit/Adafruit SHTC3 Library@^1.0.0 From c22340eaf711415ab1dc8adf0cda99528082c9f0 Mon Sep 17 00:00:00 2001 From: GUVWAF Date: Sat, 13 Jan 2024 10:43:48 +0100 Subject: [PATCH 112/472] Add necessary libs to Dockerfile for native build --- Dockerfile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Dockerfile b/Dockerfile index 63eccc4b4..0ba5a07f9 100644 --- a/Dockerfile +++ b/Dockerfile @@ -12,7 +12,7 @@ SHELL ["/bin/bash", "-o", "pipefail", "-c"] # Install build deps USER root RUN apt-get update && \ - apt-get -y install wget python3 g++ zip python3-venv git vim ca-certificates + apt-get -y install wget python3 g++ zip python3-venv git vim ca-certificates libgpiod-dev libyaml-cpp-dev libbluetooth-dev # create a non-priveleged user & group RUN groupadd -g 1000 mesh && useradd -ml -u 1000 -g 1000 mesh @@ -38,4 +38,4 @@ USER mesh WORKDIR /home/mesh CMD sh -cx "./meshtasticd_linux_amd64 --hwid '${HWID:-$RANDOM}'" -HEALTHCHECK NONE +HEALTHCHECK NONE \ No newline at end of file From 92110276d764dcf25de5fa5f5a4973f9f92ff9ac Mon Sep 17 00:00:00 2001 From: GUVWAF Date: Sat, 13 Jan 2024 10:44:44 +0100 Subject: [PATCH 113/472] Use `::printf` for Portduino only --- src/RedirectablePrint.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/src/RedirectablePrint.cpp b/src/RedirectablePrint.cpp index dfb3af17e..ba09076ed 100644 --- a/src/RedirectablePrint.cpp +++ b/src/RedirectablePrint.cpp @@ -99,10 +99,17 @@ size_t RedirectablePrint::log(const char *logLevel, const char *format, ...) int hour = hms / SEC_PER_HOUR; int min = (hms % SEC_PER_HOUR) / SEC_PER_MIN; int sec = (hms % SEC_PER_HOUR) % SEC_PER_MIN; // or hms % SEC_PER_MIN - +#ifdef ARCH_PORTDUINO r += ::printf("%s | %02d:%02d:%02d %u ", logLevel, hour, min, sec, millis() / 1000); +#else + r += printf("%s | %02d:%02d:%02d %u ", logLevel, hour, min, sec, millis() / 1000); +#endif } else +#ifdef ARCH_PORTDUINO r += ::printf("%s | ??:??:?? %u ", logLevel, millis() / 1000); +#else + r += printf("%s | ??:??:?? %u ", logLevel, millis() / 1000); +#endif auto thread = concurrency::OSThread::currentThread; if (thread) { From e4e9a1559e6b5ba4dda19209a7b7fa75cd31d75f Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sat, 13 Jan 2024 16:12:26 -0600 Subject: [PATCH 114/472] Drop the Raspbian and Linux targets (#3091) * Drop the Raspbian and Linux targets * Add lovyanGFX libdep to native --- .github/workflows/package_raspbian.yml | 2 +- arch/portduino/portduino.ini | 1 + bin/build-native.sh | 11 ++--------- bin/native-install.sh | 2 +- variants/portduino/platformio.ini | 18 ------------------ 5 files changed, 5 insertions(+), 29 deletions(-) diff --git a/.github/workflows/package_raspbian.yml b/.github/workflows/package_raspbian.yml index 61f82e9d7..02b1ed5ad 100644 --- a/.github/workflows/package_raspbian.yml +++ b/.github/workflows/package_raspbian.yml @@ -40,7 +40,7 @@ jobs: mkdir -p .debpkg/usr/sbin mkdir -p .debpkg/etc/meshtasticd mkdir -p .debpkg/usr/lib/systemd/system/ - cp release/meshtasticd_linux_arm64 .debpkg/usr/sbin/meshtasticd + cp release/meshtasticd_linux .debpkg/usr/sbin/meshtasticd cp bin/config-dist.yaml .debpkg/etc/meshtasticd/config.yaml chmod +x .debpkg/usr/sbin/meshtasticd cp bin/meshtasticd.service .debpkg/usr/lib/systemd/system/meshtasticd.service diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index ac7ba13ba..970640480 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -23,6 +23,7 @@ lib_deps = ${env.lib_deps} ${networking_base.lib_deps} rweather/Crypto@^0.4.0 + lovyan03/LovyanGFX@^1.1.12 build_flags = ${arduino_base.build_flags} diff --git a/bin/build-native.sh b/bin/build-native.sh index 64c5adb50..dbec5bb95 100755 --- a/bin/build-native.sh +++ b/bin/build-native.sh @@ -14,14 +14,7 @@ rm -r $OUTDIR/* || true # Important to pull latest version of libs into all device flavors, otherwise some devices might be stale platformio pkg update - -if command -v raspi-config &>/dev/null; then - pio run --environment raspbian - cp .pio/build/raspbian/program $OUTDIR/meshtasticd_linux_arm64 -else - pio run --environment native - cp .pio/build/native/program $OUTDIR/meshtasticd_linux_amd64 -fi - +pio run --environment native +cp .pio/build/native/program $OUTDIR/meshtasticd_linux cp bin/device-install.* $OUTDIR cp bin/device-update.* $OUTDIR diff --git a/bin/native-install.sh b/bin/native-install.sh index d1d0c8707..afba04c6b 100755 --- a/bin/native-install.sh +++ b/bin/native-install.sh @@ -1,6 +1,6 @@ #!/usr/bin/env bash -cp release/meshtasticd_linux_arm64 /usr/sbin/meshtasticd +cp release/meshtasticd_linux /usr/sbin/meshtasticd mkdir /etc/meshtasticd if [[ -f "/etc/meshtasticd/config.yaml" ]]; then cp bin/config-dist.yaml /etc/meshtasticd/config-upgrade.yaml diff --git a/variants/portduino/platformio.ini b/variants/portduino/platformio.ini index 2641cc136..d37c6be21 100644 --- a/variants/portduino/platformio.ini +++ b/variants/portduino/platformio.ini @@ -3,22 +3,4 @@ extends = portduino_base build_flags = ${portduino_base.build_flags} -O0 -I variants/portduino board = cross_platform lib_deps = ${portduino_base.lib_deps} - lovyan03/LovyanGFX@^1.1.12 -build_src_filter = ${portduino_base.build_src_filter} - -; The Portduino based sim environment on top of a linux OS and touching linux hardware devices -[env:linux] -extends = portduino_base -build_flags = ${portduino_base.build_flags} -O0 -lgpiod -I variants/portduino -board = linux_hardware -lib_deps = ${portduino_base.lib_deps} -build_src_filter = ${portduino_base.build_src_filter} - -; The Raspberry Pi actually has accessible SPI and GPIO, so we can support real hardware there. -[env:raspbian] -extends = portduino_base -build_flags = ${portduino_base.build_flags} -O0 -lgpiod -I variants/portduino -DARCH_RASPBERRY_PI -lyaml-cpp -board = linux_arm -lib_deps = ${portduino_base.lib_deps} - https://github.com/jp-bennett/LovyanGFX.git#jp-bennett-patch-1 ; lovyan03/LovyanGFX@^1.1.9 build_src_filter = ${portduino_base.build_src_filter} \ No newline at end of file From 6284f4ffe631e45cb8f7dd2116f8c40b5cf4d5f2 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sat, 13 Jan 2024 19:11:59 -0600 Subject: [PATCH 115/472] Update Linux binaries to use arch names (#3093) --- .github/workflows/build_raspbian.yml | 2 +- .github/workflows/main_matrix.yml | 2 +- .github/workflows/package_raspbian.yml | 2 +- Dockerfile | 4 ++-- bin/build-native.sh | 2 +- bin/native-install.sh | 2 +- 6 files changed, 7 insertions(+), 7 deletions(-) diff --git a/.github/workflows/build_raspbian.yml b/.github/workflows/build_raspbian.yml index 103f43a71..7a25892bc 100644 --- a/.github/workflows/build_raspbian.yml +++ b/.github/workflows/build_raspbian.yml @@ -41,5 +41,5 @@ jobs: with: name: firmware-raspbian-${{ steps.version.outputs.version }}.zip path: | - release/meshtasticd_linux_arm64 + release/meshtasticd_linux_aarch64 bin/config-dist.yaml diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index bd7d5f1be..c92ec06ea 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -245,7 +245,7 @@ jobs: id: version - name: Move files up - run: mv -b -t ./ ./*tbeam-2*/littlefs*.bin ./*tbeam-2*/bleota.bin ./*tbeam-s3*/bleota-s3.bin ./**/firmware*.bin ./*t-echo*/Meshtastic_nRF52_factory_erase.uf2 ./**/firmware-*.uf2 ./**/firmware-*-ota.zip ./**/*.elf ./*native*/*device-*.sh ./*native*/*device-*.bat ./firmware-raspbian-*/release/meshtasticd_linux_arm64 ./firmware-raspbian-*/bin/config-dist.yaml + run: mv -b -t ./ ./*tbeam-2*/littlefs*.bin ./*tbeam-2*/bleota.bin ./*tbeam-s3*/bleota-s3.bin ./**/firmware*.bin ./*t-echo*/Meshtastic_nRF52_factory_erase.uf2 ./**/firmware-*.uf2 ./**/firmware-*-ota.zip ./**/*.elf ./*native*/*device-*.sh ./*native*/*device-*.bat ./firmware-raspbian-*/release/meshtasticd_linux_aarch64 ./firmware-raspbian-*/bin/config-dist.yaml - name: Repackage in single firmware zip uses: actions/upload-artifact@v3 diff --git a/.github/workflows/package_raspbian.yml b/.github/workflows/package_raspbian.yml index 02b1ed5ad..2f9a99e58 100644 --- a/.github/workflows/package_raspbian.yml +++ b/.github/workflows/package_raspbian.yml @@ -40,7 +40,7 @@ jobs: mkdir -p .debpkg/usr/sbin mkdir -p .debpkg/etc/meshtasticd mkdir -p .debpkg/usr/lib/systemd/system/ - cp release/meshtasticd_linux .debpkg/usr/sbin/meshtasticd + cp release/meshtasticd_linux_aarch64 .debpkg/usr/sbin/meshtasticd cp bin/config-dist.yaml .debpkg/etc/meshtasticd/config.yaml chmod +x .debpkg/usr/sbin/meshtasticd cp bin/meshtasticd.service .debpkg/usr/lib/systemd/system/meshtasticd.service diff --git a/Dockerfile b/Dockerfile index 0ba5a07f9..21e42ad87 100644 --- a/Dockerfile +++ b/Dockerfile @@ -32,10 +32,10 @@ FROM frolvlad/alpine-glibc:glibc-2.31 RUN apk --update add --no-cache g++ shadow && \ groupadd -g 1000 mesh && useradd -ml -u 1000 -g 1000 mesh -COPY --from=builder /tmp/firmware/release/meshtasticd_linux_amd64 /home/mesh/ +COPY --from=builder /tmp/firmware/release/meshtasticd_linux_x86_64 /home/mesh/ USER mesh WORKDIR /home/mesh -CMD sh -cx "./meshtasticd_linux_amd64 --hwid '${HWID:-$RANDOM}'" +CMD sh -cx "./meshtasticd_linux_x86_64 --hwid '${HWID:-$RANDOM}'" HEALTHCHECK NONE \ No newline at end of file diff --git a/bin/build-native.sh b/bin/build-native.sh index dbec5bb95..7e9fcb632 100755 --- a/bin/build-native.sh +++ b/bin/build-native.sh @@ -15,6 +15,6 @@ rm -r $OUTDIR/* || true # Important to pull latest version of libs into all device flavors, otherwise some devices might be stale platformio pkg update pio run --environment native -cp .pio/build/native/program $OUTDIR/meshtasticd_linux +cp .pio/build/native/program "$OUTDIR/meshtasticd_linux_$(arch)" cp bin/device-install.* $OUTDIR cp bin/device-update.* $OUTDIR diff --git a/bin/native-install.sh b/bin/native-install.sh index afba04c6b..cc6d968f9 100755 --- a/bin/native-install.sh +++ b/bin/native-install.sh @@ -1,6 +1,6 @@ #!/usr/bin/env bash -cp release/meshtasticd_linux /usr/sbin/meshtasticd +cp "release/meshtasticd_linux_$(arch)" /usr/sbin/meshtasticd mkdir /etc/meshtasticd if [[ -f "/etc/meshtasticd/config.yaml" ]]; then cp bin/config-dist.yaml /etc/meshtasticd/config-upgrade.yaml From a7019b7206e4497eb35f493e10acb8190de74b1d Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 14 Jan 2024 14:38:57 -0600 Subject: [PATCH 116/472] Update for Radiolib 6.4.0 to fix build --- platformio.ini | 1 + 1 file changed, 1 insertion(+) diff --git a/platformio.ini b/platformio.ini index f017dccee..f6d9bcf35 100644 --- a/platformio.ini +++ b/platformio.ini @@ -51,6 +51,7 @@ build_flags = -Wno-missing-field-initializers -DRADIOLIB_EXCLUDE_NRF24 -DRADIOLIB_EXCLUDE_RF69 -DRADIOLIB_EXCLUDE_SX1231 + -DRADIOLIB_EXCLUDE_SX1233 -DRADIOLIB_EXCLUDE_SI443X -DRADIOLIB_EXCLUDE_RFM2X -DRADIOLIB_EXCLUDE_AFSK From 14736775e22961b5e2ca28464a7d108f3bd4181b Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 14 Jan 2024 14:51:37 -0600 Subject: [PATCH 117/472] Update define for RadioLib 6.4.0 --- src/mesh/SX128xInterface.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/mesh/SX128xInterface.cpp b/src/mesh/SX128xInterface.cpp index 47a79ea52..d0103ec29 100644 --- a/src/mesh/SX128xInterface.cpp +++ b/src/mesh/SX128xInterface.cpp @@ -252,7 +252,7 @@ template void SX128xInterface::startReceive() // We use the PREAMBLE_DETECTED and HEADER_VALID IRQ flag to detect whether we are actively receiving int err = lora.startReceive(RADIOLIB_SX128X_RX_TIMEOUT_INF, RADIOLIB_SX128X_IRQ_RX_DEFAULT | - RADIOLIB_SX128X_IRQ_RADIOLIB_PREAMBLE_DETECTED | + RADIOLIB_SX128X_IRQ_PREAMBLE_DETECTED | RADIOLIB_SX128X_IRQ_HEADER_VALID); assert(err == RADIOLIB_ERR_NONE); @@ -284,7 +284,7 @@ template bool SX128xInterface::isChannelActive() template bool SX128xInterface::isActivelyReceiving() { uint16_t irq = lora.getIrqStatus(); - bool detected = (irq & (RADIOLIB_SX128X_IRQ_HEADER_VALID | RADIOLIB_SX128X_IRQ_RADIOLIB_PREAMBLE_DETECTED)); + bool detected = (irq & (RADIOLIB_SX128X_IRQ_HEADER_VALID | RADIOLIB_SX128X_IRQ_PREAMBLE_DETECTED)); // Handle false detections if (detected) { @@ -327,4 +327,4 @@ template bool SX128xInterface::sleep() #endif return true; -} \ No newline at end of file +} From 30e3a28014d8a45a6aaf35939a207137dfc12d7e Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Mon, 15 Jan 2024 07:28:20 -0600 Subject: [PATCH 118/472] [create-pull-request] automated change (#3099) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/mesh.pb.h | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/protobufs b/protobufs index 1091250d2..a5d410d40 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 1091250d256d415df2a1b2644b4d282eab6570f4 +Subproject commit a5d410d40782d57efb1143250e8082124d1813f2 diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index ae80b3fe5..743cfe737 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -119,6 +119,8 @@ typedef enum _meshtastic_HardwareModel { meshtastic_HardwareModel_HELTEC_HT62 = 53, /* EBYTE SPI LoRa module and ESP32-S3 */ meshtastic_HardwareModel_EBYTE_ESP32_S3 = 54, + /* Waveshare ESP32-S3-PICO with PICO LoRa HAT and 2.9inch e-Ink */ + meshtastic_HardwareModel_ESP32_S3_PICO = 55, /* ------------------------------------------------------------------------------------------------------------------------------------------ Reserved ID For developing private Ports. These will show up in live traffic sparsely, so we can use a high number. Keep it within 8 bits. ------------------------------------------------------------------------------------------------------------------------------------------ */ From 8b362dee3a006637a6270baece6388994e9bbee2 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Mon, 15 Jan 2024 10:56:17 -0600 Subject: [PATCH 119/472] RadioLib 6.4.0 fixes (#3098) --- src/mesh/RadioLibRF95.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/mesh/RadioLibRF95.cpp b/src/mesh/RadioLibRF95.cpp index f84ec28b7..1fe7869a3 100644 --- a/src/mesh/RadioLibRF95.cpp +++ b/src/mesh/RadioLibRF95.cpp @@ -21,7 +21,7 @@ int16_t RadioLibRF95::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_ LOG_DEBUG("Current limit set result %d\n", state); // configure settings not accessible by API - state = config(); + // state = config(); RADIOLIB_ASSERT(state); #ifdef RF95_TCXO @@ -75,5 +75,6 @@ bool RadioLibRF95::isReceiving() uint8_t RadioLibRF95::readReg(uint8_t addr) { + Module *mod = this->getMod(); return mod->SPIreadRegister(addr); -} +} \ No newline at end of file From fd8b1687a1428b79e5070d2e62ab22b408f066ef Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Tue, 16 Jan 2024 03:11:35 +0100 Subject: [PATCH 120/472] Update channel of node in `updateUser` and write to flash if needed (#3094) Co-authored-by: Ben Meadors --- src/mesh/NodeDB.cpp | 23 +++++++++++------------ src/mesh/NodeDB.h | 4 ++-- src/modules/NodeInfoModule.cpp | 2 +- 3 files changed, 14 insertions(+), 15 deletions(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 1a619f34e..19ba7eb8b 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -796,22 +796,25 @@ void NodeDB::updateTelemetry(uint32_t nodeId, const meshtastic_Telemetry &t, RxS notifyObservers(true); // Force an update whether or not our node counts have changed } -/** Update user info for this node based on received user data +/** Update user info and channel for this node based on received user data */ -bool NodeDB::updateUser(uint32_t nodeId, const meshtastic_User &p) +bool NodeDB::updateUser(uint32_t nodeId, const meshtastic_User &p, uint8_t channelIndex) { meshtastic_NodeInfoLite *info = getOrCreateMeshNode(nodeId); if (!info) { return false; } - LOG_DEBUG("old user %s/%s/%s\n", info->user.id, info->user.long_name, info->user.short_name); + LOG_DEBUG("old user %s/%s/%s, channel=%d\n", info->user.id, info->user.long_name, info->user.short_name, info->channel); - bool changed = memcmp(&info->user, &p, - sizeof(info->user)); // Both of these blocks start as filled with zero so I think this is okay + // Both of info->user and p start as filled with zero so I think this is okay + bool changed = memcmp(&info->user, &p, sizeof(info->user)) || (info->channel != channelIndex); info->user = p; - LOG_DEBUG("updating changed=%d user %s/%s/%s\n", changed, info->user.id, info->user.long_name, info->user.short_name); + if (nodeId != getNodeNum()) + info->channel = channelIndex; // Set channel we need to use to reach this node (but don't set our own channel) + LOG_DEBUG("updating changed=%d user %s/%s/%s, channel=%d\n", changed, info->user.id, info->user.long_name, + info->user.short_name, info->channel); info->has_user = true; if (changed) { @@ -831,7 +834,7 @@ bool NodeDB::updateUser(uint32_t nodeId, const meshtastic_User &p) void NodeDB::updateFrom(const meshtastic_MeshPacket &mp) { if (mp.which_payload_variant == meshtastic_MeshPacket_decoded_tag && mp.from) { - LOG_DEBUG("Update DB node 0x%x, rx_time=%u, channel=%d\n", mp.from, mp.rx_time, mp.channel); + LOG_DEBUG("Update DB node 0x%x, rx_time=%u\n", mp.from, mp.rx_time); meshtastic_NodeInfoLite *info = getOrCreateMeshNode(getFrom(&mp)); if (!info) { @@ -843,10 +846,6 @@ void NodeDB::updateFrom(const meshtastic_MeshPacket &mp) if (mp.rx_snr) info->snr = mp.rx_snr; // keep the most recent SNR we received for this node. - - if (mp.decoded.portnum == meshtastic_PortNum_NODEINFO_APP) { - info->channel = mp.channel; - } } } @@ -926,4 +925,4 @@ void recordCriticalError(meshtastic_CriticalErrorCode code, uint32_t address, co LOG_ERROR("A critical failure occurred, portduino is exiting..."); exit(2); #endif -} \ No newline at end of file +} diff --git a/src/mesh/NodeDB.h b/src/mesh/NodeDB.h index 47d143cd9..e24a971c1 100644 --- a/src/mesh/NodeDB.h +++ b/src/mesh/NodeDB.h @@ -84,9 +84,9 @@ class NodeDB */ void updateTelemetry(uint32_t nodeId, const meshtastic_Telemetry &t, RxSource src = RX_SRC_RADIO); - /** Update user info for this node based on received user data + /** Update user info and channel for this node based on received user data */ - bool updateUser(uint32_t nodeId, const meshtastic_User &p); + bool updateUser(uint32_t nodeId, const meshtastic_User &p, uint8_t channelIndex = 0); /// @return our node number NodeNum getNodeNum() { return myNodeInfo.my_node_num; } diff --git a/src/modules/NodeInfoModule.cpp b/src/modules/NodeInfoModule.cpp index c266f235c..b0b4bbdcd 100644 --- a/src/modules/NodeInfoModule.cpp +++ b/src/modules/NodeInfoModule.cpp @@ -12,7 +12,7 @@ bool NodeInfoModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes { auto p = *pptr; - bool hasChanged = nodeDB.updateUser(getFrom(&mp), p); + bool hasChanged = nodeDB.updateUser(getFrom(&mp), p, mp.channel); bool wasBroadcast = mp.to == NODENUM_BROADCAST; From 4056d34bed8e7eeb754d20f73d22fae10356d1c7 Mon Sep 17 00:00:00 2001 From: Andre K Date: Wed, 17 Jan 2024 21:14:44 -0300 Subject: [PATCH 121/472] fix: `ipv4_config` byte order already little endian (#3073) Co-authored-by: Ben Meadors --- src/mesh/eth/ethClient.cpp | 14 +------------- 1 file changed, 1 insertion(+), 13 deletions(-) diff --git a/src/mesh/eth/ethClient.cpp b/src/mesh/eth/ethClient.cpp index f10c96866..97f5027bd 100644 --- a/src/mesh/eth/ethClient.cpp +++ b/src/mesh/eth/ethClient.cpp @@ -97,11 +97,6 @@ static int32_t reconnectETH() return 5000; // every 5 seconds } -static uint32_t bigToLittleEndian(uint32_t value) -{ - return ((value >> 24) & 0xFF) | ((value >> 8) & 0xFF00) | ((value << 8) & 0xFF0000) | ((value << 24) & 0xFF000000); -} - // Startup Ethernet bool initEthernet() { @@ -130,14 +125,7 @@ bool initEthernet() status = Ethernet.begin(mac); } else if (config.network.address_mode == meshtastic_Config_NetworkConfig_AddressMode_STATIC) { LOG_INFO("starting Ethernet Static\n"); - - IPAddress ip = IPAddress(bigToLittleEndian(config.network.ipv4_config.ip)); - IPAddress dns = IPAddress(bigToLittleEndian(config.network.ipv4_config.dns)); - IPAddress gateway = IPAddress(bigToLittleEndian(config.network.ipv4_config.gateway)); - IPAddress subnet = IPAddress(bigToLittleEndian(config.network.ipv4_config.subnet)); - - Ethernet.begin(mac, ip, dns, gateway, subnet); - + Ethernet.begin(mac, config.network.ipv4_config.ip, config.network.ipv4_config.dns, config.network.ipv4_config.subnet); status = 1; } else { LOG_INFO("Ethernet Disabled\n"); From a8b7490b6e456dd01ad710b6b1209d22a4ec82de Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Wed, 17 Jan 2024 18:15:00 -0600 Subject: [PATCH 122/472] [create-pull-request] automated change (#3106) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/mesh.pb.h | 4 ++++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/protobufs b/protobufs index a5d410d40..092f7c043 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit a5d410d40782d57efb1143250e8082124d1813f2 +Subproject commit 092f7c04305e6d8b6d4417a127fba695546857d8 diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index 743cfe737..69550296f 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -121,6 +121,10 @@ typedef enum _meshtastic_HardwareModel { meshtastic_HardwareModel_EBYTE_ESP32_S3 = 54, /* Waveshare ESP32-S3-PICO with PICO LoRa HAT and 2.9inch e-Ink */ meshtastic_HardwareModel_ESP32_S3_PICO = 55, + /* CircuitMess Chatter 2 LLCC68 Lora Module and ESP32 Wroom + Lora module can be swapped out for a Heltec RA-62 which is "almost" pin compatible + with one cut and one jumper Meshtastic works */ + meshtastic_HardwareModel_CHATTER_2 = 56, /* ------------------------------------------------------------------------------------------------------------------------------------------ Reserved ID For developing private Ports. These will show up in live traffic sparsely, so we can use a high number. Keep it within 8 bits. ------------------------------------------------------------------------------------------------------------------------------------------ */ From e2a3b0306fa63a1ec1ba3ffabfd9226177b1bc46 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 19 Jan 2024 07:40:14 -0600 Subject: [PATCH 123/472] Default mqtt root to msh/region from unset (#3111) * Default mqtt root to msh/region from unset * Correct segments --- src/modules/AdminModule.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index 0b1e72f9a..e19701798 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -280,6 +280,7 @@ void AdminModule::handleSetOwner(const meshtastic_User &o) void AdminModule::handleSetConfig(const meshtastic_Config &c) { + auto changes = SEGMENT_CONFIG; auto existingRole = config.device.role; bool isRegionUnset = (config.lora.region == meshtastic_Config_LoRaConfig_RegionCode_UNSET); @@ -320,6 +321,11 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c) config.lora = c.payload_variant.lora; if (isRegionUnset && config.lora.region > meshtastic_Config_LoRaConfig_RegionCode_UNSET) { config.lora.tx_enabled = true; + initRegion(); + if (strcmp(moduleConfig.mqtt.root, default_mqtt_root) == 0) { + sprintf(moduleConfig.mqtt.root, "%s/%s", default_mqtt_root, myRegion->name); + changes = SEGMENT_CONFIG | SEGMENT_MODULECONFIG; + } } break; case meshtastic_Config_bluetooth_tag: @@ -329,7 +335,7 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c) break; } - saveChanges(SEGMENT_CONFIG); + saveChanges(changes); } void AdminModule::handleSetModuleConfig(const meshtastic_ModuleConfig &c) @@ -715,4 +721,4 @@ AdminModule::AdminModule() : ProtobufModule("Admin", meshtastic_PortNum_ADMIN_AP { // restrict to the admin channel for rx boundChannel = Channels::adminChannel; -} +} \ No newline at end of file From 751bdf94aa18014bd61c5a0eaa802312decf6bd1 Mon Sep 17 00:00:00 2001 From: orange Date: Fri, 19 Jan 2024 16:28:26 +0000 Subject: [PATCH 124/472] Initial Partial Updates on t-echo (#3090) Co-authored-by: Jonathan Bennett Co-authored-by: Ben Meadors --- src/graphics/EInkDisplay2.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index eb716ac03..787b47e1f 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -55,7 +55,7 @@ GxEPD2_BW *adafruitDisplay; EInkDisplay::EInkDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY geometry, HW_I2C i2cBus) { #if defined(TTGO_T_ECHO) - setGeometry(GEOMETRY_RAWMODE, TECHO_DISPLAY_MODEL::WIDTH, TECHO_DISPLAY_MODEL::HEIGHT); + setGeometry(GEOMETRY_RAWMODE, 200, 200); #elif defined(RAK4630) // GxEPD2_213_BN - RAK14000 2.13 inch b/w 250x122 @@ -129,8 +129,7 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit) LOG_DEBUG("Updating E-Paper... "); #if defined(TTGO_T_ECHO) - // ePaper.Reset(); // wake the screen from sleep - adafruitDisplay->display(false); // FIXME, use partial update mode + adafruitDisplay->nextPage(); #elif defined(RAK4630) || defined(MAKERPYTHON) // RAK14000 2.13 inch b/w 250x122 actually now does support partial updates @@ -210,6 +209,7 @@ bool EInkDisplay::connect() adafruitDisplay = new GxEPD2_BW(*lowLevel); adafruitDisplay->init(); adafruitDisplay->setRotation(3); + adafruitDisplay->setPartialWindow(0, 0, displayWidth, displayHeight); } #elif defined(RAK4630) || defined(MAKERPYTHON) { @@ -274,4 +274,4 @@ bool EInkDisplay::connect() return true; } -#endif +#endif \ No newline at end of file From b489ee08c85839ba8361be08865fd8396593ed34 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 19 Jan 2024 10:53:00 -0600 Subject: [PATCH 125/472] Update radiolib --- platformio.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platformio.ini b/platformio.ini index f6d9bcf35..ffc9b73a0 100644 --- a/platformio.ini +++ b/platformio.ini @@ -69,7 +69,7 @@ build_flags = -Wno-missing-field-initializers monitor_speed = 115200 lib_deps = - jgromes/RadioLib@^6.3.0 + jgromes/RadioLib@^6.4.0 https://github.com/meshtastic/esp8266-oled-ssd1306.git#b38094e03dfa964fbc0e799bc374e91a605c1223 ; ESP8266_SSD1306 mathertel/OneButton@^2.5.0 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 From af157d276a507693d76d24b6dda0e72b0a1732d5 Mon Sep 17 00:00:00 2001 From: Manuel <71137295+mverch67@users.noreply.github.com> Date: Fri, 19 Jan 2024 20:11:19 +0100 Subject: [PATCH 126/472] fix T-Watch flip screen (#3113) --- boards/t-watch-s3.json | 5 ++++- src/graphics/Screen.cpp | 4 ++++ 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/boards/t-watch-s3.json b/boards/t-watch-s3.json index 080389f39..e6e363305 100644 --- a/boards/t-watch-s3.json +++ b/boards/t-watch-s3.json @@ -16,7 +16,10 @@ "f_cpu": "240000000L", "f_flash": "80000000L", "flash_mode": "qio", - "hwids": [["0x303A", "0x1001"]], + "hwids": [ + ["0x303A", "0x1001"], + ["0x303A", "0x0002"] + ], "mcu": "esp32s3", "variant": "t-watch-s3" }, diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 00880ad05..fb27e3c01 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -1052,7 +1052,11 @@ void Screen::setup() // Standard behaviour is to FLIP the screen (needed on T-Beam). If this config item is set, unflip it, and thereby logically // flip it. If you have a headache now, you're welcome. if (!config.display.flip_screen) { +#if defined(ST7735_CS) || defined(ILI9341_DRIVER) || defined(ST7789_CS) || defined(RAK14014) + static_cast(dispdev)->flipScreenVertically(); +#else dispdev->flipScreenVertically(); +#endif } #endif From 2efaaea6257d9dd149149b46b46464930bf4a99b Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 19 Jan 2024 13:14:27 -0600 Subject: [PATCH 127/472] Update oled dep to include RP2040 fix (#3112) --- platformio.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platformio.ini b/platformio.ini index ffc9b73a0..e3204f4d9 100644 --- a/platformio.ini +++ b/platformio.ini @@ -70,7 +70,7 @@ monitor_speed = 115200 lib_deps = jgromes/RadioLib@^6.4.0 - https://github.com/meshtastic/esp8266-oled-ssd1306.git#b38094e03dfa964fbc0e799bc374e91a605c1223 ; ESP8266_SSD1306 + https://github.com/meshtastic/esp8266-oled-ssd1306.git#ee628ee6c9588d4c56c9e3da35f0fc9448ad54a8 ; ESP8266_SSD1306 mathertel/OneButton@^2.5.0 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 https://github.com/meshtastic/TinyGPSPlus.git#076e8d2c8fb702d9be5b08c55b93ff76f8af7e61 From 486bf796906d6237e4d29f0bd7d90144979e2f9e Mon Sep 17 00:00:00 2001 From: rcarteraz Date: Fri, 19 Jan 2024 12:41:24 -0700 Subject: [PATCH 128/472] update default (#3114) Co-authored-by: Ben Meadors --- src/modules/ExternalNotificationModule.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/ExternalNotificationModule.cpp b/src/modules/ExternalNotificationModule.cpp index bdbe044b5..9af1f9e00 100644 --- a/src/modules/ExternalNotificationModule.cpp +++ b/src/modules/ExternalNotificationModule.cpp @@ -288,7 +288,7 @@ ExternalNotificationModule::ExternalNotificationModule() &meshtastic_RTTTLConfig_msg, &rtttlConfig)) { memset(rtttlConfig.ringtone, 0, sizeof(rtttlConfig.ringtone)); strncpy(rtttlConfig.ringtone, - "a:d=8,o=5,b=125:4d#6,a#,2d#6,16p,g#,4a#,4d#.,p,16g,16a#,d#6,a#,f6,2d#6,16p,c#.6,16c6,16a#,g#.,2a#", + "24:d=32,o=5,b=565:f6,p,f6,4p,p,f6,p,f6,2p,p,b6,p,b6,p,b6,p,b6,p,b,p,b,p,b,p,b,p,b,p,b,p,b,p,b,1p.,2p.,p", sizeof(rtttlConfig.ringtone)); } From 4f76239d4867482a4fdb443b31c273995b870cbf Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sat, 20 Jan 2024 09:40:28 -0600 Subject: [PATCH 129/472] [create-pull-request] automated change (#3118) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/apponly.pb.h | 2 +- src/mesh/generated/meshtastic/config.pb.h | 12 ++++++++---- src/mesh/generated/meshtastic/deviceonly.pb.h | 4 ++-- src/mesh/generated/meshtastic/localonly.pb.h | 2 +- src/mesh/generated/meshtastic/mesh.pb.h | 12 ++++++++---- 6 files changed, 21 insertions(+), 13 deletions(-) diff --git a/protobufs b/protobufs index 092f7c043..44e369e18 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 092f7c04305e6d8b6d4417a127fba695546857d8 +Subproject commit 44e369e1813f8ec9c7aefe1aac7d0adc75e11f8a diff --git a/src/mesh/generated/meshtastic/apponly.pb.h b/src/mesh/generated/meshtastic/apponly.pb.h index b66af0ebd..c9c120efa 100644 --- a/src/mesh/generated/meshtastic/apponly.pb.h +++ b/src/mesh/generated/meshtastic/apponly.pb.h @@ -54,7 +54,7 @@ extern const pb_msgdesc_t meshtastic_ChannelSet_msg; #define meshtastic_ChannelSet_fields &meshtastic_ChannelSet_msg /* Maximum encoded size of messages (where known) */ -#define meshtastic_ChannelSet_size 591 +#define meshtastic_ChannelSet_size 594 #ifdef __cplusplus } /* extern "C" */ diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index c86da50f9..25e8d476c 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -463,6 +463,8 @@ typedef struct _meshtastic_Config_LoRaConfig { in ignore_incoming will have packets they send dropped on receive (by router.cpp) */ pb_size_t ignore_incoming_count; uint32_t ignore_incoming[3]; + /* If true, the device will not process any packets received via LoRa that passed via MQTT anywhere on the path towards it. */ + bool ignore_mqtt; } meshtastic_Config_LoRaConfig; typedef struct _meshtastic_Config_BluetoothConfig { @@ -565,7 +567,7 @@ extern "C" { #define meshtastic_Config_NetworkConfig_init_default {0, "", "", "", 0, _meshtastic_Config_NetworkConfig_AddressMode_MIN, false, meshtastic_Config_NetworkConfig_IpV4Config_init_default, ""} #define meshtastic_Config_NetworkConfig_IpV4Config_init_default {0, 0, 0, 0} #define meshtastic_Config_DisplayConfig_init_default {0, _meshtastic_Config_DisplayConfig_GpsCoordinateFormat_MIN, 0, 0, 0, _meshtastic_Config_DisplayConfig_DisplayUnits_MIN, _meshtastic_Config_DisplayConfig_OledType_MIN, _meshtastic_Config_DisplayConfig_DisplayMode_MIN, 0, 0} -#define meshtastic_Config_LoRaConfig_init_default {0, _meshtastic_Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, _meshtastic_Config_LoRaConfig_RegionCode_MIN, 0, 0, 0, 0, 0, 0, 0, 0, {0, 0, 0}} +#define meshtastic_Config_LoRaConfig_init_default {0, _meshtastic_Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, _meshtastic_Config_LoRaConfig_RegionCode_MIN, 0, 0, 0, 0, 0, 0, 0, 0, {0, 0, 0}, 0} #define meshtastic_Config_BluetoothConfig_init_default {0, _meshtastic_Config_BluetoothConfig_PairingMode_MIN, 0} #define meshtastic_Config_init_zero {0, {meshtastic_Config_DeviceConfig_init_zero}} #define meshtastic_Config_DeviceConfig_init_zero {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0, 0} @@ -574,7 +576,7 @@ extern "C" { #define meshtastic_Config_NetworkConfig_init_zero {0, "", "", "", 0, _meshtastic_Config_NetworkConfig_AddressMode_MIN, false, meshtastic_Config_NetworkConfig_IpV4Config_init_zero, ""} #define meshtastic_Config_NetworkConfig_IpV4Config_init_zero {0, 0, 0, 0} #define meshtastic_Config_DisplayConfig_init_zero {0, _meshtastic_Config_DisplayConfig_GpsCoordinateFormat_MIN, 0, 0, 0, _meshtastic_Config_DisplayConfig_DisplayUnits_MIN, _meshtastic_Config_DisplayConfig_OledType_MIN, _meshtastic_Config_DisplayConfig_DisplayMode_MIN, 0, 0} -#define meshtastic_Config_LoRaConfig_init_zero {0, _meshtastic_Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, _meshtastic_Config_LoRaConfig_RegionCode_MIN, 0, 0, 0, 0, 0, 0, 0, 0, {0, 0, 0}} +#define meshtastic_Config_LoRaConfig_init_zero {0, _meshtastic_Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, _meshtastic_Config_LoRaConfig_RegionCode_MIN, 0, 0, 0, 0, 0, 0, 0, 0, {0, 0, 0}, 0} #define meshtastic_Config_BluetoothConfig_init_zero {0, _meshtastic_Config_BluetoothConfig_PairingMode_MIN, 0} /* Field tags (for use in manual encoding/decoding) */ @@ -645,6 +647,7 @@ extern "C" { #define meshtastic_Config_LoRaConfig_sx126x_rx_boosted_gain_tag 13 #define meshtastic_Config_LoRaConfig_override_frequency_tag 14 #define meshtastic_Config_LoRaConfig_ignore_incoming_tag 103 +#define meshtastic_Config_LoRaConfig_ignore_mqtt_tag 104 #define meshtastic_Config_BluetoothConfig_enabled_tag 1 #define meshtastic_Config_BluetoothConfig_mode_tag 2 #define meshtastic_Config_BluetoothConfig_fixed_pin_tag 3 @@ -767,7 +770,8 @@ X(a, STATIC, SINGULAR, UINT32, channel_num, 11) \ X(a, STATIC, SINGULAR, BOOL, override_duty_cycle, 12) \ X(a, STATIC, SINGULAR, BOOL, sx126x_rx_boosted_gain, 13) \ X(a, STATIC, SINGULAR, FLOAT, override_frequency, 14) \ -X(a, STATIC, REPEATED, UINT32, ignore_incoming, 103) +X(a, STATIC, REPEATED, UINT32, ignore_incoming, 103) \ +X(a, STATIC, SINGULAR, BOOL, ignore_mqtt, 104) #define meshtastic_Config_LoRaConfig_CALLBACK NULL #define meshtastic_Config_LoRaConfig_DEFAULT NULL @@ -803,7 +807,7 @@ extern const pb_msgdesc_t meshtastic_Config_BluetoothConfig_msg; #define meshtastic_Config_BluetoothConfig_size 10 #define meshtastic_Config_DeviceConfig_size 32 #define meshtastic_Config_DisplayConfig_size 28 -#define meshtastic_Config_LoRaConfig_size 77 +#define meshtastic_Config_LoRaConfig_size 80 #define meshtastic_Config_NetworkConfig_IpV4Config_size 20 #define meshtastic_Config_NetworkConfig_size 196 #define meshtastic_Config_PositionConfig_size 60 diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index ef5045e2e..6318d7d71 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -313,10 +313,10 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg; /* Maximum encoded size of messages (where known) */ #define meshtastic_ChannelFile_size 638 -#define meshtastic_DeviceState_size 17056 +#define meshtastic_DeviceState_size 17062 #define meshtastic_NodeInfoLite_size 153 #define meshtastic_NodeRemoteHardwarePin_size 29 -#define meshtastic_OEMStore_size 3241 +#define meshtastic_OEMStore_size 3244 #define meshtastic_PositionLite_size 28 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/localonly.pb.h b/src/mesh/generated/meshtastic/localonly.pb.h index 3f8751653..50772308c 100644 --- a/src/mesh/generated/meshtastic/localonly.pb.h +++ b/src/mesh/generated/meshtastic/localonly.pb.h @@ -180,7 +180,7 @@ extern const pb_msgdesc_t meshtastic_LocalModuleConfig_msg; #define meshtastic_LocalModuleConfig_fields &meshtastic_LocalModuleConfig_msg /* Maximum encoded size of messages (where known) */ -#define meshtastic_LocalConfig_size 464 +#define meshtastic_LocalConfig_size 467 #define meshtastic_LocalModuleConfig_size 631 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index 69550296f..a00273eb4 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -577,6 +577,8 @@ typedef struct _meshtastic_MeshPacket { int32_t rx_rssi; /* Describe if this message is delayed */ meshtastic_MeshPacket_Delayed delayed; + /* Describes whether this packet passed via MQTT somewhere along the path it currently took. */ + bool via_mqtt; } meshtastic_MeshPacket; /* The bluetooth to device link: @@ -873,7 +875,7 @@ extern "C" { #define meshtastic_Data_init_default {_meshtastic_PortNum_MIN, {0, {0}}, 0, 0, 0, 0, 0, 0} #define meshtastic_Waypoint_init_default {0, 0, 0, 0, 0, "", "", 0} #define meshtastic_MqttClientProxyMessage_init_default {"", 0, {{0, {0}}}, 0} -#define meshtastic_MeshPacket_init_default {0, 0, 0, 0, {meshtastic_Data_init_default}, 0, 0, 0, 0, 0, _meshtastic_MeshPacket_Priority_MIN, 0, _meshtastic_MeshPacket_Delayed_MIN} +#define meshtastic_MeshPacket_init_default {0, 0, 0, 0, {meshtastic_Data_init_default}, 0, 0, 0, 0, 0, _meshtastic_MeshPacket_Priority_MIN, 0, _meshtastic_MeshPacket_Delayed_MIN, 0} #define meshtastic_NodeInfo_init_default {0, false, meshtastic_User_init_default, false, meshtastic_Position_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0} #define meshtastic_MyNodeInfo_init_default {0, 0, 0} #define meshtastic_LogRecord_init_default {"", 0, "", _meshtastic_LogRecord_Level_MIN} @@ -891,7 +893,7 @@ extern "C" { #define meshtastic_Data_init_zero {_meshtastic_PortNum_MIN, {0, {0}}, 0, 0, 0, 0, 0, 0} #define meshtastic_Waypoint_init_zero {0, 0, 0, 0, 0, "", "", 0} #define meshtastic_MqttClientProxyMessage_init_zero {"", 0, {{0, {0}}}, 0} -#define meshtastic_MeshPacket_init_zero {0, 0, 0, 0, {meshtastic_Data_init_zero}, 0, 0, 0, 0, 0, _meshtastic_MeshPacket_Priority_MIN, 0, _meshtastic_MeshPacket_Delayed_MIN} +#define meshtastic_MeshPacket_init_zero {0, 0, 0, 0, {meshtastic_Data_init_zero}, 0, 0, 0, 0, 0, _meshtastic_MeshPacket_Priority_MIN, 0, _meshtastic_MeshPacket_Delayed_MIN, 0} #define meshtastic_NodeInfo_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_Position_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0} #define meshtastic_MyNodeInfo_init_zero {0, 0, 0} #define meshtastic_LogRecord_init_zero {"", 0, "", _meshtastic_LogRecord_Level_MIN} @@ -970,6 +972,7 @@ extern "C" { #define meshtastic_MeshPacket_priority_tag 11 #define meshtastic_MeshPacket_rx_rssi_tag 12 #define meshtastic_MeshPacket_delayed_tag 13 +#define meshtastic_MeshPacket_via_mqtt_tag 14 #define meshtastic_NodeInfo_num_tag 1 #define meshtastic_NodeInfo_user_tag 2 #define meshtastic_NodeInfo_position_tag 3 @@ -1125,7 +1128,8 @@ X(a, STATIC, SINGULAR, UINT32, hop_limit, 9) \ X(a, STATIC, SINGULAR, BOOL, want_ack, 10) \ X(a, STATIC, SINGULAR, UENUM, priority, 11) \ X(a, STATIC, SINGULAR, INT32, rx_rssi, 12) \ -X(a, STATIC, SINGULAR, UENUM, delayed, 13) +X(a, STATIC, SINGULAR, UENUM, delayed, 13) \ +X(a, STATIC, SINGULAR, BOOL, via_mqtt, 14) #define meshtastic_MeshPacket_CALLBACK NULL #define meshtastic_MeshPacket_DEFAULT NULL #define meshtastic_MeshPacket_payload_variant_decoded_MSGTYPE meshtastic_Data @@ -1290,7 +1294,7 @@ extern const pb_msgdesc_t meshtastic_DeviceMetadata_msg; #define meshtastic_DeviceMetadata_size 46 #define meshtastic_FromRadio_size 510 #define meshtastic_LogRecord_size 81 -#define meshtastic_MeshPacket_size 321 +#define meshtastic_MeshPacket_size 323 #define meshtastic_MqttClientProxyMessage_size 501 #define meshtastic_MyNodeInfo_size 18 #define meshtastic_NeighborInfo_size 258 From 8f6a2836b8ad5f8ba63a257586e888beab8297fb Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Sat, 20 Jan 2024 21:22:09 +0100 Subject: [PATCH 130/472] Mark packets received via MQTT and add option to ignore them (#3117) * Mark packets received via MQTT and add option to ignore them * Don't send packets received via MQTT back into MQTT Generate implicit ACK for packets we as an MQTT gateway sent --------- Co-authored-by: Ben Meadors --- src/mesh/NodeDB.cpp | 1 + src/mesh/RadioInterface.cpp | 15 +++++++-------- src/mesh/RadioInterface.h | 3 ++- src/mesh/RadioLibInterface.cpp | 3 ++- src/mesh/Router.cpp | 6 +++--- src/modules/TraceRouteModule.cpp | 2 +- src/mqtt/MQTT.cpp | 11 +++++++++++ 7 files changed, 27 insertions(+), 14 deletions(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 19ba7eb8b..5649bfd7a 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -173,6 +173,7 @@ void NodeDB::installDefaultConfig() config.lora.region = meshtastic_Config_LoRaConfig_RegionCode_UNSET; config.lora.modem_preset = meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST; config.lora.hop_limit = HOP_RELIABLE; + config.lora.ignore_mqtt = false; #ifdef PIN_GPS_EN config.position.gps_en_gpio = PIN_GPS_EN; #endif diff --git a/src/mesh/RadioInterface.cpp b/src/mesh/RadioInterface.cpp index 91bd93bc5..fe39f9b55 100644 --- a/src/mesh/RadioInterface.cpp +++ b/src/mesh/RadioInterface.cpp @@ -287,15 +287,14 @@ void printPacket(const char *prefix, const meshtastic_MeshPacket *p) out += " encrypted"; } - if (p->rx_time != 0) { + if (p->rx_time != 0) out += DEBUG_PORT.mt_sprintf(" rxtime=%u", p->rx_time); - } - if (p->rx_snr != 0.0) { + if (p->rx_snr != 0.0) out += DEBUG_PORT.mt_sprintf(" rxSNR=%g", p->rx_snr); - } - if (p->rx_rssi != 0) { + if (p->rx_rssi != 0) out += DEBUG_PORT.mt_sprintf(" rxRSSI=%i", p->rx_rssi); - } + if (p->via_mqtt != 0) + out += DEBUG_PORT.mt_sprintf(" via MQTT"); if (p->priority != 0) out += DEBUG_PORT.mt_sprintf(" priority=%d", p->priority); @@ -554,7 +553,7 @@ size_t RadioInterface::beginSending(meshtastic_MeshPacket *p) LOG_WARN("hop limit %d is too high, setting to %d\n", p->hop_limit, HOP_RELIABLE); p->hop_limit = HOP_RELIABLE; } - h->flags = p->hop_limit | (p->want_ack ? PACKET_FLAGS_WANT_ACK_MASK : 0); + h->flags = p->hop_limit | (p->want_ack ? PACKET_FLAGS_WANT_ACK_MASK : 0) | (p->via_mqtt ? PACKET_FLAGS_VIA_MQTT_MASK : 0); // if the sender nodenum is zero, that means uninitialized assert(h->from); @@ -563,4 +562,4 @@ size_t RadioInterface::beginSending(meshtastic_MeshPacket *p) sendingPacket = p; return p->encrypted.size + sizeof(PacketHeader); -} \ No newline at end of file +} diff --git a/src/mesh/RadioInterface.h b/src/mesh/RadioInterface.h index 85ce116dc..83c5dae64 100644 --- a/src/mesh/RadioInterface.h +++ b/src/mesh/RadioInterface.h @@ -12,6 +12,7 @@ #define PACKET_FLAGS_HOP_MASK 0x07 #define PACKET_FLAGS_WANT_ACK_MASK 0x08 +#define PACKET_FLAGS_VIA_MQTT_MASK 0x10 /** * This structure has to exactly match the wire layout when sent over the radio link. Used to keep compatibility @@ -223,4 +224,4 @@ class RadioInterface }; /// Debug printing for packets -void printPacket(const char *prefix, const meshtastic_MeshPacket *p); \ No newline at end of file +void printPacket(const char *prefix, const meshtastic_MeshPacket *p); diff --git a/src/mesh/RadioLibInterface.cpp b/src/mesh/RadioLibInterface.cpp index 4f0c52e67..8a2bc53e5 100644 --- a/src/mesh/RadioLibInterface.cpp +++ b/src/mesh/RadioLibInterface.cpp @@ -362,6 +362,7 @@ void RadioLibInterface::handleReceiveInterrupt() assert(HOP_MAX <= PACKET_FLAGS_HOP_MASK); // If hopmax changes, carefully check this code mp->hop_limit = h->flags & PACKET_FLAGS_HOP_MASK; mp->want_ack = !!(h->flags & PACKET_FLAGS_WANT_ACK_MASK); + mp->via_mqtt = !!(h->flags & PACKET_FLAGS_VIA_MQTT_MASK); addReceiveMetadata(mp); @@ -406,4 +407,4 @@ void RadioLibInterface::startSend(meshtastic_MeshPacket *txp) // bits enableInterrupt(isrTxLevel0); } -} \ No newline at end of file +} diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp index ff657fd11..977a1215a 100644 --- a/src/mesh/Router.cpp +++ b/src/mesh/Router.cpp @@ -467,10 +467,10 @@ void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src) void Router::perhapsHandleReceived(meshtastic_MeshPacket *p) { // assert(radioConfig.has_preferences); - bool ignore = is_in_repeated(config.lora.ignore_incoming, p->from); + bool ignore = is_in_repeated(config.lora.ignore_incoming, p->from) || (config.lora.ignore_mqtt && p->via_mqtt); if (ignore) { - LOG_DEBUG("Ignoring incoming message, 0x%x is in our ignore list\n", p->from); + LOG_DEBUG("Ignoring incoming message, 0x%x is in our ignore list or came via MQTT\n", p->from); } else if (ignore |= shouldFilterReceived(p)) { LOG_DEBUG("Incoming message was filtered 0x%x\n", p->from); } @@ -481,4 +481,4 @@ void Router::perhapsHandleReceived(meshtastic_MeshPacket *p) handleReceived(p); packetPool.release(p); -} \ No newline at end of file +} diff --git a/src/modules/TraceRouteModule.cpp b/src/modules/TraceRouteModule.cpp index bf7eaa0cd..311e211f3 100644 --- a/src/modules/TraceRouteModule.cpp +++ b/src/modules/TraceRouteModule.cpp @@ -85,4 +85,4 @@ TraceRouteModule::TraceRouteModule() : ProtobufModule("traceroute", meshtastic_PortNum_TRACEROUTE_APP, &meshtastic_RouteDiscovery_msg) { ourPortNum = meshtastic_PortNum_TRACEROUTE_APP; -} +} \ No newline at end of file diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index ccde03147..c91bdef29 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -7,6 +7,7 @@ #include "mesh/Router.h" #include "mesh/generated/meshtastic/mqtt.pb.h" #include "mesh/generated/meshtastic/telemetry.pb.h" +#include "modules/RoutingModule.h" #if defined(ARCH_ESP32) #include "../mesh/generated/meshtastic/paxcount.pb.h" #endif @@ -142,6 +143,7 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length) if (strcmp(e.channel_id, channels.getGlobalId(ch.index)) == 0 && e.packet && ch.settings.downlink_enabled) { LOG_INFO("Received MQTT topic %s, len=%u\n", topic, length); meshtastic_MeshPacket *p = packetPool.allocCopy(*e.packet); + p->via_mqtt = true; // Mark that the packet was received via MQTT if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) { p->channel = ch.index; @@ -463,6 +465,9 @@ void MQTT::publishQueuedMessages() void MQTT::onSend(const meshtastic_MeshPacket &mp, ChannelIndex chIndex) { + if (mp.via_mqtt) + return; // Don't send messages that came from MQTT back into MQTT + auto &ch = channels.getByIndex(chIndex); if (&mp.decoded && strcmp(moduleConfig.mqtt.address, default_mqtt_address) == 0 && @@ -501,6 +506,12 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, ChannelIndex chIndex) publish(topicJson.c_str(), jsonString.c_str(), false); } } + + // Generate an implicit ACK towards ourselves (handled and processed only locally!) for this message. + // We do this because packets are not rebroadcasted back into MQTT anymore and we assume that at least one node + // receives it when we're connected to the broker. Then we'll stop our retransmissions. + if (getFrom(&mp) == nodeDB.getNodeNum()) + routingModule->sendAckNak(meshtastic_Routing_Error_NONE, getFrom(&mp), mp.id, chIndex); } else { LOG_INFO("MQTT not connected, queueing packet\n"); if (mqttQueue.numFree() == 0) { From bccc0d47eb1fa84903df2387e64dad602fd2942a Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sat, 20 Jan 2024 19:11:21 -0600 Subject: [PATCH 131/472] [create-pull-request] automated change (#3119) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 59d4670c7..89c0e3d50 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 2 -build = 19 +build = 20 From 062c6468142d9466a0b18b53253f11a775aab211 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 21 Jan 2024 19:13:54 -0600 Subject: [PATCH 132/472] TinyGPS fix for empty terms (#3120) --- platformio.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platformio.ini b/platformio.ini index e3204f4d9..bd5b1e07f 100644 --- a/platformio.ini +++ b/platformio.ini @@ -73,7 +73,7 @@ lib_deps = https://github.com/meshtastic/esp8266-oled-ssd1306.git#ee628ee6c9588d4c56c9e3da35f0fc9448ad54a8 ; ESP8266_SSD1306 mathertel/OneButton@^2.5.0 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 - https://github.com/meshtastic/TinyGPSPlus.git#076e8d2c8fb702d9be5b08c55b93ff76f8af7e61 + https://github.com/meshtastic/TinyGPSPlus.git#2044b2c51e91ab4cd8cc93b15e40658cd808dd06 https://github.com/meshtastic/ArduinoThread.git#72921ac222eed6f526ba1682023cee290d9aa1b3 nanopb/Nanopb@^0.4.7 erriez/ErriezCRC32@^1.0.1 From 6b5101ec6712224aaf530675332d0ca9edc9ff2b Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Mon, 22 Jan 2024 01:27:06 -0600 Subject: [PATCH 133/472] Portduino logging enhancements (#3121) * Portduino logging enhancements * Extra debugging for SPI device --- bin/config-dist.yaml | 5 +++++ src/RedirectablePrint.cpp | 8 ++++++++ src/main.cpp | 3 +++ src/platform/portduino/PortduinoGlue.cpp | 20 ++++++-------------- src/platform/portduino/PortduinoGlue.h | 3 ++- 5 files changed, 24 insertions(+), 15 deletions(-) diff --git a/bin/config-dist.yaml b/bin/config-dist.yaml index 99a08ad87..32a989098 100644 --- a/bin/config-dist.yaml +++ b/bin/config-dist.yaml @@ -95,3 +95,8 @@ Touchscreen: Input: # KeyboardDevice: /dev/input/event0 + +### + +Logging: +# DebugMode: true diff --git a/src/RedirectablePrint.cpp b/src/RedirectablePrint.cpp index ba09076ed..65aead7cc 100644 --- a/src/RedirectablePrint.cpp +++ b/src/RedirectablePrint.cpp @@ -10,6 +10,10 @@ #include #include +#ifdef ARCH_PORTDUINO +#include "platform/portduino/PortduinoGlue.h" +#endif + /** * A printer that doesn't go anywhere */ @@ -68,6 +72,10 @@ size_t RedirectablePrint::vprintf(const char *format, va_list arg) size_t RedirectablePrint::log(const char *logLevel, const char *format, ...) { +#ifdef ARCH_PORTDUINO + if (!settingsMap[debugmode] && strcmp(logLevel, "DEBUG") == 0) + return 0; +#endif if (moduleConfig.serial.override_console_serial_port && strcmp(logLevel, "DEBUG") == 0) { return 0; } diff --git a/src/main.cpp b/src/main.cpp index a0246afe0..141518aa3 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -717,6 +717,7 @@ void setup() #ifdef ARCH_PORTDUINO if (settingsMap[use_sx1262]) { if (!rIf) { + LOG_DEBUG("Attempting to activate sx1262 radio on SPI port %s\n", settingsStrings[spidev].c_str()); LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(SPI, spiSettings); rIf = new SX1262Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset], settingsMap[busy]); @@ -730,6 +731,7 @@ void setup() } } else if (settingsMap[use_rf95]) { if (!rIf) { + LOG_DEBUG("Attempting to activate rf95 radio on SPI port %s\n", settingsStrings[spidev].c_str()); LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(SPI, spiSettings); rIf = new RF95Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset], settingsMap[busy]); @@ -744,6 +746,7 @@ void setup() } } else if (settingsMap[use_sx1280]) { if (!rIf) { + LOG_DEBUG("Attempting to activate sx1280 radio on SPI port %s\n", settingsStrings[spidev].c_str()); LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(SPI, spiSettings); rIf = new SX1280Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset], settingsMap[busy]); diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index a13e7eba2..16f1366dc 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -81,6 +81,7 @@ void portduinoSetup() YAML::Node yamlConfig; if (configPath != nullptr) { + std::cout << "Using " << configPath << " as config file" << std::endl; try { yamlConfig = YAML::LoadFile(configPath); } catch (YAML::Exception e) { @@ -88,6 +89,7 @@ void portduinoSetup() exit(EXIT_FAILURE); } } else if (access("config.yaml", R_OK) == 0) { + std::cout << "Using local config.yaml as config file" << std::endl; try { yamlConfig = YAML::LoadFile("config.yaml"); } catch (YAML::Exception e) { @@ -95,6 +97,7 @@ void portduinoSetup() exit(EXIT_FAILURE); } } else if (access("/etc/meshtasticd/config.yaml", R_OK) == 0) { + std::cout << "Using /etc/meshtasticd/config.yaml as config file" << std::endl; try { yamlConfig = YAML::LoadFile("/etc/meshtasticd/config.yaml"); } catch (YAML::Exception e) { @@ -105,24 +108,13 @@ void portduinoSetup() std::cout << "No 'config.yaml' found, running simulated." << std::endl; // Set the random seed equal to TCPPort to have a different seed per instance randomSeed(TCPPort); - - /* Aren't all pins defaulted to simulated? - auto fakeBusy = new SimGPIOPin(SX126X_BUSY, "fakeBusy"); - fakeBusy->writePin(LOW); - fakeBusy->setSilent(true); - gpioBind(fakeBusy); - - auto cs = new SimGPIOPin(SX126X_CS, "fakeLoraCS"); - cs->setSilent(true); - gpioBind(cs); - - gpioBind(new SimGPIOPin(SX126X_RESET, "fakeLoraReset")); - gpioBind(new SimGPIOPin(LORA_DIO1, "fakeLoraIrq")); - */ return; } try { + if (yamlConfig["Logging"]) { + settingsMap[debugmode] = yamlConfig["Logging"]["DebugMode"].as(false); + } if (yamlConfig["Lora"]) { settingsMap[use_sx1262] = false; settingsMap[use_rf95] = false; diff --git a/src/platform/portduino/PortduinoGlue.h b/src/platform/portduino/PortduinoGlue.h index cb85ce69a..a2098919c 100644 --- a/src/platform/portduino/PortduinoGlue.h +++ b/src/platform/portduino/PortduinoGlue.h @@ -31,7 +31,8 @@ enum configNames { displayOffsetX, displayOffsetY, displayInvert, - keyboardDevice + keyboardDevice, + debugmode }; enum { no_screen, st7789, st7735, st7735s }; enum { no_touchscreen, xpt2046 }; From 4ae5443c3baaa10ac9368ecd53db104bde9936f7 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Mon, 22 Jan 2024 20:13:27 -0600 Subject: [PATCH 134/472] Don't ever delete own node from DB (#3122) --- src/mesh/NodeDB.cpp | 5 +++-- src/modules/PositionModule.cpp | 2 ++ 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 5649bfd7a..2eebd64ed 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -879,10 +879,11 @@ meshtastic_NodeInfoLite *NodeDB::getOrCreateMeshNode(NodeNum n) if ((*numMeshNodes >= MAX_NUM_NODES) || (memGet.getFreeHeap() < meshtastic_NodeInfoLite_size * 3)) { if (screen) screen->print("warning: node_db_lite full! erasing oldest entry\n"); + LOG_INFO("warning: node_db_lite full! erasing oldest entry\n"); // look for oldest node and erase it uint32_t oldest = UINT32_MAX; int oldestIndex = -1; - for (int i = 0; i < *numMeshNodes; i++) { + for (int i = 1; i < *numMeshNodes; i++) { if (meshNodes[i].last_heard < oldest) { oldest = meshNodes[i].last_heard; oldestIndex = i; @@ -926,4 +927,4 @@ void recordCriticalError(meshtastic_CriticalErrorCode code, uint32_t address, co LOG_ERROR("A critical failure occurred, portduino is exiting..."); exit(2); #endif -} +} \ No newline at end of file diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index 1113bc976..5e808b6b6 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -204,6 +204,8 @@ int32_t PositionModule::runOnce() } meshtastic_NodeInfoLite *node = nodeDB.getMeshNode(nodeDB.getNodeNum()); + if (node == nullptr) + return RUNONCE_INTERVAL; // We limit our GPS broadcasts to a max rate uint32_t now = millis(); From f2c04c550430a4cdaac12c2ca84bfed2da3b80ed Mon Sep 17 00:00:00 2001 From: Manuel <71137295+mverch67@users.noreply.github.com> Date: Wed, 24 Jan 2024 21:01:50 +0100 Subject: [PATCH 135/472] fix MQTT crash (#3127) --- src/mqtt/MQTT.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index c91bdef29..d2d3f3b21 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -131,7 +131,10 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length) } delete json_value; } else { - if (!pb_decode_from_bytes(payload, length, &meshtastic_ServiceEnvelope_msg, &e)) { + if (length == 0) { + LOG_WARN("Empty MQTT payload received, topic %s!\n", topic); + return; + } else if (!pb_decode_from_bytes(payload, length, &meshtastic_ServiceEnvelope_msg, &e)) { LOG_ERROR("Invalid MQTT service envelope, topic %s, len %u!\n", topic, length); return; } else { From d6fa19002523cc5849d608fcfeb74159b235c9d8 Mon Sep 17 00:00:00 2001 From: Andre K Date: Thu, 25 Jan 2024 11:42:34 -0300 Subject: [PATCH 136/472] fix: allow MQTT `encryption_enabled` with `json_enabled` (#3126) * fix: allow MQTT `encryption_enabled` with `json_enabled` * fix: copy decoded MeshPacket and release memory after use * fix: use `packetPool` allocCopy and release methods --------- Co-authored-by: Ben Meadors --- src/mesh/Router.cpp | 19 ++++++------------- src/mqtt/MQTT.cpp | 12 +++++++++--- src/mqtt/MQTT.h | 4 ++-- 3 files changed, 17 insertions(+), 18 deletions(-) diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp index 977a1215a..492ed962b 100644 --- a/src/mesh/Router.cpp +++ b/src/mesh/Router.cpp @@ -248,28 +248,21 @@ ErrorCode Router::send(meshtastic_MeshPacket *p) // If the packet is not yet encrypted, do so now if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) { ChannelIndex chIndex = p->channel; // keep as a local because we are about to change it - - if (moduleConfig.mqtt.enabled) { - - LOG_INFO("Should encrypt MQTT?: %d\n", moduleConfig.mqtt.encryption_enabled); - - // the packet is currently in a decrypted state. send it now if they want decrypted packets - if (mqtt && !moduleConfig.mqtt.encryption_enabled) - mqtt->onSend(*p, chIndex); - } + meshtastic_MeshPacket *p_decoded = packetPool.allocCopy(*p); auto encodeResult = perhapsEncode(p); if (encodeResult != meshtastic_Routing_Error_NONE) { + packetPool.release(p_decoded); abortSendAndNak(encodeResult, p); return encodeResult; // FIXME - this isn't a valid ErrorCode } if (moduleConfig.mqtt.enabled) { - // the packet is now encrypted. - // check if we should send encrypted packets to mqtt - if (mqtt && moduleConfig.mqtt.encryption_enabled) - mqtt->onSend(*p, chIndex); + LOG_INFO("Should encrypt MQTT?: %d\n", moduleConfig.mqtt.encryption_enabled); + if (mqtt) + mqtt->onSend(*p, *p_decoded, chIndex); } + packetPool.release(p_decoded); } assert(iface); // This should have been detected already in sendLocal (or we just received a packet from outside) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index d2d3f3b21..87dacde7a 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -466,7 +466,7 @@ void MQTT::publishQueuedMessages() } } -void MQTT::onSend(const meshtastic_MeshPacket &mp, ChannelIndex chIndex) +void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket &mp_decoded, ChannelIndex chIndex) { if (mp.via_mqtt) return; // Don't send messages that came from MQTT back into MQTT @@ -486,7 +486,13 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, ChannelIndex chIndex) meshtastic_ServiceEnvelope *env = mqttPool.allocZeroed(); env->channel_id = (char *)channelId; env->gateway_id = owner.id; - env->packet = (meshtastic_MeshPacket *)∓ + + if (moduleConfig.mqtt.encryption_enabled) { + env->packet = (meshtastic_MeshPacket *)∓ + } else { + env->packet = (meshtastic_MeshPacket *)&mp_decoded; + } + LOG_DEBUG("MQTT onSend - Publishing portnum %i message\n", env->packet->decoded.portnum); if (moduleConfig.mqtt.proxy_to_client_enabled || this->isConnectedDirectly()) { @@ -501,7 +507,7 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, ChannelIndex chIndex) if (moduleConfig.mqtt.json_enabled) { // handle json topic - auto jsonString = this->meshPacketToJson((meshtastic_MeshPacket *)&mp); + auto jsonString = this->meshPacketToJson((meshtastic_MeshPacket *)&mp_decoded); if (jsonString.length() != 0) { std::string topicJson = jsonTopic + channelId + "/" + owner.id; LOG_INFO("JSON publish message to %s, %u bytes: %s\n", topicJson.c_str(), jsonString.length(), diff --git a/src/mqtt/MQTT.h b/src/mqtt/MQTT.h index 565f46ecf..fc9f9d454 100644 --- a/src/mqtt/MQTT.h +++ b/src/mqtt/MQTT.h @@ -48,14 +48,14 @@ class MQTT : private concurrency::OSThread MQTT(); /** - * Publish a packet on the glboal MQTT server. + * Publish a packet on the global MQTT server. * This hook must be called **after** the packet is encrypted (including the channel being changed to a hash). * @param chIndex the index of the channel for this message * * Note: for messages we are forwarding on the mesh that we can't find the channel for (because we don't have the keys), we * can not forward those messages to the cloud - because no way to find a global channel ID. */ - void onSend(const meshtastic_MeshPacket &mp, ChannelIndex chIndex); + void onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket &mp_decoded, ChannelIndex chIndex); /** Attempt to connect to server if necessary */ From ac9c5f81b901b013365739e8a231b9e7f4d9478a Mon Sep 17 00:00:00 2001 From: Ken McGuire Date: Fri, 26 Jan 2024 07:40:16 -0700 Subject: [PATCH 137/472] Add CircutMess Chatter 2 (#3125) * Add Chatter 2 default_envs * Add Chatter 2 to varients * Add Chatter 2 specific code to esp32 platform code * Parameterize TFT_INVERT for Chatter 2 and specify setRotation to 1 * Fix formatting to make Trunk happy * Remove commented out #define USE_LCC68 * Fix formatting again * Add chatter2 to the CI matrix --------- Co-authored-by: code8buster <20384924+code8buster@users.noreply.github.com> --- .github/workflows/main_matrix.yml | 1 + platformio.ini | 1 + src/graphics/TFTDisplay.cpp | 8 +- src/platform/esp32/architecture.h | 2 + src/platform/esp32/main-esp32.cpp | 9 ++- variants/chatter2/platformio.ini | 13 ++++ variants/chatter2/variant.h | 118 ++++++++++++++++++++++++++++++ 7 files changed, 146 insertions(+), 6 deletions(-) create mode 100644 variants/chatter2/platformio.ini create mode 100644 variants/chatter2/variant.h diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index c92ec06ea..ed32260fa 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -79,6 +79,7 @@ jobs: - board: m5stack-core - board: m5stack-coreink - board: nano-g1-explorer + - board: chatter2 uses: ./.github/workflows/build_esp32.yml with: board: ${{ matrix.board }} diff --git a/platformio.ini b/platformio.ini index bd5b1e07f..fbd1d6a74 100644 --- a/platformio.ini +++ b/platformio.ini @@ -10,6 +10,7 @@ default_envs = tbeam ;default_envs = heltec-v2_0 ;default_envs = heltec-v2_1 ;default_envs = heltec-wireless-tracker +;default_envs = chatter2 ;default_envs = tlora-v1 ;default_envs = tlora_v1_3 ;default_envs = tlora-v2 diff --git a/src/graphics/TFTDisplay.cpp b/src/graphics/TFTDisplay.cpp index 9b107ba52..b90328c05 100644 --- a/src/graphics/TFTDisplay.cpp +++ b/src/graphics/TFTDisplay.cpp @@ -19,6 +19,10 @@ #define TFT_BL ST7735_BACKLIGHT_EN #endif +#ifndef TFT_INVERT +#define TFT_INVERT true +#endif + class LGFX : public lgfx::LGFX_Device { lgfx::Panel_ST7735S _panel_instance; @@ -68,7 +72,7 @@ class LGFX : public lgfx::LGFX_Device cfg.dummy_read_pixel = 8; // Number of bits for dummy read before pixel readout cfg.dummy_read_bits = 1; // Number of bits for dummy read before non-pixel data read cfg.readable = true; // Set to true if data can be read - cfg.invert = true; // Set to true if the light/darkness of the panel is reversed + cfg.invert = TFT_INVERT; // Set to true if the light/darkness of the panel is reversed cfg.rgb_order = false; // Set to true if the panel's red and blue are swapped cfg.dlen_16bit = false; // Set to true for panels that transmit data length in 16-bit units with 16-bit parallel or SPI @@ -598,7 +602,7 @@ bool TFTDisplay::connect() tft->setRotation(1); tft->setSwapBytes(true); // tft->fillScreen(TFT_BLACK); -#elif defined(T_DECK) || defined(PICOMPUTER_S3) +#elif defined(T_DECK) || defined(PICOMPUTER_S3) || defined(CHATTER_2) tft->setRotation(1); // T-Deck has the TFT in landscape #elif defined(T_WATCH_S3) tft->setRotation(2); // T-Watch S3 left-handed orientation diff --git a/src/platform/esp32/architecture.h b/src/platform/esp32/architecture.h index 451d7ffbe..e2c5fefbe 100644 --- a/src/platform/esp32/architecture.h +++ b/src/platform/esp32/architecture.h @@ -125,6 +125,8 @@ #define HW_VENDOR meshtastic_HardwareModel_SENSELORA_S3 #elif defined(HELTEC_HT62) #define HW_VENDOR meshtastic_HardwareModel_HELTEC_HT62 +#elif defined(CHATTER_2) +#define HW_VENDOR meshtastic_HardwareModel_CHATTER_2 #endif // ----------------------------------------------------------------------------- diff --git a/src/platform/esp32/main-esp32.cpp b/src/platform/esp32/main-esp32.cpp index 7da41512e..c994eea48 100644 --- a/src/platform/esp32/main-esp32.cpp +++ b/src/platform/esp32/main-esp32.cpp @@ -175,7 +175,8 @@ void cpuDeepSleep(uint32_t msecToWake) some current will flow through these external and internal resistors, increasing deep sleep current above the minimal possible value. - Note: we don't isolate pins that are used for the LORA, LED, i2c, spi or the wake button + Note: we don't isolate pins that are used for the LORA, LED, i2c, or ST7735 Display for the Chatter2, spi or the wake + button(s), maybe we should not include any other GPIOs... */ #if SOC_RTCIO_HOLD_SUPPORTED static const uint8_t rtcGpios[] = {/* 0, */ 2, @@ -184,9 +185,9 @@ void cpuDeepSleep(uint32_t msecToWake) 13, /* 14, */ /* 15, */ #endif - /* 25, */ 26, /* 27, */ - 32, 33, 34, 35, - 36, 37 + /* 25, */ /* 26, */ /* 27, */ + /* 32, */ /* 33, */ 34, 35, + /* 36, */ 37 /* 38, 39 */}; for (int i = 0; i < sizeof(rtcGpios); i++) diff --git a/variants/chatter2/platformio.ini b/variants/chatter2/platformio.ini new file mode 100644 index 000000000..0856debfc --- /dev/null +++ b/variants/chatter2/platformio.ini @@ -0,0 +1,13 @@ +; CircuitMess Chatter 2 based on ESP32-WROOM-32 (38 pins) devkit & DeeamLNK DL-LLCC68 or Heltec HT RA62 SX1262/SX1268 module +[env:chatter2] +extends = esp32_base +board = esp32doit-devkit-v1 +board_level = extra +build_flags = + ${esp32_base.build_flags} + -D CHATTER_2 + -I variants/chatter2 + +lib_deps = + ${esp32_base.lib_deps} + lovyan03/LovyanGFX@^1.1.8 \ No newline at end of file diff --git a/variants/chatter2/variant.h b/variants/chatter2/variant.h new file mode 100644 index 000000000..b7ffcf732 --- /dev/null +++ b/variants/chatter2/variant.h @@ -0,0 +1,118 @@ +////////////////////////////////////////////////////////////////////////////////// +// // +// Have custom connections or functionality? Configure them in this section // +// // +////////////////////////////////////////////////////////////////////////////////// + +// Debugging +// #define GPS_DEBUG +// #define GPS_EXTRAVERBOSE + +// Lora +#define USE_LLCC68 // Original Chatter2 with LLCC68 module +#define USE_SX1262 // Added for when Lora module is swapped for HT-RA62 + +#define SX126X_CS 14 // module's NSS pin +#define LORA_SCK 16 // module's SCK pin +#define LORA_MOSI 5 // module's MOSI pin +#define LORA_MISO 17 // module's MISO pin +#define SX126X_RESET RADIOLIB_NC // module's NRST pin +#define SX126X_BUSY 4 // module's BUSY pin works for both LLCC68 and RA-62 with cut & jumper +#define SX126X_DIO1 18 // module's DIO1 pin +#define SX126X_DIO2_AS_RF_SWITCH // module's DIO2 pin +#define SX126X_DIO3_TCXO_VOLTAGE 1.8 // module's DIO pin +#define SX126X_TXEN RADIOLIB_NC +#define SX126X_RXEN RADIOLIB_NC + +// Status +// #define LED_PIN 1 +// External notification +// FIXME: Check if EXT_NOTIFY_OUT actualy has any effect and removes the need for setting the external notication pin in the +// app/preferences +// #define EXT_NOTIFY_OUT 2 // The GPIO pin that acts as the external notification output (here we connect an LED to it) + +// Buzzer +#define PIN_BUZZER 19 +// Buttons +#define BUTTON_PIN 36 // Use the WAKE button as the user button +// I2C +// #define I2C_SCL 27 +// #define I2C_SDA 26 + +#define SX126X_MAX_POWER 22 // SX126xInterface.cpp defaults to 22 if not defined, but here we define it for good practice + +// Display + +#define HAS_SCREEN 1 // Assume no screen present by default to prevent crash... + +// ST7735S TFT LCD +#define ST7735S 1 // there are different (sub-)versions of ST7735 +#define ST7735_CS -1 +#define ST7735_RS 33 // DC +#define ST7735_SDA 26 // MOSI +#define ST7735_SCK 27 +#define ST7735_RESET 15 +#define ST7735_MISO -1 +#define ST7735_BUSY -1 +#define ST7735_BL 32 +#define ST7735_SPI_HOST HSPI_HOST // SPI2_HOST for S3, auto may work too +#define SPI_FREQUENCY 40000000 +#define SPI_READ_FREQUENCY 16000000 +#define TFT_HEIGHT 160 +#define TFT_WIDTH 128 +#define TFT_OFFSET_X 0 +#define TFT_OFFSET_Y 0 +#define TFT_INVERT false +#define SCREEN_ROTATE +#define SCREEN_TRANSITION_FRAMERATE 5 // fps +#define DISPLAY_FORCE_SMALL_FONTS + +// Battery + +#define BATTERY_PIN 34 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage +#define ADC_CHANNEL ADC1_GPIO34_CHANNEL +#define ADC_ATTENUATION \ + ADC_ATTEN_DB_2_5 // 2_5-> 100mv-1250mv, 11-> 150mv-3100mv for ESP32 + // ESP32-S2/C3/S3 are different + // lower dB for lower voltage rnage +#define ADC_MULTIPLIER \ + 5.0 // VBATT---10k--pin34---2.5K---GND + // Chatter2 uses 3 AAA cells +#define BAT_FULLVOLT 4800 // with the 5.0 divider, input to BATTERY_PIN is 900mv +#define BAT_EMPTYVOLT 3300 +#undef EXT_PWR_DETECT + +// GPS +// FIXME: unsure what to define HAS_GPS as if GPS isn't always present +#define HAS_GPS 1 // Don't need to set this to 0 to prevent a crash as it doesn't crash if GPS not found, will probe by default +// #define PIN_GPS_EN 15 +// #define GPS_EN_ACTIVE 1 +#undef GPS_TX_PIN +#undef GPS_RX_PIN +#define GPS_TX_PIN 13 +#define GPS_RX_PIN 2 + +///////////////////////////////////////////////////////////////////////////////// +// // +// You should have no need to modify the code below, nor in pins_arduino.h // +// // +///////////////////////////////////////////////////////////////////////////////// + +#define LORA_CS SX126X_CS // FIXME: for some reason both are used in /src + +// Many of the below values would only be used if USE_RF95 was defined, but it's not as we aren't actually using an RF95, just +// that the 4 pins above are named like it If they aren't used they don't need to be defined and doing so cause confusion to those +// adapting this file LORA_RESET value is never used in src (as we are not using RF95), so no need to define LORA_DIO0 is not used +// in src (as we are not using RF95) as SX1262 does not have it per SX1262 datasheet, so no need to define +// FIXME: confirm that the linked lines below are actually only called when using the SX126x or SX128x and no other modules +// then use SX126X_DIO1 and SX128X_DIO1 respectively for that purpose, removing the need for RF95-style LORA_* definitions when +// the RF95 isn't used +#define LORA_DIO1 \ + SX126X_DIO1 // The old name is used in + // https://github.com/meshtastic/firmware/blob/7eff5e7bcb2084499b723c5e3846c15ee089e36d/src/sleep.cpp#L298, so + // must also define the old name +// LORA_DIO2 value is never used in src (as we are not using RF95), so no need to define, and if DIO2_AS_RF_SWITCH is set then it +// cannot serve any extra function even if requested to LORA_DIO3 value is never used in src (as we are not using RF95), so no +// need to define, and DIO3_AS_TCXO_AT_1V8 is set so it cannot serve any extra function even if requested to (from 13.3.2.1 +// DioxMask in SX1262 datasheet: Note that if DIO2 or DIO3 are used to control the RF Switch or the TCXO, the IRQ will not be +// generated even if it is mapped to the pins.) \ No newline at end of file From d604a76c7325e54122306308b5c22298ae101726 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Fri, 26 Jan 2024 09:06:15 -0600 Subject: [PATCH 138/472] Use correct define for native gos (#3133) --- src/gps/GPS.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 0e0b5f8b6..ff5b2e7b1 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -16,7 +16,7 @@ #define GPS_RESET_MODE HIGH #endif -#if defined(NRF52840_XXAA) || defined(NRF52833_XXAA) || defined(ARCH_ESP32) || defined(aLinuxInputImpl) +#if defined(NRF52840_XXAA) || defined(NRF52833_XXAA) || defined(ARCH_ESP32) || defined(ARCH_PORTDUINO) HardwareSerial *GPS::_serial_gps = &Serial1; #else HardwareSerial *GPS::_serial_gps = NULL; @@ -1286,4 +1286,4 @@ int32_t GPS::disable() setAwake(false); return INT32_MAX; -} \ No newline at end of file +} From 417feee47f4985735df2a00fe1d9f45deb1c6424 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Sun, 28 Jan 2024 14:53:39 +0100 Subject: [PATCH 139/472] Fix: return failure when PhoneAPI times out (#3136) * Add debug options for RP2040 * Rename: "observed" should be plural: "observables" * PhoneAPI: return failure on timeout In `onNotify()`, when disconnected, PhoneAPI removed itself from the list of observers that was looped through in `notifyObservers()`. We should exit that loop in that case. --- src/Observer.h | 14 +++++++------- src/mesh/MeshService.cpp | 5 +++-- src/mesh/PhoneAPI.cpp | 10 ++++++---- src/mesh/PhoneAPI.h | 6 +++--- variants/rak11310/platformio.ini | 4 +++- variants/rpipico/platformio.ini | 4 +++- variants/rpipicow/platformio.ini | 4 +++- 7 files changed, 28 insertions(+), 19 deletions(-) diff --git a/src/Observer.h b/src/Observer.h index 555dcd1e9..6e1ec44c8 100644 --- a/src/Observer.h +++ b/src/Observer.h @@ -10,12 +10,12 @@ template class Observable; */ template class Observer { - std::list *> observed; + std::list *> observables; public: virtual ~Observer(); - /// Stop watching the obserable + /// Stop watching the observable void unobserve(Observable *o); /// Start watching a specified observable @@ -86,21 +86,21 @@ template class Observable template Observer::~Observer() { - for (typename std::list *>::const_iterator iterator = observed.begin(); iterator != observed.end(); + for (typename std::list *>::const_iterator iterator = observables.begin(); iterator != observables.end(); ++iterator) { (*iterator)->removeObserver(this); } - observed.clear(); + observables.clear(); } template void Observer::unobserve(Observable *o) { o->removeObserver(this); - observed.remove(o); + observables.remove(o); } template void Observer::observe(Observable *o) { - observed.push_back(o); + observables.push_back(o); o->addObserver(this); -} +} \ No newline at end of file diff --git a/src/mesh/MeshService.cpp b/src/mesh/MeshService.cpp index 9101712d1..db0dd88ec 100644 --- a/src/mesh/MeshService.cpp +++ b/src/mesh/MeshService.cpp @@ -108,8 +108,9 @@ void MeshService::loop() (void)sendQueueStatusToPhone(qs, 0, 0); } if (oldFromNum != fromNum) { // We don't want to generate extra notifies for multiple new packets - fromNumChanged.notifyObservers(fromNum); - oldFromNum = fromNum; + int result = fromNumChanged.notifyObservers(fromNum); + if (result == 0) // If any observer returns non-zero, we will try again + oldFromNum = fromNum; } } diff --git a/src/mesh/PhoneAPI.cpp b/src/mesh/PhoneAPI.cpp index 10e8ac2dc..270bf613f 100644 --- a/src/mesh/PhoneAPI.cpp +++ b/src/mesh/PhoneAPI.cpp @@ -62,15 +62,17 @@ void PhoneAPI::close() } } -void PhoneAPI::checkConnectionTimeout() +bool PhoneAPI::checkConnectionTimeout() { if (isConnected()) { bool newContact = checkIsConnected(); if (!newContact) { LOG_INFO("Lost phone connection\n"); close(); + return true; } } + return false; } /** @@ -461,8 +463,8 @@ bool PhoneAPI::handleToRadioPacket(meshtastic_MeshPacket &p) /// If the mesh service tells us fromNum has changed, tell the phone int PhoneAPI::onNotify(uint32_t newValue) { - checkConnectionTimeout(); // a handy place to check if we've heard from the phone (since the BLE version doesn't call this - // from idle) + bool timeout = checkConnectionTimeout(); // a handy place to check if we've heard from the phone (since the BLE version + // doesn't call this from idle) if (state == STATE_SEND_PACKETS) { LOG_INFO("Telling client we have new packets %u\n", newValue); @@ -471,5 +473,5 @@ int PhoneAPI::onNotify(uint32_t newValue) LOG_DEBUG("(Client not yet interested in packets)\n"); } - return 0; + return timeout ? -1 : 0; // If we timed out, MeshService should stop iterating through observers as we just removed one } \ No newline at end of file diff --git a/src/mesh/PhoneAPI.h b/src/mesh/PhoneAPI.h index 65a06bc6b..450649d7b 100644 --- a/src/mesh/PhoneAPI.h +++ b/src/mesh/PhoneAPI.h @@ -108,8 +108,8 @@ class PhoneAPI /// Hookable to find out when connection changes virtual void onConnectionChanged(bool connected) {} - /// If we haven't heard from the other side in a while then say not connected - void checkConnectionTimeout(); + /// If we haven't heard from the other side in a while then say not connected. Returns true if timeout occurred + bool checkConnectionTimeout(); /// Check the current underlying physical link to see if the client is currently connected virtual bool checkIsConnected() = 0; @@ -142,4 +142,4 @@ class PhoneAPI /// If the mesh service tells us fromNum has changed, tell the phone virtual int onNotify(uint32_t newValue) override; -}; +}; \ No newline at end of file diff --git a/variants/rak11310/platformio.ini b/variants/rak11310/platformio.ini index a69b18c1a..6495278bf 100644 --- a/variants/rak11310/platformio.ini +++ b/variants/rak11310/platformio.ini @@ -10,4 +10,6 @@ build_flags = ${rp2040_base.build_flags} -DDEBUG_RP2040_PORT=Serial -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m0plus" lib_deps = - ${rp2040_base.lib_deps} \ No newline at end of file + ${rp2040_base.lib_deps} +debug_build_flags = ${rp2040_base.build_flags} +debug_tool = cmsis-dap ; for e.g. Picotool \ No newline at end of file diff --git a/variants/rpipico/platformio.ini b/variants/rpipico/platformio.ini index 727a1cab6..9537694ec 100644 --- a/variants/rpipico/platformio.ini +++ b/variants/rpipico/platformio.ini @@ -11,4 +11,6 @@ build_flags = ${rp2040_base.build_flags} -DHW_SPI1_DEVICE -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m0plus" lib_deps = - ${rp2040_base.lib_deps} \ No newline at end of file + ${rp2040_base.lib_deps} +debug_build_flags = ${rp2040_base.build_flags} +debug_tool = cmsis-dap ; for e.g. Picotool \ No newline at end of file diff --git a/variants/rpipicow/platformio.ini b/variants/rpipicow/platformio.ini index 4c8cf992d..29b5c8bcb 100644 --- a/variants/rpipicow/platformio.ini +++ b/variants/rpipicow/platformio.ini @@ -14,4 +14,6 @@ build_flags = ${rp2040_base.build_flags} build_src_filter = ${rp2040_base.build_src_filter} + lib_deps = ${rp2040_base.lib_deps} - ${networking_base.lib_deps} \ No newline at end of file + ${networking_base.lib_deps} +debug_build_flags = ${rp2040_base.build_flags} +debug_tool = cmsis-dap ; for e.g. Picotool \ No newline at end of file From a49740cd56353f2d51d59e1e47cfe5d4be8e530b Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 28 Jan 2024 20:15:29 -0600 Subject: [PATCH 140/472] Adds i2c device configuration to native (#3143) --- arch/portduino/portduino.ini | 2 +- bin/config-dist.yaml | 5 +++++ src/main.cpp | 15 ++++++++++++++- src/platform/portduino/PortduinoGlue.cpp | 3 +++ src/platform/portduino/PortduinoGlue.h | 1 + variants/portduino/variant.h | 1 - 6 files changed, 24 insertions(+), 3 deletions(-) diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index 970640480..0dcc9afc2 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -1,6 +1,6 @@ ; The Portduino based sim environment on top of any host OS, all hardware will be simulated [portduino_base] -platform = https://github.com/meshtastic/platform-native.git#04435d06e39916a6c019d511518d8e95c659dfbd +platform = https://github.com/meshtastic/platform-native.git#a28dd5a9ccd5c48a9bede46037855ff83915d74b framework = arduino build_src_filter = diff --git a/bin/config-dist.yaml b/bin/config-dist.yaml index 32a989098..e7e8ae2e4 100644 --- a/bin/config-dist.yaml +++ b/bin/config-dist.yaml @@ -60,6 +60,11 @@ GPIO: GPS: # SerialPath: /dev/ttyS0 +### Specify I2C device, or leave blank for none + +I2C: +# I2CDevice: /dev/i2c-1 + ### Set up SPI displays here. Note that I2C displays are generally auto-detected. Display: diff --git a/src/main.cpp b/src/main.cpp index 141518aa3..84419c70c 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -363,6 +363,13 @@ void setup() Wire.begin(); #elif defined(I2C_SDA) && !defined(ARCH_RP2040) Wire.begin(I2C_SDA, I2C_SCL); +#elif defined(ARCH_PORTDUINO) + if (settingsStrings[i2cdev] != "") { + LOG_INFO("Using %s as I2C device.\n", settingsStrings[i2cdev]); + Wire.begin(settingsStrings[i2cdev].c_str()); + } else { + LOG_INFO("No I2C device configured, skipping.\n"); + } #elif HAS_WIRE Wire.begin(); #endif @@ -408,8 +415,9 @@ void setup() // We need to scan here to decide if we have a screen for nodeDB.init() and because power has been applied to // accessories auto i2cScanner = std::unique_ptr(new ScanI2CTwoWire()); - +#ifdef HAS_WIRE LOG_INFO("Scanning for i2c devices...\n"); +#endif #if defined(I2C_SDA1) && defined(ARCH_RP2040) Wire1.setSDA(I2C_SDA1); @@ -429,6 +437,11 @@ void setup() #elif defined(I2C_SDA) && !defined(ARCH_RP2040) Wire.begin(I2C_SDA, I2C_SCL); i2cScanner->scanPort(ScanI2C::I2CPort::WIRE); +#elif defined(ARCH_PORTDUINO) + if (settingsStrings[i2cdev] != "") { + LOG_INFO("Scanning for i2c devices...\n"); + i2cScanner->scanPort(ScanI2C::I2CPort::WIRE); + } #elif HAS_WIRE i2cScanner->scanPort(ScanI2C::I2CPort::WIRE); #endif diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index 16f1366dc..919d298e6 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -150,6 +150,9 @@ void portduinoSetup() settingsMap[has_gps] = 1; } } + if (yamlConfig["I2C"]) { + settingsStrings[i2cdev] = yamlConfig["I2C"]["I2CDevice"].as(""); + } settingsMap[displayPanel] = no_screen; if (yamlConfig["Display"]) { if (yamlConfig["Display"]["Panel"].as("") == "ST7789") diff --git a/src/platform/portduino/PortduinoGlue.h b/src/platform/portduino/PortduinoGlue.h index a2098919c..4c48f0c29 100644 --- a/src/platform/portduino/PortduinoGlue.h +++ b/src/platform/portduino/PortduinoGlue.h @@ -16,6 +16,7 @@ enum configNames { user, gpiochip, spidev, + i2cdev, has_gps, touchscreenModule, touchscreenCS, diff --git a/variants/portduino/variant.h b/variants/portduino/variant.h index 24885d7eb..959fe6275 100644 --- a/variants/portduino/variant.h +++ b/variants/portduino/variant.h @@ -1,3 +1,2 @@ -#define HAS_WIRE 1 #define HAS_SCREEN 1 #define CANNED_MESSAGE_MODULE_ENABLE 1 \ No newline at end of file From 0ae46223935696496ba06846d14308f2dcc6ed3e Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Mon, 29 Jan 2024 06:10:48 -0600 Subject: [PATCH 141/472] Admin message to delete file (#3144) * Protos * Delete file admin message --- protobufs | 2 +- src/mesh/generated/meshtastic/admin.pb.h | 4 ++++ src/modules/AdminModule.cpp | 10 ++++++++++ 3 files changed, 15 insertions(+), 1 deletion(-) diff --git a/protobufs b/protobufs index 44e369e18..e894709e4 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 44e369e1813f8ec9c7aefe1aac7d0adc75e11f8a +Subproject commit e894709e4a96867ea8fad59a12f582e1029a6f8e diff --git a/src/mesh/generated/meshtastic/admin.pb.h b/src/mesh/generated/meshtastic/admin.pb.h index 48df9ba56..28bda429d 100644 --- a/src/mesh/generated/meshtastic/admin.pb.h +++ b/src/mesh/generated/meshtastic/admin.pb.h @@ -134,6 +134,8 @@ typedef struct _meshtastic_AdminMessage { /* Enter (UF2) DFU mode Only implemented on NRF52 currently */ bool enter_dfu_mode_request; + /* Delete the file by the specified path from the device */ + char delete_file_request[201]; /* Set the owner for this node */ meshtastic_User set_owner; /* Set channels (using the new API). @@ -228,6 +230,7 @@ extern "C" { #define meshtastic_AdminMessage_get_node_remote_hardware_pins_request_tag 19 #define meshtastic_AdminMessage_get_node_remote_hardware_pins_response_tag 20 #define meshtastic_AdminMessage_enter_dfu_mode_request_tag 21 +#define meshtastic_AdminMessage_delete_file_request_tag 22 #define meshtastic_AdminMessage_set_owner_tag 32 #define meshtastic_AdminMessage_set_channel_tag 33 #define meshtastic_AdminMessage_set_config_tag 34 @@ -266,6 +269,7 @@ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,set_ham_mode,set_ham_mode), X(a, STATIC, ONEOF, BOOL, (payload_variant,get_node_remote_hardware_pins_request,get_node_remote_hardware_pins_request), 19) \ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,get_node_remote_hardware_pins_response,get_node_remote_hardware_pins_response), 20) \ X(a, STATIC, ONEOF, BOOL, (payload_variant,enter_dfu_mode_request,enter_dfu_mode_request), 21) \ +X(a, STATIC, ONEOF, STRING, (payload_variant,delete_file_request,delete_file_request), 22) \ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,set_owner,set_owner), 32) \ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,set_channel,set_channel), 33) \ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,set_config,set_config), 34) \ diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index e19701798..94df601d8 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -3,6 +3,7 @@ #include "MeshService.h" #include "NodeDB.h" #include "PowerFSM.h" +#include #ifdef ARCH_ESP32 #include "BleOta.h" #endif @@ -194,6 +195,15 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta #endif break; } + case meshtastic_AdminMessage_delete_file_request_tag: { + LOG_DEBUG("Client is requesting to delete file: %s\n", r->delete_file_request); + if (FSCom.remove(r->delete_file_request)) { + LOG_DEBUG("Successfully deleted file\n"); + } else { + LOG_DEBUG("Failed to delete file\n"); + } + break; + } #ifdef ARCH_PORTDUINO case meshtastic_AdminMessage_exit_simulator_tag: LOG_INFO("Exiting simulator\n"); From af52dcecdf7dbda1e544566b45d3abe91aa4de13 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Mon, 29 Jan 2024 13:13:56 +0100 Subject: [PATCH 142/472] Restrict MQTT JSON downlink messages (#3141) Channel needs to be named "mqtt" "from" field should be set to the node number of the transmitter Co-authored-by: Ben Meadors --- src/mesh/Channels.cpp | 3 +- src/mesh/Channels.h | 4 +- src/mqtt/MQTT.cpp | 95 +++++++++++++++++++++---------------------- src/mqtt/MQTT.h | 4 ++ 4 files changed, 55 insertions(+), 51 deletions(-) diff --git a/src/mesh/Channels.cpp b/src/mesh/Channels.cpp index f3c692e34..80bcc10c6 100644 --- a/src/mesh/Channels.cpp +++ b/src/mesh/Channels.cpp @@ -15,6 +15,7 @@ Channels channels; const char *Channels::adminChannel = "admin"; const char *Channels::gpioChannel = "gpio"; const char *Channels::serialChannel = "serial"; +const char *Channels::mqttChannel = "mqtt"; uint8_t xorHash(const uint8_t *p, size_t len) { @@ -313,4 +314,4 @@ bool Channels::decryptForHash(ChannelIndex chIndex, ChannelHash channelHash) int16_t Channels::setActiveByIndex(ChannelIndex channelIndex) { return setCrypto(channelIndex); -} +} \ No newline at end of file diff --git a/src/mesh/Channels.h b/src/mesh/Channels.h index b4bdcbd5c..87a72e07b 100644 --- a/src/mesh/Channels.h +++ b/src/mesh/Channels.h @@ -32,7 +32,7 @@ class Channels Channels() {} /// Well known channel names - static const char *adminChannel, *gpioChannel, *serialChannel; + static const char *adminChannel, *gpioChannel, *serialChannel, *mqttChannel; const meshtastic_ChannelSettings &getPrimary() { return getByIndex(getPrimaryIndex()).settings; } @@ -139,4 +139,4 @@ class Channels }; /// Singleton channel table -extern Channels channels; +extern Channels channels; \ No newline at end of file diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 87dacde7a..70b2d753c 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -17,7 +17,6 @@ #include "mesh/wifi/WiFiAPClient.h" #include #endif -#include "mqtt/JSON.h" #include const int reconnectMax = 5; @@ -49,8 +48,6 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length) payloadStr[length] = 0; // null terminated string JSONValue *json_value = JSON::Parse(payloadStr); if (json_value != NULL) { - LOG_INFO("JSON Received on MQTT, parsing..\n"); - // check if it is a valid envelope JSONObject json; json = json_value->AsObject(); @@ -61,22 +58,21 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length) ptr = strtok(NULL, "/"); } meshtastic_Channel sendChannel = channels.getByName(ptr); - LOG_DEBUG("Found Channel name: %s (Index %d)\n", channels.getGlobalId(sendChannel.index), sendChannel.index); + // We allow downlink JSON packets only on a channel named "mqtt" + if (strncasecmp(channels.getGlobalId(sendChannel.index), Channels::mqttChannel, strlen(Channels::mqttChannel)) == 0 && + sendChannel.settings.downlink_enabled) { + if (isValidJsonEnvelope(json)) { + // this is a valid envelope + if (json["type"]->AsString().compare("sendtext") == 0 && json["payload"]->IsString()) { + std::string jsonPayloadStr = json["payload"]->AsString(); + LOG_INFO("JSON payload %s, length %u\n", jsonPayloadStr.c_str(), jsonPayloadStr.length()); - if ((json.find("sender") != json.end()) && (json.find("payload") != json.end()) && - (json.find("type") != json.end()) && json["type"]->IsString() && - (json["type"]->AsString().compare("sendtext") == 0)) { - // this is a valid envelope - if (json["payload"]->IsString() && json["type"]->IsString() && - (json["sender"]->AsString().compare(owner.id) != 0)) { - std::string jsonPayloadStr = json["payload"]->AsString(); - LOG_INFO("JSON payload %s, length %u\n", jsonPayloadStr.c_str(), jsonPayloadStr.length()); - - // construct protobuf data packet using TEXT_MESSAGE, send it to the mesh - meshtastic_MeshPacket *p = router->allocForSending(); - p->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_APP; - p->channel = sendChannel.index; - if (sendChannel.settings.downlink_enabled) { + // construct protobuf data packet using TEXT_MESSAGE, send it to the mesh + meshtastic_MeshPacket *p = router->allocForSending(); + p->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_APP; + p->channel = sendChannel.index; + if (json.find("to") != json.end() && json["to"]->IsNumber()) + p->to = json["to"]->AsNumber(); if (jsonPayloadStr.length() <= sizeof(p->decoded.payload.bytes)) { memcpy(p->decoded.payload.bytes, jsonPayloadStr.c_str(), jsonPayloadStr.length()); p->decoded.payload.size = jsonPayloadStr.length(); @@ -85,49 +81,42 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length) } else { LOG_WARN("Received MQTT json payload too long, dropping\n"); } - } else { - LOG_WARN("Received MQTT json payload on channel %s, but downlink is disabled, dropping\n", - sendChannel.settings.name); - } - } else { - LOG_DEBUG("JSON Ignoring downlink message we originally sent.\n"); - } - } else if ((json.find("sender") != json.end()) && (json.find("payload") != json.end()) && - (json.find("type") != json.end()) && json["type"]->IsString() && - (json["type"]->AsString().compare("sendposition") == 0)) { - // invent the "sendposition" type for a valid envelope - if (json["payload"]->IsObject() && json["type"]->IsString() && - (json["sender"]->AsString().compare(owner.id) != 0)) { - JSONObject posit; - posit = json["payload"]->AsObject(); // get nested JSON Position - meshtastic_Position pos = meshtastic_Position_init_default; - pos.latitude_i = posit["latitude_i"]->AsNumber(); - pos.longitude_i = posit["longitude_i"]->AsNumber(); - pos.altitude = posit["altitude"]->AsNumber(); - pos.time = posit["time"]->AsNumber(); + } else if (json["type"]->AsString().compare("sendposition") == 0 && json["payload"]->IsObject()) { + // invent the "sendposition" type for a valid envelope + JSONObject posit; + posit = json["payload"]->AsObject(); // get nested JSON Position + meshtastic_Position pos = meshtastic_Position_init_default; + if (posit.find("latitude_i") != posit.end() && posit["latitude_i"]->IsNumber()) + pos.latitude_i = posit["latitude_i"]->AsNumber(); + if (posit.find("longitude_i") != posit.end() && posit["longitude_i"]->IsNumber()) + pos.longitude_i = posit["longitude_i"]->AsNumber(); + if (posit.find("altitude") != posit.end() && posit["altitude"]->IsNumber()) + pos.altitude = posit["altitude"]->AsNumber(); + if (posit.find("time") != posit.end() && posit["time"]->IsNumber()) + pos.time = posit["time"]->AsNumber(); - // construct protobuf data packet using POSITION, send it to the mesh - meshtastic_MeshPacket *p = router->allocForSending(); - p->decoded.portnum = meshtastic_PortNum_POSITION_APP; - p->channel = sendChannel.index; - if (sendChannel.settings.downlink_enabled) { + // construct protobuf data packet using POSITION, send it to the mesh + meshtastic_MeshPacket *p = router->allocForSending(); + p->decoded.portnum = meshtastic_PortNum_POSITION_APP; + p->channel = sendChannel.index; + if (json.find("to") != json.end() && json["to"]->IsNumber()) + p->to = json["to"]->AsNumber(); p->decoded.payload.size = pb_encode_to_bytes(p->decoded.payload.bytes, sizeof(p->decoded.payload.bytes), &meshtastic_Position_msg, &pos); // make the Data protobuf from position service.sendToMesh(p, RX_SRC_LOCAL); } else { - LOG_WARN("Received MQTT json payload on channel %s, but downlink is disabled, dropping\n", - sendChannel.settings.name); + LOG_DEBUG("JSON Ignoring downlink message with unsupported type.\n"); } } else { - LOG_DEBUG("JSON Ignoring downlink message we originally sent.\n"); + LOG_ERROR("JSON Received payload on MQTT but not a valid envelope.\n"); } } else { - LOG_ERROR("JSON Received payload on MQTT but not a valid envelope\n"); + LOG_WARN("JSON downlink received on channel not called 'mqtt' or without downlink enabled.\n"); } } else { // no json, this is an invalid payload - LOG_ERROR("Invalid MQTT service envelope, topic %s, len %u!\n", topic, length); + LOG_ERROR("JSON Received payload on MQTT but not a valid JSON\n"); } delete json_value; } else { @@ -818,4 +807,14 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp) delete value; return jsonStr; +} + +bool MQTT::isValidJsonEnvelope(JSONObject &json) +{ + // if "sender" is provided, avoid processing packets we uplinked + return (json.find("sender") != json.end() ? (json["sender"]->AsString().compare(owner.id) != 0) : true) && + (json.find("from") != json.end()) && json["from"]->IsNumber() && + (json["from"]->AsNumber() == nodeDB.getNodeNum()) && // only accept message if the "from" is us + (json.find("type") != json.end()) && json["type"]->IsString() && // should specify a type + (json.find("payload") != json.end()); // should have a payload } \ No newline at end of file diff --git a/src/mqtt/MQTT.h b/src/mqtt/MQTT.h index fc9f9d454..dfcb75b7d 100644 --- a/src/mqtt/MQTT.h +++ b/src/mqtt/MQTT.h @@ -5,6 +5,7 @@ #include "concurrency/OSThread.h" #include "mesh/Channels.h" #include "mesh/generated/meshtastic/mqtt.pb.h" +#include "mqtt/JSON.h" #if HAS_WIFI #include #define HAS_NETWORKING 1 @@ -100,6 +101,9 @@ class MQTT : private concurrency::OSThread void publishStatus(); void publishQueuedMessages(); + // returns true if this is a valid JSON envelope which we accept on downlink + bool isValidJsonEnvelope(JSONObject &json); + /// Return 0 if sleep is okay, veto sleep if we are connected to pubsub server // int preflightSleepCb(void *unused = NULL) { return pubSub.connected() ? 1 : 0; } }; From d1ea58975755e146457a8345065e4ca357555275 Mon Sep 17 00:00:00 2001 From: code8buster <20384924+code8buster@users.noreply.github.com> Date: Mon, 29 Jan 2024 12:14:21 +0000 Subject: [PATCH 143/472] Allow NRF52 ADC overrides; begin simplifying analog battery logic (#3134) * Isolate esp32 adc logic gymnastics, try simplifying getBattVoltage * Set sense resolution for pico platforms * try silencing cppcheck when variant has no battery pin * ADC channel for esp-idf calibration * Missed an rp2040 device --------- Co-authored-by: Ben Meadors --- src/Power.cpp | 104 +++++++++++++++------------- variants/lora_relay_v1/variant.h | 1 + variants/lora_relay_v2/variant.h | 1 + variants/nano-g2-ultra/variant.h | 2 +- variants/rak11200/variant.h | 2 + variants/rak11310/variant.h | 1 + variants/rak4631/variant.h | 2 +- variants/rak4631_epaper/variant.h | 2 +- variants/rpipico/variant.h | 1 + variants/rpipicow/variant.h | 1 + variants/senselora_rp2040/variant.h | 1 + variants/t-echo/variant.h | 2 +- 12 files changed, 67 insertions(+), 53 deletions(-) diff --git a/src/Power.cpp b/src/Power.cpp index 12e92b3f1..dc8a43d46 100644 --- a/src/Power.cpp +++ b/src/Power.cpp @@ -164,7 +164,8 @@ class AnalogBatteryLevel : public HasBatteryLevel #endif #ifndef BATTERY_SENSE_SAMPLES -#define BATTERY_SENSE_SAMPLES 30 +#define BATTERY_SENSE_SAMPLES \ + 30 // Set the number of samples, it has an effect of increasing sensitivity in complex electromagnetic environment. #endif #ifdef BATTERY_PIN @@ -176,66 +177,71 @@ class AnalogBatteryLevel : public HasBatteryLevel if (millis() - last_read_time_ms > min_read_interval) { last_read_time_ms = millis(); - // Set the number of samples, it has an effect of increasing sensitivity, especially in complex electromagnetic - // environment. uint32_t raw = 0; -#ifdef ARCH_ESP32 -#ifndef BAT_MEASURE_ADC_UNIT // ADC1 -#ifdef ADC_CTRL - if (heltec_version == 5) { - pinMode(ADC_CTRL, OUTPUT); - digitalWrite(ADC_CTRL, HIGH); - delay(10); - } -#endif - for (int i = 0; i < BATTERY_SENSE_SAMPLES; i++) { - raw += adc1_get_raw(adc_channel); - } -#ifdef ADC_CTRL - if (heltec_version == 5) { - digitalWrite(ADC_CTRL, LOW); - } -#endif -#else // ADC2 - int32_t adc_buf = 0; - for (int i = 0; i < BATTERY_SENSE_SAMPLES; i++) { - // ADC2 wifi bug workaround, see - // https://github.com/espressif/arduino-esp32/issues/102 - WRITE_PERI_REG(SENS_SAR_READ_CTRL2_REG, RTC_reg_b); - SET_PERI_REG_MASK(SENS_SAR_READ_CTRL2_REG, SENS_SAR2_DATA_INV); - adc2_get_raw(adc_channel, ADC_WIDTH_BIT_12, &adc_buf); - raw += adc_buf; - } -#endif // BAT_MEASURE_ADC_UNIT -#else // !ARCH_ESP32 + float scaled = 0; + +#ifdef ARCH_ESP32 // ADC block for espressif platforms + raw = espAdcRead(); + scaled = esp_adc_cal_raw_to_voltage(raw, adc_characs); + scaled *= operativeAdcMultiplier; +#else // block for all other platforms for (uint32_t i = 0; i < BATTERY_SENSE_SAMPLES; i++) { raw += analogRead(BATTERY_PIN); } -#endif raw = raw / BATTERY_SENSE_SAMPLES; - float scaled; -#ifdef ARCH_ESP32 - scaled = esp_adc_cal_raw_to_voltage(raw, adc_characs); - scaled *= operativeAdcMultiplier; -#else -#ifndef VBAT_RAW_TO_SCALED - scaled = 1000.0 * operativeAdcMultiplier * (AREF_VOLTAGE / 1024.0) * raw; -#else - scaled = VBAT_RAW_TO_SCALED(raw); // defined in variant.h -#endif // VBAT RAW TO SCALED -#endif // ARCH_ESP32 - // LOG_DEBUG("battery gpio %d raw val=%u scaled=%u\n", BATTERY_PIN, raw, (uint32_t)(scaled)); - + scaled = operativeAdcMultiplier * ((1000 * AREF_VOLTAGE) / pow(2, BATTERY_SENSE_RESOLUTION_BITS)) * raw; +#endif + // LOG_DEBUG("battery gpio %d raw val=%u scaled=%u\n", BATTERY_PIN, raw, (uint32_t)(scaled)); last_read_value = scaled; return scaled; } else { return last_read_value; } -#else - return 0; #endif // BATTERY_PIN + return 0; } +#if defined(ARCH_ESP32) && !defined(HAS_PMU) && defined(BATTERY_PIN) + /** + * ESP32 specific function for getting calibrated ADC reads + */ + uint32_t espAdcRead() + { + + uint32_t raw = 0; + +#ifndef BAT_MEASURE_ADC_UNIT // ADC1 +#ifdef ADC_CTRL + if (heltec_version == 5) { + pinMode(ADC_CTRL, OUTPUT); + digitalWrite(ADC_CTRL, HIGH); + delay(10); + } +#endif + for (int i = 0; i < BATTERY_SENSE_SAMPLES; i++) { + raw += adc1_get_raw(adc_channel); + } +#ifdef ADC_CTRL + if (heltec_version == 5) { + digitalWrite(ADC_CTRL, LOW); + } +#endif +#else // ADC2 + int32_t adc_buf = 0; + for (int i = 0; i < BATTERY_SENSE_SAMPLES; i++) { + // ADC2 wifi bug workaround, see + // https://github.com/espressif/arduino-esp32/issues/102 + WRITE_PERI_REG(SENS_SAR_READ_CTRL2_REG, RTC_reg_b); + SET_PERI_REG_MASK(SENS_SAR_READ_CTRL2_REG, SENS_SAR2_DATA_INV); + adc2_get_raw(adc_channel, ADC_WIDTH_BIT_12, &adc_buf); + raw += adc_buf; + } +#endif // BAT_MEASURE_ADC_UNIT + raw = raw / BATTERY_SENSE_SAMPLES; + return raw; + } +#endif + /** * return true if there is a battery installed in this unit */ @@ -894,4 +900,4 @@ bool Power::axpChipInit() #else return false; #endif -} +} \ No newline at end of file diff --git a/variants/lora_relay_v1/variant.h b/variants/lora_relay_v1/variant.h index b310223d7..9cfb69337 100644 --- a/variants/lora_relay_v1/variant.h +++ b/variants/lora_relay_v1/variant.h @@ -80,6 +80,7 @@ static const uint8_t A5 = PIN_A5; // Other pins #define PIN_AREF PIN_A5 #define PIN_VBAT PIN_A4 +#define BATTERY_PIN PIN_VBAT #define PIN_NFC1 (33) #define PIN_NFC2 (2) #define PIN_PIEZO (37) diff --git a/variants/lora_relay_v2/variant.h b/variants/lora_relay_v2/variant.h index 172da17f7..3afe8620e 100644 --- a/variants/lora_relay_v2/variant.h +++ b/variants/lora_relay_v2/variant.h @@ -100,6 +100,7 @@ static const uint8_t A5 = PIN_A5; // Other pins #define PIN_AREF PIN_A5 #define PIN_VBAT PIN_A4 +#define BATTERY_PIN PIN_VBAT #define PIN_NFC1 (33) #define PIN_NFC2 (2) #define PIN_PIEZO (37) diff --git a/variants/nano-g2-ultra/variant.h b/variants/nano-g2-ultra/variant.h index d69235fd4..c328d2271 100644 --- a/variants/nano-g2-ultra/variant.h +++ b/variants/nano-g2-ultra/variant.h @@ -170,7 +170,7 @@ External serial flash W25Q16JV_IQ // Voltage divider value => 100K + 100K voltage divider on VBAT = (100K / (100K + 100K)) #define VBAT_DIVIDER (0.5F) // Compensation factor for the VBAT divider -#define VBAT_DIVIDER_COMP (2.0) +#define VBAT_DIVIDER_COMP (2.0F) // Fixed calculation of milliVolt from compensation value #define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) #undef AREF_VOLTAGE diff --git a/variants/rak11200/variant.h b/variants/rak11200/variant.h index 007ed8f15..3399594e5 100644 --- a/variants/rak11200/variant.h +++ b/variants/rak11200/variant.h @@ -56,6 +56,8 @@ static const uint8_t SCK = 33; #define LED_PIN LED_BLUE #define PIN_VBAT WB_A0 +#define BATTERY_PIN PIN_VBAT +#define ADC_CHANNEL ADC1_GPIO36_CHANNEL // https://docs.rakwireless.com/Product-Categories/WisBlock/RAK13300/ diff --git a/variants/rak11310/variant.h b/variants/rak11310/variant.h index 6334157f5..ba3d4fed7 100644 --- a/variants/rak11310/variant.h +++ b/variants/rak11310/variant.h @@ -12,6 +12,7 @@ // #define EXT_NOTIFY_OUT 4 #define BATTERY_PIN 26 +#define BATTERY_SENSE_RESOLUTION_BITS ADC_RESOLUTION // ratio of voltage divider = 3.0 (R17=200k, R18=100k) #define ADC_MULTIPLIER 3.1 // 3.0 + a bit for being optimistic diff --git a/variants/rak4631/variant.h b/variants/rak4631/variant.h index 956bcd772..cc18a901f 100644 --- a/variants/rak4631/variant.h +++ b/variants/rak4631/variant.h @@ -254,7 +254,7 @@ SO GPIO 39/TXEN MAY NOT BE DEFINED FOR SUCCESSFUL OPERATION OF THE SX1262 - TG // Voltage divider value => 1.5M + 1M voltage divider on VBAT = (1.5M / (1M + 1.5M)) #define VBAT_DIVIDER (0.4F) // Compensation factor for the VBAT divider -#define VBAT_DIVIDER_COMP (1.73) +#define VBAT_DIVIDER_COMP (1.73F) // Fixed calculation of milliVolt from compensation value #define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) #undef AREF_VOLTAGE diff --git a/variants/rak4631_epaper/variant.h b/variants/rak4631_epaper/variant.h index bc2eddfee..d8a5e5597 100644 --- a/variants/rak4631_epaper/variant.h +++ b/variants/rak4631_epaper/variant.h @@ -223,7 +223,7 @@ static const uint8_t SCK = PIN_SPI_SCK; // Voltage divider value => 1.5M + 1M voltage divider on VBAT = (1.5M / (1M + 1.5M)) #define VBAT_DIVIDER (0.4F) // Compensation factor for the VBAT divider -#define VBAT_DIVIDER_COMP (1.73) +#define VBAT_DIVIDER_COMP (1.73F) // Fixed calculation of milliVolt from compensation value #define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) #undef AREF_VOLTAGE diff --git a/variants/rpipico/variant.h b/variants/rpipico/variant.h index aeda3d833..ad6d0b211 100644 --- a/variants/rpipico/variant.h +++ b/variants/rpipico/variant.h @@ -22,6 +22,7 @@ #define BATTERY_PIN 26 // ratio of voltage divider = 3.0 (R17=200k, R18=100k) #define ADC_MULTIPLIER 3.1 // 3.0 + a bit for being optimistic +#define BATTERY_SENSE_RESOLUTION_BITS ADC_RESOLUTION #define USE_SX1262 diff --git a/variants/rpipicow/variant.h b/variants/rpipicow/variant.h index c48b901ac..27117680f 100644 --- a/variants/rpipicow/variant.h +++ b/variants/rpipicow/variant.h @@ -24,6 +24,7 @@ #define BATTERY_PIN 26 // ratio of voltage divider = 3.0 (R17=200k, R18=100k) #define ADC_MULTIPLIER 3.1 // 3.0 + a bit for being optimistic +#define BATTERY_SENSE_RESOLUTION_BITS ADC_RESOLUTION #define USE_SX1262 diff --git a/variants/senselora_rp2040/variant.h b/variants/senselora_rp2040/variant.h index 9eda65521..2f68cf034 100644 --- a/variants/senselora_rp2040/variant.h +++ b/variants/senselora_rp2040/variant.h @@ -8,6 +8,7 @@ #define LED_PIN PIN_LED #undef BATTERY_PIN +#define BATTERY_SENSE_RESOLUTION_BITS ADC_RESOLUTION #undef LORA_SCK #undef LORA_MISO diff --git a/variants/t-echo/variant.h b/variants/t-echo/variant.h index 8679dbde9..345091c2f 100644 --- a/variants/t-echo/variant.h +++ b/variants/t-echo/variant.h @@ -213,7 +213,7 @@ External serial flash WP25R1635FZUIL0 // Voltage divider value => 100K + 100K voltage divider on VBAT = (100K / (100K + 100K)) #define VBAT_DIVIDER (0.5F) // Compensation factor for the VBAT divider -#define VBAT_DIVIDER_COMP (2.0) +#define VBAT_DIVIDER_COMP (2.0F) // Fixed calculation of milliVolt from compensation value #define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) #undef AREF_VOLTAGE From 1e4ecea6fc5b63c4a44103485f9bd60e1e98ce42 Mon Sep 17 00:00:00 2001 From: Andre K Date: Mon, 29 Jan 2024 23:07:09 -0300 Subject: [PATCH 144/472] update to `Meshtastic_nRF52_factory_erase_v2` (#3146) --- .github/workflows/main_matrix.yml | 2 +- bin/Meshtastic_nRF52_factory_erase.uf2 | Bin 122880 -> 0 bytes bin/Meshtastic_nRF52_factory_erase_v2.uf2 | Bin 0 -> 127488 bytes 3 files changed, 1 insertion(+), 1 deletion(-) delete mode 100644 bin/Meshtastic_nRF52_factory_erase.uf2 create mode 100644 bin/Meshtastic_nRF52_factory_erase_v2.uf2 diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index ed32260fa..76f9841e9 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -246,7 +246,7 @@ jobs: id: version - name: Move files up - run: mv -b -t ./ ./*tbeam-2*/littlefs*.bin ./*tbeam-2*/bleota.bin ./*tbeam-s3*/bleota-s3.bin ./**/firmware*.bin ./*t-echo*/Meshtastic_nRF52_factory_erase.uf2 ./**/firmware-*.uf2 ./**/firmware-*-ota.zip ./**/*.elf ./*native*/*device-*.sh ./*native*/*device-*.bat ./firmware-raspbian-*/release/meshtasticd_linux_aarch64 ./firmware-raspbian-*/bin/config-dist.yaml + run: mv -b -t ./ ./*tbeam-2*/littlefs*.bin ./*tbeam-2*/bleota.bin ./*tbeam-s3*/bleota-s3.bin ./**/firmware*.bin ./*t-echo*/Meshtastic_nRF52_factory_erase_v2.uf2 ./**/firmware-*.uf2 ./**/firmware-*-ota.zip ./**/*.elf ./*native*/*device-*.sh ./*native*/*device-*.bat ./firmware-raspbian-*/release/meshtasticd_linux_aarch64 ./firmware-raspbian-*/bin/config-dist.yaml - name: Repackage in single firmware zip uses: actions/upload-artifact@v3 diff --git a/bin/Meshtastic_nRF52_factory_erase.uf2 b/bin/Meshtastic_nRF52_factory_erase.uf2 deleted file mode 100644 index fffff13ecd3a563c726bab7b0ad3cb27b8661b4b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 122880 zcmd?Sd0bOh`agbda0<5Npq&qB9kEs;(&a`$E=0)hIrkEbLqFf&=llBn^L;^h zUG8@7cHYnPoM$`dJVC{{J+=4`yO07QWE3Doz#4uGEIRf6YJ^C|AFc>cB`mvP*$Yb* zEc;>k&);5w5FH#k{wZu%<8neFs)hCcX0bW`@2_{h+yCjgJ^Svzuj@5<8(%w`f7+Mo z-JWp8e+7>}CV_kSkLDT}+ut?<|8yRIO!ZFuZNJKAFJR28uE07c5w*yhM2l3pu}8@i zzj`vM_BJvTDpiiWc~J%@L6C8g5J{VaDZ%x^g+lJUv>DfO8l1=H#-$*Qw8bx_lB()4 z&qiSzDR0Uz$v@dQ$c?FTc*9vlmnC`)t>KM#N#O~k0zU`;@Vnf2n|~j?kKa2iN#2y&eI=TtgiOm_qC>)DITWyMxhtgH6i9Q2 z4onJMNK$Uhqjm-S*Vrd4#A|&0X#I`AKZD0#2p{akKhZv(tB0O`TxV%qo#oqw6v5S* zN0J*e-tGqf{p_AeLgpCju}}hg|L!Lg5@wb|nuM4q+2$K^on#>a#}&ure?3uEvNU?6XfYjR5=DNo9v)Uh6OP?#Iz>p-ggM%7Bv_BcT(q|7&c zisuznTr+C<8DHN-QeG5#F_m#dOPO!&;dxISeW(6?V>CtDJdl9-Vz92?-1DL=d?ivT zUJRlFDGAf(P*XY0@0-x{Zu+Jbwd6F3D11G7QOX>)Yw|`b_V~L-;Qt(tKMCiY_?Olr zmB{8H)~wW00_GD3Ntxk@dZ_j;IF9tMWpuKf=7T0E1$7+TPg1{H51Mf4X|RpdRtvxP z<{;kdun;QE%1hR1olNSwx=Wp2De~Ro`e0sHi4+xK;mZpRW1 zo764Gs1-p=sHN1H!vA?5e~}CRfrgf##|>`Gw83*wo3$3-jy9ImR_W{8Fg695L56+$ z>Y;jTW2JIjb610|SdoISUyQSadaKTpdbv?(vaqPGm@3b-bQ1F9Mq)N$BV=y|9PC0e zLue{PxJf(wSz<;dJ3(8nS6SZI&oTMaL0P2FqLOIKuS0UfP-T-Mx>B%7{A2CB7RGlB1|Tee4&hH0JU_3%y^p; zBL4&-!tc4hPD1(b^sU@Tm0)U|`UHIuzH#*aM)3a&JpN)A{4pOsLldz&X0JKURFK(Z zzja$+_j?R!k}do6No_~?{RN`Zt3jxgEM05ztB3+V+ygxJhUFM=b0kex%xUzicqWvr zAiIPzzY39!kRIp~N+m;RPXe@Guq;aOr{|c0vbO1^fObYJp%j#O+9q*`FQ#GvZ;bZU zL5%j|i+<%~g=nV_6=?9=Jkfxr9<(5Zj6=IC=u9Wd0Oa7!_gOBor2L?MSKDk;Nv50O zkbVcysz|yg;UX(V>XtoJW{}jNr~G!fF>?pvOny5GG7}8*4bHE8uWR(8|2y*kPdxq- z7yPB9-)5v))16xjH7ZXDiSJ%ji%Kqb5-OUNnolJfk1nB>aeU|od>G&TTrH0R<~e># zoFYz^a6Gs2F5V`SJ_i2FzI#9anSlp)0xx1dB&pU;q}^Nx62aZA6sg>c#hXc+ztq#F zmWfJLre!R-JUFXTzq(bf^0aB)kn(INQH4r0)O<<-G_n|IWR^u#fiy;oXN8JE3;Z;x z?MhQ?W~n}<4a)}E0l9K9B`Xy$zYOptW ze;;wVM@4I9MG(@IUHI9W$_U*5ZoMbRzqH>^M+;0u>_aqA(SkzQDy$jLqxk4~D8D!Jx{)vMA04dOyCRj56VkR5&~|iQ zoMn88ArOh5mLElBn3k~q?&7RQy~IYMpjM9vz)~*Q<^%UbN=NVG14wnR;}RgBLFQx$Vnu%-Bkx*no8?XgeOHzksQpzRPra#SV!@1 zMEjq`C~V)*TfNZNCBZann-S zC)XlPDkBv{QlbOQMK{K5N9vy~M1+>|t7DqQ6u$;~NgPk1$%OJBoicp^RYXms#J0(@ zWY8bd;Ldr263TQGYZG`c&5>4L7&6JSDvO8}(2el_rX`L7x_E199?9g8im9EJ!zQpC z6s3A8eFL^gd68a7Z`2cXf&QX}n8KHqP*=gugJ-91q$=y&ZKRMab+>s4&vuID5ZNS1 z3POs)&v$xi#jPL9M@mA4!q0X}RnW#u2<3F@JV@aySwFA}ts;9_keA^j`|Tc~ecbcw z^zznB*^k*GW|C+L8>W@^i+Uz5(6eD_xa^fISvfB6W@xbAwh8S%szSY6>r&a3Yg( z4;z91pLzT}T<}Mr17R+oau?TBpShBqrKn_QYb)6~M*kgTOpu|Hjnl>$giMam%^=tK zmmsFg9LQ;1v9P*CkJnK>X2z3-BJYxQx-<5emsIxtp z|57HJftV%vfd8HgY>1JFm(KfGe~S5M{>Sz^3=!wXEMW!O54y~P2K${m=UHvXl`KuB zWUI(F6^W<|fN&0Ydi-VYPy|&Lu&2w*>!ke_Be2VV+yIpDl&m9L0Q8&2PLX38c3Yrh zrzp^L#7xM?*NPcJ@}*7SR;o|ExdEA(vV8Z0NI9nPf04)E(*=Lf_2j5zAr-|@!FwRb zU$wZ|9CI;7ejUeo>#uR69;7DnZ%w`VSg4cVrYq18zfISkXQy`HI(DxJ%ih=J&#>RBF#VWCWce8y?Y3Kl-8Ysj*R$lD^PL`kJM?6U#Nyqt zFPn%ZW^dG=?(~e2(tnU)dGsV3o`&&^(*I_;)Jeva>eqDduDQep)S)b}{D~MQm*qKg=_6+MGA5-}M zg~#8^1%ITN$Z7Lo*{@uegGCkJ?NjUIPod2*=Y5-0b|xX`+;Mv!aHx#Qcf1*Lxa&>v zNA|uu-W6A}FzT37%K~&kb@p2}f!#;&a)LWh%94;P96v5*ry`7>03`EN;K%sxqcubP zDEr!lA89k@N1h&enRKZiscV0S8doL!pQ(|5EB6ZgUi-R;`>64tO(4Vc_$bgLwr0i@ z{x9+P|MA@`Yk3L~Q`@XBF~R6ntE93kvqJdy?`LG88L!b!YT%{yYv*`bEo1Hu zat(|!?btf(WxNs8Qjkh8`?!;S_HJmn2q zwl$lWwKQaJhB4zQR%ygiT?7&#Mvs`Nd?B?n;TH=8{Fo&LD%16>bDdJb5yNKCF@2~L zcIGy+`+XjkaTRpT)9g$$uVuc$VlDG5jdjd#XsltL?G&pBB~oA=a~p+qRiCVg>@z{a zF642-Zes|${M4Izc{>IAB4Q??#cYID)X!DJs3n0B`rk?(e;*h813)TAp!1#X5Bg+* zN2lXV(5m6~x$!^rYtgWNEk5MU>DK{V``T$vWjv(5L z#V&fbduvBFZrefACeoli7xfc1tZ75b4!ZqyGro%iEbOmbTK1fL*>KCgj0*Tw9)&HA zUs)w@_6{W(qNDrmwI_$|wFv&XKt&N86@BldBJn?5sOYTu9u)x%1z{Rm1T=JT zn1=rU>=h>!-LqF@6=Mqjzw-F|yWsC?ukm~&n1{LOA<&OSyKaLXsI%pp9|BGA?@mon zLBs&`h1Un~mnTWB_vpYWO$K|v1kdD}?#aU% z;r~>gj4AwI;qf2mg8%hraSrf|B(kE{stOLUA!{$#LIPu=p$=RJ*&4tW}r^J8jaD38P8TA)LC^ zV@Axpe6Nb|a__Q;9i^ae7Uyq-|E2ktIwvkxl}8khDg0mM@gMJkzrqw=O2i=0pC^uU z-wM&!lFvhTbkQmN)BGeH0msyW+s^T2A8o4&BO}dtWwYt#}&wNjOVE+ zO0aDq_@D-R4>|C)pIIgkX@GJ~3`Cav-5;)1n%sx3>dq&yr{HC@4Jns#SA98%ull}AJG&!Gfb+~jC#XlpLdqy!lV@%=yHy-~9F8JfzJ&6$>15Il;vqu0 zkb3w4!FUax)a!1o&&TqiBEih$=5x{MQr!Nd?aPPWZ6U;`f1*VYBV0JFwZzomh;R(W z%Z`041F@xFES|QV9w#6k9a7`{54`sN$C$!Dm&ZTA1^=BlB!nU@ z8pzr(RmH^3XFJ2wh*(vrbaQBltOVmjL?}#7X^~1}S+mn3t-zjILZeJy&@RK0rk$5F z-`X*UzipYg14r!`0f?88^O!|Vod@3 z&#GAle!*B#s#R6H4?H`LSS-yY2PCBgGjHH&7g=5legL_Qm*!B@#fv$~tmh;%mbF;c zkaOgknVdYAgFKfF$@90(AkAMr%c5eZJb#vJRn~NmtHlys0H7nLfF8@@_2Cr!WX>4KbWdkH<1yUXnmV?ys#I z@;)&l1mtAN0m-VnsR?oIyiE6M1tj0c@*Jb@l;|BGKdyoN*n0h)ly{TggTImWd0<+LDig;p-l%!TG_ib(ekHxb6k3+Af016R&!#u% zGwEQ{uU2`vguCXu8tgUFF$HG0Y83xQ;J=#3KiCz2sI`otT0_ifGhc6rX)&(_J^6%r z1N=W~4mRDiVyXWqC-on$ajQ)MSwD-CAI7@DMzFmccj9a2(;(@E^48{2Rj%W(X7?CQmI0(*B@Z>yrGR|fk#qf{x|Gm!RAL4@l1rFD=AzU8; zRON@I(54UeDmYZnS1-V*3gi|3r5>>XrM|@;DxU*@YmQ$@G&QaiMNB9i5ACe~Aq5q< zJ(xo^g+uk@YAJ{6L|Vq78VIOP093~fqZ;2GUt0xK72iFl79*Pp$i{a+P%EN#T;s9T z4`cfiU@JYyBRc?D9gaJ10kV^R2U!meS>M`=R@WGXGxrqRqTgkDQjnoOe}5hE;F!Yy z?>zn!UGOiaq9$e<3#eaLd}x%Gh)N6VLn+9tLT#*vHYzJPNH9IfAhNWvAvtZVzj3yq zBsePl0%XmfWdqFEYIOIPm0}H!q&n*TL4SML;y$FmeFOf#ne85+!9}-Aci;@K>^_n* z9miK^nh2HiI;8&5BC>@@=waQ$=YS9B7IOPi&@Hk}yq)No&)JEIO0W~>gM~NPJN|AV zWvs_B+%IU7B04}vAr(~kumzyW;`NP2eRjJW*crG*dI(yh=VUV>R{<$JINf7R;r|AY zf2a%oX7Jf_wsZ+^Qz0d;TZJ9><@qnLrWaB^&|-hnk88|{#g{`@plwRX$j0SquKb$r zH)_Fld(c_)yY$mrMHR~vzPuzZPrd2xC+KqbIk!}@`MCb1#RKkZ=@j@9%+8^E%d@VS z_L*>Y)^@B7hGE;Dzx&>yyQkJlDxNl7G`ZUd_X&nj!#CD@Z}mFpcRpCZTOlZ!5BeQ` zt93)y#nyr^T8=f>9r|xre{CQ{nGw3csQ}x&KNZ^fC}`)^Tsyx3w6}_(n%_?2R^U~@x&*L3a2+FowKdGEe$e(i?z~aEj*h0_ zO+Z&ufv%QDDd9;fcv5_KUhPlTY|}UJv_tS;s`w|@zTGPcgF^buLr2d!B;~(aN|8&#UOz}3+ zF7M)!V9=rEL@e$T=e7BCrv$vhQfS*{TgwvnP-5yv{dj0==UTjm+V?ZizRzj*hW0(K zU9w{-V7S^Lri{n&^*A@1;I1x96oXv3Vv*WH$O}U)d>G|>z!zHhNqyLRfcqQrZG1|B z9P)(Gb1{&;w;1|n4)#ul9;S*$+{S-S6;~Vw zYwvx?mP88gAI^2%b_UBmi!q9mx18+^Q$hdrQjg8p27$MaBc_NcmXlO#x~(-H6@WNIt=8PJ)_8)X zT65=WP4GcXQ{m9-1=Gox!hbD~|6~{ZzpueH89W@f!?kkR5?0*~F}q00?Z8=94KdVj z95`kdJR}o(&GN~>q0fVy-ooQev-rBtEy`gZZ!DIsZtm4^cZKKBb>CyX{wcHtfgf-w zHPHJDv=v;UbUGT^8yZa^QivN(DNrRY& zFqL5KANK{an8nm1*6?y)PE+r#zSJpwz(65Q4)n&BYlEnl>swj!)C$wv2~W|*rVmV? z=pTdrg^THYeJbs1`ptTg^-w4qfmeB9@ATTcjyTwqmSw( zU>9J!;d=GcrWN2({LRvCiZX51-)_&scRBT2URfp?lWv%87*qJa$>Sg4g8%xUf}nO| z`HJh-&pL^}eQI57+-urwJZ!B<*_pf(>?kQC9wWlisp^iJY59iWe6~3jQA?Q6~E7^E7zSKh{-{Mo^S30hALUCa6EXunY z`l70Qf#&?T25fQk{;eO{pHci9;r}V(@mIUz5BzrSLysYTi>5t?`0aix9`oCQq56N1 z#z1RDOy}_@3}3q`}rY_j_EJ>ugs6_wjRPh?v+st z|493PJ&%8+EB@1T3@U^=eDDLCR0utBZ^s%M`wMS>Zc_+9?ke;?#oR1dk`=xpk~-Zf zc)nE%(YUl1j8f*|yDHPQbm*(00#8qiADs1gU|)ukiyVClnR>bPDpPqDiprob!2jiR za5mCBPOGVeVGDj5SN1TM)prAW_Dv6)S>XjaN7H?YSh9F#spn?M^N`)k4_UzFhn#~E zKO)izjc25GiQjkkJP@AZDDOG0=O8 z%jVc+d0^N+NTg!9ED#v;MXEG`T(|wTHd0b&qfsaDM#hS59xN3>4#VtRULpWZHm|Qz(0Yh?RHXkkKvWj`xu;y+6 z=SMyR^n~*a*L2SS${;W+jN0D_{cjVG|1|hwXa7%six~JLzWaq5k)_+MQA1L^QNOGmqQ)C=RK3GpR6L_YY2u^mX2yYi zJx8%5$76O4^!|-&p+5zm@iM>*F<~xfT{UxZ{3zPSV--0h^CvjQPvma)R`ce4VOE^R^+7bjNT*DmneA^TiFth_Ba3fF7QL+`sJlKbTbITlJ4Xe0VbC{Vk-|=@TJ7oB)0x#!9HfrBdtW zl+DQ{NxD0e2r09ZErwjecVKT!;r}j={|p!WRZtsS*>_SlByUVg?G~(%GVib(Q{GB` z3+l!n&b`I1Pbo}Z3wwUBXJ)ZpSlMT|j`hMFeJazO>sT+`0$VZH*QA(}^Ef}zpV`+_ z-bj9x^B=tct;dXt!^Sko*P9IadQDu$8De&uaqd?f#DEb~0iNDjlqX~p4)i`ZAOah* zx(52{n4#qmdRF>u^>|?1R_|hua2%7Cmqt^*Tm82}L^>Qtq`hizKH-F|e%l6n-x?VFvgUR)9a@SsL0b0iRO{d5@5NHm2||=JCf)Z>Rjn-m_;R`wsfu z^h3KkEgt%4{N*~%_52H$6Bt+HS)0veOZaf;jN{PR{NW0)@TUuWDgq%ZaAK(+WCi*{ zR$xk+KV$_4m4=jpk1v8y1wv~Qx>d1t5@4en!e-Tno*Xu_XfF<%2LPK`z$V%yFYsVB zpBK2l8o${ehTd#f_2b|>P;t4Q>$ zdxiMP@MT>!#C3RU?)tCbdQZ51OyR$o$3NNyf1FV{(0iV%zlaaxyZ;Q{{OSKue^;?4 z0QL9BYX6_kL$1Y#Lpc{SVGZN0qZ4p!CoI^9gYz+PE(X(tJvSAc=jL_V>9;8y_S;Nk zvGx|m`E8Q2J_o-bTj1$e&! zdK)+%*aKdRCh%HlhP@VboY!KV**&W&12P((INd2!p6+y4;ymK?46Ngj+~@^oJ4w)T z#uWY~JpM5*_ogSFKg9nCWt~>Um z$2EqTUbUW*lFVfXcpqS|5Ihbf^Rq)`Iu0HOlCi>8BX}c7=0``9)vLV9_SPzxSs;dN{K~26k=$Rr-mcpJt?5!GfhjSum@g>ZQFlWP`GynQmEFYY*0?P+1E3o{) z^1|uw6#`yz7}q}vFk1qct*%E3dGjeiJ`3Ik+xp!WOc5Edhb{i!EEvCM9Jthv^*KkL z4E1_MVDd673Wbry;|p&J2!in@-q%0DhRO49`uY~!^z#!k-ohtXm9`M}yDT{;1jd|1 zJf7(%@IIsYH$wm4!s9>F1%Elr*)Q zCv5^hK_61UtRFC!0@3r!;%|w9I?`qqJHiR*De7sH5dMZutRxMAp7_4L8^)3l)a5iw zxw3+;PvwI0KngMM_Q6~YFtdP8FTHopCx8-^gDn7k^S*^Kf(Zpai(2BEP?!kbaE+tv zXlnP1lNA)%V}2YloBNj5AL;q)j5`)JoGpQw9#B~GjX2%i-mDfpXN0^-vPiN}0q2q( z;uMupL5Y*a3!Cw570gyRkLRWsQ}}P?@qfSte-cK~$G9R`6F?uB7g6SdkO2CsNmaih zGqu~iq%1M#s2E0d*$Y~}0&)P(calVgi9dsnALebp6+k`QxT}SAMCpRY%WO`u2u5Zu zhIt$QaogSP8^BDHc|tF~DRWo1%%zqms3B&oq$a?)!>1jGO{UB*Sb5ztiodTZ6Q4^n zNSKa+_}~b`9>Wh7qKq4r_+3*bK7JmK?=eIe=;7mtaX6-RvI``c6RFi9Vi<4MpAymA z_3mww9`j@6dhNMJQy6#_qo}e(HH<9F7Cwf%LXO(s2>##3kJf(k>YSJf1;e=?UtVbZS-R1Q?M&6>5L$K(qdb_D0hcC?i2P zp)_Bka1RfU9`iF-f}^0OQyCc^~t(yvZLV%wGnu>|vS; zVTJ|-W4=q!c*=wNUJ7zV3v&WEhz^n|7>I&*!*c}um%~RbgnJX{Hhu1BC6qaLRMPdN zgzS2f#3f%GF8P^DNex#r+SWE-Ej@i1-u-+TZe16hxUVZTUe)U#@O+w z6*(|6DM#@b;@W061<4SDY9rPZJFRLHev*i}*~gzn+;fN|M{mnX)G`-jk^G2k(H_0q zxjK;Vl2$+J4=kDD2IIbxQ0DAOxLS*kKr3z(Ailf@+GOKp|j0v!i-xvmhndbWzg(Jvu3E zW`02(0;cZx=eY$%LPm%L>d$Vw2}HC|9Y_;u35`dV7et28x+qy2!ENhqIbx+PAaycI z^>FUvB5mdaNVuR>6_RPIHT1{w^T!>_qa#gwn|m0-9FE` zDL1iG;oj4AI@Kn2rotPpnX4rZYAM|<$rHL;GD@$kW<8A6Y#dy_Kzo*r2MzFuU9a%1 z8&mj~^Z3tp!9NFDLSN9&6@+N=WPv~=5t)Us2+$i2wHqx5N?`Ajl(ZhV&l2WMma`Fn zPw{y#8bOPVHGafQ8&K4Pyhp-1kiK>-pZl!%Kc+2Q)|)F!DEZPC?*6x>p)5fo#=Dt+ z2Hwtucf|K$n;?S-&WF$wsHf{aLAygt;oV4(`R01<8;F@TFgb{TIRn^c5ojn{79U&1 zok!|lE%Cu|lnv&sVu6N*rhw$-rh+<%dXD1Xi1xpN$A69s{=kj$FbjBapk7r_*URq$ zLSkZaG}LNQy&7uJ3u;whAvh~e4E0K~_-Nu?Tmq?ov7ELM2wQkOwq=QUo45I@f!;>S z3x)mvC3!K5;UB60?d0*FdmsM)Q+c_wAIr=CPF@fx0lAn*r$YN7e8Zs;SR^Syxq|wf zMDaqwtMgY7N@SB0WKvKLVitVDmy?3siQAidvIHVQc6mK7Lx^HA^QZ&cd|0Aj2>|hA zxF41|nZWrw?Wm%$XWL5xdZ+{wY45XYk4V8QCmMGegH~uy zEHf@!k&}q$s0@H-voIIrn8Lr3$Nym${Oi~N;?J2)Y*4hD$%`Tl!9f#DTiFnwiUuY0 zxBDb9tx*}UML)OoRg<_wqzR{0x$cc2hJE_j_KaLo(_^`si!|L9d<7A`4*sL*ztCG* zosT54vyHGNNfOv8#;}+15qw_f6H2Mzic8=XVw<=037~hc^x{@FGM%)+RO}EIU(fFgNUncU@|RXN3i=B;b1J@3}zz$Yr*!_(RApDx&a+ zUhC_GwccL}YrMY`+5El2Deo_K!RS^$K$g)Qb2jy$X}VeXc{U|H6a46&6{Ia-R677i z$p2kD{_|Y$2R-|BBK*pVwa}Y0V}SWCMloAlf2Q@TDQSK0=}si*mUSr1EIdt-W}E5CKm^sClvd7mL`7OgI@ai9AQx4ktEIGte@iL zXNcIp1)!*FmWvHU>~gfATephr+57q*z%J<+&Fnu?{_p1Tk9WcUlp4Xzj{=549k8_- zwphfd&sYSEM3BmmUb(r5IpuM}X7>KnvYi#2@?cI$5fhI-fg`$`1->6yJeYWolQyCE zBG`L{W^s9mdB!0NE`>|%>oIHVdd!pJTJZgLwE{}IIzVa1xrQEd{7S>YbD^60AD~ps zQncMoZTRfAOz=UE;;DT-@+E*@j@~SYU2COTMf4ul0CchU_0;b9tKMVv(MHOho4Z1A z05R2l7*nEH(THHyif8*b-d3kVPj7cmo7By{tI+*@N?fxYIXVH{@eDj`x~D=;#}N89Gpg%hUTT5a8U%`IR^2UqY&`rI z#Ll%EK^~x_oJ6bx5GhMDvHpO!v7ZO~f_?#C5Z)Jn4*=C8?);Hgz^8LWn$*ln(@2w{ z{<+MV^-}6R$_JwT8cKV@m=rv1-y?~N#jOX0c2NAGWh{NKytKi>s^Tu-=urS-*Z z8p=uh1olBTCr(}z4l_XL=}8poIwcf!6$(k}92>A_J^1tgf$+SqS{Thi!n6!Z)dEW0 zB2~^bh`QE_zVDPgcbR?W6wCuZUE1;j^zKc9nRcZuA(WW0JG5}c`-5`0A{wrdD|K*` z;bKe`gCrcq{#|tosf2OI6UEHcmdo%&snTM_v%o>T4&JQ}Xl4&ATVP?E+*9Y6HrB%% ziiBP3L?o4!`41FSUz|9{w2qBJGY!J7wZc-^Vw(fND#X`Iz&EuVUx9>OW+Xo{deQ$K z|L;B?f4vL-!cB%O4J#0Ne*#i#ZG5=f5j^^>@mO0GHTdT!fjz`T#yg3->`y z@)Vu2u&$7uqH^?p)1S(i7of@K*to|xu}EhE8k){ZQ;1UHfS7rL6*JGWT@t~0f{{7y zS{0O#d2E2SqARGw2H!7a7Gd8%6L}1HzX`r;6#qu>e-)4a0vG%X>x3|pGExZ_l1X1F zNoInBx2BE&f9;3*5;H-^puU$p_LtyeLZcu2Utp91Wnj5|0?OnxO?pIQYOLRJ)Iaz1 z?fL%1RCii1RbqKOmze6wZIu>DG-0%q%4uGltBmxZ!OIKWnA7}2W_P_R*9W`^%{Ov% z0w(9=;vzIFpoItveANeLmw$9H%H)@YG}meQ8)bkb zK-`jGejbn>h3#g7`3*+3>9dfKx$yKVp&e$t&x2755M&lWd2tFHeOX{f+B9|)!#`60 zdymH-D?QHmpE%y#SXfk$w_)W*;D6MD>qpuIk)WX(l4}X*|0Ct<4cdkIaQqdK9rXmJ zifnRnuA!s>Jj9Idt{8iYnW($*YC)S8&)S(UfqA%*qKp;F1xzTQaT`W&B$z-b;odIl znf)?8Guxn3LHonJJiuRrkKz4!L;L*u2=9BF*H7Sg#P5O;Uo{{H#PRb8=9K~P52|}D z@Qy1lvqm#vC%Z}8R8fLK4J9Eqq3)z%?s18hI+`nB&O`5#EA*Jce?N~up7hv>KiQM~ zR|C`!#Kn~a^8@658|#neV%uK>JQy*cJBlUqMaj1i%{gPm^~T&)Q~$8ySPRA>uE_(V z^H=cD%$z#2q=AbVFj;qnKo22M>u=fP)kK?uifhI*0>1}sNE}B?t~53kXl#?6r!l4} zWKm%q3d8gV^b+m`(p@s>06)JTMs7+XGFJX*)=<(ZXd7vhW$>$)4_%i-mP#3jg*$8Wr z#v@1zxH+7oQ;+9r>Z3WDxeYX9vu@0tljD)=VGvU*awkWoGBT07MH(e&^X@pL_dKV{ z4KZj8_)KNP9a)09xbwY2?L<-Z)L-$R?OR&$7xs}fZG3z<8{AWA!8IOG#-|S zMWsdIxs`f}<*{7F9HBok&O!_K_)b>Y!pO7J~wQws24=`TS8Khrk4(0h!nNA zq5k1Giu}#uLrGNQlLZi?!AJH&$!nG;io#cl7=rXkTFVfS%Xif-hilvEFK+7uVH8q0 zdSCBvwPO8X9(NT`t>zmVG>3b4=I9yY`VV;LpJA!SesB0;yXL7!Zsu;#d%&DTq0}>$ z@&@k2DE&7=|2x3rp9J6QMyTon>Zv9uJ zpo32Eq_gt^SYifD*=k7wsi1)#IkzpDc^J>%tcDa-y#e@A0Y`J_`LGoZ94cz>pOd)S(rm4Y)yIBH-v+ZD$jgllY&_xGy>P5+r5&%}#6EeCVs0B6LF z;`t+u_hMnRKmoJd{)6>!?neC&bW}=+$sefYJkAanx--oE!CmpaB@FKQCESySYhgxM z<|4e^H+1MiopNtad=9}}>l2PG|NlWA|Aj92OB;id`P$I}O0|}8oaFu(BzKe58|v@V zzIe4;yH4ek%wsvxemJ+>igDX$<&WIx-)ubydcjZqJFR?M;$$Z*JMcEMPmLx+?g-XDb11Fuf@OeI`0D+U7K9~boVmukh>GK7Om?R>m71nuM+^Lld zKPcJ^*f<(aBuFg2j8Pz_#FoP2>AB)4E#v^4FnC%vIr;XT?#wwYWhXv>l zuq=dS9lZO0F41t@9hR@*Tt=fnBei4{J(Ya1!F^>=J>(bIxAE;iN|={$aoejS#76wj#|9OL|dKlCN9xN_D*t6+mGw z2bn22jsiEx_3*D!$uT>z5lwahbt70rSW)fo3f{Ap@Q;72kcbAKX3l zrk_#-PY||mW|LsXaDUo61#Q9iAB}wP{H787{~?e6A{YD}y?+K==2_(nCsL=a-b0v1 z!LgZEcQ|&;O3Zajd9T3=vK{lb^WK=(r@}G~mS|Y8eAmKyB`jL7;r4-+Raoa?S&_S0 zKfw~1tgH`Qc%k7QPimXfp~NlPpKEV~Sc-!b&|=>l{;#ZP@Sz|&Un++=qLPG;-oXC7 zxoVI-uqO~OPlM#XXu+201<5tI_Fq=#yWw}h?~>Dm!15=--h9oQ?B)4YPyMqtDV zbuUf!xV@?dFSPS}M&o(}{?$DGkHE(|`Cq3*%oUj1%UCZ2`z!`HLcnPHoL2u;s9Rib z0;Y#mgSQQ}a5y)OUxaORPq4Rxz)BZ05B6i*99!gQE1@#OJyRWKC29MLAXL09ju^^; zEpy2CWiH<(d%gu*oKS!*{+N*Yue)H2i#Xg{(l%gUo^%lcq~!?aXN`q%hhholV-{QV zycJpx`6IX-=m`r_@(4{KXNN)y#@V5qBq%(S2Ns9LJ@?xHG4*`zCRR^UyT%>zc5VK%__ zPhidc$XRojEtz1y5zG#_7gD#;cn@211k>$kwYtF*--ah1%oVlEIAjUthT|WAEWv!@ z_zc<}4nKHrj3<^s7}K1l>5G2cP-R+jtfZl!PDJ_EH`;IADrwl0eV+A^*V%8~2@Yz6 z>~J+?jH6YuW2jVMA1_d*7*|Id9KAt(!cf19qY-!KH;ur*j>kXE1%Da6g`F;+m|W3- zedINcrHwd$6CXpRYKW;5Ozt2)vd>hNz2KHmi^9$Y?Rjf0J5LT7p)_9388YzwpwbgM=VJTsYL{xCS zaW&RC>+1JpSDEnj6O&yLR8!E?7x(?Fk87U5$s*jxAg*~|_Ffab5!x7}za@DY@_^nF zD2Lxnfg-K&X4kkk6LVjSdn(1jJFSBEbk@~qT#vxNp2vT&3;q}*zBc~MFygp9AeMF7Mor9okRHlWGXC>T(h{=7}}^mNR*2&=!x6 z61Rl_YV8smpoY)pGzC7gF?St1P3xWu{A-&b5ZR`S0}TS0R|rJ}K~5jR{4$_D>cwgP z-f$JBL7@}v0A|K+@PXM9{{|laB`)|YGy*`1gnD}{cTh8vb^ub372%xDe-$-0 zAPr-g^N0_`a%$fCqSG@L>RY=G(*oldBotSzPvjEQE^_66utYyvTC|PTD#)md4GZXP zAOUvhBVj!wtx_+tD33-0njb=&FqA-mC35hR@4m@c*{1fHrlIZAjG?*C7VoTGqJ zpnwub#ExeoDSy!WRJp%tm9{0crVkcvVYO+*w0G-5!DIdsEu2Qt)9MA&5X=%wD7?Y50#aJL5q!dv zrt4r-)}1LzQ@LKp>@Z(lU7l<-?Z@py+Wrh>`hJr!olvSZ&{im(&p^xta};D~?k+%Z zugHAm>Q?O~w_pqO-`SrIEewp>!L=_6)lvN|kpQH;cHdiAj~F+I-|VOr zS{iu%Cl=4?A6c%hR>M7CEWme8FIWveY2#|r=1p*Z3J@c2LOg8$3FE8s=76`PS_n-$lfFCC>>MptDkSH~J!WmOr8bb5BV-m~4r zanvJ||E??P_tWk8AcS)a)9VTer%zFS`_MuCUc#%R(){ zt>IPaxXhEuP&zG+@&vkjg)6(P_L!Aa;dA&t_#XQQ;wX$2!R#48iiH?w?%q2F^wz3( z5|epk2YU|!-JZJjb$(U$VQa?*-7#}RKz)@7#*Jaj4Ok1@mp%8920L>bv_HF_GSFaL zjkalEOrd)2I=2F6U5&=|2>hFP{GV{a|4sdpcBIxZu>}a~ALL`d{ac$+5 zd-T@Qomd-3{lLkpCmz!;fCY;*PG+4S(kqRt!!=VNCh5mKL`0wn zGy?yRc>JHlbp?w~y}z2T4N$l4`}-$qx^F)Mt%m(22xE>kvn_SWbqfzS4EEjx?v1^u zV}Sp-`4;Rod$TdB%Y*K>4wP7WLmz^9ioI{)(I#)!U^@Y*E+5m}w(H~}(LvzJ0a1mj zzL}MSUsnh7!Q-c?jzX@mo|pUB27zO8LUAq#w+jLV*7Ct5!FLBMWS)G_Ti7Ffyyjc0 zs2YzW;3XgrW*bGNhm9}~$N*W6qR!LJtQUL(P5T~OeoU%x*41cSkHG(99{;D{W1aX5 z!m6QvuDE0qI{`ueTKQJ!Et8wF-&6=|4+Wa0V`hPD7B~=nbqDRrnc6#SzFuSHvR7T6BwD@`$)Za!__i zS}G}(m3o$Xl!|IR4~t;Tx5~TT-$C~9r~6GGLbkv6cldv->09twO;(h0l4lG1Fwpa8 z#NGK#Bk=!($A75{{`2IQ+3r)2+3y95@NB2(*R!3HU(;_3g}BBUrJD-+T6b(>6+j(f z@=dJ2ViOyz6+!C5VOVXZ0GmetFk}47R*u9-fH9O!QNl*?z|Sj?eBnn zOe0&a@$C^Fo9@9H+*ZVQFRa0I2Ca(H*)Ac?YR>A%t=el`s}_0<>{jqSe2(qHQT!W$ z|4|ysRYaQ3PK#6sJtpe);N-P}&fHmms7^9b}$6v3?elSRAhzy7Ue_>UIh;i6IyB3&y zxB;W{8$^}Ybo*7$ymkQQ6i`!z4aN*#(Aas+uY)^FR)=2`D8B>_p26vZKKA@;gu;4V zx^TaVm=k==_t>YMC`PK-dwsuY_w{?vZy&;3+ca)CcJV93E{4B<6mE>b{}_+|)9|fM z`7dJH?4)fjp_qsxH#iz}i`7Bo=Jlb-jRJ~xLhR)P0r)cogJjQ}Ly;TtV*(fh?sTUo z7rE&MUXnM77eS4xbSyasF@J=Zkb;ZYAZFN=a95W@&^QJrv(#C9vAh^+o11j}`bK;J}da^w-*VB-hD~e<-sz-@!t3m`2 zBaEa3Djm?zQ;^Sdpngu?-rUc-J{L|jL?2y|yZ7jgU~>b1cb!UnYq>8jIlEs7Ug+N} zemE6k)c!``f1JmEIef7be;iY90h=xWX8?e=eL0?`1^o7&T$a>H=&juf@zNh?937NG z_6Na)03V*WkeoG0!z>>NrN#n!nimT zsg~%k=I=LK&1+$HkG=Wn`Kp3|`XJ~5Bw#+b@5zj-M=E~rgq`5?^11(fjy`JnbiH81 z`i7E*jX|6B6%B$`{rZZaiUxC08AyES6_WVbdf|rRhKhz$LHrnD*yrqejr>SO!`dQ2 zt8RTTT-Om~Zoqw)auNYgm`%W(Sww9f{)Rb@uJuzlR5ZNT5E@*i{|KIzwf>`^j~Z%= zKGw@xkLwr0{-^~XK5PX3%{=~paKV4Jp(3cfA*x{NhI!O`4QP4-{V0s|_9*p%UfA|i z@Oup(=fK9pYe2xuv-%4tfVd+z`ee z!hM!=Pu(^n+&Nsc(H-h%xV*MEf7jT>kfu_m}7BHkL+3C^`ME# z2{$j`xZ6v8`2Sz}hzKn;J%`66nA6g#K}&O@beUahCOSkjd}v8mqL6rKDI2TB_akF> z>u+DW0Q0vat*mRIK-l$}@M|kl1)CiIMlBd~OapD8+ZkakU4azO!5U+G9*)tlu+Ud^ zNbgJCSU1qy1ljJ0c_|;48Lht&?f<7d{wv^vo%o-G@pA%7VX1uI)LRj828ikO-Cdy_A|9#g+J**CWoVgn)h6+xJm(5*@Nn3~*x znnE%w*)WByqLK}PUjMb$%WPT!Y#Ymf4i+$k5a*zkvEf>H25g59Z5Iq}M+_a0fa7=@ zACJ%iT`;>~d`pEE;{Q+~qxUxg|Ic{*(_Qd4MtQ>6n=mF zf3h|^8T*Qs)M9yk3gNRU*5?+brz&&N48(MsQG|a-;}G%#W+(E?GlO9~!4OoIsLUlE zywl(}u~F~1Go!Xaf1@4GRV(hI2w~T!!kgB`i&9fnxtJ>O{f?Q@l;iq8wb`Atw08K8 zpzoC>s&a{k91TGekLkNEJOt6J(To1?=>MPd_-DA_AD=`rPdOHF^D_k*pEi~oFThA? zPp>FnabZQ!S{PA#@L>+uTQwNDU#~x~Xy$NjKTV@4yY+GBoORt<_}|xc_##}}FmgMi zaDaswdm4J0oQB>dr&)JcykYT!Wdbb0uuRgv2jlg_NJ4{{Ppfhou4BxhP2eQ|4ww=6 z-riSuPl2E83ld{Z_q7@yXjj@en&rm_!tx_b!O<_%IQaJU%dFZQ*nwJ{ZNzA$ff4+F zn#cb+7yNO%iN7DWlX#7PnxSL3y~OP%Za+o9TX}_TEU9&J5pI*Ewg9Q^QZbgxg#u`| z5%Z`2D07@Ib0Nuk=FwHIJpGX0#NB$aEkGRKYp4;;U?3-Fd8XsvpC#dV@7FN<)1pBw zB|U_~26`WX{NFX*(KXH26(FhBnsMZ*u?8^J%Kks{-aI^tD*GG1we*stlXMm!8_-E7 z5YiwG0R^H%(@82zvx?53=uC&8RzSy~x{}15e91 zgED9dv_8=?4(*`49wj;XC78vb=muvnC@&Lr;r%Y<94*pQrFz))g>|W}E$4fmI2KQQ z0#6)U^F)s>F|9|Jn0z()+A}x%XuV0;87)w0z)D?&fd<%5p;tbu5B{k8bpO|b0r&@( zQmPn0!Hg`c03FR1+7!ngZMN~OS-*9M9A_hvx$Cj>kg+z3UUcIT9$vO~yhNq0jn)fZ zsTbIRJ90_OqFs&Wsc!ZnJo>Qwk!D*|LMBF8FcTlg_LkP!=>T#`R<=A&!2SYj1=f?( zn0jgbTPX{D(k4YBraJ^s$F{)9^M-ay(<+c6tEF)5RAaBtqU$t{sPj`(ge z|6d=f_*18cz4Cu@XQY`0?J3fu6&n6|dyv9aWKC`zla`q^+LMvRHJNmf4c1Cs)JZaO za?8T)RDwU%86d&Yt9rbX_Org$O};XB`?d?T#039Si!&vbdukDl8N^>Ja^t!rIkElM z7lvk;ZhLBRh0c4D=CLCWshHP1MaeY}J-eqC9re*SR5>3~05Yk*BlWvE;QFrCZ_!g- z;xHUcKI%{5O5S)LfFt-(2ng z$145{0`RZz815hy*okLCuWW4J9^kDv^t`_G#X79QFlyNe+J3PIenQu5$QfJ0YyeJU z-%)V7{H0d-myf`=_5=^9lnn7z ziGy;N+O;0?;y}cDH=9h>AMmkeQvQxF(!sqRfSa++D^docG3`cCqhq{6jLDgD2z+E?!4D&bGw^oJnwFP^!a+< zFqE06J9#p;BzY>v^qAOU)Gm1a)}-sou|5s!)CL$$B1s$VjS@6lX|0C6sEz}^807m@ zSBHE9bEil=L&VtPd+U@B>8Jnt;Qy(L|HJs+-u6FAV0&ovT?a)eoZ8w=YxWScii8_$ za*5?-Pn|EeM4wCPP3cC`e!^Z6%~l3j?d)QZVzpiK2ui!+(ey#S(RaP<5aDU;;K~zY z#K>tV*~V_?juNvrF;(0FOC@-MG4KiSJ&z}#^sQJUq?8X!V?E{fQ|Oh?>VyAhD*lfI z;D4R7eh8rN)71l~aqG|@w~Z3%N?QgVcJxMFqKaaWLgB1BidiaVTq%cTD>SC4rV12C zvqI;VYjnQ;oJ-f9L+6vvUJPDI(r)*BExXp};8$pfFo4eCh74-hh<)Cjt%Y5jVimZt z23FwP<(jIJFR{OLC8QM9=-`c@i3!=3osboewMH6?NeJ_PQ^H6bQ)3VER?*#l80D$2 z*JDKROJzh*-G$1YpzBfO=dlm5AOHH`|Gz5!zYoB_9XskMCFocm(>w}d!KgDVjW_9%r1FU@L zg^eYhSl^5O8f?v|`%#Hh{7&yX$+fY8vq}+6lZkgOhF366EbJECt2@%{(lIAf1^Iw+ zI%?w>tH?-qbgL;skYcVb=tLpp^+60WdYBi05MuR1Org0A}{!ynr8GemB zk>7b94ig40zX~86FNiTqQb>a%;6O-io)8yiCw4P{a4Z-Yy zoz6Q(ti^mIwf9@BtQ9cAMrpv^==DlZmYg&mFpcZS?B93&mq*3FH~@bl<#$ltU={k( zK6>FIx?Y3QwJ%K%Hrsk=8X{Qt22afsHA0M-Byfkz+c1A%roO+~^i*Ms+m&d2cb_{J z76kmQOWi1M32>@Kt(uW1!d9^Oj`I$Idygcxm7ZU|4Qqrf!qV#frLWh-@40i&3vGnh zEU?{VCaGzs2V>Q#zqJ6qf7SH@Lx4QB>9xKMBTkm>coH2$w!o{azjZoh3K~7sr=)ZM zrC=Y?cD#ctF%G-M45(%GIs+s>y$jouxeP`iZz}w~D*lTC@aN$tjn8K)U5TGyho4dS z2K-8~x}D+$zT#jN_Q*vV*rYi4PNMg))&@svI!@s8?-7X@C2&WG`7qE|(@3>brlyp9 z6jalAa_G|Pp|H0%(34(+9zELO-}GQG32T276)R)rB4Qcs83&|U%qXb%0bk&!J-taJ zsTVxfyf|2L|I&Yc#jE1C%kO}dnTc6%+0U20>Ky2qJUY65^9rOVv$49bx8{sK{Wp7t zCn=xS4u9*R?&=z~Tyv4RCN7^*<{dWG+*J4 zTNJ)WJ)(4`b;=GOz?leHJ^p}4I_8Q;n)O^%-OtU&rIj@!9Od#U;C`!@Nm_~{)=7JP zwD*^szs5e?!%tdcPxch&B<9Z+1NG zrUZEY30Tf7W^Lpf(ol+eMdbmb&=p6xrgI#ZNi;$-{7GcaXmK$|aC}6bgP4y(8swGs zE-zWV{L_-G8Ha)hT5lGu_jGcagu!peGh9X%FLC^P&A}RG~weu_vc7WdrIMtzSwVp|V47B8hkdY3~tvnW>l4 zhvW~L9-7Fc5cA-vuQmn4#$%~L)6TTc&(gF*_Zu@IGkV1PvYsn+R?RyMJ94ybI((5& zXPaW!^WKQO$b8&2_gnDsVSVsFsp9`c0RHdG3F8mR2d$6KJ0u^q?wNl`{?Ph9_~VfL zDPrT@hc1pwXBEDtoCMwnZ?Esc#`7p^Q*hE_>aP|WHdYUW3V*_C0vq$SJmJts`|WEAd?>HzOAQ~AQ@NzjIms+Fha2&=5O7KT_#kY8?=YZGBh4BkVY5xt{iE67rV&c zm7{HEWW&rm<0`R#g==zUa#s@4Q}Q5*e!UqwXOh6&T=w5TSMmR!0Q_A9+&9eMn$fM& zaR}%=zUNq<`pRQr-hq(h2a~?+I&r1Gim5aF;)e#1Aq$YGhk&ELv(KjWkPt+XNF zaURE05poe|osw%KFm|K!#yOazdmreP=kfu)MfMEHpVHzg{wU}$q z4w5(iNN)Mw!(CbbKd(M^r##I0>hkZFkDe2fYlwe!ckOPjajAiAe2(1;>_^b|d6L{* z_?4k)B`&D2-OtFo3qI9|xg*9l*O8V4W!^ zLK3T*nIadE2kY)zU+i- z9DiD4YYHm+yZnW+a%5Z?lf)%b{{Va27PCW77E=8qi*IR|NA-?xk?X6{2Q1A#^dsG9{$_OarrsKQHa+djz+v5@c_gd5D!HB;y759u->U< zyqXcbhe_hMQhZG9lN}khjGDj8r+^%ho-U=s-Tv0G?fP5p@G#?I#YzK+G3*M@me1 zaN}RY=E1sejBvs8m8|!T7Jt|N*KS>7Sjc-aseV`1Ru5@k)iD&I--3@1>w|y2ivQvO z{PiQZgBn9Yoew;%5S?zn&YTjws&?6B~;cEo-kDI z)7=2?x^$x`vO!HTL8mZ|>!P{#JkM9i6&ShrBT@uE~G)av0D5BaX>rz31|(J*%*P z(~i9#E(ScBWJQ|MdQbCTcmI`A@SvnErPn9nIvE}8d0U=tdRv}qU5EXi2c;0@-kmhh zPwE4ESMF8Ne9FC@xVOFM z-Yv?#-Bz9A6P8LYgmFtH7k8xjU=&vljWUWYALqMsC1WCM*6pT#0D>`Q)PH|{@IS5M z{}evC7ynEjU2!?N#lCB{uX*|I<#ey^L#G(?p2z;=TkZI3{$Hm*pNm=Cl*8x~97ccO zF6a7r_c>pj_oDO6yfe;(!i0kR3hyg;vGB!$Glgdg66W7EZ~gqk@|-E?<&8s#4#|X` zMUT=C%lh<0Xk9#K70x7aQbLCf7CaMSm2pp5da1wlL77~5LK$;fa%J&O^3VT)RS^wZ z^zPPA{I}s4y~q?^IX~imK(pkEWoOKV6Y{}vXSqM0r24=q&EzZcj*jza$D)qnS*kwJ z-MZa>_56K#<3z8#iEmzhNG3T{J1y&x0R0#JeRz;W-oW92?TLw4b{$ zI)B{nkIB_Y_aM^Eydj+x>Fz?hhW4`;K9>)gj>?;ckA&Cq*KqCg_9uO&yuFWl<-Ppd z@?WfnUWIwUV6 zz2iZ&*8$BQfm}ic^S#oh3v>0%&H(T7s#n%t}9t%ID_Lj(N4wMywv-9T}c zQath+#VbJZv)D20$~-O`&?Xzkea(@k?_I!#Ep@l;Q z;&ePmgEF(=rPdzdIe~XT7+23-J$YQ$a`L9)|F2d2mjvKHSHbT(S5b~*wvgdi=~L`) z-P!gMc6`y5c+3{&1^Dl5qienDJ?DHBy;(iz)!cyYS#Hb86S_A}ntTo*!&!Ep%6G(J zO_@#lrz;B)|8HHW>%oe1FP7r=Ay>XYnm2Gu>R$tk%iNEm=KpQ7_Y4xuiwh z*?2*DHbxn|*HW$6>2G~sUVcHZNSI8Y)^QM$X7dG&a(+|c|BZ@&X#oDS;5CHQufDpU zxP$XT@|$4hveK(v)Jwo-StE3`R&_A&>zf(>qMe+YaA0JX zDNgll@JStUtNy{0I@weneyFJ*Ay)dEn~`oR{J&N4FAKo`&ocFlxdvWY7-@K$p~fT_ z53tf}o$aU(D$VquS+F;&hLIjp(w6yEFHFWdte@(kWC_xiRWoZC>28_Xz)GT0o?nhe zd2BT;@hNx_rbjbt)KaG?W!=|P)}?)P40%Fr0`_JaXJ+mpBlK?g9x)%i7|tX)m&t;a zfj^lO7sI2H#LZ5ogKPREE-DK%%US-!O@-%>BFi`r|FezMYZNQZ@8p}35j#7n|B_|$ z)R}ZOnp~?D1__};Q4K*&nF$H?n*XN4|D1~d(g6HfPF=%HNY4$x z&$r^TKlrzm{#~71SbO@Sl#e*scD(3#90`zdqwX z->LX7!xvM*N5}t}m#7B@?6=+VP7?_y(rFj$EOrrTk)M&gu>787^}{nLfsOVo*!R!A zc9so}{GZ~ zj4YJ#M|{b<_>zZv-fM=$1eYC4dieE)R3G)ZhTUBKzw;{oPY2*nZXr^eiy8lVVc`N| z`4jAPI=dJXPsdQ7r4(nRIbF=gnP?sEYGb6_|AOZ~VSSV0IrSGW7mGtmA zF%h0(R@u)v4>u8(KUOHlWqs>pM=$e|QA@r3mih5vefa-^ivKeK_%r4z1^F@$m8Xn! zKMINen?(F4l%A3jBK;G=-?^}EDJlfWmzqg}x*n~0y z`1^)3%tfkYc>tZ!zvt z>o?UM=va5?uH`E;^$_o?_l8-PFM`v*alB`r&Kk<_K$?hBM}hV|hacgusj z3ZN6xKAVhn+>7^+6vmwBJajR9d@1xZE%2C(az8(I z40Vm#apbYnFI@2-y0QbU_9&Z#IY9LGVVBy)Zoz&&`D^*PGAe%u|6H{A_ruo$wYstk8eBmKvyrazz8_lCEYR`)uDxOO z7p*aE?eCWRO7}aUmye-1T-V-$0$T`kQ7*JMBE8;IM*1(xpwc}ac-{{WGqaTz|HB(v z{JaME7x^#m_he7mnqQPnwUHkodA@1C$^3s@Qt@9Ifd7BP=Wd0DL^|ic5o3zaC+$QE z1-~6=uUbg8`6Hm|KiVmm-sM$C&)o+rNbizial z)*=5h$p7Eox*ar@ZM+#s7^e{;LA;f6J5f@SQc^h=pQA z)<*j`&SZC@_>FS{#)OhPm^)rCG#6Rw80pvTOb>>%4adqKg}!_r9r2=%>Ic1YTj_bP zrFJ5#(DOc1Muyj6-H=WC!lm{)r=Ztar}R3%g5*gCE^k9>45av8>u2`ubsDi(k=aV5 z3wVd$L3(w!snY91l)<*sR-Z`mrK%KbNA3Kn?LXGHep~_i=>I>c_&*nbKauA5@XF=x z8#$cv+n4C`{V(YE-}uemQ-lj1M`XMCjSp0YRpqHOwpEAf7R z`G0u7%V0^i*WK5B#%cY>yO;TU5jLA19t zVpkG8>%b2XY%eZ%(VcpK0M|`xV}?%Y>jzgtazwN!#H8VYE$=3 zh5t_~{(rpz|L(?zDXRf-3Lt1bvtNn_d2Y^bu)ax6}E!BKLKe zL5!=Z5ZM~+CrdK!g_UkTQyyz{_UyIWr}%8=;b&w3O5ZI1XF30(OyzpEhmlqzrK&Of z-$ojU#PrmF=ezn!u_t9lT1cOET^GGJ(r{DZ|Feq!^8xtN(O7k)g-Bn+0t1zjkNkp$ zS=IyJQy=cL_oZP?HSM{>|8M7RAKLjTbl&I=d0hUuX;C7R9_6&4{k3|=PEQxp_nccW zCU;DpP7D@dCD_e5N9QtQu?K?-c9O=W&8{YK`_?2a(6J1fb?#2I`3V%t(e@y`XXy3acL5okiA{~+WSXbj3>O8k#v+qL} zG0j0pEhVNih)*HRN1*y$3*r)l=MXj_>_v!1Ivc`B1Sih#Luf#NjhD=`7lV$Hkq>&_ zg|6rHgbIHr8(%At82KMy``te;y z<*94z!bIWqg5-i_^2{~!=h3l%2*1fm$K-T=I^QcVbt?bWV>;LNcjCg{@KB7<`CFgD zn94klPPhxRh)>8oY;gV#wxo20D%ul-*Rf7usBED)TP-CgWa}pG|3`$$@N4)Mzd4`( z73Tdqd%y43S&Z~ur*Ho21;ZpAW)Wu=Cl}10cT@5IWflK*0r=;`GY-{*f+|f;t|mdj zxg7id=y*C^$wA`@z|}0%vu0m$?Xqf;!o9_AWwyXB)ZLh)>ttReBLxq;fuv@7xR*_Z ztody+7D!Y6W~42C)54*S!b1L6+N`4&Bkrc$H(@3?aOU}W48|1Iy7xjSP|<441M;d0 z(uDK#tpY^{D9t3&tZudb<#dNT5}ZW(xr<4S@Y>8vG430ZXUI38z3`7SIE~K1xI43( zuP#2oE313x5pm~bP0ePm!mcf3lL3Lsw7U@4{3!9J!oOL?zdQhc+Gf+W7bhUAVb?>X z$GxCQW7s4ilH6$gefx$Sytj?+h%tnfL6#5zYoy^8_3r;Dv`$gRzRl!7tnO!ii&_AT{4G7&y}JASnrWLt-(& zcPQP>in{y!07p!Ij2M#_EheCT1dGhrU}u~dDc)NLoAuRb5&H43PyfF~#eaPO{{D1I zLlwVQ>PgC3U%dFWJg)jQC_PuC_twDQvYHB3J(YSw>jQ1yJqUAfOxt@SV#-@oSC~() zBhWg7`XcSFrw<##i^4vO&YK!wcT2z?g61 zLsZG|cE=oOYvZqWKd^+%5(iA9JRK(Tutdf~CXDT{h_A)o=L|na zZB&jB`7w-S>{A)Vk-FP`X6e8anjVUWq$3XX_LT*q;wMau(R4MQj3co$YFyOYxXwN8t1oj(mI(ldNdb(2MlN;u3P?x$P z^R4mwA8z|?sp5seOnZ8qc)B|ey@n9U2+E9-u&S?XM61 ztt$R6;EQ|lr+i8Ig7OFLzft*3`DFy?77uGobe~Ld&hY%=+Tl~9oJpb?7{xEFu-{&v zJT2LgCbErX#6{MUm^u3WGlx(M5O0%G^71{u-oGZ`Y{-63z}ba5wnJshk zx%pjN@HM$wd|-sA&+Se10oGDeTGKj10{KYmpwy4Va;sd?Ur_T(02W#ySMRSPJEUl*N z!8W#0eK2Ex;$Xc%_0P3!vH9l~7)55|Qv0CXD&Q zTj<(UlPYsZIv7)oGeT+QH@J!E&bsiPcAkSJ<c4R@Ccx*wreZaA@ zB9g|Rre}wnG;CSHpy~69=vc58p~4;pnS6S|xp{aZdh8a__VAeno9rV|^VBQ799%7@ ziNOxf0`w*}Hq2XNC-v~)ioSprfsq!=jOi<2P3zr!1X>Tp8f)#+hYu~VKg?vTwbL55 zbUyKzYfuwueKmm;{r1>|t!TE&`8^v?;mfC|9>39SqgA^l0 zLTr4!0PBB2VU^D*ZRaBtgTD5Mk1SXV9Xvuy;_CDV(>m3aWvTN+i-72mc;7a=)RvRM)@1xJ7&*dSP;%Z{W zl@BvxSI$?*EGXvaZ)OgL4*RDyPt%^g-q1it3x>~u@aoQ&&mPQZ!Zam9kr=P}8%(zD4 zgd*tO|J(7E&ngx=lM9ISzy4F;x%$Gy_Z~aw=zcs5PNi4IM3gq%m*V1g0({|bIB1x&@w#FdF-|Cb7t*1L|b+jk( z@eMtRR9L2Gw|2MwfSJF4d8ieO$4{S?jce-VXjm)^LVtxw8~py(=nk{E!LAbyN>97k z%Hhr+%QvS~kAW#&phrLc_2GZ|z3BhF6o5aa0S)_6HZdj z>1JSW`5imf-c=;XVuFI)>QQSc6&)`wFh}juqKljmG#+0-9+tL ze`{g4Y9Cw+)JAoriZA=PN?Pidv9vt;1l~096tS%Jpx;M;AVZ{~{#0?LZ=*aCwee|h zF6!QI+e?w}>_wj0kV8@TU;X2*G9R@);BS4oJxN@Hx}-mj5?~dAtcetNx0hYMGw9by z@pCu5;%`mwaN_Ly?k9cw?EM)2zU_avivP<2_%ron#LFJ5s8aj;?o@F$Xp_`27Gq{# zh!d5z0bY8$)4b^96W#~a*P)BS~y%8lnBGpO94@`Lt0rP`rW;aNt46?gFp zMj>91P2#~ClB|16yH$f(2Tc}{3cJr<)Qn-_n}Q^=<+_Tfyy#pr<|#gqqo`N+cPLMM#S_9&?@J`n<$aybcf}K=aIjKI|ez!oMHLK#G49#zl#4W0r;C>U*|}h$w^W_ z_Jrhhx4z_m-$${yJ&z-ILneHOc+vSBJ@ z^%FLkzt1M?6Kt|+q)kq~-TH3U1gc9;!8?Rc)z>y)msgS%KIG(3M<{G`$2w2Q%dMF$ z#oSTEv&BrwmO0yLF3OaQoEfc5QCshm)bYIU@ebCXNrQTo&g7^w8T2|w&oZK%A$4?y zs5pmSo6=)%y0~_*GBZ?GO>IqJm1;l!^^yOCQ{?}q0Q|A1;u)2OF?lf#ugqsFqx9vZ z(%<@In<>sDEy*;)D*)o`%DRV#JW@k2eqPeX++LWFeTisfZ%R$bwK3dhKyRwS`&)m+ zu3?`CGQUlO5gX#RMKCsEM4&NvJj7whv+f;g3YiAmA{tm9Np3JvJHTnM&TvG|$}E*5 zxEU=ZJ;Z5M?atD?-;f49V(58OG}zw>i{WLDyVqv zAY5iFaAJIV4D1FQ*}8de&z=6c%s=gKE$b}VbI*)>@^{@_@}J=p{9g^gKh-^2&^78g zGjOIm`-uTok)z(1ZR4>PDhZ&;FM%3Qa82ycWUah8`IKt1yYdnX+fNBQ-UKOo=hqxHlNyxm;PS#IT2&ZOl>GHQ=aR zlER9|blMXQiA<6UR=5s=`&lQf_vKO_3vtE8IeacH=fj@5LCB5}0|M`0MU*yWMvJrf z5G=LRnT8g$)wl+a0Z!N*=G8I6T6*P~YH)q#Je}s`aao_pU0L=xNt^Di(sC!$fIYkz zdYw2C-$@;e`wX1n~V>vu~2lU^?E_$kz?JNqs8_^>|sYgGJS55T{`aZKi; zkI1G0$7DU?WW)xSR3sRgiK|%RBtPY72xwPj`-R`KoFRCWPaeH2@lO8Xu z8STi(ix)@dcfiJ5jE2^YB`r_v;^6mv@viYmQB^bEF@9>SXcC9zS6x~ExJe2pbWWL( z!Wkx0Z%K46X}MoXU$AQ=($C!!@3^V(*Q)rx5rDr1+&QC#EQ)Z>@D0vSa730+i)=G4 zMMW)X$=nqs8N#)mf%${3@sZOP2Ase-c9J+J;jnCofK^z82?Lh2%-VGkTsHaY*j-d! zLr+USrpt0ainfBg@o?Y6=12nqIY?|-=ubZPYhueS?9in4% zt$QQTFCcf(HySu~P+nRleV-GuEroU7RQT&u{ND_~pGgAxR@n7Vsc;@bpQ%@lhE3(J zEKi>yZOVprZB_eFxg4}??p|kw^F3LQc3(e0?VHJv+noqx6H)qT=w{B;D{c04SnNzd zfAJ0f=+t;{^laH=9cp>TosrK;LphXg4;v8A9I58A!h3*&sW)Jhmi=l}; z9WAagizXpn42Ew%l4?-rl@C}1E|0GDV3T5iInA33nUArZ9357muHW>9%&(z)#mIBAgNmP(^g;Y%Mg{(?^l4o@XgaI`meMKoe_@xH4%=&nk%ipf*qa`c~>)WU1^o89}XU0RK~hwd)S3x+u`I%^KgBXs;}9x)qoyIb=*;AgCu zNL*WY>;4YfQt9*b|4s{720M~?-!b%ip=(fmU_z}f*MNP8ZLL^gUN_+YwLH&aHB#@R z`(xZk{)edeZ^Os-_Wvf>*vtOSdl&7za5@WKK+u2h_XN;gfK&0w+ zgPEfvsp<55KGoe|qf=iiw_fb-^`w5?8W(aXYi_A5r-65HPUGJBW^SrM*$GN_9Pq$s z4uVFx2aF%*1MU*{_fKOE;u$=rNe?~2KZYb7yvU`OI$38Xa-)1Rr}!Yv6j}5aUlgBn zz9>4J%-90wM&%j$0#-?9-5V+{OfY(AISImC%=*7&Z?9*Sv>TnzIr}5-z2DRae}jtu z_5l0~ocaRmyOdUZQK5L*#}yg(dM+}N_lYZ=%j~n9diT8;DWN@TjIK^%3gVpVdW+)P zq0^RCD?Xyfa$CDvM_`wJtA~5h{Kp4Hjl}?+j+2IsNQ{r>PF&QOPh8}f?~2I!>KyJx zlW45zYW23`Na$+)46}i~Dd^pwamGhBi1hd(jyZ-NednY9zk#(N8lQ#Cu&u<{RISY% zGOdiR8cT{1_(Y4dt2MMkKTQwWp~VhEQm)Ip#kqMmF>4_`(%R|F#O=sO^JXF31sTzw ze|_)|Rq@{ufd53)iP?4eb=2Z2NlkE5UPHjlTv^?YCcWX2i~Ro*DNa5Me?Vt1vS#e4 z%E{Do(%tC?$Plr!fYfKhtG#ZH%ZiPoR6M~I|!S5#8a_qeno>Q!TEOo844-#_f z>3qDs=5UjVP>UaHZ7$cMLp~d5Ou?c7!!;v5wIThcP|t5|>3f!n)tc4ywOBmNfa(U6Q8s zjcnUxwv?T4dzS5z*7jOs7*B=`t~p^N=Jzg=%rVeiZYuo4RQz`a;4eMP*7?7pn2@xY z-cRCz!gSDIW`^zQ=gzt#8_v|uU46mEw6hX@+j^Td zlQZBQXuXlcItJ4BK)unU-tg^gOHbXo-6gGd(YmwJrPiHN)SYhH4EEb!AN~(l@!y3n z?rr~pn}RRt(D&dA-nsp8;Jc`voiH)$lQ?jWP~v;P$z=Zeg4?KMmDUd zk!P3*U;Fd|tjzV}UmyI9D*n|0_&bHwzEYvi_n`2E&no2mwl}eciCIxTDl?PO&Qe_~ zL|}v%tezRVkC36Y(eM#Y*9>cfQ{vPborA2!KHzcMJPT6X3R^4Pe%_HF(0x}T^u+to z#x6kEfMBfEOpOvo)&!$G)tOrvmwU> z5Agfj)c(SYC@*X;SIY?8HcjqqnYR$kI}q5VVXL97G;(OCXj#Rzq0>UA&X0f1NQS*( z5AudgGfd^AiniV>{TTkf{r?CR|C#{&HQwR_cguXnh8*VBpM1SXmwgioiK#c_;+S=y z4q%nn#(gTTz2{SU&aJh~M3TJO&Um5IH*ohe<3jJ>X20s06K_2boVC_YTV&!b&N0?T z$c%%NnHg*CZC>Mn<#uB&)5!8{{W7~*(4ER0@+w9ikj8>Eqh%kP#Rx0y1Sz9rW*Upo ziffzzuXHF4Y2w>_x7Csnxt>`ve>?UnT3&79`F-y1Vpu6rHsv!Lu#-?ouPby$JJprM ztQ5bm3VQ|;#d$F(r62$L@PDL=|Ly?%d3T&RS1fe$?mJ_WoFkn-_~Ot@3aP0=FDXL2 zJLYwJh&NeG%(^S4${yi7>rFuF+0MkQ2`+Zb;tIUloy-myvzB4 zkFNjDg`O?fewL6TaT@)2!>9>vLkbxMYq6)d+BxJ;cjEp5*dOsH<^_w>)ST zCBmWv8maCH&JoH{M^|Qo*-O(~F&6ZW|D4Y(&W#^*BE-Vgo1F<+DNeqjP~2=cxI>(? zl{8!Yd{YRVgPUOO;c(oip7^+`nIHL*g!$s9zM~1r@GZZ|e$La6;qS};Q7Zm>0`O0a zqjdhXi?N>d(*4~Ouc-*-SV2cD#=YfE{g>;Ds_e|^;1Qfx=?6-m9f%U=Bp98s#d?8W zDbAsu6~cvR;bhEqMFQv==&0c&Am?xW(w~{o?1lY*I<_|>RCuX6TG$|Hg_xS9MIm*J zbh&GV<0X5%_X%;~@9TA%6Wdl)XxI~59$}>A-P=~g>zI?4qQ*M47JS=vux8=!&*;KV z(mu*yWrzP$$jx|b#jkyfain)&5x?|pTd_g&qf*90-LOe$4k|a9SIZ-;pUDQ7)%>-5 zuynPYhFJ|*IP1s1KKvi8;=eZlf3r{_K(bnbYf{qMyzeyfAt9c*LK3VnQ|!w940?iZ zxq>S0%?esqq3j7D(q|m@vSW7JX-E-}BiDh+o>OMEW&RlYf#o#S0NwbWH_tH3;Y8|ocqdnPl zcATaheuXzBmT*bbhJ9|gt;S~F)EG=S^ga1XF0&uQ-$%YG~{6A2||Lp+$HJ*J< z+2O>?+{z}B1}>4?#+0+bD;sp2EsRCm@K)Eprkrq{zC00wY zmn0Fh3G#xKvb$sI-fv>GAIrq~C3t*e*7bY0b?a*&eb-o%xJpO1?l@N&R&hFhf)M3Y zZTH`kz^#odmVB+X9A

x%2Ft%v$!kMG;=#;Nfow!NS^()~mXX zfdj1L3)A=}|F|%jxo?cnbjCVnXA`U8WhNmjVT4eS9eg~rDTv*SUg87U%iSa?Dk~w`adg)oHtBLIJ^**a!v@u6aFa1)&uoiXZ1cGc=?gK$=Mx&{hE z1r4O8yVC>9Dl<_RKI|ao;BvF5DaYI({K3Rjs}h21(zBRXF&)RQ-lG>IG2R=wVuVC8 zb>*MQF)sa2#^6^RXD@0Q+G?<{&9{6%J*!am6tmKSuH5~!rr6N0XQl03#+p&s9gt}) zcdXCdkGi+sy+LpZoY`EUsWeMGn}nGN5=34|7ed}jL=T@xr`i~+OF@z3-^xIz_{9{!7(T%@0{_{1fU3YK7 zWUtm-=+smeh?&Z48&@8@4ZZq3LEG|vFs>ryNzTwFGnWdD;InRRWzfbPi%ZaZKTKdx z7m6G0Q_gN{Vncq{zN%w?(*xnAQ_RGBVI^`V3BsPQLH^*1s2C=#R4^B?XOgf^lsUqDRGJgHKzLllD(95b`qSI^X`L2g75$WCRd8n^+K4mn3?0Eb@h9nG0Th zfTI7Ek6xvvvFR;7#(Wu8iXI9HuH0zXoHmPz1*deEPC62NJ~HA2cAT;-1Kw{ypW$AO z?u5C>jxonnVP6ikn|}Q3gMX}we_a6nBfaxM?FYhbmm6H*T88o=D>c9p=s3@9`HZ=j zPLr{^3w9jM6?PW%J*6|AjKPZiJFn4ka?2E~`XYM1DK03ulF7)-4mx8ND|MtvQ`#Vg zRBo{EbH@l)AeA4GXZS9C6QjT23&K9WiD%+(cwVgXyr@jpYZmKur}{iEh(0d}&kGK! zoNISvGiQP;*P;BtcWT`k)Wih+1l_^!|9MFbbc9-j0|<2phYT;2&I3 z^+<(%3%u=-w6(%*XF$`C5tlA523^^zM>OSCjX~Vp?DR7#_8GwbOWlMM!4(=vf#Y$T z8=0Vu*<0Kj1!~8AJk71|$sJ5{RL0T#nb}KP7w@_enYVUQ1L+>=`t?(D7WHx>TzD*pQe@Mon<9jEGoD}e^fWb{%q%zF=z2;`(Y6}(i=ZaU+j z@|`_%p@-vxFN5#w!q>mx?g>hsb7IKGxpA4<(wX+2^szxLRM*I%K7Ce-Aw_3pldBx^ zAxcPhu9Y)QI#`eiu3^&CVP|Ti*6vOhSsbT`10=0R>*bqbgU^X$VJT{xeb|}xNFOyM zNyL6n^E$2N1mBd&<_QyogQ!14JZAAcQgV`(<1Kpkj<_l@smS0?xpe*sl2UFz>aL8t zsqjxw@qae}{~u$>u()xx_Bf2&>KiELz0~92bw#!R$&7#B_f5>b30707oJo?hV2#^Y zCTAMi^bde|(zP5HJj|{2(5PuY%pj~4hX2K|v1GIhBMcN3-Klw_gHMss(AHdY@W0B% zH`%qzWP9HaFND+b}?~h0{AR?oqpc_JxQkV$5K@GgZr+94xX8McR&&gO}fx`{-zcTW=0F z6IgxCG(IT40o$OP;Y%b@;+aHeXdSs_nrEO;+tJ*_bwvE;gZs5I^XJjRetW3UQm?m! zppE}pr$1>fDu6!umD_5@{o66)f9tyVq=L`T`)~*xbbT8%&~LjL>r|y~sy)Z?x$x^% zY!<`Bq1s=|{M;~S^vQaRHDyXB&g>jqXBN@p$C1%o4gF8OT4GM6xvb}IuKpkRg5v+r z0Q`Te&2{hCeZe4l$inzhS&LQGF zktEV__)Ts48dtp2StyzdsE^Q0>lUB6Xe=axP4GYhZ-WG`)J2_W5V;-=@HI$`>-Q_+ zm+hR$p?%n9zkH_Ahqb3ovDz!p*N#9pJAp8vRy&QDc|k8&oZYR~?#u+%YZ18`vvb0M z@35bYQ${aIT8B3#j=>Idxi$YQ998EN-Kn_0W;)D>5+`7FMk=OUcNKW7rZf1OH4(k8^X8 zqpoTN*J677ro!K(;(rhy-HZR8D`W}hp|fp_^rXB=p}i6N{ewMpuXbV4TzgdktT5CW zB^P-IbH$~)IqpJmQVVwbwE|Z<#~wH?tFP6X;NPzkcDtnWZKE!>&ftm+m_LI3oy(;z z=60qjT2GpyHJZj{98*3AmSgUglTA!IyfR-}7NT!l7PPyg`RbVC&@97j!gk@ZFcWk8 z<-4^V+&Sz@nqIm4twxTEG{D;1CT$1%ZB+Y8tU`&znx(RKTr+*#7-?r4&GyROnU~ni z((I|2+n#YLDgX4byX6ood|6fU886x6gjI9iQ<@4r_wYSG_?w4v|e7V7<7u|`PF{I9I#&{!FPR!JT_*slJ z|HJXFn@OUhlIfR%xOi`Ph5d5)<5A9!nxnY%Od>t;bYf*89SZ5Uzdrr{Bo+U|_~Ksv z-|0wc*y$kU`t-z#C@0x4;M(Zv7F^}hn|&|+$Ua4qX8kY-lj*B}41S80X2~wWSrcBt zn4_GD7`Y+R)Tdu|(EOM)EVFMP{V8yUKcwIy$r%A%GW9$=lN6bvGvXWlTt;xmR)UL5Y2I8xJeH~VyO{{Ag82;;1e{gV( zA8~k6KmPT>->l+)BmjS61{ScA+XUO$(>#2OMXKC;5@=% z1VZG=F3b(jK{yNi)tc~>j~TPbc_(?w$EIxawV{VO>xY<-&lUOdOy?9F-&FXgsQAAZ zfIl;SiBW&+%kbm2%?0k#zUA09Lo0=|@ZCnGV~=zw?xbkn8iBci6mpAATInK|=e%Kx z>|g5w@(;ayO@hN8dn%Ehaly70T81(gwfT7aSxA<2T{%hmn?se^IZBDl_|If(HO)^g zbRO?eCH2J4)hG?V9ok=Qn)x_=GFNUuX-@C*YfpK!o$f}Ua-V@6Ig)CVHkRQE?UiEA zpSB9im8+|8H5hj2SaTFgICyz(XS$pf90}C50@=;C@nwG_^E?Z96DDw^YU%*>tvJcW#pwXW(`*E&{>vWeR~r@9bo-zNAQGeS*;JgJs25m;d8bkRCAK7TwV5peopjri!#je$F?0q(^akKFRG9ueE zBM+8;;g3$0Cv9!yCCaN4m0rrd-G(*rIoEN${lC~|sI;cj_n_(3IuQi)AMn!pG(jor zi#D~aE?5h-!L|rn`I3Ed%ObiIzTf`(wEx3Z{6D}K_v(LRfG?yV@cm22Ee=H@_Gn`N zqi9t}eH4F2db9(!HeWK7U&mo!cLZ=~Yrl@e>unJ|I8f?R9H2F@Dc*SH8I1Ho+x4_x z0Ea(#DJIbhKF1Y@ zj=ssNWh9{u9JG+U%)GKQ{vUQqo7=qLGlg$dp89jwhjrH}IvwjYVz4489Q*2LLAOeS zjZaH)cqL>3iBb9mlUu&nKG=EUJIebOVK5!38#OUa?egA4f{Wuy zn6Yuit9`T;VWhftIt#5nGahxJ(({>5UqSuPzVFgtj*m3I|BnLjf7L~9i8wnEE4`?G9NB#*_GajmIwxNwZdP{#vv!YB6Vph8C)qjOZx}uMbyH3Oc6%-IuACP2ww@WV$x7l zz~wHSV_weIT#BOv+~KlZSsL^!_CaINoSlVvVOrk6?lOVms5v_ZJ5T79&~B|jbq~=q zMxd*bs0ZtLUlQ{yAvlTN|5K+Pwa`Biy-sK#%S$JsPpIB`w3BKhs2k1CyEK(7o_$l{ zpQhsfaRC0ST+F)zo5qPMiqO@F)^bP;23vj+0|u;z*AN?I zAnv6JS0oD&35>1SkU)DaCM0PHy_SSD*I<(46Nj{U5e#t-QXEl2E^Y79$^lazrgdH@ zteRE=gN2RJeP`Fg$~kwr&wcLxICJCA&$~N2JG+|iJbp9tdt3>y%{_rf{i$NQ@$c{r z@blJ1vAOFUbWUZ9;bS`T#QPyxOtIBnV<0tDI(}*(A zK7QCR{HH7U|7#rnfopjp`bn&;ku0W}?dtA0qyA&(tn4!#vodKp(s7%a10HPptZ7w# zI!adt;LG9Mtn9z|nS$R0n4Rk9pp{kfq~hFCv4r~hEtBb58&ARW%q)~D_uA!C0N z#ui4dA87fZEVRd_8_#6)t6@Wi_RnPJzxw`GWTvE8X`3Fx>Z!qR{WGM~_II%zO!Haw z-V-s-!Z@wZfBih=E%tQeWzrc*viHjQq>5;7+dFiXa#PQ?SM|8s`wo2vC-*V)dv7ZI zXDIl87>EDw_hJr*b{6e@n%@i#p*pQ zFzeM?@!k^^u=TF$N~|T>Y!{(^V>h2)O>(Yc|0t=aX=yGz^5pyNYg@M7huNW%?zyf> zY|X4aG7)PD;`!AXtFy#?<(Bl8tqC1d-IJzHKQ-;{-PsnCEa_y}F zy7x!-5#I=m^^n|G{5#Y-H*6k^;4rNH=P3C9E)M?+&sa!ykj$5ZYRxt~9Wi&E%UJ#L zYKu4sMIp}unUJHv7SF>P&C))e%sI%^jS|xU$XxZAVIw#*7 zbMi z=AKe*(TS??I_7$B%T-=1g%&nSd4krs+pY?`+3UTfR|V1A&Mbh1Ry@}Y84P-UAnyEi zoSz+x|M}oKMJw7Hine&tTB)sBoco|DP>|_Lu1JOr$`@-|pg{_WEC=Nz@2ztrW-rhBRCAh->Bg4kHa6Wv#RsZgo;lg6?ZRj zt-@X&JnlRjJ%)YPV;A`9DfT@M4R|{~yc}LPk4BDN7=!qvYHCZ*U3facXHf6pHBnwP z!iPj>2gO30Imb?Au4ODpGzuT1mIUz$k%SlU9(snBU8Znr(&h=NV(eLEwSpVq57J(>C}G)X6kYRvqy z?FY6_OwgaO!G651do^m#dhiGr&oVpN9s zs&FGV48uQ9!Jj(4it+!?tEn80x|0u=Lq;ys!DKoe)J_uf+G^nXn<#ls1uWnfB(mTT z?a6nl{(2%a#Br7oi?Q_6z?g~yH7#2OyCu|wYtrm=FwKJF{?@mE5Y_gxT+3>uQaJPp z1}S!LRay3I{xCq>C=E;~%IK$MpVf!dV>Nzg5zb*|Z!^#E(`)mAD;=S?OcIj;G8sZ@ zep863NoME^_FI~g$0SDexWptp)>nSHrSFHAAMY!_vZwEdSAKlxFCC%7G+#EPX7gK> zJhw;;m)shGlq)=*QBNc@5`0A>S1fmw<|9l1ikMMhA_^XRku!g7ZV2ml)?_+)R zcw|0fLB-sDizH0R) z_m)=Y>a*@;ktyWhAtrVZz4Zp@dnkXQyl0pE9=H6SlGZh=Yv84PS;U~vuv;RAQg1uuOLZPK^vj{6 zik)BVFS=jZ&-OE$ZPK{P8Cteq_5RlVn4bn!rWeeRWJw#L(91t-82$wc{>S6+w@E1r z{@g|RzBGS}`+zyA%i)GxR9>|A$58`j`8;O$bf&L04)mr)Gay-y`BZee$Oj+in3?ZI z#y8!85u0-ToHmU=eu(h;OnqpRjrS2&Q=kud=^4Z0tQ2QWge@RhDzx?{8;AX1cx%W^ z710_qVV~WdjP}ZiiT*R{+fV#Vz0h~Rrdh)XiT35N=|DYE{%rrgLup#QkQ|DR<$Y(JBM zV!NsEFI4b95r=<@INFo#*$M57M6{X1zUdfI@AP!SD_e`(;Z_GnB^inGem{fY0Zg2`o6#!qE=xNM;;k(N^V$tkAU6yc6=%?Bdvc0Qj|fgU*uo6xW+x^ot+PtbeDC|w<*XWzeGF0R!l`UQ9KAp>TOG%h15*pI-QA1{7}l|ITr!gfi8 zVn0|bE_7$YyKGHri(3sn6q{5t5o^z=$@9+Lccax(Yg@a@41Kzb zmrlJNHM&(3W)qls#bSj9hy!**J0ds^O%M=_9@Uv)M zrU;+AtL*BjK)~3>LRvT}P1gZ*xbb;h@KM49A7vl|{I{_0v}li+^Q(?C2EAx(-(tRW zyboHx(fnRoBW+sj3yi}`<1KjG*{JF^O$VJtM0;NyV8Bc8MW`b`dC50Nyc4k--7ovn zMJl6qQ{jJ?g8v`l@Q?QH9GK^M-#*2oMtcDMqfqiXby&}$pVy8GKBl@Tk~_bR{$Xi^ z_f78G61k;sTW^{c*7!8<1=B2CFv~Kz?}^Cd@r%k9NF1#na{{NbZ;S#dg?r>N;8ts+ z^#$;Yt}@+mZJ1-1PBftZ;AZ`(tQd9~CR&mE-0!s}I9{VR$hO_m_e76jJR3|kzqH>f zu~zg^6}OD<4lwg1VBKrkijka34sQp(vj;wagefn6fL*7eUy>YVN0#3$l4qm6CkM!L zarB~7FYvF?hH5_p9h#V`Q4VlidDAaVZJia*%p!hINn*nw}A$(SN%+GNn|u=`VB#6gzZL z*@iXMMSz{}L4Bcd&=?}2ZLk|Qq%lN%RA-2UyzP`5lvfc(a0M8~|I_tO;D0&}e-e5b zdOEN9oLHexOU>+QTK2ln>1x?5bH}F1;gT)ATKy zsg#x6yPGIpH%c~C9ii*`DL%W4rbAsq+EgFSTQ2!f@<9UqF7+a+-8Bwl417PrBJ`_x zY6vlkSG*1w39(;6RJs3E%&%UH&q2Zbt9e9jq!_{Q58wZrt>Awq4*!@Q-M`0ygs$8u zqga|p_A!T;SIn&yt;rh_?MWN-w^1*2o!>dMph#`@{@O;h;%V%M0blPLSC()iq zd+DCS&yb6^Ttnx9WOIm^*lyz60@(p$n@uwDHp!xTMpD7E-*$-|JK1-SM6}fstKB56 zT)s(iEhnK*nrzZN_nZh;S0D7PHEYjJw>H5N>}HAM9sz%kl^-T{J#)qrK4bg15V6@L zCJ(EH={FVra}@l~#^GNnjmu;GrDjLa#3ak*!WC3X$px%`so5E{aJ1w}=;uu@g&DpR zyx^F#Y@hC$p-*+ODb*Av3=ay7X<6u6s{dQ0b70nTGglS-#2;tEKmjq%H}5 z`XIEe%G9vjM|53bqWwXTkh&nlv|etSoOZnRGMTJBzEHD5G7_6qqUG^En`B*@bh&A4 zQ)p+?;V`jjd@H0XZ54QSQ;=U`l2nYbeT7u1Ej5{t4^xumqj_EU=&2CF`Tzsla;<%v zFJXTa%{@)yup={fae%hxR3B~8Q~g8j zUFE0k9kxY9%JV-Zabs`ukqr2L2J-hTS9O$|@*3bGLGH2;ZmKJ*>wSnpuPs+(*6KUcy3Tpa$e-0WK_aYeLbO+C=+#vbW* zx&4p~Z#jD4o~D(2IG;xu!lxQxs<5x~b@%ls?*+b6GfguOY0PNFpD;El55#&W`;y>a zcn8)6H;3#?yyf|!P0$tgmeUyCN8hWw%f61{mH{-=kw=xpurw9E0&gGPJ#>v8yo~Ks zdM(@F7p{<=T0Xz$)Lt9r6)U7JZK{vUj~&@y7mM1>kv{I40K4%_A9uY}(xJxQRQ>-v z1^++B;g6PYZ9fk?-zej#wz8+YHeDKb&m>>ElwAFcq#gTH5DEP;GTn;tG$BK(T#_kO zE&~!psdBwBq5XohOD^`qHv8`=P9OKPpC^Qfxx1hH9M=gS_jBLcg&LLWTO49^FNLH0 z+t4{)dAW2Q|IrF*v2LwN3??L)rGLgQPxTU;^uACkeW%JM{VwON@PPIS-{H&M^|zgR zH`f2_V*S6j9d8jujP9ipOYn8fTfyc0QQwK6R%Md-CEj-WZTJEmQ$jAi)-*mmbL<~| zRIh-Tyy&3_FO(EfR%pbAVf_Dm1^++c7svL0w1sK0zFY-2NtcxVTy>F_DN4$mfzr|k zk9*N`Uoi(0nD0my9Y$2?xR;ip+{@!R9?z+0Pak_ueunY~UrjI2cU)X7u{ylx6842I zLW+;0qXI<*$BP2qOYpw<=jdoL7P9C>EXByrFynffCTo05Nw41|B``mg>lSQ*!%?f+`+)=;-)E`Ee=}Zj(58oouQug9lQJl;p(dVJMTvrIbl}mrWvf=qYnBNJ|@S z(ou}R>FGy0Xgf{pFiAw_z)-^~-wx0?@a7gG4E65wue`apEy#h(176yA9^cyzycaLV z9A*4}*tc&#Uxsh_`}4Gg)B38BTlxH+Id9Ud(X{p!Zt5v~lh)r&JyYJKwR?JiUL~M5 z-&FXU75qPm!=Edf-!rh6mWd%S)Gu!8d4Dgi_)R@y-b7EJ+SC)=n?%>zOA;_Qho-fb z&e7>{QH1{xvvkbHYnNlD4z7!yrTLkCcwVcey{wkJ z_no?>Ui#EqiuD6;c`Prv*C|nV&^&35Cuz@9a@-Gl^NCm|@I8w8Kn*-g-6}dof^T8k zqP_nF9rgu2nm^OND5Ci?+S?PQ-X`INBm%!gJ|#|y7RJThRQOvI{6CGuUn!IB=reI; zqQw2~YvPW5rR=_n)#w{ou`*UHY;<8vDMu|)aAlJ&lcbc7#&y>BY-l_XtXZ0L+9v%f z(}I;Ai&V7?JiRRwym=~S5%ekgEZVM7)qy*u8u*bWrLlP8V=L~3-4D8YxTY!sHd8gX<9GlZIr!Xih*8o}&oXl$fqUe(}gY!n=I8-+Eljl#Nm!PVesbRlA; zuxjvWq>!K9SiinO$r#U-)va?i#GY%U4?64X)_LmIyJi!yzG1Bc=MM-uIXMC$*7`aZ zeOD~3b+Y6^P)%*UbB$0U)UIlr5xX}MkHg0QG6nz7@nd8B-#q842WHHZOJs$!etq3K z+{<;>uXW|FZ*(=}<~SNwuJ_c{=N0989nLk52V9N0j+Ks84eLGYa^1N3u%p41Ti39v zC_gtZry$3eTkEN5a5Q+3&NP^AMWtumx>}dGEVr@2iTm_oRbwtnKgUVDPKVR&8vFub z?p(pRVbx$D6d&dLYU}IQINUDBN@0pnkS{00cYfXdd4e%6-rG?Bz=}rCcU^dHD0Kre zQex-M9f`Qde$z1gMFs!!ND#vx#T8dxNU_-@70V0LdP?js|ybtGR4WT9E3Ry!% zJe1Ll{Aq<#rwS!=;{X`COJdc5elyKgt_~|GLh;x11C(n|orhLYIjq$G)1+Sub#q=f zp1xzdsq3MhC2Q8)>)5}j!H_qIYzR+u?Dq+5Y^aO zgiY0}Nb%d6!dFJ^F5fn=`=KXN-gY5VCLQsAvY$J(wd{k+T_3rge_`d5|43jxXute! z^3)!djCz@V#>frB@L!4F4jO!Hl1?PK;@7{zlE*+l z1y#QadVMhc8;Aq7gTCC$k}!yd@FA8gdWR)zL8ca@|D_U7p`rKbKN^ECB0NY1N&u-r z8W3s&84aQadbFT1ARTBdNDmqZN&+Q=Am>X`KodZ>fKoxXf+m8ffG^$Tn*_QIG#Mm- zGC&57bx@T>}5*+AJ zSoV-p#&Qh6!YJ*f@fJsIZ4I~uGF@1;zRtPMQ(re*AZW<026`?SrZgJB<#}pdD`yL< zaFAoB3$>m)4Ad*9G)`%x(34sRbTwuevjyU=t%PpM17%`4S-4mvp1M_Jv1u`>bJP*z z@GfSk&vDc^S3;*{VcjY^Zfqor9gAtkH%SrpD4#C-cydN zBl5B7(Hs*&@FzLtSS*slrnzJRZ}dBZULD;50z zj3W78Z~t+{{^ykFCRDo{;W6-=9?)D+9;gX-V$?l&j>A{Nlz(8!-#?3eKG1_8u$@uu zN+QSuh0NAz zvmKA|t`J211>THd82*bD{QrW&h~fX=Ef>o-Jotb8{x|%*{}Z=|;crv$|0}-!oA6%` zSK#m~r diff --git a/bin/Meshtastic_nRF52_factory_erase_v2.uf2 b/bin/Meshtastic_nRF52_factory_erase_v2.uf2 new file mode 100644 index 0000000000000000000000000000000000000000..8a83bc8ecff5b9cc00839b16f338deaf071f275b GIT binary patch literal 127488 zcmd?Sdt6l2`aiz*+=uIMQMswZ3@9>Q2IxX+fy1yt(9oSE_pcK@AtYNy2!k#D`teDQd21gb3jM+#WMn-) zui&!*pGtf-;q%+SH5xhDGID-5_P1hxy;e@%!1lMF?f>E2Z_A7xw=4g19i!L(({}XT zJg*gb{koprwZDEZ&wJ>8H_G40f9A&-^dgg+rRBP{Fh7k)0RDo zfA=rC*(tnz8+lpsX7TTV31^33o? z`Fy!}UDHCT{2;E=YvVGBNz)pXxs|Q$wa+Gz>sWs_C_OkMFwC1j?efP}!d0dDjcie8 zq=NVo-*gfq<9x*Wy!qd|^kf?G<~Ir6e4LB45~9Hq6ngp``bXa-@nz|K=rMh7eY&nW ztLJQ-f|c{VgG`5pkLuTBUp*vez4XL%g$qd!nXh2I_@CT*e1Gm9Kc8;t{Wt30b@=B< z_*1DjivM{xrInvZt3xh1%ZRk{P50tIaQmgp`4+)%z7|KNZbq-+2Lx?8;gZYc(Vb zK66NtLlGu;5j~7ThOxG z1}cHZ2?GlD7w2vpEjJ0%eFe#?BWT_D6{d);EV4_x>9@O}oGay( zDK-N;nT=x~U_VGJJ0P#Qm#wizSjnt^I&SMAl{>;d=_JcJL9uPGEso{VNX!?UvZ3Wi z{*_!?O734AUl zzzI;Z-VxYwN>G?L;ys$c&IIIoXCSea|%wYBu<_z^&`p3d)Vs@8M31eE1;8 zB+zzpqyAmj{{JZ9PleuS`%mV#+Y@aixy`Oimu0S?CB&5B*kMUO^{#ZBqO3d@Mk*DR z&)I@%V$lw_p^ZK3IEdCfjZ@Uj*&kH%;3P$jqD!s~s!?_`nq6ITjd}#_$w2#$js>Z~ z+#Fk2-e!viXy+Vf46+K}?#UwJi`fL=P0>C#OwnF^I;dJvqkJs@?K5b@L@SxT+d=eN z5$&$9FFQ$&gxn6tX+fdeZF&9FY+FUHmvxV23wTwj*_L`*(2$tcZES9s#%f`Mws`Y} z{fV}qEhV|B)_K;^U-@R2MiI1um{#}PsMyorbsheHlJHl1;9pn|is~{Wl6qFwlZw-w zjFA&G_O`U_19!1Y#dhe0c9_)jaJ_^AZFAC|DpQrA7TerDf$l5P-$(mo-7#8arO~!jP&^Qxx7D)hxX$R?ZT2FD zW1UPbsW7qgSUq@TF?i%Qhq8v4vK_uPMxLYunX=jqw&S^#mdsOBHfVS042xN9rHuc1 zNGhQ-#c;=jh;rQ&-)^IN3#;y6Zea|!vD#fS{`62|>X^dcCgD%5>CyH-fiv1D&F39w zjG*>Pve_g`U`p>$(A&vQPnu)Ev*P2_vSeZ+>!S@iOnf zIj_la`EU3r#l|Gu%7KegO0iekpkQOTaj*)rc%lJ6Y4g}=EOf{kcVC9PLUhs-`ztb=10e>qJu?4McZ=~2|?EHZL_mY)-bEL_51AFWl}vd zSOIcKBrpD9x2FxjH&-^0DZVT-RlPfpa><_*c+2;ORjjUYOyQp=;qT>ve`H5#gu$V! zVG<&^0DOmXx;^UMwDs>CZa5$x*?$)NanZ50UuPz!EM6m<#wvI5r@ixtH5U!5S=#|>P0*u7?nRBI5tAJ& z^Oyt~w;$gZ9f>UX;>GDj3cf(0pWf-%YeUaLUun^BKVnazE3?SCbryyzv7B}=Q>D^s z_8j_ocy`u0c58!ow?eL{^zQbNAL~@kVe%D_6pV&MpX~HC>pJe&UdU$>ABxzPGp6v* zm+<%Y!2eGR#B=dg7KGDI| zQ5||)U=7JDwb=Qv62IMO|Bnw+eHz zgSRN+!>n6{M031V&KJnNtU6P01>w8wp`z8Lm?MKvpvrQ*{oBs4lDt_N}g=Z4I z_?HJ|=C`}-vL@G+D<=hW$Jsnnu6mQQdpc3F-vHqPczS}hFS86=6|$|%&+oA75-)S< zzF!MYxL4beF9ZKB5~k`X4|}B~3sd!ECgCR((|c7sqyDU0=2dCQy116u`Kn^?-J)fw zBNg-6F@^tQ68^p(_{WN^;7u2adCK9{?Vd|93hFo{_5Sv+vp{N+;Nw{rmrNRMZ!`5| zq`l2FpA@EdP#SyJMCR}4^7F2-W~X+Xj@T>jddWwY^q^p!dx!Ncr{4B`9+MYj-S6tY z#JBNqC)NP@7R&gBrvnrS&nx4#%s9WYpFc?oe;f<;u&lCx8vJR zMSP`Ybv;GYPuLFFV!dF9jbR(N7eu*)fIxpC$bLJn)aq|H}m(dQ?e00rjKpQ{L^K zv$I>H{W7)S#35I|*g{)eFGTF^dO`J`tN)6B&DlJPI&G;{A<1D4u1noASAgt^RBv#~ zT@h!+_PAJ>PAGmdNapEik4ZfT>PFh5_H&Q+$l0&8M@c4sJ3wOU{{uI!O#R<;qx4qZ zHT1o9bTPl;#@*dAE#=2M!H={zlhm`Ko^rsL!vApze}51B`BzlzX6NI4IC;vc-rAL0 zBmdjiv+~HSr@2vXkfim~Cq`v;qDz$3^8Ht3b$;IetE{$g*GuY@nevkJTE8lB(6e7fZS5I9 z%huI2FwqKDv0=B^8;6A*hZfl84=dZ5&)jxj#P*!*oO=aBHkIm1NQ8I`;bV*C>}#n% zI}qsO?G(2i|2Ouv@~VBU+T$Q?X+j{KAOO4 zpE_elq)k_&&07Z>ySJEBz>{PfwXmP+r@HtAEX+7qnDM%;LPA?$jUwI)7N%LZ9DR5O zHm1%L2n+KQ`-E#2CbPwI0v2Y7-#l2DDnA)_xZ9nyp4ympmZkBeq@J|;%c6}LQ~X!a z#*7-ZG0jX;ZMQ~~mfFVef|V(VI_z}6D7n-)?gPJ&vw4tlH}Kze{@*7g`~yAkH@8vA zn~}>Dj9r;wZ!_sCJL7yuJm~LumL$kxSzhI}esL{jz zyN6~kDAr!Jw3o6WzvyCVkLwqK#AII8?tvY!XvD!W>2%e>5PP>sr{9u8I%n>Q(kHb;FxIDh@DwFVrMRe zop}Spf4%>IrG$Tw2mX^~_X?3ZDwVxpXA^yRL(5OHbu@zN_d2!Nu3Ck9=8hfR8t*@( zdYyRB5pDi>8QN z^z|qgsXq1KqGR@JTm&8pqdc?#Jhb~N5B;C|E2CU=t-m7i5$&&xDg2+5@DKLDpZ3?J zb|kxlwxU~MA1hzK3_CEnyV!m!EWy8xT7r5e2^;{K`V4GANuo9h*Gp7MqO8pOe~~DX zJ@{*Rl79ReAB;+q;l9t{fn41ab=4yLzm+Fr3je=I_>c3zpZ44TCwWRa;TB}jtnOJ* zx8XePBmDaUnYz|Vrap85E%9mQ!f3q4i{JYn;_lQo{2Y;*=>`%RvCE5p0P%a05@VRU zi$q3MdhtsJXzYnG#8n_GjQ_ltOoct6je{4O@QuahJyS(n<9k7g{E}qer#K4z)V520 z#geD-&Jj;zMsa*yJnOSJS}Z*eJ%qMPy>`OiQS4U}UF}~rWlJUO&GO=P_^vGewsYcQ zWA&7By)C+ui6_P}h5u6${^LFHKh`;MocAU~Un`E-yf##&!CR83WckK%=p!fd$L(G< zM+Lo|F(qFrD)z3S+rJb~6e&%HBwX6;dfUV;G}3p(R+UE2bvTUmzTJzwwzE2TSr@U# zghh6Se{*=Lpf^pd3Cyd6l{l_MM`Jwq#LKXiWGCvY8l`ig$fBOz--egT{0hu?)Xr*kBud#<{DdV_E4Lh2k^HN1nml zqL?$L@c*lX{{#>GU$^|%iE9-5qF90K4B(On&nUcU!+j5l6kFZ%*ZRo3qe8GfBO;K~ z+iLSla!JMWw&i)dM8sG3{Hfk(+m=W3bi9y*LwQDTljlnOu)62I`l#2x6`pK3CiK{+ z@PvAE<%&CCCCn!L=3+JL+nub{bTGFvhWYI6yBOYY_^>7U(wbr_A8JzVd||N|ovx(% zpS=3O$h*x)eEJ7Yi5TJht5!>V9gPUbvy$xCA@GPT{p|4Ve$D4Y#G@nX{6D2z|4(20 zQB7XJ=SKd!&i*fy@DK68UzEVNzJV6G#%_k>UER}K=Sk14{a+y_@D;K`Pkuw??mV&Y zeFt}wCxD%)} zSMO3+GW;Dw_j}0ldiVi!T1lFN(&dXq$!rlN^Qf#<%+Z-{66LuL@?1M2&tI}bnm=_+ zAmyX-{2@`RtnL|CPbInjBH3mIeGrsUCk-s%!Z{ z_tfQ{GCit3>J2K>r}Bha4e_E(PogqiSCPsg_qV$Td7l&!202+eAXz(@m73Tt$#lQt zKyoLQ=M?=>iQWPEaUSwx(}kBaU&(j{xg1)4cz9jr%NZ}FzlMEb`1b1Hnrd+8{(UqL z%NQH{OYG8J zIk;;~;lE14KimULOtwI_Jc{Qjqpnlxu37bR9$&~Q&yI97k zXUD%9wwdtnL2pnmvsYD)t;!O{c~@_@t+kBj$}GWLr6rJK3{1jvLbCo9@wqQ?w9o%f z@WzYa4fTclvnN$oXK#RxnHYbxlZkga>6_ig#*1<%4_1NuO3ywT;fZ5WCYu=3%ENGt z#gmKhWSY(RjrhA3jjjBzXC(Y1Jn*jty0_OY1gg5d8tC-lKD~(Q$$cplRhh0PxY8#f zq%yGF#~82+xE2Ie#IfTl$&?9|mwo? zSby5-8KW4@J*9oof8_eI$WWj6Rs(ZOIU74MH@jqP>Hoh;_)qk}|CeR&WNRvvm8Ff7 zSY%d_Q-Y5y2_+alj4^%H%I#eQO%0sX{z=;00bjUOy!vm0p)_Y+RRG99o{6nZxLY7fAaM>B&J zbM{;E+r7}wpc?5`XrqUle;zZ}kl9y8vq6Et6HugMCNe>iLoT66)cL)=|rKi{%R;*c^%| zGa=syF=pC(ea`lc5Tzee_^+1mpX`DEwls?P>Yj<96)}T0g!bXJ{PRPUZfMImM+oi7 zOXalnro68Og`KuBYW3~!R%k;j(9XOka_Gm`A-^8I_&7Ec++!LzkQzv7ZVu0@N}VBP znCFmJQ-IS_k$-IP)?Gj=p5zRz4iIg$Gj-aUAjk@uX`0j%RR0HCo^3O9#}%8kz zMC-+OFXfWy&?X<99#i<+CHyJVkLLf+=DzM^UXNw>G&=>&TBLeVH~@psG{hXB1J-DLy*-gFTv`=Dk}{EFf(oEa#fp^ua7DGizWOcJ@EH0uLy??tz!}}4v6?|INGU(S6l<#uH96X zwvAP>KQ@ksuAS@f8`1AyLch;x_lJH@Y*%l&4;Zd;tJv&A^nRL~&4_nbrKuoS&N?*R z5sGg{G<+l*xGNAEesVwc9?8KL{PSLLo`M{ctb)B3OS|`o zRWJ)y!I;9oM8e!A@ufkB3qK^{YR`Lm*hLYY8_Bi0{SVY?~B$!AmsZY zf!=WqN9V{rWK%pV;n*hLLH#q(3O9SAaOBjl@BJK}=Rm5*7fXH``n>HUcPC+t+Nd7? zQq<#=*G^y6hfq zsf0fbdX36|MFHAH2G!&TyA@v16=)k;!uu90*|2xuk-wQSM6%JqI#t+{N_eK2Qa3!0 z`it`8zSwT<=!5-$78~s}U@Q>jk!io-k$Z|^<5|fj!w84W8o~Hj-M5`e zBNO#TNWRmM7rEtRr&h6?CzhaOV|hlzx1Hh4vCeRvZ#hLVYU8oaNF&DYSNd$AUSzy| zA~RLR3ZkT1-Q%qDsR81MTCKj~tn-DWT7BhQUHERwQ_&dpL-GH*j@A^uZ z68=#h_>aczC{@05MDA-x%x)U%wdr(Kn}Z#UFeLi4iqi*zJ1?zYHqf& z#8iOM*gA6<`$Xe$LD9C%_EPG-T)FLS+Xt2<+=r=)xnfHe7ijyp^R(cjH|$4iz16$p zxS;7cDQMa*q-wckscNnuRf#ft8W-ELVdwwb;jqPEYvy{|ZAF^|RmUbl-KH=XShKC# zFh_Qvjl_03at?H#f5W!T_M*ibBf+%X0gD>_0@`o5uI+jUd03GRV+oX;$E>=u@1e8q@HweDt(Kjo|Jm}?D_CmCiUE2uVQo0 z8@7HcJi6_eFx?)_lT>QyDQ=&{CZXTq+r3eX-sw%$x8c2u@DC2ZWl0!Y{@)iR{HJ>0 zkM<3HUY%M(<1w$2jY}Xs<3uT4joz0Nx;*K;g!VjkwutmW=y>-P-@2q81$uEnyMP#H zq0e?7I}=EL4n9cg>8twy{`D_`@B%M(Dm0BHZ2y9IF@iRUt|@|@2*EH@i=h2LI^`htGdB=?o>cjj__HG!3| z5G+0kTZJStzS762+Za$0R5`A4LV0NUZLI%3j72pDg6D!ag=}>9{dGXnKPTStsTx!5 zzf8hE=2!Sjy?Eb|_V(*uJZ*2gM(F=0N2y*(?WdWqbMO8TUGMWwS9-r-!C9Z|DC`z4Im{hxgG>++cFPa5EJLT1>j z_9M&wo<}v%>-KHS*NXnBW`WxE2Agqt&ax$W?W$ycYAG!{u~e5&OIFxBa*lT@7dN_k zFDqR^LBy2I50v~X_kCA)FXI~b7cwK6C#A?mxPkw!v;Wsf_)qh|-+jy5-5NPY;$BX$ z?jI<JHHgM7`eU{h@iU|C{Bn%dFv8Q*8icDp zH}A+Xh>@d@kf~SLXtY)5k=PvW8+<>&h36B~-CPWtdbI~XLoB;j%8Iy0jAMAOr_L*WWcZj(mpJ48(nOhW< zKZyAXhn?xUO1^ujV;SXx@9dE_$~&ujme-fz{Q046%jx+OIKR|+icW=b!~R`||5^$E zSp4GA{-2URGt`koDe{HgV0*;bfl=7bp`Ffcc}o7=kkR(KvjbH7Z|rS$-h@05nggQU zr9~w5!$IoBnK@$P|E&Z$AR1WU$ml~3h@IwV4E42%nHH}*Zob+-NMjSkED+53qA}PY zxy5Y2hfAP+){s}FERdnTGlMkeXLZj~WP!}X^9cX^pusl!th5p_4+Q0q~z=g6;@ zp2OU#nDd61*EV{`%o2q`OZx{aMzcVM`koN)x?#b`54#TkbrSw25Byj6EJ7B{AD3lD z{O1gic~>()H2f;}lwW0lB!J%E3Li9hZ5DlN-N7=&97Nk<=W-KSBdhtPd{1J11*>4I zSjq0X4gE^O>j&S0kC@H`C*}5CpdNuDvXSP1EM}9zHNS^X_yQvRR`%2dNtzJ;@5NM} zAU~m)N)*DsU;H@lt@M;DA$Xn@@qVpnXZ%>FfHyFiA72ukyS~u|-l>9*>%HPVwpp+< zXnt`SzUzv|6#g$s_)qu1pXNsIEuLZf$@zAM(Y9X5TcnvX@6yb)eS)oEy^x<>@uQra z=u}UcSfSrjg8f<5s!fp3x|v%iZN4c|H)Th5M8)(9nPGDIBiZ4bOq)VC$BOb>Q4sgiesxp+ADpcq#BA ze540j=j@^!KR`B1SWO#|`cH__l+{vQ@{zh0)Z^`MF;7)i{?mD_{7(3bq^R+jYX2`w_|Npf|C&C$C?d7GCjt6^ zwy-UhoMl1(F)PsEp%c2rII;0pdLghr7JA_&8Y9j`P4S1i72b&zlR5Cr{hl%6M4-53 z;1FWOG$*hsHJkQ9bEWt&otjKUoF6PCfB@DK-` zC6jUrlX`MSvdeCzYYY>5C7 zopB;M8{S!l9{x;OKusvJ0w-1mAuBKtS%I00f{_&%RvA$VAKw(l7z%ANX_J1_WMGp# zg3Zczd_`<-P?85a?wr5x`8*)ea^aG#t$8NaNnj=6xh7VrN%?)SZV|4G-F!heH= zf1C&Ylzvm*N$PnN-u#)rq2D=b34nfo*cbdmHs2z*Se5enH=3~%Y z48ECqZfZo&%`@Dn-==iLZ=>Ot4pQ9`Df(^F^Nzr8bHq-2pI_U(Vb}kKJD20=RANLi ze~GvP<4J5X|B?Ogxed~+&@y`5gwY1>o43Jh(G0JJ>8jVFLG)TYZ}-lt%|S-PJx4p` zhNGR{2AW5_Jcrsi3UT&=W1R|EIq!qFvf-;3Q}|a%_{V$TPklA4=&QLy^wp%oR}+r8 z{32Oh&0-G2g<2qtRJ1eXFZ6s-DqJrW3*4fb?Dy|P|>){}U`kIpfLf2D*!o%DLt|3kI-))(?7$1#4>0Z&}DjO_~06~q23$t&D3OQa768d`T=iTQ;HgY_W)^qH229T zseBlf6;wV@SwZCol^3J_UODj6VP5}OV0ITUTh&PPx|TM)O$^?K_Vs%l)Ygc^5$*B+ z+d=UQ>!+o@Z!CECca!`U%4~kt1(Ptdcv9&_8N=}Y%udTaLZq(vVqjp&#h@TL?=Qbc zFq%to+~p|vP?lYgM&~oNLQd(hhJ`#E{^c9^?>hg_MhX9$Jn$dvYruLKx|WwjnkYq@ z4EF8BISoHfT&;n$(rcP#_z6ILtoDJm6qw$h7k|Z+G$^|5Dt9!4k)pocY9`paUQjP0 zXwy3_J(x>E)= zC9R3gBvQ!^_N{hT9mwi=EK1KRdhK@;enbC#jqmn8IqQle23ITG7{wRa@?&E1U|(J< zT{A-0tX`m=ugA3vw<^<^t!Gsks`)Kgr2;np0n$p>rchuOdHTC<9s{x4IeR(6h6he&3eYcREe_^zhcX!=XE&0%{s-(T|G~D zw|hpXkfP3=$gYY|VZPa5R>{3;@jj*QwJ)i*m{07tMZ&Wf%T}euU}jmNbV=wNmY(DE z>X^cRvxNUG9{5*V_~UPPDKIy0B)i|1%sRuX(w+|0bZH6jc#uRcPmO6^&aTXzfEoF- zKz&Dli{(uFe%o1;QIm@(Em0J8`1thNA3Pf#3rc74M0?gb?Yn}s7<>Zp(KKuLw?^7N zZQHu$U`UufSa(L(!Z(*M1>%)GnfgCYoO#rM-qu`U>v3NJSM!>(^0Wosa z&5+C7i33|v=EMPY*YDJduHPwWNz>JmAA6KEi6wImm{~dO8iJXv`4$cJOT>lPlw&LY z_o{^dtseNFbA9VnT&2bt*9etbL$H>QxjAIvG#j03y}dEYn^JgSn2y)lbd|cjToClO zyusW;v6E0Mb5mq8570Tp%`IMf1>fq9$)=WKr!&Sz>8|8=xumN^d=8WD?rS|vTIWI* z>E6{Y*ku368?!E`2QNa*z2%cb{%#Zzrs#vmKO%`j3Ue-FT7u^WRG07 ztC_F$tkB|zyln~XIG0H*@s3c0C(iIR5^Xmz1wE?U1C{q|5+!QT(t zLujFEKKZhmks5R^VeG?Jk}^3j zC$gB2FMG+9oIEC!V`9`Coy}f0ErLsq)t+L+{p3qy3jZw<{LshsitB0dKa&nG%+@&mxcS`$h05tl&ZjWa zy4E6`GJjZ*_EMpOU#%ovsmdR;rhB9-UE&pLe={tTPWWFA&V`JDjmN**pWH~Il;~A5 zH{twHN7M6`{!@wIfr^HS&7eb*L5?wM<5cAMGcOX_=)FKJneVV~fWy-!HQ{VC>SLQ=Atf6r~v2ckDX z#BV*LjEa)Ulxn42j*pBy>yGi_bl`-LAqA^xq&9(?|7DPFDIe17ejI_7KzkX4Uoxa` zgpMKd21tCG-*4`B(r?OJw5-2amN7`B2L}Jg(kMHo@UM~ZpW}f)!x8@G7Kz4m|5b_N ztwJ-hwm_c6^B~O8e>qyO{i7oV8ouI z3iUoZNYCaD(h?-*XUEZQhR|N6gl$zC-Iw~Aq4;gTl^1H>;Ql|!i!p`&YZCr*J@Eg( zm6!kj$cxv9|9A3&$qXr^Z9NhCL;kGWBy*@U!wO}M1!=1JvZv-PV+^EQ$0*Xn3J8Dt z1F76b^!2H}xh6{p-{Kl$>%VN3@W0&ye@TWi<&e=X+RvsEmC9Vi@Ig;1b92%154%Xs z{@%@x%eave{6bg1)BLUmov_p$Hw zlE;5K5p31RsJKXsFfjd|G0zMorV9?fMb3A~+G6kGMhLr?!;QBhzFiPS8OT0_LOd{_|eNh z-rDnYz0B~ullp7rQ@1%o*n%_xe9|CemvEcD(VVclU#XwNBBn0g)Oz;itgdIuBtJif`ypSexKq5$t{ zou`=YbakpQHG53q|AvHrk_Y~gPf&_b`YZ~V#2P`dZ{fKWS~g;CU##SOdXq3IZfV5x z!lZ!hh2AN(1z$Ng2@}OL69amk%|b|Iey+}HZ+Z(@-Dd}_Bg0lOxF7z&lqn0p6Lyuq zgABkjmd?7jra@ls|Czkb{~yZkV83YA|C84-1K$~B0?x7Lv$xo0+T};`S^1ZkO};xs zj$X-AIm@;!JG<;Tj5t>GRuvo-LN@3PZwe91NaS7Q@`sZl$2zbou(*0*DOn^Zr^cH9cbkNNvIqVh zpaGT9T0$6Lmc|LwnX(4--5X_b?!GsN+nO|Vos<`Cpx)R0FJO#i$|M!$d^p_{u<%D# z+f}Mnyt4_|h6v26=de}t{yx6ldasjKudWFbA_U!669nDdofsFk(yq9rG4)4B*2O!? zXsx96CyGIOK^oP~Oy+&LRIk&0U2{XD9M2C^m#pznS7huh~xHpBnmP_%%x1I6ylS8&{r>Li9xpaY=bP4;R6vdENF>Vwk0^^o<{fsMDC+pqPY89u6LvP z!;myaD8U1Aox;KhjD8+)RxW zX=0Y=${RxvIj1yKdYms6&r?sTgf-TRJ4~8`GLsFZ4W+_VBP2TC4n*xKBaO|0Qw;m`Y}sioZ0VLLP6IT78m4QmkbBLc!hFJJ9FUvvPj^@MR}COF9>zxnWNYYK zLeHd&ygg~5$yVCPObc?1Dg57*@TZF&^y8Bp^VYuL!lRex1vAsVIoWiza#>wwiqNNj3 zgxMyDuBAidIh=h0oS0B$(_~k#sadsd#ahS@dQH=e=#_NUtTQwG(4a=V2e!;Sod1i` zMS3H$vaYySW?dOBPtdi-FeqwQjF}B znXbE9tj0>}L|-MybuzvSV{tBH{!NCzh!WoI%HCU^pjT#FlhM9qxKFx=o}e(;@ux}}(WmdCYu08GgSU z3I8+?{7V{Sj&-1ef}^vc%f$7#C+khm@6rUYws_l^5F<( zdia71$Jvi@w!bi_Jv2j-B>!|Bc2XN%#;-@2R<5>iRl#V@TbsT{zfH!!>w3rOm$6YG zcBVpR#F(-Qa7CAf3Bz3j7%TE7r|kBVhhQA@)~1h~lqYC==dt|&Pyb$Q_d$hnK3lFg z`8cL7s4N>(`0tYNPxrt-x^SyS?O0N%pCdQPPkr~JocEfbS3o|tFw@MOd|CoDKi&7i ze!n9klbEh>;q!^U{xUESul(W&VAaO)88UtdnE|wHFv^~D+*204LW#_Pfb{2h2HBaP z4*KKne{r8&PL@T&2kh=!IKVln)$o~kAKI?z?;Pxjt94WSC_X=8t9Xj&L#h87f7DNL z@4}0PYb`!lV`>unprg78dT9l;J7IXvwK(%cV}6m_G=Y1sQF-ZKF`6!w*RD&SO_OzS zslHr(5quT1umr6m9g;z;@CN<5uK&MV!hb$~@2LFmMXR~&$StCH{@ZEIG&Wk%HZS6A z0XGkO{~kz+QMPxAZTCFR-sjj`_?kt|G05AXexchkX$FwU4g8mb`a`$iow&N%lLuCtusVlyLb!QhpXH1lAjW`^H8 zNbmUC5s5lCpiU0=VufFRJNCceCe2SaZ126jfI$wjoYm|P%aE=%;cC5OoG88ChxBT8 z`s4m}_#IyD$;N;T>9@Qwu(z<71l6l5V=vtuS72KNv^htF)3Ql6|E8E z=9l0>@ETBedC3_=*oqy6YQal?Vr=Dq?3M7(1eT-izf8ZSunAc*-`L5tk2y_ux@@); zxg4ONAKK9Yhem8i&A??paxB&ZiT6HoaZj67h1GuO7urJJi zwQL;gRp@RyXen(_v0mH;;U)b+j5q%;JNgFH(kKa$sbxq$vS!03x{e}%)#N^3MintzWR;J@NrnS<%l z$Sz~A)X^-cI`Yf>LkigB7}To|66*~z%wZqEDzJ?I{q0PmTwucOO{6>ean>)|0~_Y^F26P-R+;bz<|&!o4C*p_~Cn$@TOe*}%m4FBxxO_^ z?vwCe=z+f+EkVY*$|QVW0~T@4a>GWn#*=7`8#I4nZ*fw|sSY|JltEG_^+eVO71GjT z%S?g3IM7v=Y)ZO<6??k;WM+8ZWqcv(@paC|KDFmpfNNAvA9k0MMC}}r8KZQkvZJ8c zxL^mYxsrzEg-SLMyLvwx(51>D=!4kv~Lrs&S zJ6#pPlF9_2+T6drFdi#{Q3ZuquPV~a$V@{{+MmhS3@v!e@{A0qX7v>zELhqCDON1CPHb8MVH;-RHeFVPf@sEd> zK*fJCM12F)BS1DWM!SLV-@5GvMfV2`W2Bw}_yhQpZt5F=X5f2=6un2`4Pf-t8zAR@ z9+JEPX80x=)=__eW&ttM+KzUT1k7WV!0r7ZmrJ^qY7L(`;kTma?Ma0zS@Gkr+M8!T*7&T){lec4oMb`eabFHOI?D>0J zrSn%f#ft{^gIcj0`opGEmA~V_@-w9vYs|1Er2{QAdi*l`!Gl?xv^32s1mLdK> zwNPL5W$4zXsaEp=L&u!L;?#-OeNB_C5y$sf!cMFzR3eY#HpmjDg5jTaGu5{Jhj2%` zHn_D+V9aHx`L;r=G$r@7J~U9;zpu&Pdd3-q9OH6#Qp}ciJQ==8hJPMD<_gXi=byuQ zdREy!N~;@jdma7_68?)k@b?nEFAV>x`*}!IhA(v&JLRIRUETW(bf}Uo5`Cs^;FGfT zL{IsJT5Uq}jD>q3vnR2kV(k=}QJ5OcLhI0cl>0;QGhyCE?!hqRln14Da`LQ6jS zeHw1^NWZUlq~9mBs3B=EE(~)|Uc~A!w7mxdwI9%%{9f!$e&@(V{}FS@qb?G2ilaxg zH_7m~xQ{!%@Wkc%<>ItgM1gp-3P1} ze2^9Hi(Gu2c|Gc8kVi~Q?XcD6r(BWgN#u#JZ7)72+@XWsj;vk&oG_g{Czy34_7q1< z|KyCTPNU7!r)(5viBED3e~Ix+RFi)O9rKBE(K85NKP_RK*c_P|xj@N=H`4dqAv82@ z%dfT3J11t0{-RM@-H6-k@Nbgvzsm!Eif9ark@WoLVbYk`GC`!}0BD)mvLk;x;{A7! zbzzoE>L(ceju&NytC;A?G$$}QFJhvCy+)Czqi`9%@vwxBbhPJi9AdJbxG2)?!d#tQ zxLt1-?l4R7V|rbdo{Ui*D*m%Wq}B7db>uj+NMk~dI;79KB9&>t@nz8>=%(?ps#6ho z>vnZF-kM%5XbxStuJCzbhS|HYq(Rv|OQ!6esS35qux=HZ5{7&<*a1W41Agc$+=#f3 z{-*2j-!I`$2fdEA|KntHudUg|928o(%jAfq}%)rriSl>87&r{Dku2ZdWT73nj zC+IJTI)P%uOk+5TU_mqW0IXKXrauP>5`cVM>SOnUXL;BZ!?{gL$C9$}1OF`Bk6zkb zV5mTiG}?R-=iyU!+%)pYX?PmF zm)>>SaiWYdopMY|UoZHZ&5caOaNp;{Of>_|aEx0pDF&G%3`Uju%WxgPXU1@cb0Xr= zG3?G4k9PWEg+a45`Hvkskps4Y1Kx0k0*@9%)v6J*p%VXJDADL3w7eOp>EszP>|`U2ztPo# z&WdvR5#*myoeO(&-aE+aGcRIhyxcGeKKuesJ|m60xluNQ@N4ai-cO7}L5i5yS^6B4 zXC`Cj-|d+OTeT&b-(vrM)f?$KHcaZWoYB|X-dY|L3q7&utsLMlo_dZxsm^_!@pU=|DIprZ#EkaSS~5$-~@f` zi`2GSJVdeiz)5xYI?MYG-`N0prFbi22}-?zz0YY60GO-s4je8Z{)>v3&uP8zp7zuMy4{+P&FN5EP1 z$*Y_vJAI7_)=Eol&RlL}?bn0z zoV716$dHg7?n{6b*LLZr;@bSZ&W^Ro2klKEjkPw+&BWWAsAae#f8N3-7k?QRp)1G` zYRz6nHk&YSSEhKMx#R`QgYCD3k(gxuz7i4%itCjd)J7#NLDl&6LU6%)Ayl_s2!S;? z4l?MQffT2^?>3S51}>1pgBPS{)*hfU%0E+&c59ZwK0vFb{HEW&oWPg2vL3uEqf%_g zi;p^^SN*K@=IDG3b?=|O)&^U#wn8F%MwH?AEU~2EBhH&4`tC;T?MGHc$4*83 zIFQd`rjRKlK>VhA|LOnZ-<;h=zW>dc5**({C}MQZFV6m9M$7z~rWkOS4HBU3(r1`8 zEWuGLuJ-Xu-S&K1@`12l_ZmdGhOq#5=(oQ}=X(9Nj`kmt`HW)P`qx~DVHJDE6#gGb z_}}M&zjF6*-;5zTzbfJ1E^ZNYpf}-n6mOf)%n3gjc<`f660d=lrE@8lK@x~`w)~pT zv>nygUDF}EE-35hY#x3xP@zX!N0*c3 z3}#%=YKQyY6*a0=l*Oh4=&>VjTap~K2M^xRG5Ql>)UJ|2(n7|PNNQW44}XVl+lw@M z5MFniD2F!+x1)96p+gq_N8btNvspYrOp(Zsbt=n_b*jsjUzW=$qP)S&h!N=a^@1L} z5ea<}tY0sLo0S+v^bW?GB-q}8|L`!z3=sYs`#Tu-83S)Jd4l@*kq;!ywd2|L)+;~O zJ+dk%|1{b>*0IB{*vfTWpzl1U@INTwf4>L*zzpb2U*rgrMQ^8wEz(oOl%N`UOGK=0 zADNcavv(hrosbOnQETDwKyCgT=fg!#d3Im+s^Pvz28+&zh{sRim?E&^yrjb^H$~J@ z?UK}EuA?&K*LoNp*{k(d3{V@e{|ER0;Kz9g`i1%rh+QVzg7FKXbbsWpHh+gL!RiR3 zo}=0vViY|`W@_2fUm|*rpyQKzmWjXM5BpYMVD$9ap8Ppl*NwQn&i+3n;r{@B>}da= z%5D{v-L#GB(MEyP{CxxGYxAdt1P$0P(^y(+t_j!v8@J{EJ3%rs4nVAC1;Ykr_(2 zXE0t;%9$=lJ2W?syBe>%fOwsfzcj4qp3dke(r6ugcf6`U8PU2&N1}Bh@ZJvzitcw9 zv`K!FThTqpNYOgQ5*hsTM?1C1-8Hw+x^>N}1(=Q5m@Fvfpr1K_5ujp}4*r0H^m-=p z`6S;T<%Ssx{#aOBn2=J^AcrqW%3Ad;^eb9dXe{t&eXZm7=Obq1#qAB*YLT5#b?mh$ z+NTxzT5}7P(*#7Mp0OVj6m|_FMx(U45x3Xj-y-4vdk_3cB{K1h)6j13N3?uS(e^^* zX~`#Aix1=!E;;ZcGAtzO28ekTe@74fGx!7DeK)(QUl6(3hyo)!zZ-<)+l8bUb^G>0 z&85shn$yehKMALu+r`+=zl47}DUP(yumRhGX0sUc58##~isbE>krCForAf*p#9Fii zA%_^`BO}r;ej{$*yK@Ejj9=Ctbv3>u)m$yEB;@2KBlc5;H`rciYM(d~`*}zB&Pn(e z#r3}a=?FoI$MC)mZdoB>iTvN_oj35`b@(5a@c)A+{>Y>Z5;G|eVz!L6!m>g+)^PIA zp!8V}S{-uuioO||NqIm-{0X7i$?%U0O(LG7rw4eE0f8;MamN*`pTu_NNQG>(L{%GX%d*vl%KYMLr7x3qrTl`N|Xt3h6nq@^(T z*P4_y<+$1wCe1-g$E}UN|Bbl44*ymO|A##A|DS30LTg(X@~hz62aZ^=h2)m88%D50 z&bHgM=Fv6vWi?H2Hr0aKN4wHglftiryw^l#F5up`SWeuDnIrFH-?qHhBtP{-_?t~{ zTU_nP>nfjSn-gBs^!a5!+3S`Ktjwhdn9?5Pl3nf#pFB`HFxPq)M)d}}v^`2bd}x|& zN0X+@izxYVLwR^wMN?&HO;fdHV*Aqs*fz!F<`?U)azzVfFQhriGMDO7GPILx@CWB1 z%k|=yb*C9{Y}^5-zMRo?SX%yIPa_P zRa_r%8`k8k*)F!CYT$aLYaZdk>>=QU{lymT@wK4mlCULcRahUSSbpjOps)qVeqR=8 z`xuyF42eq~pyXQynP`3PHEbSt#bC^klI=kZ9{iLwjxB8n+pmI5SabE+6Wy1J-ox5q zE7!bVc3eAopiHP~8t14=rEifY-_<3Tr&w#6-mpwRMWT7zwYuk_ZZTWsl@`mQ<0Iu| zC@-^MlwT2v#k_Q(r{!I0ugL>z2lile8?8Gf^}hC9U8A(R5x3Xj|B;0MG7tP2krv7> zjYu1>4p&$;GPGk_$6@CGuej0kAEa7Y`3c&JKeV`xUoJD-FyE{9im&O8#sN=G+=CocT?^&=HkG%ln*95tK5`gfRYL0uooIZ$>~sca-f9TJOx{Y22ZDVN z-zLcQZOBY-6TI>9$0rD%3HXHLGg-e)FpAn=%H!;ZeFE8EoDJKf9Ams6#P;10J4BXw zUm;1vC}rp}dJgkZ6t-QqlQF0Nk4X6Ec;G)u5BCUt9$qHp1KzgKROm)VAV&J=rA)wE z5qnXvH>E52zq)RkPkVIDu7u1G%;IA zISFh1T9EZ;Y&4})uTU)Rin;SU;T?N?;nXZ}jW(0@>zD(cX_JRx<)*5%c$&?peQ01! zf561~shR8qa7;$3wrf729MgG91CF`q425NSMy&+$`<&y&{)rFrgQd6Cv(pP0{$b2V zfm{!P(PK;t^1-(_eQ-~^x(oN1*$T*!8&U3${-*2X|4|A5hduD8cvBvD7@wc;(cqZJ zmexVr5^YDc&qmu6)!W|*q_heiSGQ?>LmXDs#=LJ&5TjkT-B-z13QSBQT3H?DeL7k3 zop5GHDf`EW7#rdLVJFjrTknTQUb|a{@u1r`|qxxC8}R4GK0$1#4Z6kBP(MBFDc z5y`N>l5zT(z`{zz04waeiB*=iOPlRAVe2v||H!~SlXABT)AZgo^mpEW`x8AjgBC)bRfP&#IU*Rce;U$ghir28VHUR670&_zvp&!Lu2Nh_x

5H9oZFl=>o9U)+aRT>E-+rTFPk&cG z{6ClRe+1tJ@F$<F_aW>zd=HR;RIvRepgbzzie$G+84Z1d|9 zA$JjG?TfGuT`?@eLGH5S$t1G%j&RcYEmrW+amLT>cpCK`atuZZYszWO#oL)`wkjh# zHhU5eX}3kRrLdp3n^mkKbn{jz#fBJ_J!e~V#`&0&xTItHcGO@B!K#$p?aVuOVYS!` zU$UeG+akz-@hf>Bjs1=M>4*OpGX9SS;lI~UllQToh>hxg+8zY#s9^fgcHj!eUuc^_ z+XWzPiUN%jw|`oYksVWZ0{Yf`7A4lG#IN5=dEYUJfw{6?fLiOtAZU1spxq5FKsWd^t(@kt;BEPt-$`a;W zjF^#T@!fJ3a|q0$sr=8@FbCDYZ1v(&)U}z2-**pb*^7G^)Ua$@24?I(-hPk^-JAiB z<5%4wEg5BRYE&YtI@oTG9hQZ);+Q*-!Up8}aJO`BaoHDZB-{^nPfZ|^ggnxhz zbiWGU(+u4lBrqN0b42{Mms$iYEP{_HwS5R0d9M3^-Bzxp*Yi?$jDZDb&?gl8t}ox}IXBLCcgNOVkFl4<*xrw> z^XG2zUAwr|UnAy$o!uG>{-IpO`|ez@^*G*ajJDVFNH@Lf7uVr)e)->8otSV{{xADD zkgZ%$&s1k%mH0OyvDr-8n**!=|Fw+&{2=_(ogC)*qD3{WS6dnhWO!=Fw5`XW3!X*H z=g<#M2!5>%3vW?3wfRn{r(Q8_rRX_YNW*X2iJ$%B^KVKcbZgb9n>*Tw{sLi;se7^) zZTN=!pDAje#@@e(?g{pX+_F?d!qJMK=wiaSe`21Mj9OcpRHj_Zy_V37Hq{*0 zdO)!dnP8Pws`YAQY}cfzH>fdQ%JOWJa{X!xfB1Cm6f5^yQd#2A*DOgVxvD*ucUn1x zqBUEgZp~#+9-Cn0S`R5sxik6kdFr*wH9a18-_2Ham2yK;S#&m6rO2qVe01s*(4p3N z6Ku`456P$hI!m>}ExkL-NF~krR7fL_m(FYnD_esoe+k*vvUlCXt*W=^eUw+H`?O77 z%O0!>Pj>FXJfP1JXMk-c2DZ5-=Zn&YrpQ)~+}nj&Vi~I?Zr>+u-l&tcZBF{kV`|iL z1AqFp|1hwr{$Ch`KiRe9O5KMC+=!StJuI)rf^0A%8@ANHZ*uo~CUmj<`j&v4e*wFX zlB^T4#FSW1O2>vQW$ct?i14t2=hDgLchR3`#VPm1vv>J=XOWGGWq0PIr^srA#8MjF zb&$)76~olWN7vyfX#f7DT$FXHC6wj!Eu!LT*$Yl$7{@aoAYP=H0sVpK@6O*LUzPo? z`)%fihW5f&8`>X#Rj%Wff?M-r%QV8{=()z0Mwb!8D5q6gHYXl?EK!NPKAP6g*jXjS__K47U@BXmJGtzL>~-pulXFdEm#M=iSWa`B=fvi2M8GHt5OitK1yo29wcCI{s_> zBW~I!@%g3D2MO>Z?SmkeaAD|MB>i{J)6(+Q*zDnm2sH@YMZ)5n=^Eb+64}_}c?z-Y z^!!ZzjDv`ayG2J$+3}FU4PjL`D)#hu^~3-F$@u><2>;B|SVUP1Yh%K;i&MEd;KJ2eJmHp(q)g8coQr#;5 z`>2}2d~e~48HBNjkb)3vIN}wqDH~eW#(={AA2R-r2jLG-4Mt(6F`DdXp~tiS6G|WI2M*BZ`tNsL{eDp1q&j>@b9_+` zPn>Ro?U{XQRU=&^Ci4i5A@}ez5qUWxqacWDt^WW|6%c> zSn!e?9(g*R(bh!-e;cAidy7$)J=#l zBjO)=ihZ^teGau9ix+AA^;7-~)IFf^cgpye2H}5=w)@)6e%gldrd^@a^93azFQo9? zfyz#_`39Qbo5ig9O$~Ov>66_J35W^r^*q-A%$7hm*M;+Gh4~os(Fq^hZs)nrh`zJ@ z-103LOEzMxe^2>)j-;J;?R*UlkJ*TrJ_eGOeqt!*8F@YTA-^w;?{Y#t3|v5?d9Ldu zm^u0(o<#ICqH8)z@rVP^>Kly`_o5c8Q}__?VAm&NWr{qiBai-wdl8Q?kAZ(eAwJuq zC}67X`fo7$qve0Zcn^KoFX{V&$2dd_9Z>kYWc(Ke;eYS~NjZ3dO-V$q9!eYJR>F}? zCyrMX+$Rtrmgf!}bd#7NQ zp57N($^a{2taAd8=Je}x>1d)4U*M-Yu~8stElyKD#VWPu+={n_pO)W_$RCrlKd_uD zf7>?LIdyDY(>p7`4`dc*4Fx!7?1{fxGMy;}lsmkh`o0|wxn4tw!I4hrD`AGd7=w+$%#56k#J5rjWtGJX1Xe4Fx_o9IJ%8cV|`_mCq>Ln>1isMeDSfF?nMOnJeoSGp*&}GbMwq za{1xqRf(0gm{HdHGFy0YTJlbdrZ%l1gTEX31rJE%QFUuMb3jtunk(sM(p~`V4J2DP zSVEkN%ncTmQ$+rW!PX6c1k}2XRm>-ei^}L6O9bwTlwnIezQHd}IrH$%?(z~M~Yyk>W%8>?*9kNx*n$xh& z#74je^{77&$8lC4>M6i`_`&nj$9@8PU-BUy4aDPI?A5x$tm_d=RFS#fLY&AE?Yobp zER}S6S_86>`SSkGLA#w+j<_DEn?Cm*JV)F$!N*(sF*Epo;;qTxtUF>v$0piq6~P&v}1 zmy;O-*QMy#Cn>U=k~W9yV%qds`y}n4306yoebGTFe#Aj3d{96SFuoitH{~&H;Yxa^ z@(S*p<&@&?S!ISEUu49+aTCpw-u#1GGg|FT^=B78|x`Q97C;k{Xr>t z5TZ&O_9NGmOClMu9VAxMuphac1|dqnIhta6M2Z_U&G#O0gX)lZOcNbxCAx#iR~7A$ zYY5H1{$7<;lP}+?_1~!-v>xqNfX}E6IH2(Vr;Pufg77CA9T^6>qVxC;O3QQsk6Pl4 zq{4_)_{cS6WJ3N%@@^aA=4NZU6qhw!TzhQR7m@~jfjex>gul$y(V1c5rOvo9$~K+S z?TWP0Z*?hONXZWq{eR63%lmYmLOj{|g%tO~7n1e`)+fhwwjSnRL6+0}ZHe=7)=V@e zqJgeQ&yR?8Pu-DC6zE;5S{2C={OeMf7XF0MX0gVeiiqM~_4qprFE$SQP*RvalvJf8 z&Fmt^yIlfwgMGrm_I4ic32HBezVtNIc!l*}&N%eZ3 z?ZS#M*!FZS?jV<{)jXInv_BEh7CWCcING1(M6ZGv7rST-xIkIniL%k8)y{pla^=eK zRUsvJB~_EPwOpG$i@TDX@eX>BDf}%npx*~WnnzCbSqaKkJHw=qTG$wc2hZn@C1Yiq z@@y>`Gu4$N>A=adMK}@`A?vdU5Bh8n8ly(G0r$8K)&Yh8F&Y1|ApGUH>u>wx?@>&c zlw|8=;5O$~nYPo$5=8!|=VxnA)(^2J{+3sMjN|FIOWa}k(a5x@=$?y+>s}A({*(Jf zDYV(^>F!zN4#^M2wO_jy2I=2`-KaoYP3=3XkEi39+IP{Ae@&eltB;tJ`yUQqsoASZ zlbjkW+JPs&3ZX4hn@fdpCUb1nvn0LMx#0=K4(vgWzXsa=Q#~IoJ{=X~4E5bXTQ6)Q zzNU8$QZ&$3YCz%NB;)@~5dK+`{;H%<8;jD7&hvc7T9XIsDwY^l>=+7^zyyUusct0a5PD`_E)0CRVHPFPHZeb9kcZ)Q5+$v-T z-OMI8u0p29xQWM=r0tItM39LcWe-2%vtlWxK z|6Wgi=K^+k27@~ zEC><<&0%;KPb{uTW6g~VXbW-nh_ozjK;eH}#{bzM{1Mf8-Vy2L>?6|ZCyz+$6i1}> zsYj&OCkzvpL_O4Hm%gg~wf1c7LtQWRJk(Xuc??H?>0(^U(Zif%R3<-#pWm+L7PhO| zqV_0*&>ofYNc)hilJ+5%dF{iCZSBM77Iy5L$LM`Af5vZ>2A2X!v)6N0nr=0kDcX(Y z*23I7_VD$*`pW7uM4xM(lYJbrOvEQDjxXOVDRd;|_!B3VtJYT6sw{8!XQBU?^&t!B&-d*Q|G*am04q#?^Kdt8T?*JHeH zZS5LMUDL;C)4z2wDOArNgBA7V`D?8LVzWmj<(tK671vu4tNg9(POR*pSQF7}kAU1Q zeD@%>fYun)VSkv2kCsCo!FTovOGP9BhULap9>9OLlBC8qQ=LQ>vF4uc;e_gR+C~rs zVF=>TU$pOTQ%Bte>~**9F96n<-My4chn*TDGEu;K5V$}pytpjf?K~oBR8va!)w0=B ziY~0wc9plSs2x!FpOo=`J_!E{6&F^1x^hLW!?H8KD4SUWi$6p_Z<*kTL}E49CcF4| z`}viVS3%c~ye09Y+P}aai{v*IK%+iF`Qb45;lTN6Zw0Ib$`58yvcF}WE^(^^I8&59 zbR~A!r!p?CdV!-_3NvLo_DCwz9>_Rd(@8Gd%NfHeDb$qML8eAHt0kka#7LA#^_N)e zE0K;8_OY~t)mMT?iEMv~N?(ZrT8FR10$+(oP-33H#9Cj8`LvGV5zYaH|0x;&KL_Do zEv@oV=tWRynV&-0J_@a*G#qXg)#ad66s7hzzLKA#IHHMBW;6A8_Io_oE6 z+$RDbFz@kEAlA4oGoN9gwt7-ECVp_W|4Mb6>ZeoO{xiT%26= zK=A`buNS{wbh7wlQS!XI=dPP~K$<=6utX+ciwnzwcZ(in96--hPkmh6Y^+^bOI_hN z?5Cgq_XipO|H3a0_10vxtT8WZfUY~?zjVy3oNpC`=ww{uk5 ztNmJ?7@u&B#wZG%w>4}V`8278*)TG%03$34sjda%{r9}xGWN}Fa>r@( zBz){Ks<%HdU2NF{D<9T7?0w~0YVAK^Gx6#abtR);Zh)NYwt~A5C#o;<9KGYB=}OBe z-$)$h{(*=7)j}hS%w1T5ee3#}Df#|IIS~ z_8|QIlw<;wJP!JN{NdiS9OyH=b74zBb^_x&VjYwA!VZ;_O(WteL|DsmQlG(2+9w-9 zGpt}VSyGG$wEElf?YjNaG7|7A(jF!HXxPZrGFg`u4A=I`tPp{_^0a}wd}7uH3-cl7 zAD6#{9$ljCt?Ru|i0wwbP&#A)WilAZy#m_llioe9Kd3}4-2bvp7r4waOQ$*l5=Pu{WEFVv_8*Ah&=Nr*W5esG$m@zHVQi}(axiI z6KoTjxL+HOs5=_(@u7H)+kD=uO=J}28J2oIzmwj8UzixrIGIh%YhKR;iOwEva-MP1 z-(dCsh8q@q{IGub|0LsI5rqHF>o7jWz1MhDUDFun&H+B0ar?1sYob6Sug;~ zYFvViwI$dx3vLJfAWi9Sx;W$O$8Ik;@<63yvcGJteM(SSQ^9zD+2ttv;;{+&6RhUT zXG+Z}8rwBr;FB#%yHjz|tgt^aC=ao5PYDesL@Wi@4&j&C$Zro2l{Ljev zFAc(<%EXe6H@3yN|A}=S8@5IIeW!F>MuDkXRPUP@qCIiWaVL7*<_S0^msI9BY??bc z68E#pOv+$yVIu}+6DW-q-hP$R|Jv5)S?pcdat(ziu6}3nqwuJ2UiXrY`?s~U=y=os zjsDQpQqQA?yS>k~XneY6np7(dptk)5u&&U5#ww`H@g_mmN*^J z5Yp%F{|8@mR+2Tj5G_jaX=$My+iHvfj$jNQk}YOMn>{8CUFR{XLVR za?Zx;qeRCbDa7<#{pws|IE3$*iJF_vU>u_mvy|mOB~~8X!0`9i|L0`e;1j%R_`P!q-`c=mv|j# zQ#a2UlRX{Qc$ME#v=E5dMsK7p3xez3_f9hbVkiiJ{qH+1`=pU5)#RVr--6 z0%aR*17w7c^fBTzFKeI~SEieMbf$5jauxhC%m!xGF6WUmQpJcPyzeYHv*5I3uB@`a zn;iQ55q2yQ&)b!KXvdwHp+)=D0FpIz9&dYuDDOHvtCnNrfH@nz}duBdXOKwu0jA>pljQXP=tc`FM z&o}Y2piykNvmIss)lI(}Q23vh@u!1cf&L$*O`FRLT2t!&6ZHEU^vm|qZ_p`VAF2qV zp`m1^kA}bV)9_m#4X@RajXHLrj$eV~-~G7IOwkpGQx?9rfc7KY_K^aO(9>yWCcal( zJf9e!cQImBAET4k@X;qS;@UoD!%S#%j5UfC{|lZHRsvHzU;NFx(BJb%yvy9Hzvp^> zkbld7!vBJd|B4{|8S$8(evkZyeiX|)K)==Ki@%1f>-Je+!M4A)=JFLc&HEJAt#ixR zu60i1n*~lZODPM_2zq3ZT4gz7JJ3d0#o=NhG5aSQJ9e3i+_coi7;1dTS2(FYLGDSs z0nPA|({J6^B1D=E??V;|-x^Uy>_K)IS+*%}rmBK@Ga%ok{@>Hr6_EXF{N2)vJTs`{ z8h;Nc{4dJ*uMEOpdmRl8C9;mZ!%xGLzo8-Ji9?{F3M)iqOs4VbJsT0L>oaeSpkFvw z2%}k>Y~Bv-c3Hlu?LgOQM{Hm2wh7EcMojOfa{mafF6mgZoun;w^|dskhIhTc<(r0% zN46JHdlY?83G0iV*-7nwy>0)6sEOsUPgLN)#l3Rt^`%r2b_$~WZO*n4y#N5*u_*A+n8H-`0D++Pp)@B;eScS z|K%Y3uhI3NhYv&6Xn$M5zpx|9muvY@4_fV;%;KnW>L()NVLQ8t5!ZB{mR_!)`j
*<|K)Wpett6}X8teuIQ+Do`fuhJ5BR+5uVd(M>Y(qZ#QWuf-#pzl z3#c{Ui(X}0H|5g1U9vB8;&${2y0OBS+6+sPg8(I(yZoQXe=|7T)FfQ79Iovo~0Nw52xa zg&%E*`z5~9%iR86v7y9R54*FQ@ncBaa7I-4>R0r$5ihu@eGt%FzMkhAMtl_ffe54( zWK=y*_00GFUgtFQI%)g~BK`o)^M~#Mh5s)y{;vk%PvG-|Uxwm)wV&O;*Ij@J>$KOc z0|pO4drty&DOJA&4R7nFtv(Tx%BdD7;so^M)BZVcl_7s81 zL{2Zv172>YE6AS&*CFQks7Y8iLiIYb`-wBWL(xBczKe`4a0RY2;*+RLxQg$;|9wB8 zg=6nwf2>y1?&1*NEK3@X z2i>@ze*XW9VZao2l2=jyRe@-IZE#;AItqe@^wIVR;A z-E21b4qB!Z7(^oG5+i=t`Jda7zjxAhBgY9_A0_{@Cx?h(eh%Bv*PlzvI~nmQ`m}4d z{=e~L5b*+90V?TF|E7*?)86x?W=6bm(f>E|KiXydD}(TVus$8J*r;cOh?TvyZrD-C zwa19Lof8Ts%!n13j98ly?YoJ__!lyEo|!)`Z(P1w2o>J4Olsh4WAm8t9A?~y+DPkC z@>8*XC@UU8KWdE6vo}bid9m49*h1V{l88cg8yrL|NkPHVKuIjsO`91ipBL8eE%z?7#uH= zVyrO*m~~_yZaXvo9d|RvGE3>0W(Co8V2|~ux&eiMhm8NaApD=FG=Tja4w|gS@w?b| zWBV4{7+gcDYp!DW)yY#5!7Wlxfnup|~lnK`{d3N+IXwK0Hr1 z6jxUtlJZuwVwCh*n^H+L2(n^`bV!L&znnq4M~#DMtxob3jZrI z{(lX^UyU(xL~dJZ^Zl2P=~&+1h#j-RBj5q_daSVe=Q`E=-590K!Pr0g0Eo({E|$@r z#J`7`Adht!Db6Ni*-^=~k^BDpK8*3%nTP`| zkI&9D5%Ci*Z6AK`$`ER36qmj9>=Bna-%=1F#0YCF^POhQ>LW(MHMJntHeSfU)g+A9 zKGJmC^xLf|0^3?a>|_mzpPja6<}j=SS8gTcmAjfrz4Vfjyd%VL2*7|RcjQ?vv_$LC5yBvu^ zvh}cVSh!0_v=MQZcfEUp@SJ-H+HCLmMB5ca_Qd$#brDxf_hx{GVZIsKrF&Wa3%5xa zCrlWJzFi;9t3%sa+HTOcmbSZ>u$AJNw!5^=p>0Vj&S~4T-eIa6I>RU|wJhDC;6q`p zX}pQnxg}K=wUdr9n9M{BX`q>6OLJ@H4=Sj%z@js@x%5LdJhO%o5B5bDoSCl`m<>xU zQF+T7Vv&DfDM#%Qx1wQ;6&T{05%kp z(z<1sWygKMZuZ4{xQ7v^^f9lKF}#yqPiOseZ|aI!!$)L1v_Eb0S>$@vEf{VsE>`?b zm3`UJy?CaYDFFYa5DhXZ9&}lassXTV~ z*34%%P`qOujM&l3Y&bLj7)FdCm88-V+G;1u8@@zMjQD9UR%Polg&)yNNJ3kY*1(J) z#wpHB;e>D!{$c&lH!T|e=;3crTG2ezk0Tk8>}yfN8_-Vae4~)B4zk7<#0&BHaY8cq zBUE6O<*H z=Pl6f#5mVE5jo#3*(W02^!e3vR!}Q2RN(emy?!2v+WIq&5EFGT?bJSf4P~nJDP5wqV2Wm>^*8=m@VT-m7t-^i1Y9$u+@7 zBLK{DBwW`D3@H4e8!?9;0k*H84>ATGp=BMvJT(s?^ zwt&-pS{k$ZJ2%y%v|SIh8I>Oj{5uvtDiAyn&|AX zZ>}3F1~2tN=bMuDK$p|G8NQNV92;sKR*(dltxjZ&`Fd{0^F{)J#|CSvV`+oTRft{ZR(DLwIb_~kGqSLhd5`F9U1*w@=3Z%^>_kuj2bcBjyK49 zzI1Qk`Sh8=?_jDs=(8N+l}mR}PeoQYwFfiz1p0%S-3eFwgF}APA5?-%euAw@dxRAY zF$1gr@0Ia?D+qr^7jKL9wess5i0-cXD1SRod)pCtqe0zEUFY11LdaF?ihd*8hgang zd_rY2(Ed}KfGbe=R%q_KKn%2RLG4D$OJZFFW){MSC=Lcc#1-6^tQCf$7cqU`(F>&L zq(n+T#i(7mMRknvStJqN)FKi0<|gj3gf%54hGnCSHbyYohz@f&V=lRg?xLF*j5bEs z0vmungFcJ#Yc%>^l)vKZL%<`kbo@_OnyW5QTeVof%4C8RH|(dM{wG*-2m5a$esMtm zueZcCAeS>}LK-M;lwMTcXxpg-#WEc9KQV?kusTXP1{>{H({_~l4J&qh=@>fW;QVyq z@cc^4pu-gb%sg(v54w2T4g z$yWjre1BKE5NdVKM{i<7^W4=I(iD&JB|A}Jqhrd9?gwB^^#g6+DIW^(AuV0Ff4*fQ zlexy{M_M|MI1LVPBIQ^5=6-L{n6A)*;)Pn_%-p4xkh~ifeEhI}_%ky8ZwKK|y=4b6 zT5{E6w&A@Z%%AC`{c0-bS7jXZwJbb1e+_K#XnvKC!mP7mA(PI+M@Kz#6(!L#_Rl5h zv?fc*rUp9Ruf*}DhVr5+%OzKU{+Bv6)@C2Ft1ZhLWLy!=lgOSvtRJZlV5)##N^~R$ zD;F~3SI(1tHWYL8H?xMqhJPL_LE*vIgf~-f!EizLTYu77JYR?S|7S`VW2iGjpzGKF z<%%hY7RK3PZSw4qnv%@yw=AQ1?U4b6KP%(^P7waIPfU!hPGre@iCyRQD80mhYb22` zf!)2X>j(ICi*2dkiL%aPkhv!z`(@Y=)Wg^BUvbAu^s2^GtU%81G4HI}ks%<)#}1l@ zjfk7=Cwym!#nA2bWOt_s6_#?IT;671nxnIsFE`jpN}8~xHH7K&obq}-C%Vn`v?uZP zbv+5>4^Lq?_jziO(dQpdnq_qHiBpnxbrT}iBsoHS{S`~6*As_%XzML%exLXPa*vL( zg&2Q4Cg=W*;5ZW4YCwZWasI0R+JM3zznSX)njrisT>>=W);A$O&sU)Bf%q|qu|o78 zTd?Lw_t3FPiAybM$C{*6QywI%NlG@Qq2E{QB56C2NiSZr%8~XwiZvDh3`_j2NeDa8UJ^K@E?y+pYMgq{aco#Z@>J6$tXy03`8$Nvn{D#QvBwT?P;x$Pp>~oM* z^#`iWG-9X{qq`B(sSC<+EHcOuJzJ@+ip`J9Gk`nxdSk63wxW#8v+`YrEQL>pu71iaDIPFOnq;%2 z8)KGIZ!>+8J&D?qqw%b$>6*G`tSn725%D=G!Ww~mJqfm>(sEN)M=5s*`&mMkXwI5t zGn8bBTFy{J#FEaylVpD$d4cFmzmR76YS2gyu5;9Tlo@LatEVGGcq*<<^XHx^tsCka z8LHSpqZ2XJSjY6DTt|F>wFoax|6( z-@QMQW)13qoi|O1HRZpwYb&1ksCasfu(W=zwK$K_zimUTSd`GC4m&{{XKj%U{^@bZ zV4!8|=YBNjj()8lb7@T_8U z3SxcfxlQ;#?iDF~pVwnR%%5YYDqGxPG z;8t_%qw#+1T5#0{%2PDzSYkm3H6PO{=ez}X=MC21>qmoIM{lpz;&xV?_YUx)caSoPd9`ztuGDvJ;qs{ z!Mv|mozx>F&;3~8?r^>YtLeMGkKD?ngx*1tI|!ip|6hEkaJycrz?fSrY_}u;aW~Xm1Z$PREBJqrMWQxwOys zOM8f&UX4SaaG0o#(lqFP)~?iHSL4QrQSrIILD3 zZPqg>c0_XA2kB>ROo}p(&IL~_EzMQr(R$+jyg|s;uyAY&D=VP3X@woO(*2T#OSF~d zhNG>G`t475&rUQG#1$NnRoaQ?o z>(Z;(#*sJ<-Sd-@ZKUzy*4Ec3BOB?+@cj-NosftkJG@5BA=wb&T(e|@W4Li;Lv&uDxDk<~hI7b0gSh_tr0|KvFze~qCk|gA<3jV; z9r3xeoVs5*%|v*HO{`gq=fU+kGamb-pywvwxdRISFd6?XLHNsbUn^yq0+f$*u9Ym> z%|6=4^rI=IeT6j5RDquQ;R_-E3;hvIOuR<_+d%(6!JDkz^*}NaciW#V&=_Nc6z3vb z(-@y{-j_Vc`FKH$FGlM(_CF$asN7RHfPFx(mssZ)__Pglh)_^M#~8{Ev~w|M-CVl) z^4s=@eD^oHxb!2(piS;7LL5Lv+(Ah<2)Q4yPsKhQ`!wve*bgZD!)5$G48ng5=nw}w zn6Qt>eggK%*qgD}VV{kCD)xEUr(r)G`!U$h#NLGc-PljS-iG}o?B`*B8}={6xY z=mZ)c6gHnw1f9Fu$(@HExEUMSN6aVTM|k;OV$Lh)2tCGC-?iB+(VmTzkIjE$&82n2 zXDr*1hPUvJ=Qj6xCStyi$H~2Jc=i!NX$(Jh`aCC&9Ia1^ZC*;R z=g&P%+7*oDuCr6WA4xG2g}&F**R8^ekqfwPhtD2SK0RMxG~l&vrn%QMuZN^?o703| z&%r*72^;3&3~R{8w7JrRKF=GSH=`Hwa<_cf!XDIW3M)tx<`6o2be2HhYcikVFz_jO zqtrh6ZRnd!>XDCS9}@jNv$5HHze~z`1AagyAH}c6>Xre8f0T^>_8|P6n73K}5{&B{#P^ z7Y+NWHU!z2H@7L+yClWbEm(6)*WInLcwDt4AL|RlA?+Ex|8!HijOaG=jo`D=IkP^=;^hR5+=h1G>42_kkRADt4sZ{6RY*?}F(BA4asyX1BfTzihTo22zU#8!W2;
Q01$vUkfbqhs9=nV;fNT zYi0cDq{o2&k5Ys*^tx$Zp6YD{>7o(Wvl0rR-{TVUOuM4tYa@44Z9jPWko@#4s_TzR z<`J~#SJ**JGz(vqZ9n{Q0UIrHI(KDx2CViRcx+6vUoMY>=Z3oT>n|ob!T@5&IT0z(K7yyApCul zniimj?`+(4XZq{TqOYAHLtjuya6-^oZ2q-!(Lu+GpxVNNj=7*?;y)%0G&VKuwdpLy0x~B$aJuCcKYzSD4=?F-e%yhfzS1*5RU&;o|si-}>-yzR95$>^xRq zAtuLjf)*>XRQw>96JrL7W@h3x%-}*>U79Jxp$@aJhIUsPR+x(A5xl%-c|C8YSEj}1 zDtXbZ#Jh1q1m>SUDE!qD=}HnJ^a?rx=`aX7K1m4G)AtCM=PK@T?0gEwt8Z~)RTJKEQ_d(shjk`5F#P@J z|HR7p?+n79qD*JYP>e?jly0t^cvmK@Es#1quVVkG^ee8c#L-+_c@g_R;0o-!z^88M4vgpb^?H(} zNZ1dIAu^xPF^##z5Dx3%uM+fCsn_#aZ=WZ+i?&pnd=2b?!0k8UzMuTZ$@uTWj}5f{ z0XryQ2P{NeECR2`D6jbKfk}1hyl}+#kUX{?Qa@>LI%Jo{4Bts+$+H0Sgp;2nx?aya zyEO$N`I{X&V;Y3d|Td6)9)*h0W|z#YDI z98{OnO=0D1+FkPu-1Kl?#F1F|eM<3;hp;Jq-vQ&rilA>v!`&|t-6m|LO#?f@JC3C6 zyTE0X+gMu`?neCvu88il1a@HIKS;*EE(m|^uGfW^ZLbSf8#BJhw!ueZO%dy(lWA9k zupn9Mq;yQ?=U^t?2bQiT)>n3e?PXh$O;cq0gqBs56bqN#T#0s<^8yp|fUwfG%yOqq z({Mk$@6=m|5xXf&QKC(r!#AtGpq@sXCuzwI6d!DuAy84jwM`TL*agM^BVwX-N>VhR zy1*K+vNJbJ!-@A~>`PpVeMScQ5vKTT(yG-GG0H?*fpaTt$H>xLs{auef`8c;@olMn zrDX`8+eGIDSsVx2bR@M4b4|>znavlO@O9?Gi$n4Z=$72LpMLT`SjPXOApAe+mVO=H z^-`avd+`3Oi%gcPJF;zqC8Vi4Ue)F`*~NtN4Hom|!R74lGPCC-zFWJqTS9a;ZASJ* zE}L{m_WeC4r0KQ<(&o*ui^}r9=a?_EU7U&zG2yJG=XO^x=`+$r;lwa?>>3;q9v|>ZWJn!|@*M;Z?{F zdcnSo|0=Pj*3sQ3Ms{nX@xIxbZX#{WQTyM4J-ji8TyC<*^Y6B56y}TJ<_7mF{2Cf> z-eD&r@fM5;trvZdon1?RMI`bY_|p&nAu|5|9fW^@Yn6pPQUU7jwl7O8YULP42l=^a zlM}R>{+=6h!|A%XUtcpbU93paYBHO$xNu-V`9_ND9!zln-)O)$iY~Up&pWr-#aHZ< zcUIbE-YEy~_;B;#OS(0Fe8D@nEe5`en%GH`v%g6M=kR6j&)an2T$idNr7OHWIZM|S z?qRxA?S&WP?$CFIw++wAq;JqU9JzfXyA$XeObhAObgj%`yHuA6N@|*l;zPhWd52f# z@J*ZB*bsg8+pVEY!&UCdy~yN}fi?dxUdDfS5dIozH>Af+C3xJ;hj-_U0Scoay&>lJ zTQ%y9-Rz3OoX`1uKJmy9=Yx)&t&!}bt&CdT72b2%JpCfedd%RHQDmenQ#Zr94|A*d z3oY?{Z%bCrxx>3#*~pSs%@huVD)NCC0QC4q{q&Rn1R4K&{NRB7M`@<1 zQ(F~$tb^z&jg(j|vvfY^Sf5L?^z7}FZR`o4XXGxfjzOj%W!@}FVI&y;CE|mf><+Z> ztsL5ET32aZ#EgjP^OD}xl97M6gt)?Hgiq(h*E<7Ol&;df_ehG&^|{O~|8fV8F1yXe zL>JiZ#xZLJ4~-HIA>uHTcrdTkLel))iz$BR)70??*JKcn4EO z^j^;;f3_t;ZmlDu^PG1|ircWJ-1v5zLb1EyY&rjHPqB@$U2-SF@(gp-!19b1?umcT66Q)3^x1dE*I1%$ zr(DS>JBB#_$ z48LhW;h!Yqzb6R)Ne$s6$W6$kaALEC1N|~=pwC`L{Kl)#4;AA0*XwnN^-r|yM*EJsd$W=aE?S<>xBl3B#%&PhBn>$lX5^X-w&d&)Hbrx>@Qx+CAKTr79eJD9qM{_P;-$MLuZ>%soS!+uu)$sI6X)et=6~)K#jqxA)G=#dD zdZMP_&Ap!E-mK(y7ji>Ue^KFp!arHY|C1p6BltIV#PRES736qnNmxDBe)X=fzF|pn zJtZvoW0P8Wbjyk=C3|$!V~n`GZ_A1#HPdJ;X|0#J;HTbwjs<@_sg7)isEj1({- z2EK}i<}rpkMx=MTK5kWng*oS7e2+fQ3y%<0SmS*BQwT^kJp3jd)p{$Ty9 z?LVairDM8rkW*cCH&18fg@)^SvJIN_$A|Nb?mci7gW3}?Z!t7n$7{hurYRxmToW;V=2WgZh>{FE z%8WsDb6ZGdIzQN|pkvK9@TXt4>0@0JyFR8z0SY!6u< z?Wb9YOf&J`?z7O%AHpX57Te3%CSkK+dt*39zDGOrI~?D1!JB)}C9Rd*6v-#>Mt)C& zvW;X7#W?>>hOp9z>QjgmxrR50I?X2yDbUut+xRG@b9Y-#6mc=PuzJ$W>A5XTB@4WA zP|qxWJlcj2dUvh8gV zOcRUK6>Z)LkrMO3IKJ(qY23CpR;iGfL@Y&+MvKc7*e%B%6IOKb%)WYc%vYC9-iQc;U-# zVhF7?2+B%2H)Nd@zeCm#T$_f)91-0SL?1YGAqI1VVpfb6NtU|uJ1O3-`Ik2IE$gWZ zDyC2zQ26U){PzXPzjr(xfBS`{15q?hxCBKBm;!1Dj=W&HOC;eQzR9Ft)vdP6c`<<09( z8ISdDRaI{Kr!F9bY<>0aJ#CLf#kn8Wvi;!J<525cEaI)E67A$!<3peH4)aSeAk8H>1yRzfyhFP-1~kHjUq% z%b3Qv=HY1%N0~1-+aa|KO zI>Sa^yzmU_WosT&R@StJaC34pPRiJ40{i3YNk>Dgl+Xf465nZMLN?@VYS_Tj96uB3 z-5UShq4bXGM0$T#&Jxcv+vPXAA%XY*sDAhxWc&{X;V(6sT)02mH5YC|_C#pDwQPZ$Bu|`NK32zv2@!V5n zM5X0WLv`ZM@nmG;ggQ$i{JNTEih1B}4jJj>*zL^3&)q-9-=A#Kl}lM9B^#MUv=vg8 zmd*GAh^Jh=qs7VG(gY1p`yt`{8h+G&g>NVuYlnw{zLome+_9kp%l|t<#{aWm{Kvvt zv(Lu=8oQ#+qFN?dN~bix-&V{GGX8pu**H@&h=0a?Yp_N9X8U*7-WbV|{V2Bt`#|{y z|1rHDxb_mRg$dL<5Q+@rzUP{d7r1!@R)OBEB5evTv{5O9*~m@Y@tX{fS*ZQ_hrCcj zLh~Te97Vs0Z@8)U7k8L2LWm!#v8Ab)#-Re+T%zi39J>7OyvN6eH)sr@27>6+S=vX0 zzaxh6JIFJq7Zr@&7Ew=bp5YwK*A1-kKhT`^|2_}GzrBs?j{f}@52_^Q&tv&LmI%J1 zNn;E{8-H4@X*84+!Jhu1!DPVqw_!%WEo+lfioQed%gS@G_06!rf9hjQ(|xij_Z%nY zA?ItUL5LKFtL~K)b0TeVjZN^iWr;e@U>jO*5YXetk=C#S_Md#U%#cR!GM#b%L6z6A zwYJ4QnBN0zM+&x*p+h5V6IEDk*cfkPn->A!c=-DaMT7Z|Q6h0@sBM@qS0H-ohu+w! zaoCe=wqn6hMDxdInKro%CF7wH%)ApCXbUt@wL11F@>KgRz#CZo_wWCYlJWl{2>*AX zF|X058aaE<2prnSEtbnCTiuw?*_NQX0()%^Y_o;fCe^8C5Q749KaI9N&x?Io$*jvL za1MiQ(%uPJ_sjXbw@oHHO}- zaLFZ?dY9Kv!W`95)Xum*6#n53!I7rnlJK=#E)kB^?B6)ihTMu(p;vuZ0}B5%8UHVX z@Tb1J@m54j5mad9M>w{W#MaXu{4d^{LBA-9(~4c4;kpF%n4_mu(MLlt;$sobTunJ` zjeplX!cXs3cdDP>E$-Rsn8u<7(~vtPo7-Svoz!!GMIwgc;+ho(F%|dX7%^WAz&}gW z;M`DRt*=?Zb?6rFyh4_6PCDAeh)+u!eb3e+E(x+i7;0?AC37q_MTiztuNCd&V~i!2 zt7kV9gOfVkMCSpnbPW1K{HAZQ(ch-2Q|TCSWDnvCir;tMbiq@|m4svbNX_rNTyAG> z8&LR0l!6n7?~%ex$n#pQ$b7?+$lrYAwjvt8>2qYBPd&lhk_JCM z37?H;!PnPZS^J^yDY0FDX+O|9EU3o)Ify_+Yn*-_HKyw5??|ba>kLJmCSHzb9wR6+ zN&2@g=C&`~^0A0xXt*2r)6f1-m+}8P2!EnOZycY1ul4trvaBWM08$!=F-rVab3 zf)806Re5{8R@d$MTkpOL%ssZbO510);`s@}osRp30vla_u?kt17_n4B9(F_w$Q)MR zV1U1st0V@xR__!%?f-541bG;#S2p8f2$$rFs;S{!Tpsy&v=$RgrXFX*d_>$h1) zG;gz#N==5oD%M8U54!3-+=Q!KM!WlspV{X~%AJ>nU@-ZWpF^Kx#VpCr+Z<68^{P|1cz@n*y-xwF@Jt;#i>~;l`2LzFOcPmq z40Es=%*>(&UVQ>%|4hUQKX-7UaKb<0;8Mti>Jl!Q^$j8~7#^|y^c)W@V?+QEhiSAB zcxa0PI@fH}Qum6DBKufN+WlePXa(!}KvDZO`PtoVwhcw%=(`SnQ?SkZ&9ZF|J4ay- zC!9HTS%cE4xCvRssJ+o@#mMB@B(2y5>v3k@S8=H*!`<{;B}Nkt^t@r1M-hQ>ECrK# zN8vwC#{WbJ{tV{qDPQP_Ju{M|C~Gy(L9?4ok|}nvDPhn24(Bwr(61cSI?!yaEPM5- zlevfgQnG#2wm;`~t^aNDK+~yQEbra$B=oJvKo5Zk@#n_PQxGqXTY$e@5`N}p(jO_A zOMd2NNA7cXpocl3 zcA+0{edPam8UMe9;Qw5qES+;Cjxt#%{JMjbf7Gx3hh4IyPQCFG)a^(OhrduZWgv1mc4gtl zqrRwUa`nd>tE3iy*7PuYu#S^d+m+8`w4zXI`SCWbUG#~JxAZ2ndlEbh zXa+$q%5_7Qr=AY7i`LZ~sh2kM zrgjJ8P3!7y|1WfC?Yc~g1HE1@6J3bIY;n=@lr81;afh7Ow@A-}FCf;w%aGgl$bod= z8y7)KTUFQiLi&`TCSsMeisNpIKjSrb!6)!8ZEf#+Xl@R`dw4o~-{UtO1A5+r=1$)O zS_3=Ml^{KX@ow#4?=1Ttos7RT1plDU_Azi+?V^|rlJHp%-UQF>!nxeGlmpsbD~4%n z2V*2qm+E)6pa#uoRTd(au7u1V-9dSewgBzHh&)0PL4!c8xm2c*T{M4L-lX1OU}s>1 zTzIBaE(!iy$Z32!730nBKnYqwb~C@-pYVGFeVa)xlryQ^$YrXs`!7d(bIgOCLL4lD zqOn$a4s?q#@I{WzsAaPQ^Ah+!wZw@Uv{ROT2slre?Qgvt9|EA0MyF&2K8KZHL zx;psjP}h;2OosXyU2=F;{5mEhzUr55+KMvXeVud`Ugmiu%7Wc_!mX(zV~F?9HYMix z$kjJ&G1BjsY>F$HM%C_ofvaPZ;!RjXY~o-izO`G89#=#Q2br&F*=OMDUUQ@huXz-j zuj5a}bG0gaSA#}spMPf~;|H|lz|xEAhp{*3V(o@nI?vFtjwV)kvCNW)xE6Fbb(rBEkR3PdY+`r5yF${`G32iK`jjApx2GQ`Ie12 z=o89kDsND23}xf$uWd>@i)U}Q&1#Lcf8d*_Scq2oC&N_s!v=>#Wmi3aB|g&rj>8_e zJ0TLig(D7f4@qrwpbROY*`?$Q`EJ#2&2RIurbty+tEDsE{TKc3SpShJ<9{jyfAs5WX^q*?R(*isA4UJ@x|_APxgU4N35mLY z0|to4d68l>sRe6trN|DEu5@7`EUPKDQ8yUaj#Jbx(^jJWy|>W++f^wl!e|ej`UxQ3 zFS|%uZrj`YrE=svlCN;;rSx-MInutlYwsm;&m`efw{|yeRVE2_U()tN0}D~^AT2Yr zU#Nss7$aT30MbN-_gdgw58n{PyRqxOayCOLJVVqzEu+=lY`@vbB#)M^&Fv<@8Y`9T z3r*@;)~>)<@)1E*s}>l$R9gFS0q9fzC&>7p4#8jH3rr5Q*K{fbT_(Fj4GPx&S%h zHJ~&xcJ^Yc>%97t=A6{?uACH_4{f)Z$GMOK{nL71O ztXi6~%`gUSLr~64?mCjciE4lF2N2HE(x-M2uMVE9`Z4@{$A7Y9{F_7Yr}co=57d0` zDAY%Aq(?R3@-iWWwKZ;Tke794bn*@)W+KbWghHYChdJRwUF>0;w!0AH7q)=XrSV>aZ ziv*s_yc;hqC*wOXe-ztho12EnVHwVnRrOmRLhrE5dPm_uQO5sF2>zIJT@lfcvhr9w z#!`e!%afLm5)Kv^6YICCT%)Z+M~^)_=KjCtol%c!Cds8G=eXqZHQP&Qi}7Mh((+f98-@EY=6n!-YE&14chVWi zU%Az$*E~dnRYeX4u7&HN zRC81m_S>zG{GTM_{||g|Q2*PBwOxBw!Q)29D0p=Vv_BXqt2nP#3azK>x7w90(z(cv zb8cnNJnui5(0PiCEP&dnudBj?fpC+HCCr`bi{MVm6Y zgxVa_cVS2%fLPE*m9Rx1zUkZ@g@2BW|G5zS$-Sp9GtV7G>#S@ZVI^bRUD@!C;@`Y) zE0d}|*VqxIV=@)a(HQAFR-iUovmj>)ftUZ|rC94Ssu90~U86MJ)0V;VZgik3M0?(d=Y~Nbb zxJym#P}I$wuK+e;DP|_6%uM}$GW(VT*N+2arxNc1-?0AaN2w&QQ+|6o#j8*ly)4?2 z&)t!QhfC|X@+C&E4Zn%K%*@z%^TLL=@rGFK=gqn?s)1Ue&^s75h>Y?{kx@O-S#Yhs^Qmi3b{1UU+xgV>Umg9%<$agt%X-ypMuVK^ zW|2`0Z1BU%7m+z>#Hev9N0y+-R%Z{!7@pe2=mulHk9E-fv0O%n9Hh8X%ydK&bRbr# zB+mowxjn~KjlyzHh!m#5PNB2iK$j`Bm%YhO*@stn>UM$&sTpih%NZ z_0VSs^+hXvbU*#q2mi@3{ul7QLHWNkP|^Ti{V1w6DVf6vT6g;n%*lF7EV)Q5HRW(t)JgQuc_2pQj ziUSGp$pe2-gQtIWk?MU3&U))%L+nMf z6?Q@Cf%abolF`eDCt-&6^r_F{h(Ho7%h8_*j1@S~lL}_y2mV2}d(dK0tzV%{;7%PS zTue%gcS8~9Agm@c##=>?7!F5yII{IqUO^ z8UL0L{2#igGE2VFe{F=V-9`5y*zx@VwQmG^bc3R{N>+G3ffYA=upiuaXgJnXhIc6r zqm~vTrMS$5qnY7d5g#f&1M{hkpVIhf{tU??Z}7~|&N6nrUvW%fKkR3Ba2eF9gLg() zk+b$!H0SVlk;i*}_F!0-vhfWQy+7PI8+R`Py@zuN+ORIgJcTFTxGW#mhWB4O%j_zg z!=>+b!!mFxN!{aOroD)@D}Li(A=ay4=^TaHnKYBRkEG1^C&PR6dpFg>TQOPA)ythTx23GXjtxx@*CgcAJzBnlV&-yiaGmqw7c?2`{0UBum_Iet^ z3DjdJ3G=AKn{(iOgPzj`=;#nVdhBL_uqr0P$y>9JCZpF#(~<&w$uUG-<%BOV(nmE& z;%J5a2kJD|-psJ3APRVCT)kC|bvQ+0X*|Z>QIm5oQ2CvNc(F=oe)9v zoFb&glM<{m=TiP!9NwVuu_|U-wlLmI`?(1>Wk0q37JPhIAN+G={Qnt(Ka;+Y{K0MT zbJ0xZ`))3W@>1{T(q7C*xM#Pnk%hH%Y(kU^=qLuID?E=A#`8D>8{miG-)YufgTkpi z#U#fFx~9#BtEW1#>Nk+lPHSY57V`oFFw%M#xP2j@9Hw#6UPPe%jcx|I1eb*}^6Qr! zlZAVcy59PVBT=9>dV%)3?rG&8mW(V{qdWlrFg!U*jdB4wuMP7&p}ZoHdmn^+K%4=` z@XpQtyE?bGCurfVPV<2$!KmYQMN3XChj#$q`?^1Zg)Jw1gju(&Ka%lG?I@>J zAkPQd&vcWW#OE>cxMvl7~+P}j+JXQ{Io=u89S2FT&ABiguv~TD><}t+l z(>;82HpY4)1@7FC6v+>Hm(g5|th3#7}C}|&K zh@fny*TV)WnRu;!x)LQShF)L4ky;W-5?oKbcOB`?d4ZpfT@QAYSm<>qFSs_&LGzZM zJn#s?8YcBDx`Jr{+L1d7e}jzwXCe3_4lnwAQ5~U(QM^Lec_D_|ZHUU}Z^yjjMraN) z=C|kJzwL@(9zh)Fdl2vSKG$qI$Q)%}H#8JB3|tpc61y&D7*-bZ7!fLnK{SF&FGKw9 zP(0;)&iBb@MnhoC6OL^t(cx8e-rxn~f~YZfmi#x$_< z+29R!qo`195(&ZR4io%6aoiS%u4#am6cvd~Iz|K&XNm*TS!bTX?9nrbz=m{1=1g&5 zChMGQDDxN<^vT5gs_kVT!!<+Si@d;gM%_s6R9>;g>3xJzK-06u89S9%AJj*+?)CA? zC|t#iLHdnRj+tIoOV1sPo8$TX5yngM)$mS7qAvP~_U9f#Dm)C+aLqP6;Z(ylGW?FJ z|0Ws#FGBFwo|>UqEb2&+I7Q2W-$kNnZtOK%w9Q**d)G&bG>*k$v9{Pph~C4^(Thq( z*R)uism;^t!AEAwCXJo+;|n^2$}W12*qI^&uY(WGc+x*``5nj z)3Qvb)|=GH`n0V`Vb40?Us?;#(mr^2zH!l^7q!feyf5Nkaxi$>Xrr#FQslVdQxeZ> zCq!L@Hpm@Ej(jKQ#XVQ^LbI=+++Syy*l}=jU;XhTNdi~R)B6^sE zBoUq>KYx+Zl}BdiM>+J68oH)I*KFJr2XoCfKnJg(BtPGKQ?GBUl00kany9>pm-3;{ zNW_>9D-?_H-t3qwDza$K`ZlcG#ysE-sr-Y>sy8-Kgs|sie=b+D}&+5PE ze@FjMknz71fJrcu^bYP-F!6tmh(2y~mSI#SI?5;}N^}W}X;@8jG55YPtm75zh!{XSTJjOcV#q zAL>XH2QGM4)J8uCBHmB@V@+sJR7v8@IVs}Id3ckoIH}y|QGcP?4a|1JKl$J2dw$x* zeyQ>jLu;4fOZ--S+NJo>izrcXj@e!&>SbSmdk5=^mt4zR&7E8<&W>887d$GJLHu*l z9ff~^j6a>i3y%Nj#RYSU#1HvA@h8Pa;@`%kO=v`W3m&8cdl*Z_ejtgODe&o;<6G5Qk+T{}SZRglnx#uFCRUd4=YQD-B7wI>vLV3X=P}!J}e+A{wL6qKK!eXdaT3$9){`Q&LGE zyidA^>Ib)9&(mjInJuzWc+OSK{ak^inu4|p^sVkF{HM$K|0@K4@Zky%z7y~}ly9`P zjE22E5%SRTGt7WC+i;D8nbPjmiz?t20GJA+au{aVLVHU0ZCZ5lQ{xf9!FNfey?Y^o0jhK%M z@(~r;D8`nd^-Rte2Mo>^V=P4?xhD!(QBTg#8%(}#j)N3sPcGCHi5cuW@fO%$%g04+ zwirYK9QzI;KCJO5qLLl&#IF$$gN5{5`@f|x`kwR`zbE}7Ss<#S;+#dI5^pwSO_8V? zQY3z$Fp6_)ip2NP{v;+IbJ21d;nIsl(m+tcX1?R5Y0yoLgzuGZxz`WuZ}cd%cNG5j z%lK2JHz@x(2k_E{>iAVnz;e3}&8a z$^(v_D91YtV;yJjsuVx3%7X;zzgr*uzfi^>o#0#eGo-2@$V*A;PEorkPbo*wP^_k$ za>A#61jY#*kE1_Ois)K*3uOWU7EEKH{r6a>Kixt3%QVgMYrYP&w*_dFM#4YrM{FjC zoF)b)^hs+CJliMjZ{Lx2{I+{*lQ$q@W}zqm2K;4 z4tq-H#-1w@|CD0HNQY4@o(G+_A8&o|pDE-2RS5p1C%{oXOK5 zwmZoSrV|HS_yBx+(9yH10y=*8ANx(~pFAG;AG^Lc|C{KK_!~j*YTn%qtAx zYIDu%@-n_+u8@_%3+A%bmDTI{xt1F2E&SRHK0TYi-(10G=rSho&snP+nWgSW*ruU0GSSf}g^#Tv{`3TG`TNv(!l%iWk{q=r68q zo3moY1Li}sraYo7<~JYt+Eg3u{a5{&Gru@&{vQY5Ut&Lf^3;>-J`3NIc%_MkBaya_ zT9!mU%aZx!73&wwGw|~))#c`p8fvz)g=@0yLu&I6u3x zdPzA7wImX}*fWKB&eN(Ujz=p4ev#VASk zJDLfvhwUlY-o0n-mcj2>kSUXh^naGLoZXuL(aaZ5T6XPTvhBA7o`Via&nAm$CW{|g z0&9Qr;43US0qOwxUS&z+YxMO9`Q;&C40;QsKg^OfZ_DXZ-(bls(8Hh^`%o_4lG7jC z&yp69@&HS+4zeT%M7MG8vScghb_fJT5ug6;v`3mOF)4H^TYj+@4Ur~`-bpfu3@Rn>E_qkDed+A`@| zjOLXqOU-2~XnG`G9IaOs8OtwSQ&G0Myt3jxn%-ZxKKNt(3uVd`d~mS-^8}UJQcZcm zCy%U2hSFEQ(z4_}ekpcR%2#bPaxW{2vS(!s)pbmNbkjpq95owSiUzNd;h=t8=r$rx+K~t4 zecrF-{gw~p{c^vww>>^yPp~;-%cT9||M-oxx12aZ_x$2LtO5Ift(`uJ?q7N~eiin4 zU%se&3Hu$xj=y^b`w914TcI_Q9-PRYvrqhZ!dfHw%j{*V{u*rs8iuJM%?+q3N0CS*pK#ZKmt@fBF$SuF>@Nu5;^+>qHZkUsUEi1~QW3qIokO zpz?wbZbFCf4%R}|Bm|L|05ay>-f|l{yE?gm5p?ZfkxN%bHYDP`w9Qa zTY%=b!>P!|xFOXa=+E2MkJE(z#Lf5vdHvA&AGrPhiPL@X|FMieUGx~l|NB1Vhxqef zef~0RS${|ES+QM*UegAmG2efPsC??(zVGY%M|vOpACU2ff&4A}8KR$OoH66y`QRTq f50$bMZ3d_rZN}7H*niHF0r>s@xBprWQ2hTFz}`kt literal 0 HcmV?d00001 From ca45888f3e729f7681f09dac27816f00fbdcb23b Mon Sep 17 00:00:00 2001 From: Artem Date: Tue, 30 Jan 2024 14:06:47 +0100 Subject: [PATCH 145/472] feat(variants): Add support for TXCO on TLORA_V2_1_6 devices (#3124) * feat(variants): Add support for TXCO on TLORA_V2_1_6 devices * chore: remove long comment * feat(variants): Add tlora-v2-1-1_6-tcxo to build matrix * feat(variants): Use RADIOLIB_NC as DIO1 pin for tlora_v2_1_16 with TXCO * Use generic naming scheme, add variant to build envs --------- Co-authored-by: Ben Meadors Co-authored-by: code8buster <20384924+code8buster@users.noreply.github.com> --- .github/workflows/main_matrix.yml | 1 + platformio.ini | 1 + src/main.cpp | 5 +++++ variants/tlora_v2_1_16/variant.h | 8 ++++++++ variants/tlora_v2_1_16_tcxo/platformio.ini | 9 +++++++++ 5 files changed, 24 insertions(+) create mode 100644 variants/tlora_v2_1_16_tcxo/platformio.ini diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 76f9841e9..af40d95b6 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -64,6 +64,7 @@ jobs: - board: tlora-v1 - board: tlora_v1_3 - board: tlora-v2-1-1_6 + - board: tlora-v2-1-1_6-tcxo - board: tlora-v2-1-1_8 - board: tbeam - board: heltec-ht62-esp32c3-sx1262 diff --git a/platformio.ini b/platformio.ini index fbd1d6a74..51106cdac 100644 --- a/platformio.ini +++ b/platformio.ini @@ -15,6 +15,7 @@ default_envs = tbeam ;default_envs = tlora_v1_3 ;default_envs = tlora-v2 ;default_envs = tlora-v2-1-1_6 +;default_envs = tlora-v2-1-1_6-tcxo ;default_envs = tlora-t3s3-v1 ;default_envs = lora-relay-v1 # nrf board ;default_envs = t-echo diff --git a/src/main.cpp b/src/main.cpp index 84419c70c..f853dc0ec 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -248,6 +248,11 @@ void setup() digitalWrite(PIN_EINK_PWR_ON, HIGH); #endif +#if defined(LORA_TCXO_GPIO) + pinMode(LORA_TCXO_GPIO, OUTPUT); + digitalWrite(LORA_TCXO_GPIO, HIGH); +#endif + #ifdef ST7735_BL_V03 // Heltec Wireless Tracker PCB Change Detect/Hack rtc_clk_32k_enable(true); diff --git a/variants/tlora_v2_1_16/variant.h b/variants/tlora_v2_1_16/variant.h index b8c43e557..8bb5ce3b1 100644 --- a/variants/tlora_v2_1_16/variant.h +++ b/variants/tlora_v2_1_16/variant.h @@ -16,5 +16,13 @@ #define USE_RF95 #define LORA_DIO0 26 // a No connect on the SX1262 module #define LORA_RESET 23 + +// In the T3 V1.6.1 TXCO version, GPIO 33 is connected to Radio’s +// internal temperature-compensated crystal oscillator enable +#ifdef LORA_TCXO_GPIO +#define LORA_DIO1 RADIOLIB_NC // no-connect on sx127x module +#else #define LORA_DIO1 33 // https://www.thethingsnetwork.org/forum/t/big-esp32-sx127x-topic-part-3/18436 +#endif + #define LORA_DIO2 32 // Not really used \ No newline at end of file diff --git a/variants/tlora_v2_1_16_tcxo/platformio.ini b/variants/tlora_v2_1_16_tcxo/platformio.ini new file mode 100644 index 000000000..e54c1a920 --- /dev/null +++ b/variants/tlora_v2_1_16_tcxo/platformio.ini @@ -0,0 +1,9 @@ +[env:tlora-v2-1-1_6-tcxo] +extends = esp32_base +board = ttgo-lora32-v21 +build_flags = + ${esp32_base.build_flags} + -D TLORA_V2_1_16 + -I variants/tlora_v2_1_16 + -D GPS_POWER_TOGGLE ; comment this line to disable triple press function on the user button to turn off gps entirely. + -D LORA_TCXO_GPIO=33 \ No newline at end of file From 9586c68c657e1d4020d54e47cdb7837a201b1366 Mon Sep 17 00:00:00 2001 From: Ken McGuire Date: Tue, 30 Jan 2024 16:38:31 -0700 Subject: [PATCH 146/472] GPS updates (#3142) * Portduino multiple logging levels * Fixes based on GPSFan work * Fix derped logic * Correct size field for AID message * Reformat to add comments, beginning of GPS rework * Update PM2 message for Neo-6 * Correct ECO mode logic as ECO mode is only for Neo-6 * Cleanup ubx.h add a few more comments --------- Co-authored-by: Jonathan Bennett Co-authored-by: Ben Meadors --- bin/config-dist.yaml | 2 +- src/RedirectablePrint.cpp | 8 +- src/gps/GPS.cpp | 70 ++++---- src/gps/GPS.h | 3 +- src/gps/ubx.h | 204 ++++++++++++++--------- src/platform/portduino/PortduinoGlue.cpp | 10 +- src/platform/portduino/PortduinoGlue.h | 3 +- 7 files changed, 177 insertions(+), 123 deletions(-) diff --git a/bin/config-dist.yaml b/bin/config-dist.yaml index e7e8ae2e4..c48b0bf38 100644 --- a/bin/config-dist.yaml +++ b/bin/config-dist.yaml @@ -104,4 +104,4 @@ Input: ### Logging: -# DebugMode: true + LogLevel: info # debug, info, warn, error diff --git a/src/RedirectablePrint.cpp b/src/RedirectablePrint.cpp index 65aead7cc..d3f39c377 100644 --- a/src/RedirectablePrint.cpp +++ b/src/RedirectablePrint.cpp @@ -73,10 +73,14 @@ size_t RedirectablePrint::vprintf(const char *format, va_list arg) size_t RedirectablePrint::log(const char *logLevel, const char *format, ...) { #ifdef ARCH_PORTDUINO - if (!settingsMap[debugmode] && strcmp(logLevel, "DEBUG") == 0) + if (settingsMap[logoutputlevel] < level_debug && strcmp(logLevel, MESHTASTIC_LOG_LEVEL_DEBUG) == 0) + return 0; + else if (settingsMap[logoutputlevel] < level_info && strcmp(logLevel, MESHTASTIC_LOG_LEVEL_INFO) == 0) + return 0; + else if (settingsMap[logoutputlevel] < level_warn && strcmp(logLevel, MESHTASTIC_LOG_LEVEL_WARN) == 0) return 0; #endif - if (moduleConfig.serial.override_console_serial_port && strcmp(logLevel, "DEBUG") == 0) { + if (moduleConfig.serial.override_console_serial_port && strcmp(logLevel, MESHTASTIC_LOG_LEVEL_DEBUG) == 0) { return 0; } size_t r = 0; diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index ff5b2e7b1..592fc69cf 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -251,17 +251,9 @@ int GPS::getACK(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t bool GPS::setup() { int msglen = 0; - bool isProblematicGPS = false; if (!didSerialInit) { #if !defined(GPS_UC6580) -#ifdef HAS_PMU - // The T-Beam 1.2 has issues with the GPS - if (HW_VENDOR == meshtastic_HardwareModel_TBEAM && PMU->getChipModel() == XPOWERS_AXP2101) { - gnssModel = GNSS_MODEL_UBLOX; - isProblematicGPS = true; - } -#endif #if defined(RAK4630) && defined(PIN_3V3_EN) // If we are using the RAK4630 and we have no other peripherals on the I2C bus or module interest in 3V3_S, @@ -380,7 +372,7 @@ bool GPS::setup() LOG_WARN("Unable to set GPS update rate.\n"); } - msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_GGL), _message_GGL); + msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_GLL), _message_GLL); _serial_gps->write(UBXscratch, msglen); if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to disable NMEA GGL.\n"); @@ -416,6 +408,12 @@ bool GPS::setup() LOG_WARN("Unable to enable NMEA GGA.\n"); } + msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_AID), _message_AID); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to disable UBX-AID.\n"); + } + if (uBloxProtocolVersion >= 18) { msglen = makeUBXPacket(0x06, 0x86, sizeof(_message_PMS), _message_PMS); _serial_gps->write(UBXscratch, msglen); @@ -423,36 +421,31 @@ bool GPS::setup() LOG_WARN("Unable to enable powersaving for GPS.\n"); } } else { - if (!(isProblematicGPS)) { - if (strncmp(info.hwVersion, "00040007", 8) == 0) { // This PSM mode has only been tested on this hardware - msglen = makeUBXPacket(0x06, 0x11, 0x2, _message_CFG_RXM_PSM); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x11, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to enable powersaving mode for GPS.\n"); - } - msglen = makeUBXPacket(0x06, 0x3B, 44, _message_CFG_PM2); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x3B, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to enable powersaving details for GPS.\n"); - } - } else { - msglen = makeUBXPacket(0x06, 0x11, 0x2, _message_CFG_RXM_ECO); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x11, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to enable powersaving ECO mode for GPS.\n"); - } + if (strncmp(info.hwVersion, "00040007", 8) == 0) { // This PSM mode is only for Neo-6 + msglen = makeUBXPacket(0x06, 0x11, 0x2, _message_CFG_RXM_ECO); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x11, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable powersaving ECO mode for Neo-6.\n"); + } + msglen = makeUBXPacket(0x06, 0x3B, 44, _message_CFG_PM2); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x3B, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable powersaving details for GPS.\n"); + } + } else { + msglen = makeUBXPacket(0x06, 0x11, 0x2, _message_CFG_RXM_PSM); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x11, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable powersaving mode for GPS.\n"); } } } - // The T-beam 1.2 has issues. - if (!(isProblematicGPS)) { - msglen = makeUBXPacket(0x06, 0x09, sizeof(_message_SAVE), _message_SAVE); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x09, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to save GNSS module configuration.\n"); - } else { - LOG_INFO("GNSS module configuration saved!\n"); - } + msglen = makeUBXPacket(0x06, 0x09, sizeof(_message_SAVE), _message_SAVE); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x09, 2000) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to save GNSS module configuration.\n"); + } else { + LOG_INFO("GNSS module configuration saved!\n"); } } didSerialInit = true; @@ -682,7 +675,8 @@ int32_t GPS::runOnce() // At least one GPS has a bad habit of losing its mind from time to time if (rebootsSeen > 2) { rebootsSeen = 0; - gps->factoryReset(); + LOG_DEBUG("Would normally factoryReset()\n"); + // gps->factoryReset(); } // If we are overdue for an update, turn on the GPS and at least publish the current status @@ -1286,4 +1280,4 @@ int32_t GPS::disable() setAwake(false); return INT32_MAX; -} +} \ No newline at end of file diff --git a/src/gps/GPS.h b/src/gps/GPS.h index d05bad950..80894dd51 100644 --- a/src/gps/GPS.h +++ b/src/gps/GPS.h @@ -103,11 +103,12 @@ class GPS : private concurrency::OSThread static const uint8_t _message_JAM[]; static const uint8_t _message_NAVX5[]; static const uint8_t _message_1HZ[]; - static const uint8_t _message_GGL[]; + static const uint8_t _message_GLL[]; static const uint8_t _message_GSA[]; static const uint8_t _message_GSV[]; static const uint8_t _message_VTG[]; static const uint8_t _message_RMC[]; + static const uint8_t _message_AID[]; static const uint8_t _message_GGA[]; static const uint8_t _message_PMS[]; static const uint8_t _message_SAVE[]; diff --git a/src/gps/ubx.h b/src/gps/ubx.h index bc839c41e..63558b536 100644 --- a/src/gps/ubx.h +++ b/src/gps/ubx.h @@ -10,24 +10,32 @@ const uint8_t GPS::_message_CFG_RXM_PSM[] PROGMEM = { 0x01 // Power save mode }; +// only for Neo-6 const uint8_t GPS::_message_CFG_RXM_ECO[] PROGMEM = { 0x08, // Reserved 0x04 // eco mode }; const uint8_t GPS::_message_CFG_PM2[] PROGMEM = { - 0x01, 0x06, 0x00, 0x00, // version, Reserved - 0x0E, 0x81, 0x43, 0x01, // flags + 0x01, // version + 0x00, // Reserved 1, set to 0x06 by u-Center + 0x00, // Reserved 2 + 0x00, // Reserved 1 + 0x00, 0x11, 0x03, 0x00, // flags-> cyclic mode, wait for normal fix ok, do not wake to update RTC or EPH, doNotEnterOff, + // LimitPeakCurrent 0xE8, 0x03, 0x00, 0x00, // update period 1000 ms 0x10, 0x27, 0x00, 0x00, // search period 10s - 0x00, 0x00, 0x00, 0x00, // Grod offset 0 + 0x00, 0x00, 0x00, 0x00, // Grid offset 0 0x01, 0x00, // onTime 1 second 0x00, 0x00, // min search time 0 - 0x2C, 0x01, // reserved - 0x00, 0x00, 0x4F, 0xC1, // reserved - 0x03, 0x00, 0x87, 0x02, // reserved - 0x00, 0x00, 0xFF, 0x00, // reserved - 0x01, 0x00, 0xD6, 0x4D // reserved + 0x00, 0x00, // 0x2C, 0x01, // reserved 4 + 0x00, 0x00, // 0x00, 0x00, // reserved 5 + 0x00, 0x00, 0x00, 0x00, // 0x4F, 0xC1, 0x03, 0x00, // reserved 6 + 0x00, 0x00, 0x00, 0x00, // 0x87, 0x02, 0x00, 0x00, // reserved 7 + 0x00, // 0xFF, // reserved 8 + 0x00, // 0x00, // reserved 9 + 0x00, 0x00, // 0x00, 0x00, // reserved 10 + 0x00, 0x00, 0x00, 0x00 // 0x64, 0x40, 0x01, 0x00 // reserved 11 }; const uint8_t GPS::_message_GNSS_7[] = { @@ -56,52 +64,59 @@ const uint8_t GPS::_message_GNSS[] = { 0x01, 0x01, 0x03, 0x00, 0x01, 0x00, 0x01, 0x01, // SBAS 0x06, 0x08, 0x0e, 0x00, 0x01, 0x00, 0x01, 0x01 // GLONASS }; +// Enable jamming/interference monitor -// Enable interference resistance, because we are using LoRa, WiFi and Bluetooth on same board, -// and we need to reduce interference from them +// For Neo-6 const uint8_t GPS::_message_JAM[] = { - // bbThreshold (Broadband jamming detection threshold) is set to 0x3F (63 in decimal) - // cwThreshold (CW jamming detection threshold) is set to 0x10 (16 in decimal) - // algorithmBits (Reserved algorithm settings) is set to 0x16B156 as recommended - // enable (Enable interference detection) is set to 1 (enabled) - 0x3F, 0x10, 0xB1, 0x56, // config: Interference config word - // generalBits (General settings) is set to 0x31E as recommended - // antSetting (Antenna setting, 0=unknown, 1=passive, 2=active) is set to 0 (unknown) - // ToDo: Set to 1 (passive) or 2 (active) if known, for example from UBX-MON-HW, or from board info - // enable2 (Set to 1 to scan auxiliary bands, u-blox 8 / u-blox M8 only, otherwise ignored) is set to 1 - // (enabled) - 0x1E, 0x03, 0x00, 0x01 // config2: Extra settings for jamming/interference monitor + 0xf3, 0xac, 0x62, 0xad, // config1 bbThreshold = 3, cwThreshold = 15, enable = 1, reserved bits 0x16B156 + 0x1e, 0x03, 0x00, 0x00 // config2 antennaSetting Unknown = 0, reserved 3, = 0x00,0x00, reserved 2 = 0x31E +}; +/* // WIP GPS reconfig +// For Neo-6, Max-7 and Neo-7 +const uint8_t GPS::_message_JAM_6_7[] = { + 0xf3, 0xac, 0x62, 0xad, // config1 bbThreshold = 3, cwThreshold = 15, enable = 1, reserved bits 0x16B156 + 0x1e, 0x03, 0x00, 0x00 // config2 antennaSetting Unknown = 0, reserved 3, = 0x00,0x00, reserved 2 = 0x31E }; +// For M8 +const uint8_t GPS::_message_JAM_8[] = { + 0xf3, 0xac, 0x62, 0xad, // config1 bbThreshold = 3, cwThreshold = 15, enable1 = 1, reserved bits 0x16B156 + 0x1e, 0x43, 0x00, 0x00 // config2 antennaSetting Unknown = 0, enable2 = 1, generalBits = 0x31E +}; +*/ + // Configure navigation engine expert settings: +// there are many variations of what were Reserved fields for the Neo-6 in later versions +// ToDo: check UBX-MON-VER for module type and protocol version + +// For the Neo-6 const uint8_t GPS::_message_NAVX5[] = { - 0x00, 0x00, // msgVer (0 for this version) - // minMax flag = 1: apply min/max SVs settings - // minCno flag = 1: apply minimum C/N0 setting - // initial3dfix flag = 0: apply initial 3D fix settings - // aop flag = 1: apply aopCfg (useAOP flag) settings (AssistNow Autonomous) - 0x1B, 0x00, // mask1 (First parameters bitmask) - // adr flag = 0: apply ADR sensor fusion on/off setting (useAdr flag) - // If firmware is not ADR/UDR, enabling this flag will fail configuration - // ToDo: check this with UBX-MON-VER - 0x00, 0x00, 0x00, 0x00, // mask2 (Second parameters bitmask) - 0x00, 0x00, // Reserved - 0x03, // minSVs (Minimum number of satellites for navigation) = 3 - 0x10, // maxSVs (Maximum number of satellites for navigation) = 16 - 0x06, // minCNO (Minimum satellite signal level for navigation) = 6 dBHz - 0x00, // Reserved - 0x00, // iniFix3D (Initial fix must be 3D) = 0 (disabled) - 0x00, 0x00, // Reserved - 0x00, // ackAiding (Issue acknowledgements for assistance message input) = 0 (disabled) - 0x00, 0x00, // Reserved - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Reserved - 0x00, // Reserved - 0x01, // aopCfg (AssistNow Autonomous configuration) = 1 (enabled) - 0x00, 0x00, // Reserved - 0x00, 0x00, // Reserved - 0x00, 0x00, 0x00, 0x00, // Reserved - 0x00, 0x00, 0x00, // Reserved - 0x01, // useAdr (Enable/disable ADR sensor fusion) = 1 (enabled) + 0x00, 0x00, // msgVer (0 for this version) + 0x4c, 0x66, // mask1 + 0x00, 0x00, 0x00, 0x00, // Reserved 0 + 0x00, // Reserved 1 + 0x00, // Reserved 2 + 0x03, // minSVs (Minimum number of satellites for navigation) = 3 + 0x10, // maxSVs (Maximum number of satellites for navigation) = 16 + 0x06, // minCNO (Minimum satellite signal level for navigation) = 6 dBHz + 0x00, // Reserved 5 + 0x00, // iniFix3D (Initial fix must be 3D) (0 = false 1 = true) + 0x00, // Reserved 6 + 0x00, // Reserved 7 + 0x00, // Reserved 8 + 0x00, 0x00, // wknRollover 0 = firmware default + 0x00, 0x00, 0x00, 0x00, // Reserved 9 + 0x00, // Reserved 10 + 0x00, // Reserved 11 + 0x00, // usePPP (Precice Point Positioning) (0 = false, 1 = true) + 0x01, // useAOP (AssistNow Autonomous configuration) = 1 (enabled) + 0x00, // Reserved 12 + 0x00, // Reserved 13 + 0x00, 0x00, // aopOrbMaxErr = 0 to reset to firmware default + 0x00, // Reserved 14 + 0x00, // Reserved 15 + 0x00, 0x00, // Reserved 3 + 0x00, 0x00, 0x00, 0x00 // Reserved 4 }; // Set GPS update rate to 1Hz @@ -111,58 +126,88 @@ const uint8_t GPS::_message_NAVX5[] = { const uint8_t GPS::_message_1HZ[] = { 0xE8, 0x03, // Measurement Rate (1000ms for 1Hz) 0x01, 0x00, // Navigation rate, always 1 in GPS mode - 0x01, 0x00, // Time reference + 0x01, 0x00 // Time reference }; -// Disable GGL. GGL - Geographic position (latitude and longitude), which provides the current geographical +// Disable GLL. GLL - Geographic position (latitude and longitude), which provides the current geographical // coordinates. -const uint8_t GPS::_message_GGL[] = { - 0xF0, 0x01, // NMEA ID for GLL - 0x01, // I/O Target 0=I/O, 1=UART1, 2=UART2, 3=USB, 4=SPI - 0x00, // Disable - 0x01, 0x01, 0x01, 0x01 // Reserved +const uint8_t GPS::_message_GLL[] = { + 0xF0, 0x01, // NMEA ID for GLL + 0x00, // Rate for DDC + 0x00, // Rate for UART1 + 0x00, // Rate for UART2 + 0x00, // Rate for USB + 0x00, // Rate for SPI + 0x00 // Reserved }; // Enable GSA. GSA - GPS DOP and active satellites, used for detailing the satellites used in the positioning and // the DOP (Dilution of Precision) const uint8_t GPS::_message_GSA[] = { - 0xF0, 0x02, // NMEA ID for GSA - 0x01, // I/O Target 0=I/O, 1=UART1, 2=UART2, 3=USB, 4=SPI - 0x01, // Enable - 0x01, 0x01, 0x01, 0x01 // Reserved + 0xF0, 0x02, // NMEA ID for GSA + 0x00, // Rate for DDC + 0x01, // Rate for UART1 + 0x00, // Rate for UART2 + 0x00, // Rate for USB + 0x00, // Rate for SPI + 0x00 // Reserved }; // Disable GSV. GSV - Satellites in view, details the number and location of satellites in view. const uint8_t GPS::_message_GSV[] = { - 0xF0, 0x03, // NMEA ID for GSV - 0x01, // I/O Target 0=I/O, 1=UART1, 2=UART2, 3=USB, 4=SPI - 0x00, // Disable - 0x01, 0x01, 0x01, 0x01 // Reserved + 0xF0, 0x03, // NMEA ID for GSV + 0x00, // Rate for DDC + 0x00, // Rate for UART1 + 0x00, // Rate for UART2 + 0x00, // Rate for USB + 0x00, // Rate for SPI + 0x00 // Reserved }; // Disable VTG. VTG - Track made good and ground speed, which provides course and speed information relative to // the ground. const uint8_t GPS::_message_VTG[] = { - 0xF0, 0x05, // NMEA ID for VTG - 0x01, // I/O Target 0=I/O, 1=UART1, 2=UART2, 3=USB, 4=SPI - 0x00, // Disable - 0x01, 0x01, 0x01, 0x01 // Reserved + 0xF0, 0x05, // NMEA ID for VTG + 0x00, // Rate for DDC + 0x00, // Rate for UART1 + 0x00, // Rate for UART2 + 0x00, // Rate for USB + 0x00, // Rate for SPI + 0x00 // Reserved }; // Enable RMC. RMC - Recommended Minimum data, the essential gps pvt (position, velocity, time) data. const uint8_t GPS::_message_RMC[] = { - 0xF0, 0x04, // NMEA ID for RMC - 0x01, // I/O Target 0=I/O, 1=UART1, 2=UART2, 3=USB, 4=SPI - 0x01, // Enable - 0x01, 0x01, 0x01, 0x01 // Reserved + 0xF0, 0x04, // NMEA ID for RMC + 0x00, // Rate for DDC + 0x01, // Rate for UART1 + 0x00, // Rate for UART2 + 0x00, // Rate for USB + 0x00, // Rate for SPI + 0x00 // Reserved }; // Enable GGA. GGA - Global Positioning System Fix Data, which provides 3D location and accuracy data. const uint8_t GPS::_message_GGA[] = { - 0xF0, 0x00, // NMEA ID for GGA - 0x01, // I/O Target 0=I/O, 1=UART1, 2=UART2, 3=USB, 4=SPI - 0x01, // Enable - 0x01, 0x01, 0x01, 0x01 // Reserved + 0xF0, 0x00, // NMEA ID for GGA + 0x00, // Rate for DDC + 0x01, // Rate for UART1 + 0x00, // Rate for UART2 + 0x00, // Rate for USB + 0x00, // Rate for SPI + 0x00 // Reserved +}; + +// Disable UBX-AID-ALPSRV as it may confuse TinyGPS. The Neo-6 seems to send this message +// whether the AID Autonomous is enabled or not +const uint8_t GPS::_message_AID[] = { + 0x0B, 0x32, // NMEA ID for UBX-AID-ALPSRV + 0x00, // Rate for DDC + 0x00, // Rate for UART1 + 0x00, // Rate for UART2 + 0x00, // Rate for USB + 0x00, // Rate for SPI + 0x00 // Reserved }; // The Power Management configuration allows the GPS module to operate in different power modes for optimized @@ -176,17 +221,18 @@ const uint8_t GPS::_message_GGA[] = { // is set to Interval; otherwise, it must be set to '0'. The 'onTime' field specifies the duration of the ON phase // and must be smaller than the period. It is only valid when the powerSetupValue is set to Interval; otherwise, // it must be set to '0'. +// This command applies to M8 and higher products const uint8_t GPS::_message_PMS[] = { 0x00, // Version (0) - 0x03, // Power setup value + 0x03, // Power setup value 3 = Agresssive 1Hz 0x00, 0x00, // period: not applicable, set to 0 0x00, 0x00, // onTime: not applicable, set to 0 - 0x97, 0x6F // reserved, generated by u-center + 0x00, 0x00 // reserved, generated by u-center }; const uint8_t GPS::_message_SAVE[] = { 0x00, 0x00, 0x00, 0x00, // clearMask: no sections cleared 0xFF, 0xFF, 0x00, 0x00, // saveMask: save all sections 0x00, 0x00, 0x00, 0x00, // loadMask: no sections loaded - 0x0F // deviceMask: BBR, Flash, EEPROM, and SPI Flash -}; + 0x17 // deviceMask: BBR, Flash, EEPROM, and SPI Flash +}; \ No newline at end of file diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index 919d298e6..71765c8e4 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -113,7 +113,15 @@ void portduinoSetup() try { if (yamlConfig["Logging"]) { - settingsMap[debugmode] = yamlConfig["Logging"]["DebugMode"].as(false); + if (yamlConfig["Logging"]["LogLevel"].as("info") == "debug") { + settingsMap[logoutputlevel] = level_debug; + } else if (yamlConfig["Logging"]["LogLevel"].as("info") == "info") { + settingsMap[logoutputlevel] = level_info; + } else if (yamlConfig["Logging"]["LogLevel"].as("info") == "warn") { + settingsMap[logoutputlevel] = level_warn; + } else if (yamlConfig["Logging"]["LogLevel"].as("info") == "error") { + settingsMap[logoutputlevel] = level_error; + } } if (yamlConfig["Lora"]) { settingsMap[use_sx1262] = false; diff --git a/src/platform/portduino/PortduinoGlue.h b/src/platform/portduino/PortduinoGlue.h index 4c48f0c29..2cfd3fc48 100644 --- a/src/platform/portduino/PortduinoGlue.h +++ b/src/platform/portduino/PortduinoGlue.h @@ -33,10 +33,11 @@ enum configNames { displayOffsetY, displayInvert, keyboardDevice, - debugmode + logoutputlevel }; enum { no_screen, st7789, st7735, st7735s }; enum { no_touchscreen, xpt2046 }; +enum { level_error, level_warn, level_info, level_debug }; extern std::map settingsMap; extern std::map settingsStrings; From af5ac32048dc1a6bed56ef041652e077b1b80aec Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Tue, 30 Jan 2024 17:44:08 -0600 Subject: [PATCH 147/472] Re-order GPS check to eliminate TOO old message (#3152) --- src/gps/GPS.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 592fc69cf..bc186c181 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -1115,6 +1115,10 @@ bool GPS::lookForLocation() reader.date.age(), reader.time.age()); #endif // GPS_EXTRAVERBOSE + // Is this a new point or are we re-reading the previous one? + if (!reader.location.isUpdated()) + return false; + // check if a complete GPS solution set is available for reading // tinyGPSDatum::age() also includes isValid() test // FIXME @@ -1127,10 +1131,6 @@ bool GPS::lookForLocation() return false; } - // Is this a new point or are we re-reading the previous one? - if (!reader.location.isUpdated()) - return false; - // We know the solution is fresh and valid, so just read the data auto loc = reader.location.value(); From 4f64c4f7b90c778b93e4fee48a755f87f6577ca8 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Tue, 30 Jan 2024 20:01:00 -0600 Subject: [PATCH 148/472] [create-pull-request] automated change (#3154) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 89c0e3d50..d9de4fdc1 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 2 -build = 20 +build = 21 From bdbe42dfd02ede2684e0da0085f3866060f83a49 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 31 Jan 2024 12:58:04 -0600 Subject: [PATCH 149/472] Update version.properties --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index d9de4fdc1..89c0e3d50 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 2 -build = 21 +build = 20 From 84e578323e96db1b64ba16fdc44934dea6262686 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 31 Jan 2024 13:46:48 -0600 Subject: [PATCH 150/472] Update version.properties --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 89c0e3d50..d9de4fdc1 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 2 -build = 20 +build = 21 From bf762bc58db89dc7c3903752fc0ffe85fc8533b4 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Wed, 31 Jan 2024 13:47:17 -0600 Subject: [PATCH 151/472] [create-pull-request] automated change (#3156) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/config.pb.c | 1 + src/mesh/generated/meshtastic/config.pb.h | 26 ++++++++++++++++--- src/mesh/generated/meshtastic/deviceonly.pb.h | 2 +- src/mesh/generated/meshtastic/localonly.pb.h | 2 +- src/mesh/generated/meshtastic/mesh.pb.h | 2 ++ 6 files changed, 28 insertions(+), 7 deletions(-) diff --git a/protobufs b/protobufs index e894709e4..b508d2e7c 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit e894709e4a96867ea8fad59a12f582e1029a6f8e +Subproject commit b508d2e7ced34c752533eb02786e37402cc5a184 diff --git a/src/mesh/generated/meshtastic/config.pb.c b/src/mesh/generated/meshtastic/config.pb.c index 361e28d7c..0fa8ba588 100644 --- a/src/mesh/generated/meshtastic/config.pb.c +++ b/src/mesh/generated/meshtastic/config.pb.c @@ -45,3 +45,4 @@ PB_BIND(meshtastic_Config_BluetoothConfig, meshtastic_Config_BluetoothConfig, AU + diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index 25e8d476c..b06e9a707 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -108,6 +108,15 @@ typedef enum _meshtastic_Config_PositionConfig_PositionFlags { meshtastic_Config_PositionConfig_PositionFlags_SPEED = 512 } meshtastic_Config_PositionConfig_PositionFlags; +typedef enum _meshtastic_Config_PositionConfig_GpsMode { + /* GPS is present but disabled */ + meshtastic_Config_PositionConfig_GpsMode_DISABLED = 0, + /* GPS is present and enabled */ + meshtastic_Config_PositionConfig_GpsMode_ENABLED = 1, + /* GPS is not present on the device */ + meshtastic_Config_PositionConfig_GpsMode_NOT_PRESENT = 2 +} meshtastic_Config_PositionConfig_GpsMode; + typedef enum _meshtastic_Config_NetworkConfig_AddressMode { /* obtain ip address via DHCP */ meshtastic_Config_NetworkConfig_AddressMode_DHCP = 0, @@ -300,6 +309,8 @@ typedef struct _meshtastic_Config_PositionConfig { uint32_t broadcast_smart_minimum_interval_secs; /* (Re)define PIN_GPS_EN for your board. */ uint32_t gps_en_gpio; + /* Set where GPS is enabled, disabled, or not present */ + meshtastic_Config_PositionConfig_GpsMode gps_mode; } meshtastic_Config_PositionConfig; /* Power Config\ @@ -507,6 +518,10 @@ extern "C" { #define _meshtastic_Config_PositionConfig_PositionFlags_MAX meshtastic_Config_PositionConfig_PositionFlags_SPEED #define _meshtastic_Config_PositionConfig_PositionFlags_ARRAYSIZE ((meshtastic_Config_PositionConfig_PositionFlags)(meshtastic_Config_PositionConfig_PositionFlags_SPEED+1)) +#define _meshtastic_Config_PositionConfig_GpsMode_MIN meshtastic_Config_PositionConfig_GpsMode_DISABLED +#define _meshtastic_Config_PositionConfig_GpsMode_MAX meshtastic_Config_PositionConfig_GpsMode_NOT_PRESENT +#define _meshtastic_Config_PositionConfig_GpsMode_ARRAYSIZE ((meshtastic_Config_PositionConfig_GpsMode)(meshtastic_Config_PositionConfig_GpsMode_NOT_PRESENT+1)) + #define _meshtastic_Config_NetworkConfig_AddressMode_MIN meshtastic_Config_NetworkConfig_AddressMode_DHCP #define _meshtastic_Config_NetworkConfig_AddressMode_MAX meshtastic_Config_NetworkConfig_AddressMode_STATIC #define _meshtastic_Config_NetworkConfig_AddressMode_ARRAYSIZE ((meshtastic_Config_NetworkConfig_AddressMode)(meshtastic_Config_NetworkConfig_AddressMode_STATIC+1)) @@ -543,6 +558,7 @@ extern "C" { #define meshtastic_Config_DeviceConfig_role_ENUMTYPE meshtastic_Config_DeviceConfig_Role #define meshtastic_Config_DeviceConfig_rebroadcast_mode_ENUMTYPE meshtastic_Config_DeviceConfig_RebroadcastMode +#define meshtastic_Config_PositionConfig_gps_mode_ENUMTYPE meshtastic_Config_PositionConfig_GpsMode #define meshtastic_Config_NetworkConfig_address_mode_ENUMTYPE meshtastic_Config_NetworkConfig_AddressMode @@ -562,7 +578,7 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_Config_init_default {0, {meshtastic_Config_DeviceConfig_init_default}} #define meshtastic_Config_DeviceConfig_init_default {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0, 0} -#define meshtastic_Config_PositionConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define meshtastic_Config_PositionConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, _meshtastic_Config_PositionConfig_GpsMode_MIN} #define meshtastic_Config_PowerConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_Config_NetworkConfig_init_default {0, "", "", "", 0, _meshtastic_Config_NetworkConfig_AddressMode_MIN, false, meshtastic_Config_NetworkConfig_IpV4Config_init_default, ""} #define meshtastic_Config_NetworkConfig_IpV4Config_init_default {0, 0, 0, 0} @@ -571,7 +587,7 @@ extern "C" { #define meshtastic_Config_BluetoothConfig_init_default {0, _meshtastic_Config_BluetoothConfig_PairingMode_MIN, 0} #define meshtastic_Config_init_zero {0, {meshtastic_Config_DeviceConfig_init_zero}} #define meshtastic_Config_DeviceConfig_init_zero {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0, 0} -#define meshtastic_Config_PositionConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define meshtastic_Config_PositionConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, _meshtastic_Config_PositionConfig_GpsMode_MIN} #define meshtastic_Config_PowerConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_Config_NetworkConfig_init_zero {0, "", "", "", 0, _meshtastic_Config_NetworkConfig_AddressMode_MIN, false, meshtastic_Config_NetworkConfig_IpV4Config_init_zero, ""} #define meshtastic_Config_NetworkConfig_IpV4Config_init_zero {0, 0, 0, 0} @@ -602,6 +618,7 @@ extern "C" { #define meshtastic_Config_PositionConfig_broadcast_smart_minimum_distance_tag 10 #define meshtastic_Config_PositionConfig_broadcast_smart_minimum_interval_secs_tag 11 #define meshtastic_Config_PositionConfig_gps_en_gpio_tag 12 +#define meshtastic_Config_PositionConfig_gps_mode_tag 13 #define meshtastic_Config_PowerConfig_is_power_saving_tag 1 #define meshtastic_Config_PowerConfig_on_battery_shutdown_after_secs_tag 2 #define meshtastic_Config_PowerConfig_adc_multiplier_override_tag 3 @@ -704,7 +721,8 @@ X(a, STATIC, SINGULAR, UINT32, rx_gpio, 8) \ X(a, STATIC, SINGULAR, UINT32, tx_gpio, 9) \ X(a, STATIC, SINGULAR, UINT32, broadcast_smart_minimum_distance, 10) \ X(a, STATIC, SINGULAR, UINT32, broadcast_smart_minimum_interval_secs, 11) \ -X(a, STATIC, SINGULAR, UINT32, gps_en_gpio, 12) +X(a, STATIC, SINGULAR, UINT32, gps_en_gpio, 12) \ +X(a, STATIC, SINGULAR, UENUM, gps_mode, 13) #define meshtastic_Config_PositionConfig_CALLBACK NULL #define meshtastic_Config_PositionConfig_DEFAULT NULL @@ -810,7 +828,7 @@ extern const pb_msgdesc_t meshtastic_Config_BluetoothConfig_msg; #define meshtastic_Config_LoRaConfig_size 80 #define meshtastic_Config_NetworkConfig_IpV4Config_size 20 #define meshtastic_Config_NetworkConfig_size 196 -#define meshtastic_Config_PositionConfig_size 60 +#define meshtastic_Config_PositionConfig_size 62 #define meshtastic_Config_PowerConfig_size 40 #define meshtastic_Config_size 199 diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index 6318d7d71..e017be9a2 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -316,7 +316,7 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg; #define meshtastic_DeviceState_size 17062 #define meshtastic_NodeInfoLite_size 153 #define meshtastic_NodeRemoteHardwarePin_size 29 -#define meshtastic_OEMStore_size 3244 +#define meshtastic_OEMStore_size 3246 #define meshtastic_PositionLite_size 28 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/localonly.pb.h b/src/mesh/generated/meshtastic/localonly.pb.h index 50772308c..7d39da01f 100644 --- a/src/mesh/generated/meshtastic/localonly.pb.h +++ b/src/mesh/generated/meshtastic/localonly.pb.h @@ -180,7 +180,7 @@ extern const pb_msgdesc_t meshtastic_LocalModuleConfig_msg; #define meshtastic_LocalModuleConfig_fields &meshtastic_LocalModuleConfig_msg /* Maximum encoded size of messages (where known) */ -#define meshtastic_LocalConfig_size 467 +#define meshtastic_LocalConfig_size 469 #define meshtastic_LocalModuleConfig_size 631 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index a00273eb4..57054a74e 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -71,6 +71,8 @@ typedef enum _meshtastic_HardwareModel { meshtastic_HardwareModel_SENSELORA_RP2040 = 27, /* Makerfabs SenseLoRA Industrial Monitor (ESP32-S3 + RFM96) */ meshtastic_HardwareModel_SENSELORA_S3 = 28, + /* Canary Radio Company - CanaryOne: https://canaryradio.io/products/canaryone */ + meshtastic_HardwareModel_CANARYONE = 29, /* --------------------------------------------------------------------------- Less common/prototype boards listed here (needs one more byte over the air) --------------------------------------------------------------------------- */ From 0c0a3c4b5533c61221907160141c1f234e0904fb Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Wed, 31 Jan 2024 21:04:52 +0100 Subject: [PATCH 152/472] Fix: mark packet sent to MQTT as ACKed only after we sent it out via LoRa (#3155) * Fix: mark packet via MQTT as ACKed only after we sent it out via LoRa * Don't need to check for broadcast, DMs also get implicit ACKs --------- Co-authored-by: Ben Meadors --- src/mqtt/MQTT.cpp | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 70b2d753c..5eaf7f98d 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -127,11 +127,17 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length) LOG_ERROR("Invalid MQTT service envelope, topic %s, len %u!\n", topic, length); return; } else { - if (strcmp(e.gateway_id, owner.id) == 0) - LOG_INFO("Ignoring downlink message we originally sent.\n"); - else { + meshtastic_Channel ch = channels.getByName(e.channel_id); + if (strcmp(e.gateway_id, owner.id) == 0) { + // Generate an implicit ACK towards ourselves (handled and processed only locally!) for this message. + // We do this because packets are not rebroadcasted back into MQTT anymore and we assume that at least one node + // receives it when we get our own packet back. Then we'll stop our retransmissions. + if (e.packet && getFrom(e.packet) == nodeDB.getNodeNum()) + routingModule->sendAckNak(meshtastic_Routing_Error_NONE, getFrom(e.packet), e.packet->id, ch.index); + else + LOG_INFO("Ignoring downlink message we originally sent.\n"); + } else { // Find channel by channel_id and check downlink_enabled - meshtastic_Channel ch = channels.getByName(e.channel_id); if (strcmp(e.channel_id, channels.getGlobalId(ch.index)) == 0 && e.packet && ch.settings.downlink_enabled) { LOG_INFO("Received MQTT topic %s, len=%u\n", topic, length); meshtastic_MeshPacket *p = packetPool.allocCopy(*e.packet); @@ -505,11 +511,6 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket & } } - // Generate an implicit ACK towards ourselves (handled and processed only locally!) for this message. - // We do this because packets are not rebroadcasted back into MQTT anymore and we assume that at least one node - // receives it when we're connected to the broker. Then we'll stop our retransmissions. - if (getFrom(&mp) == nodeDB.getNodeNum()) - routingModule->sendAckNak(meshtastic_Routing_Error_NONE, getFrom(&mp), mp.id, chIndex); } else { LOG_INFO("MQTT not connected, queueing packet\n"); if (mqttQueue.numFree() == 0) { From 7f7c5cbd629e5188939926fd7c0a64280405df6f Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 1 Feb 2024 15:24:39 -0600 Subject: [PATCH 153/472] Triple GPS state (#3157) * Triple state GPS refactoring * Skip probe * Move GPS toggle into the GPSThread * Consolidate * make all happy (including me) * corrected screen texts * NOT_PRESENT guard in main.cpp --------- Co-authored-by: mverch67 --- src/ButtonThread.h | 10 +------- src/gps/GPS.cpp | 30 +++++++++++++++++------ src/gps/GPS.h | 5 +++- src/graphics/Screen.cpp | 28 +++++++++++---------- src/main.cpp | 3 ++- src/mesh/NodeDB.cpp | 16 +++++++++++- src/mesh/generated/meshtastic/config.pb.h | 2 +- 7 files changed, 61 insertions(+), 33 deletions(-) diff --git a/src/ButtonThread.h b/src/ButtonThread.h index 3301df097..66efd6004 100644 --- a/src/ButtonThread.h +++ b/src/ButtonThread.h @@ -193,15 +193,7 @@ class ButtonThread : public concurrency::OSThread static void userButtonMultiPressed() { if (!config.device.disable_triple_click && (gps != nullptr)) { - config.position.gps_enabled = !(config.position.gps_enabled); - if (config.position.gps_enabled) { - LOG_DEBUG("Flag set to true to restore power\n"); - gps->enable(); - - } else { - LOG_DEBUG("Flag set to false for gps power\n"); - gps->disable(); - } + gps->toggleGpsMode(); } } diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index bc186c181..ed286228d 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -604,7 +604,7 @@ uint32_t GPS::getSleepTime() const uint32_t t = config.position.gps_update_interval; // We'll not need the GPS thread to wake up again after first acq. with fixed position. - if (!config.position.gps_enabled || config.position.fixed_position) + if (config.position.gps_mode != meshtastic_Config_PositionConfig_GpsMode_ENABLED || config.position.fixed_position) t = UINT32_MAX; // Sleep forever now if (t == UINT32_MAX) @@ -625,21 +625,24 @@ void GPS::publishUpdate() // Notify any status instances that are observing us const meshtastic::GPSStatus status = meshtastic::GPSStatus(hasValidLocation, isConnected(), isPowerSaving(), p); newStatus.notifyObservers(&status); - if (config.position.gps_enabled) + if (config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_ENABLED) { positionModule->handleNewPosition(); + } } } int32_t GPS::runOnce() { if (!GPSInitFinished) { - if (!_serial_gps) + if (!_serial_gps || config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_NOT_PRESENT) { + LOG_INFO("GPS set to not-present. Skipping probe.\n"); return disable(); + } if (!setup()) return 2000; // Setup failed, re-run in two seconds // We have now loaded our saved preferences from flash - if (config.position.gps_enabled == false) { + if (config.position.gps_mode != meshtastic_Config_PositionConfig_GpsMode_ENABLED) { return disable(); } // ONCE we will factory reset the GPS for bug #327 @@ -662,7 +665,7 @@ int32_t GPS::runOnce() // if we have received valid NMEA claim we are connected setConnected(); } else { - if ((config.position.gps_enabled == 1) && (gnssModel == GNSS_MODEL_UBLOX)) { + if ((config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_ENABLED) && (gnssModel == GNSS_MODEL_UBLOX)) { // reset the GPS on next bootup if (devicestate.did_gps_reset && (millis() - lastWakeStartMsec > 60000) && !hasFlow()) { LOG_DEBUG("GPS is not communicating, trying factory reset on next bootup.\n"); @@ -902,7 +905,7 @@ GPS *GPS::createGps() int8_t _rx_gpio = config.position.rx_gpio; int8_t _tx_gpio = config.position.tx_gpio; int8_t _en_gpio = config.position.gps_en_gpio; -#if defined(HAS_GPS) && !defined(ARCH_ESP32) +#if HAS_GPS && !defined(ARCH_ESP32) _rx_gpio = 1; // We only specify GPS serial ports on ESP32. Otherwise, these are just flags. _tx_gpio = 1; #endif @@ -1098,7 +1101,7 @@ bool GPS::lookForLocation() #ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS fixType = atoi(gsafixtype.value()); // will set to zero if no data - // LOG_DEBUG("FIX QUAL=%d, TYPE=%d\n", fixQual, fixType); + // LOG_DEBUG("FIX QUAL=%d, TYPE=%d\n", fixQual, fixType); #endif // check if GPS has an acceptable lock @@ -1280,4 +1283,17 @@ int32_t GPS::disable() setAwake(false); return INT32_MAX; +} + +void GPS::toggleGpsMode() +{ + if (config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_ENABLED) { + config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_DISABLED; + LOG_DEBUG("Flag set to false for gps power. GpsMode: DISABLED\n"); + disable(); + } else if (config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_DISABLED) { + config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_ENABLED; + LOG_DEBUG("Flag set to true to restore power. GpsMode: ENABLED\n"); + enable(); + } } \ No newline at end of file diff --git a/src/gps/GPS.h b/src/gps/GPS.h index 80894dd51..1b56c2ee4 100644 --- a/src/gps/GPS.h +++ b/src/gps/GPS.h @@ -133,6 +133,9 @@ class GPS : private concurrency::OSThread // Disable the thread int32_t disable() override; + // toggle between enabled/disabled + void toggleGpsMode(); + void setGPSPower(bool on, bool standbyOnly, uint32_t sleepTime); /// Returns true if we have acquired GPS lock. @@ -144,7 +147,7 @@ class GPS : private concurrency::OSThread /// Return true if we are connected to a GPS bool isConnected() const { return hasGPS; } - bool isPowerSaving() const { return !config.position.gps_enabled; } + bool isPowerSaving() const { return config.position.gps_mode != meshtastic_Config_PositionConfig_GpsMode_ENABLED; } // Empty the input buffer as quickly as possible void clearBuffer(); diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index fb27e3c01..82b511e6c 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -558,15 +558,20 @@ static void drawGPS(OLEDDisplay *display, int16_t x, int16_t y, const GPSStatus } } -// Draw status when gps is disabled by PMU +// Draw status when GPS is disabled or not present static void drawGPSpowerstat(OLEDDisplay *display, int16_t x, int16_t y, const GPSStatus *gps) { - String displayLine = "GPS disabled"; - int16_t xPos = display->getStringWidth(displayLine); - - if (!config.position.gps_enabled) { - display->drawString(x + xPos, y, displayLine); + String displayLine; + int pos; + if (y < FONT_HEIGHT_SMALL) { // Line 1: use short string + displayLine = config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_NOT_PRESENT ? "No GPS" : "GPS off"; + pos = SCREEN_WIDTH - display->getStringWidth(displayLine); + } else { + displayLine = config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_NOT_PRESENT ? "GPS not present" + : "GPS is disabled"; + pos = (SCREEN_WIDTH - display->getStringWidth(displayLine)) / 2; } + display->drawString(x + pos, y, displayLine); } static void drawGPSAltitude(OLEDDisplay *display, int16_t x, int16_t y, const GPSStatus *gps) @@ -594,7 +599,7 @@ static void drawGPScoordinates(OLEDDisplay *display, int16_t x, int16_t y, const String displayLine = ""; if (!gps->getIsConnected() && !config.position.fixed_position) { - displayLine = "No GPS Module"; + displayLine = "No GPS present"; display->drawString(x + (SCREEN_WIDTH - (display->getStringWidth(displayLine))) / 2, y, displayLine); } else if (!gps->getHasLock() && !config.position.fixed_position) { displayLine = "No GPS Lock"; @@ -1549,7 +1554,7 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16 drawNodes(display, x + (SCREEN_WIDTH * 0.25), y + 3, nodeStatus); } // Display GPS status - if (!config.position.gps_enabled) { + if (config.position.gps_mode != meshtastic_Config_PositionConfig_GpsMode_ENABLED) { drawGPSpowerstat(display, x, y + 2, gpsStatus); } else { if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_DEFAULT) { @@ -1777,7 +1782,7 @@ void DebugInfo::drawFrameSettings(OLEDDisplay *display, OLEDDisplayUiState *stat char chUtil[13]; snprintf(chUtil, sizeof(chUtil), "ChUtil %2.0f%%", airTime->channelUtilizationPercent()); display->drawString(x + SCREEN_WIDTH - display->getStringWidth(chUtil), y + FONT_HEIGHT_SMALL * 1, chUtil); - if (config.position.gps_enabled) { + if (config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_ENABLED) { // Line 3 if (config.display.gps_format != meshtastic_Config_DisplayConfig_GpsCoordinateFormat_DMS) // if DMS then don't draw altitude @@ -1786,10 +1791,7 @@ void DebugInfo::drawFrameSettings(OLEDDisplay *display, OLEDDisplayUiState *stat // Line 4 drawGPScoordinates(display, x, y + FONT_HEIGHT_SMALL * 3, gpsStatus); } else { - drawGPSpowerstat(display, x - (SCREEN_WIDTH / 4), y + FONT_HEIGHT_SMALL * 2, gpsStatus); -#ifdef GPS_POWER_TOGGLE - display->drawString(x + 30, (y + FONT_HEIGHT_SMALL * 3), " by button"); -#endif + drawGPSpowerstat(display, x, y + FONT_HEIGHT_SMALL * 2, gpsStatus); } /* Display a heartbeat pixel that blinks every time the frame is redrawn */ #ifdef SHOW_REDRAWS diff --git a/src/main.cpp b/src/main.cpp index f853dc0ec..f89ece9dc 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -685,7 +685,8 @@ void setup() readFromRTC(); // read the main CPU RTC at first (in case we can't get GPS time) // If we're taking on the repeater role, ignore GPS - if (config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER) { + if (config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER && + config.position.gps_mode != meshtastic_Config_PositionConfig_GpsMode_NOT_PRESENT) { gps = GPS::createGps(); } if (gps) { diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 2eebd64ed..891b7a61f 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -182,7 +182,16 @@ void NodeDB::installDefaultConfig() #else config.device.disable_triple_click = true; #endif - config.position.gps_enabled = true; +#if !HAS_GPS || defined(T_DECK) + config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_NOT_PRESENT; +#elif !defined(GPS_RX_PIN) + if (config.position.rx_gpio == 0) + config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_NOT_PRESENT; + else + config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_DISABLED; +#else + config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_ENABLED; +#endif config.position.position_broadcast_smart_enabled = true; config.position.broadcast_smart_minimum_distance = 100; config.position.broadcast_smart_minimum_interval_secs = 30; @@ -454,6 +463,11 @@ void NodeDB::init() memcpy(devicestate.node_remote_hardware_pins, empty, sizeof(empty)); } + if (config.position.gps_enabled) { + config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_ENABLED; + config.position.gps_enabled = 0; + } + saveToDisk(saveWhat); } diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index b06e9a707..1f1ff6a74 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -836,4 +836,4 @@ extern const pb_msgdesc_t meshtastic_Config_BluetoothConfig_msg; } /* extern "C" */ #endif -#endif +#endif \ No newline at end of file From 7db02ad722bb22b76ad2c4c4e0d93a2cab316cec Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 1 Feb 2024 16:33:40 -0600 Subject: [PATCH 154/472] [create-pull-request] automated change (#3161) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index d9de4fdc1..841be3b27 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 2 -build = 21 +build = 22 From 4c55d5d9e46eeb7ca5c1ab22c9e5b75a9cc9a9a7 Mon Sep 17 00:00:00 2001 From: Ken McGuire Date: Mon, 5 Feb 2024 08:02:30 -0700 Subject: [PATCH 155/472] GPS rework phase 2 updates for M8 and stub for M10 (#3166) * Portduino multiple logging levels * Fixes based on GPSFan work * Fix derped logic * Correct size field for AID message * Reformat to add comments, beginning of GPS rework * Update PM2 message for Neo-6 * Correct ECO mode logic as ECO mode is only for Neo-6 * Cleanup ubx.h add a few more comments * GPS rework, changes for M8 and stub for M10 --------- Co-authored-by: Jonathan Bennett Co-authored-by: Ben Meadors --- src/gps/GPS.cpp | 250 +++++++++++++++++++++++++++--------------------- src/gps/GPS.h | 8 +- src/gps/ubx.h | 104 ++++++++++++++++---- 3 files changed, 230 insertions(+), 132 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index ed286228d..02bca211b 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -326,126 +326,158 @@ bool GPS::setup() // Also we need SBAS for better accuracy and extra features // ToDo: Dynamic configure GNSS systems depending of LoRa region - if (strncmp(info.hwVersion, "00040007", 8) != - 0) { // The original ublox 6 is GPS only and doesn't support the UBX-CFG-GNSS message - if (strncmp(info.hwVersion, "00070000", 8) == 0) { // Max7 seems to only support GPS *or* GLONASS - LOG_DEBUG("Setting GPS+SBAS\n"); - msglen = makeUBXPacket(0x06, 0x3e, sizeof(_message_GNSS_7), _message_GNSS_7); - _serial_gps->write(UBXscratch, msglen); - } else { - msglen = makeUBXPacket(0x06, 0x3e, sizeof(_message_GNSS), _message_GNSS); - _serial_gps->write(UBXscratch, msglen); - } + if (strncmp(info.hwVersion, "000A0000", 8) != 0) { + if (strncmp(info.hwVersion, "00040007", 8) != 0) { + // The original ublox Neo-6 is GPS only and doesn't support the UBX-CFG-GNSS message + // Max7 seems to only support GPS *or* GLONASS + // Neo-7 is supposed to support GPS *and* GLONASS but NAKs the CFG-GNSS command to do it + // So treat all the u-blox 7 series as GPS only + // M8 can support 3 constallations at once so turn on GPS, GLONASS and Galileo (or BeiDou) - if (getACK(0x06, 0x3e, 800) == GNSS_RESPONSE_NAK) { - // It's not critical if the module doesn't acknowledge this configuration. - LOG_INFO("Unable to reconfigure GNSS - defaults maintained. Is this module GPS-only?\n"); - } else { if (strncmp(info.hwVersion, "00070000", 8) == 0) { - LOG_INFO("GNSS configured for GPS+SBAS. Pause for 0.75s before sending next command.\n"); + LOG_DEBUG("Setting GPS+SBAS\n"); + msglen = makeUBXPacket(0x06, 0x3e, sizeof(_message_GNSS_7), _message_GNSS_7); + _serial_gps->write(UBXscratch, msglen); } else { - LOG_INFO("GNSS configured for GPS+SBAS+GLONASS. Pause for 0.75s before sending next command.\n"); + msglen = makeUBXPacket(0x06, 0x3e, sizeof(_message_GNSS_8), _message_GNSS_8); + _serial_gps->write(UBXscratch, msglen); } - // Documentation say, we need wait atleast 0.5s after reconfiguration of GNSS module, before sending next - // commands - delay(750); - } - } - msglen = makeUBXPacket(0x06, 0x39, sizeof(_message_JAM), _message_JAM); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x39, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to enable interference resistance.\n"); - } - - msglen = makeUBXPacket(0x06, 0x23, sizeof(_message_NAVX5), _message_NAVX5); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x23, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to configure extra settings.\n"); - } - - // ublox-M10S can be compatible with UBLOX traditional protocol, so the following sentence settings are also valid - - msglen = makeUBXPacket(0x06, 0x08, sizeof(_message_1HZ), _message_1HZ); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x08, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to set GPS update rate.\n"); - } - - msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_GLL), _message_GLL); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to disable NMEA GGL.\n"); - } - - msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_GSA), _message_GSA); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to Enable NMEA GSA.\n"); - } - - msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_GSV), _message_GSV); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to disable NMEA GSV.\n"); - } - - msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_VTG), _message_VTG); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to disable NMEA VTG.\n"); - } - - msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_RMC), _message_RMC); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to enable NMEA RMC.\n"); - } - - msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_GGA), _message_GGA); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to enable NMEA GGA.\n"); - } - - msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_AID), _message_AID); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to disable UBX-AID.\n"); - } - - if (uBloxProtocolVersion >= 18) { - msglen = makeUBXPacket(0x06, 0x86, sizeof(_message_PMS), _message_PMS); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x86, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to enable powersaving for GPS.\n"); - } - } else { - if (strncmp(info.hwVersion, "00040007", 8) == 0) { // This PSM mode is only for Neo-6 - msglen = makeUBXPacket(0x06, 0x11, 0x2, _message_CFG_RXM_ECO); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x11, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to enable powersaving ECO mode for Neo-6.\n"); + if (getACK(0x06, 0x3e, 800) == GNSS_RESPONSE_NAK) { + // It's not critical if the module doesn't acknowledge this configuration. + LOG_INFO("Unable to reconfigure GNSS - defaults maintained. Is this module GPS-only?\n"); + } else { + if (strncmp(info.hwVersion, "00070000", 8) == 0) { + LOG_INFO("GNSS configured for GPS+SBAS. Pause for 0.75s before sending next command.\n"); + } else { + LOG_INFO( + "GNSS configured for GPS+SBAS+GLONASS+Galileo. Pause for 0.75s before sending next command.\n"); + } + // Documentation say, we need wait atleast 0.5s after reconfiguration of GNSS module, before sending next + // commands for the M8 it tends to be more... 1 sec should be enough ;>) + delay(1000); } - msglen = makeUBXPacket(0x06, 0x3B, 44, _message_CFG_PM2); + } + // ToDo add M10 tests for below + if (strncmp(info.hwVersion, "00080000", 8) == 0) { + msglen = makeUBXPacket(0x06, 0x39, sizeof(_message_JAM_8), _message_JAM_8); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x3B, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to enable powersaving details for GPS.\n"); + if (getACK(0x06, 0x39, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable interference resistance.\n"); + } + clearBuffer(); + msglen = makeUBXPacket(0x06, 0x23, sizeof(_message_NAVX5_8), _message_NAVX5_8); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x23, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to configure extra settings.\n"); } } else { - msglen = makeUBXPacket(0x06, 0x11, 0x2, _message_CFG_RXM_PSM); + msglen = makeUBXPacket(0x06, 0x39, sizeof(_message_JAM_6_7), _message_JAM_6_7); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x11, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to enable powersaving mode for GPS.\n"); + if (getACK(0x06, 0x39, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable interference resistance.\n"); + } + + msglen = makeUBXPacket(0x06, 0x23, sizeof(_message_NAVX5), _message_NAVX5); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x23, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to configure extra settings.\n"); } } - } - msglen = makeUBXPacket(0x06, 0x09, sizeof(_message_SAVE), _message_SAVE); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x09, 2000) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to save GNSS module configuration.\n"); + // ublox-M10S can be compatible with UBLOX traditional protocol, so the following sentence settings are also valid + + msglen = makeUBXPacket(0x06, 0x08, sizeof(_message_1HZ), _message_1HZ); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x08, 400) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to set GPS update rate.\n"); + } + + msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_GLL), _message_GLL); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to disable NMEA GLL.\n"); + } + + msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_GSA), _message_GSA); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to Enable NMEA GSA.\n"); + } + + msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_GSV), _message_GSV); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to disable NMEA GSV.\n"); + } + + msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_VTG), _message_VTG); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to disable NMEA VTG.\n"); + } + + msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_RMC), _message_RMC); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable NMEA RMC.\n"); + } + + msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_GGA), _message_GGA); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable NMEA GGA.\n"); + } + clearBuffer(); + if (uBloxProtocolVersion >= 18) { + msglen = makeUBXPacket(0x06, 0x86, sizeof(_message_PMS), _message_PMS); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x86, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable powersaving for GPS.\n"); + } + // For M8 we want to enable NMEA vserion 4.10 so we can see the additional sats. + if (strncmp(info.hwVersion, "00080000", 8) == 0) { + msglen = makeUBXPacket(0x06, 0x17, sizeof(_message_NMEA), _message_NMEA); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x17, 400) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable NMEA 4.10.\n"); + } + } + + } else { + if (strncmp(info.hwVersion, "00040007", 8) == 0) { // This PSM mode is only for Neo-6 + msglen = makeUBXPacket(0x06, 0x11, 0x2, _message_CFG_RXM_ECO); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x11, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable powersaving ECO mode for Neo-6.\n"); + } + msglen = makeUBXPacket(0x06, 0x3B, 44, _message_CFG_PM2); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x3B, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable powersaving details for GPS.\n"); + } + msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_AID), _message_AID); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to disable UBX-AID.\n"); + } + } else { + msglen = makeUBXPacket(0x06, 0x11, 0x2, _message_CFG_RXM_PSM); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x11, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable powersaving mode for GPS.\n"); + } + } + } + + msglen = makeUBXPacket(0x06, 0x09, sizeof(_message_SAVE), _message_SAVE); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x09, 2000) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to save GNSS module configuration.\n"); + } else { + LOG_INFO("GNSS module configuration saved!\n"); + } } else { - LOG_INFO("GNSS module configuration saved!\n"); + LOG_INFO("u-blox M10 hardware found, using defaults for now\n"); } } didSerialInit = true; @@ -878,9 +910,9 @@ GnssModel_t GPS::probe(int serialSpeed) strncpy((char *)buffer, &(info.extension[i][4]), sizeof(buffer)); // LOG_DEBUG("GetModel:%s\n", (char *)buffer); if (strlen((char *)buffer)) { - LOG_INFO("UBlox GNSS init succeeded, using UBlox %s GNSS Module\n", (char *)buffer); + LOG_INFO("UBlox GNSS probe succeeded, using UBlox %s GNSS Module\n", (char *)buffer); } else { - LOG_INFO("UBlox GNSS init succeeded, using UBlox GNSS Module\n"); + LOG_INFO("UBlox GNSS probe succeeded, using UBlox GNSS Module\n"); } } else if (!strncmp(info.extension[i], "PROTVER", 7)) { char *ptr = nullptr; diff --git a/src/gps/GPS.h b/src/gps/GPS.h index 1b56c2ee4..15c355add 100644 --- a/src/gps/GPS.h +++ b/src/gps/GPS.h @@ -95,13 +95,17 @@ class GPS : private concurrency::OSThread static HardwareSerial *_serial_gps; static uint8_t _message_PMREQ[]; + static uint8_t _message_PMREQ_10[]; static const uint8_t _message_CFG_RXM_PSM[]; static const uint8_t _message_CFG_RXM_ECO[]; static const uint8_t _message_CFG_PM2[]; static const uint8_t _message_GNSS_7[]; - static const uint8_t _message_GNSS[]; - static const uint8_t _message_JAM[]; + static const uint8_t _message_GNSS_8[]; + static const uint8_t _message_JAM_6_7[]; + static const uint8_t _message_JAM_8[]; static const uint8_t _message_NAVX5[]; + static const uint8_t _message_NAVX5_8[]; + static const uint8_t _message_NMEA[]; static const uint8_t _message_1HZ[]; static const uint8_t _message_GLL[]; static const uint8_t _message_GSA[]; diff --git a/src/gps/ubx.h b/src/gps/ubx.h index 63558b536..4fff51d52 100644 --- a/src/gps/ubx.h +++ b/src/gps/ubx.h @@ -2,7 +2,15 @@ uint8_t GPS::_message_PMREQ[] PROGMEM = { 0x00, 0x00, // 4 bytes duration of request task 0x00, 0x00, // (milliseconds) 0x02, 0x00, // Task flag bitfield - 0x00, 0x00 // byte index 1 = sleep mode + 0x00, 0x00, // byte index 1 = sleep mode +}; + +uint8_t GPS::_message_PMREQ_10[] PROGMEM = { + 0x00, 0x00, // 4 bytes duration of request task + 0x00, 0x00, // (milliseconds) + 0x02, 0x00, // Task flag bitfield + 0x00, 0x00, // byte index 1 = sleep mode + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 // wakeupSources }; const uint8_t GPS::_message_CFG_RXM_PSM[] PROGMEM = { @@ -21,8 +29,8 @@ const uint8_t GPS::_message_CFG_PM2[] PROGMEM = { 0x00, // Reserved 1, set to 0x06 by u-Center 0x00, // Reserved 2 0x00, // Reserved 1 - 0x00, 0x11, 0x03, 0x00, // flags-> cyclic mode, wait for normal fix ok, do not wake to update RTC or EPH, doNotEnterOff, - // LimitPeakCurrent + 0x00, 0x11, 0x03, 0x00, // flags-> cyclic mode, wait for normal fix ok, do not wake to update RTC, doNotEnterOff, + // LimitPeakCurrent 0xE8, 0x03, 0x00, 0x00, // update period 1000 ms 0x10, 0x27, 0x00, 0x00, // search period 10s 0x00, 0x00, 0x00, 0x00, // Grid offset 0 @@ -54,36 +62,63 @@ const uint8_t GPS::_message_GNSS_7[] = { // to overwrite a saved state with identical values, no ACK/NAK is received, contrary to // what is specified in the Ublox documentation. // There is also a possibility that the module may be GPS-only. -const uint8_t GPS::_message_GNSS[] = { - 0x00, // msgVer (0 for this version) - 0x00, // numTrkChHw (max number of hardware channels, read only, so it's always 0) - 0xff, // numTrkChUse (max number of channels to use, 0xff = max available) - 0x03, // numConfigBlocks (number of GNSS systems), most modules support maximum 3 GNSS systems - // GNSS config format: gnssId, resTrkCh, maxTrkCh, reserved1, flags + +// For M8 GPS, GLONASS, Galileo, SBAS, QZSS +const uint8_t GPS::_message_GNSS_8[] = { + 0x00, // msgVer (0 for this version) + 0x00, // numTrkChHw (max number of hardware channels, read only, so it's always 0) + 0xff, // numTrkChUse (max number of channels to use, 0xff = max available) + 0x05, // numConfigBlocks (number of GNSS systems) + // GNSS config format: gnssId, resTrkCh, maxTrkCh, reserved1, flags 0x00, 0x08, 0x10, 0x00, 0x01, 0x00, 0x01, 0x01, // GPS 0x01, 0x01, 0x03, 0x00, 0x01, 0x00, 0x01, 0x01, // SBAS - 0x06, 0x08, 0x0e, 0x00, 0x01, 0x00, 0x01, 0x01 // GLONASS + 0x02, 0x04, 0x08, 0x00, 0x01, 0x00, 0x01, 0x01, // Galileo + 0x05, 0x00, 0x03, 0x00, 0x01, 0x00, 0x01, 0x01, // QZSS + 0x06, 0x08, 0x0E, 0x00, 0x01, 0x00, 0x01, 0x01 // GLONASS +}; +/* +// For M8 GPS, GLONASS, BeiDou, SBAS, QZSS +const uint8_t GPS::_message_GNSS_8_B[] = { + 0x00, // msgVer (0 for this version) + 0x00, // numTrkChHw (max number of hardware channels, read only, so it's always 0) + 0xff, // numTrkChUse (max number of channels to use, 0xff = max available) read only for protocol >23 + 0x05, // numConfigBlocks (number of GNSS systems) + // GNSS config format: gnssId, resTrkCh, maxTrkCh, reserved1, flags + 0x00, 0x08, 0x10, 0x00, 0x01, 0x00, 0x01, 0x01, // GPS + 0x01, 0x01, 0x03, 0x00, 0x01, 0x00, 0x01, 0x01, // SBAS + 0x03, 0x08, 0x10, 0x00, 0x01, 0x00, 0x01, 0x01, // BeiDou + 0x05, 0x00, 0x03, 0x00, 0x01, 0x00, 0x01, 0x01, // QZSS + 0x06, 0x08, 0x0E, 0x00, 0x01, 0x00, 0x01, 0x01 // GLONASS +}; +*/ + +// For M8 we want to enable NMEA version 4.10 messages to allow for Galileo and or BeiDou +const uint8_t GPS::_message_NMEA[]{ + 0x00, // filter flags + 0x41, // NMEA Version + 0x00, // Max number of SVs to report per TaklerId + 0x02, // flags + 0x00, 0x00, 0x00, 0x00, // gnssToFilter + 0x00, // svNumbering + 0x00, // mainTalkerId + 0x00, // gsvTalkerId + 0x01, // Message version + 0x00, 0x00, // bdsTalkerId 2 chars 0=default + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 // Reserved }; // Enable jamming/interference monitor -// For Neo-6 -const uint8_t GPS::_message_JAM[] = { - 0xf3, 0xac, 0x62, 0xad, // config1 bbThreshold = 3, cwThreshold = 15, enable = 1, reserved bits 0x16B156 - 0x1e, 0x03, 0x00, 0x00 // config2 antennaSetting Unknown = 0, reserved 3, = 0x00,0x00, reserved 2 = 0x31E -}; -/* // WIP GPS reconfig // For Neo-6, Max-7 and Neo-7 const uint8_t GPS::_message_JAM_6_7[] = { - 0xf3, 0xac, 0x62, 0xad, // config1 bbThreshold = 3, cwThreshold = 15, enable = 1, reserved bits 0x16B156 - 0x1e, 0x03, 0x00, 0x00 // config2 antennaSetting Unknown = 0, reserved 3, = 0x00,0x00, reserved 2 = 0x31E + 0xf3, 0xac, 0x62, 0xad, // config1 bbThreshold = 3, cwThreshold = 15, enable = 1, reserved bits 0x16B156 + 0x1e, 0x03, 0x00, 0x00 // config2 antennaSetting Unknown = 0, reserved 3, = 0x00,0x00, reserved 2 = 0x31E }; // For M8 const uint8_t GPS::_message_JAM_8[] = { - 0xf3, 0xac, 0x62, 0xad, // config1 bbThreshold = 3, cwThreshold = 15, enable1 = 1, reserved bits 0x16B156 - 0x1e, 0x43, 0x00, 0x00 // config2 antennaSetting Unknown = 0, enable2 = 1, generalBits = 0x31E + 0xf3, 0xac, 0x62, 0xad, // config1 bbThreshold = 3, cwThreshold = 15, enable1 = 1, reserved bits 0x16B156 + 0x1e, 0x43, 0x00, 0x00 // config2 antennaSetting Unknown = 0, enable2 = 1, generalBits = 0x31E }; -*/ // Configure navigation engine expert settings: // there are many variations of what were Reserved fields for the Neo-6 in later versions @@ -118,11 +153,38 @@ const uint8_t GPS::_message_NAVX5[] = { 0x00, 0x00, // Reserved 3 0x00, 0x00, 0x00, 0x00 // Reserved 4 }; +// For the M8 +const uint8_t GPS::_message_NAVX5_8[] = { + 0x02, 0x00, // msgVer (2 for this version) + 0x4c, 0x66, // mask1 + 0x00, 0x00, 0x00, 0x00, // mask2 + 0x00, 0x00, // Reserved 1 + 0x03, // minSVs (Minimum number of satellites for navigation) = 3 + 0x10, // maxSVs (Maximum number of satellites for navigation) = 16 + 0x06, // minCNO (Minimum satellite signal level for navigation) = 6 dBHz + 0x00, // Reserved 2 + 0x00, // iniFix3D (Initial fix must be 3D) (0 = false 1 = true) + 0x00, 0x00, // Reserved 3 + 0x00, // ackAiding + 0x00, 0x00, // wknRollover 0 = firmware default + 0x00, // sigAttenCompMode + 0x00, // Reserved 4 + 0x00, 0x00, // Reserved 5 + 0x00, 0x00, // Reserved 6 + 0x00, // usePPP (Precice Point Positioning) (0 = false, 1 = true) + 0x01, // aopCfg (AssistNow Autonomous configuration) = 1 (enabled) + 0x00, 0x00, // Reserved 7 + 0x00, 0x00, // aopOrbMaxErr = 0 to reset to firmware default + 0x00, 0x00, 0x00, 0x00, // Reserved 8 + 0x00, 0x00, 0x00, // Reserved 9 + 0x00 // useAdr +}; // Set GPS update rate to 1Hz // Lowering the update rate helps to save power. // Additionally, for some new modules like the M9/M10, an update rate lower than 5Hz // is recommended to avoid a known issue with satellites disappearing. +// The module defaults for M8, M9, M10 are the same as we use here so no update is necessary const uint8_t GPS::_message_1HZ[] = { 0xE8, 0x03, // Measurement Rate (1000ms for 1Hz) 0x01, 0x00, // Navigation rate, always 1 in GPS mode From 990ee5dacf202ad6d080f378e68173d9b4f553e5 Mon Sep 17 00:00:00 2001 From: Tommy Ekstrand Date: Thu, 8 Feb 2024 14:06:29 -0600 Subject: [PATCH 156/472] Update link to docs from webserver when file not found (#3175) --- src/mesh/http/ContentHandler.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/mesh/http/ContentHandler.cpp b/src/mesh/http/ContentHandler.cpp index 4ca37a256..7640e879c 100644 --- a/src/mesh/http/ContentHandler.cpp +++ b/src/mesh/http/ContentHandler.cpp @@ -398,7 +398,7 @@ void handleStatic(HTTPRequest *req, HTTPResponse *res) if (!file.available()) { LOG_WARN("File not available - %s\n", filenameGzip.c_str()); res->println("Web server is running.

The content you are looking for can't be found. Please see:
FAQ.

FAQ.

admin"); return; @@ -854,4 +854,4 @@ void handleScanNetworks(HTTPRequest *req, HTTPResponse *res) JSONValue *value = new JSONValue(jsonObjOuter); res->print(value->Stringify().c_str()); delete value; -} \ No newline at end of file +} From ca5795d3e7ebd06485fe3bfdf8f1c42c5ff04b6b Mon Sep 17 00:00:00 2001 From: code8buster <20384924+code8buster@users.noreply.github.com> Date: Thu, 8 Feb 2024 20:46:22 +0000 Subject: [PATCH 157/472] Fix init resolution for all architectures --- src/Power.cpp | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/src/Power.cpp b/src/Power.cpp index dc8a43d46..ffae81aec 100644 --- a/src/Power.cpp +++ b/src/Power.cpp @@ -389,11 +389,9 @@ bool Power::analogInit() #else analogReference(AR_INTERNAL); // 3.6V #endif - analogReadResolution(BATTERY_SENSE_RESOLUTION_BITS); // Default of 12 is not very linear. Recommended to use 10 or 11 - // depending on needed resolution. - #endif // ARCH_NRF52 - + analogReadResolution(BATTERY_SENSE_RESOLUTION_BITS); + batteryLevel = &analogLevel; return true; #else @@ -900,4 +898,4 @@ bool Power::axpChipInit() #else return false; #endif -} \ No newline at end of file +} From a3755dfce5ad0be58efa75105f2f878107fd3442 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 8 Feb 2024 14:56:46 -0600 Subject: [PATCH 158/472] Trunk fmt --- src/Power.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Power.cpp b/src/Power.cpp index ffae81aec..38f8ed771 100644 --- a/src/Power.cpp +++ b/src/Power.cpp @@ -391,7 +391,7 @@ bool Power::analogInit() #endif #endif // ARCH_NRF52 analogReadResolution(BATTERY_SENSE_RESOLUTION_BITS); - + batteryLevel = &analogLevel; return true; #else From a40b4e4d69c1ccbbdf0cf90ac1c8288a4b7defaf Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Thu, 8 Feb 2024 22:43:24 +0100 Subject: [PATCH 159/472] MQTT JSON downlink fixes (#3183) * Fix getting channel name from MQTT topic * Allow specifying channel index in JSON field "channel" for downlink Still requires JSON message to be published to channel named "mqtt" * Make non-breaking if someone adds another slash --- src/mqtt/MQTT.cpp | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 5eaf7f98d..8d7c329a2 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -52,11 +52,10 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length) JSONObject json; json = json_value->AsObject(); - // parse the channel name from the topic string - char *ptr = strtok(topic, "/"); - for (int i = 0; i < 3; i++) { - ptr = strtok(NULL, "/"); - } + // parse the channel name from the topic string by looking for "json/" + const char *jsonSlash = "json/"; + char *ptr = strstr(topic, jsonSlash) + sizeof(jsonSlash) + 1; // set pointer to after "json/" + ptr = strtok(ptr, "/") ? strtok(ptr, "/") : ptr; // if another "/" was added, parse string up to that character meshtastic_Channel sendChannel = channels.getByName(ptr); // We allow downlink JSON packets only on a channel named "mqtt" if (strncasecmp(channels.getGlobalId(sendChannel.index), Channels::mqttChannel, strlen(Channels::mqttChannel)) == 0 && @@ -70,7 +69,9 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length) // construct protobuf data packet using TEXT_MESSAGE, send it to the mesh meshtastic_MeshPacket *p = router->allocForSending(); p->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_APP; - p->channel = sendChannel.index; + if (json.find("channel") != json.end() && json["channel"]->IsNumber() && + (json["channel"]->AsNumber() < channels.getNumChannels())) + p->channel = json["channel"]->AsNumber(); if (json.find("to") != json.end() && json["to"]->IsNumber()) p->to = json["to"]->AsNumber(); if (jsonPayloadStr.length() <= sizeof(p->decoded.payload.bytes)) { @@ -98,7 +99,9 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length) // construct protobuf data packet using POSITION, send it to the mesh meshtastic_MeshPacket *p = router->allocForSending(); p->decoded.portnum = meshtastic_PortNum_POSITION_APP; - p->channel = sendChannel.index; + if (json.find("channel") != json.end() && json["channel"]->IsNumber() && + (json["channel"]->AsNumber() < channels.getNumChannels())) + p->channel = json["channel"]->AsNumber(); if (json.find("to") != json.end() && json["to"]->IsNumber()) p->to = json["to"]->AsNumber(); p->decoded.payload.size = From 996e72a81642100c1fe2ccd124a1250a04ddb5bd Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 8 Feb 2024 16:14:58 -0600 Subject: [PATCH 160/472] [create-pull-request] automated change (#3185) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/atak.pb.c | 29 +++ src/mesh/generated/meshtastic/atak.pb.h | 269 ++++++++++++++++++++ src/mesh/generated/meshtastic/config.pb.h | 2 +- src/mesh/generated/meshtastic/mesh.pb.h | 6 + src/mesh/generated/meshtastic/portnums.pb.h | 3 + 6 files changed, 309 insertions(+), 2 deletions(-) create mode 100644 src/mesh/generated/meshtastic/atak.pb.c create mode 100644 src/mesh/generated/meshtastic/atak.pb.h diff --git a/protobufs b/protobufs index b508d2e7c..1a25fb62c 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit b508d2e7ced34c752533eb02786e37402cc5a184 +Subproject commit 1a25fb62c92e946cb386b602e0fe3109b92dfe42 diff --git a/src/mesh/generated/meshtastic/atak.pb.c b/src/mesh/generated/meshtastic/atak.pb.c new file mode 100644 index 000000000..b0554c48c --- /dev/null +++ b/src/mesh/generated/meshtastic/atak.pb.c @@ -0,0 +1,29 @@ +/* Automatically generated nanopb constant definitions */ +/* Generated by nanopb-0.4.7 */ + +#include "meshtastic/atak.pb.h" +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +PB_BIND(meshtastic_TAKPacket, meshtastic_TAKPacket, 2) + + +PB_BIND(meshtastic_GeoChat, meshtastic_GeoChat, AUTO) + + +PB_BIND(meshtastic_Group, meshtastic_Group, AUTO) + + +PB_BIND(meshtastic_Status, meshtastic_Status, AUTO) + + +PB_BIND(meshtastic_Contact, meshtastic_Contact, AUTO) + + +PB_BIND(meshtastic_PLI, meshtastic_PLI, AUTO) + + + + + diff --git a/src/mesh/generated/meshtastic/atak.pb.h b/src/mesh/generated/meshtastic/atak.pb.h new file mode 100644 index 000000000..9a964702a --- /dev/null +++ b/src/mesh/generated/meshtastic/atak.pb.h @@ -0,0 +1,269 @@ +/* Automatically generated nanopb header */ +/* Generated by nanopb-0.4.7 */ + +#ifndef PB_MESHTASTIC_MESHTASTIC_ATAK_PB_H_INCLUDED +#define PB_MESHTASTIC_MESHTASTIC_ATAK_PB_H_INCLUDED +#include + +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +/* Enum definitions */ +typedef enum _meshtastic_Team { + /* Unspecifed */ + meshtastic_Team_Unspecifed_Color = 0, + /* White */ + meshtastic_Team_White = 1, + /* Yellow */ + meshtastic_Team_Yellow = 2, + /* Orange */ + meshtastic_Team_Orange = 3, + /* Magenta */ + meshtastic_Team_Magenta = 4, + /* Red */ + meshtastic_Team_Red = 5, + /* Maroon */ + meshtastic_Team_Maroon = 6, + /* Purple */ + meshtastic_Team_Purple = 7, + /* Dark Blue */ + meshtastic_Team_Dark_Blue = 8, + /* Blue */ + meshtastic_Team_Blue = 9, + /* Cyan */ + meshtastic_Team_Cyan = 10, + /* Teal */ + meshtastic_Team_Teal = 11, + /* Green */ + meshtastic_Team_Green = 12, + /* Dark Green */ + meshtastic_Team_Dark_Green = 13, + /* Brown */ + meshtastic_Team_Brown = 14 +} meshtastic_Team; + +/* Role of the group member */ +typedef enum _meshtastic_MemberRole { + /* Unspecifed */ + meshtastic_MemberRole_Unspecifed = 0, + /* Team Member */ + meshtastic_MemberRole_TeamMember = 1, + /* Team Lead */ + meshtastic_MemberRole_TeamLead = 2, + /* Headquarters */ + meshtastic_MemberRole_HQ = 3, + /* Airsoft enthusiast */ + meshtastic_MemberRole_Sniper = 4, + /* Medic */ + meshtastic_MemberRole_Medic = 5, + /* ForwardObserver */ + meshtastic_MemberRole_ForwardObserver = 6, + /* Radio Telephone Operator */ + meshtastic_MemberRole_RTO = 7, + /* Doggo */ + meshtastic_MemberRole_K9 = 8 +} meshtastic_MemberRole; + +/* Struct definitions */ +/* ATAK GeoChat message */ +typedef struct _meshtastic_GeoChat { + /* The text message */ + char message[200]; + /* Uid recipient of the message */ + pb_callback_t to; +} meshtastic_GeoChat; + +/* ATAK Group + <__group role='Team Member' name='Cyan'/> */ +typedef struct _meshtastic_Group { + /* Role of the group member */ + meshtastic_MemberRole role; + /* Team (color) + Default Cyan */ + meshtastic_Team team; +} meshtastic_Group; + +/* ATAK EUD Status + */ +typedef struct _meshtastic_Status { + /* Battery level */ + uint8_t battery; +} meshtastic_Status; + +/* ATAK Contact + */ +typedef struct _meshtastic_Contact { + /* Callsign */ + char callsign[120]; /* IP address of endpoint in integer form (0.0.0.0 default) */ +} meshtastic_Contact; + +/* Position Location Information from ATAK */ +typedef struct _meshtastic_PLI { + /* The new preferred location encoding, multiply by 1e-7 to get degrees + in floating point */ + int32_t latitude_i; + /* The new preferred location encoding, multiply by 1e-7 to get degrees + in floating point */ + int32_t longitude_i; + /* Altitude (ATAK prefers HAE) */ + uint32_t altitude; + /* Speed */ + uint32_t speed; + /* Course in degrees */ + uint16_t course; +} meshtastic_PLI; + +/* Packets for the official ATAK Plugin */ +typedef struct _meshtastic_TAKPacket { + /* Are the payloads strings compressed for LoRA transport? */ + bool is_compressed; + /* The contact / callsign for ATAK user */ + bool has_contact; + meshtastic_Contact contact; + /* The group for ATAK user */ + bool has_group; + meshtastic_Group group; + /* The status of the ATAK EUD */ + bool has_status; + meshtastic_Status status; + pb_size_t which_payload_variant; + union { + /* TAK position report */ + meshtastic_PLI pli; + /* ATAK GeoChat message */ + meshtastic_GeoChat chat; + } payload_variant; +} meshtastic_TAKPacket; + + +#ifdef __cplusplus +extern "C" { +#endif + +/* Helper constants for enums */ +#define _meshtastic_Team_MIN meshtastic_Team_Unspecifed_Color +#define _meshtastic_Team_MAX meshtastic_Team_Brown +#define _meshtastic_Team_ARRAYSIZE ((meshtastic_Team)(meshtastic_Team_Brown+1)) + +#define _meshtastic_MemberRole_MIN meshtastic_MemberRole_Unspecifed +#define _meshtastic_MemberRole_MAX meshtastic_MemberRole_K9 +#define _meshtastic_MemberRole_ARRAYSIZE ((meshtastic_MemberRole)(meshtastic_MemberRole_K9+1)) + + + +#define meshtastic_Group_role_ENUMTYPE meshtastic_MemberRole +#define meshtastic_Group_team_ENUMTYPE meshtastic_Team + + + + + +/* Initializer values for message structs */ +#define meshtastic_TAKPacket_init_default {0, false, meshtastic_Contact_init_default, false, meshtastic_Group_init_default, false, meshtastic_Status_init_default, 0, {meshtastic_PLI_init_default}} +#define meshtastic_GeoChat_init_default {"", {{NULL}, NULL}} +#define meshtastic_Group_init_default {_meshtastic_MemberRole_MIN, _meshtastic_Team_MIN} +#define meshtastic_Status_init_default {0} +#define meshtastic_Contact_init_default {""} +#define meshtastic_PLI_init_default {0, 0, 0, 0, 0} +#define meshtastic_TAKPacket_init_zero {0, false, meshtastic_Contact_init_zero, false, meshtastic_Group_init_zero, false, meshtastic_Status_init_zero, 0, {meshtastic_PLI_init_zero}} +#define meshtastic_GeoChat_init_zero {"", {{NULL}, NULL}} +#define meshtastic_Group_init_zero {_meshtastic_MemberRole_MIN, _meshtastic_Team_MIN} +#define meshtastic_Status_init_zero {0} +#define meshtastic_Contact_init_zero {""} +#define meshtastic_PLI_init_zero {0, 0, 0, 0, 0} + +/* Field tags (for use in manual encoding/decoding) */ +#define meshtastic_GeoChat_message_tag 1 +#define meshtastic_GeoChat_to_tag 2 +#define meshtastic_Group_role_tag 1 +#define meshtastic_Group_team_tag 2 +#define meshtastic_Status_battery_tag 1 +#define meshtastic_Contact_callsign_tag 1 +#define meshtastic_PLI_latitude_i_tag 1 +#define meshtastic_PLI_longitude_i_tag 2 +#define meshtastic_PLI_altitude_tag 3 +#define meshtastic_PLI_speed_tag 4 +#define meshtastic_PLI_course_tag 5 +#define meshtastic_TAKPacket_is_compressed_tag 1 +#define meshtastic_TAKPacket_contact_tag 2 +#define meshtastic_TAKPacket_group_tag 3 +#define meshtastic_TAKPacket_status_tag 4 +#define meshtastic_TAKPacket_pli_tag 5 +#define meshtastic_TAKPacket_chat_tag 6 + +/* Struct field encoding specification for nanopb */ +#define meshtastic_TAKPacket_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, BOOL, is_compressed, 1) \ +X(a, STATIC, OPTIONAL, MESSAGE, contact, 2) \ +X(a, STATIC, OPTIONAL, MESSAGE, group, 3) \ +X(a, STATIC, OPTIONAL, MESSAGE, status, 4) \ +X(a, STATIC, ONEOF, MESSAGE, (payload_variant,pli,payload_variant.pli), 5) \ +X(a, STATIC, ONEOF, MESSAGE, (payload_variant,chat,payload_variant.chat), 6) +#define meshtastic_TAKPacket_CALLBACK NULL +#define meshtastic_TAKPacket_DEFAULT NULL +#define meshtastic_TAKPacket_contact_MSGTYPE meshtastic_Contact +#define meshtastic_TAKPacket_group_MSGTYPE meshtastic_Group +#define meshtastic_TAKPacket_status_MSGTYPE meshtastic_Status +#define meshtastic_TAKPacket_payload_variant_pli_MSGTYPE meshtastic_PLI +#define meshtastic_TAKPacket_payload_variant_chat_MSGTYPE meshtastic_GeoChat + +#define meshtastic_GeoChat_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, STRING, message, 1) \ +X(a, CALLBACK, OPTIONAL, STRING, to, 2) +#define meshtastic_GeoChat_CALLBACK pb_default_field_callback +#define meshtastic_GeoChat_DEFAULT NULL + +#define meshtastic_Group_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, UENUM, role, 1) \ +X(a, STATIC, SINGULAR, UENUM, team, 2) +#define meshtastic_Group_CALLBACK NULL +#define meshtastic_Group_DEFAULT NULL + +#define meshtastic_Status_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, UINT32, battery, 1) +#define meshtastic_Status_CALLBACK NULL +#define meshtastic_Status_DEFAULT NULL + +#define meshtastic_Contact_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, STRING, callsign, 1) +#define meshtastic_Contact_CALLBACK NULL +#define meshtastic_Contact_DEFAULT NULL + +#define meshtastic_PLI_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, SFIXED32, latitude_i, 1) \ +X(a, STATIC, SINGULAR, SFIXED32, longitude_i, 2) \ +X(a, STATIC, SINGULAR, UINT32, altitude, 3) \ +X(a, STATIC, SINGULAR, UINT32, speed, 4) \ +X(a, STATIC, SINGULAR, UINT32, course, 5) +#define meshtastic_PLI_CALLBACK NULL +#define meshtastic_PLI_DEFAULT NULL + +extern const pb_msgdesc_t meshtastic_TAKPacket_msg; +extern const pb_msgdesc_t meshtastic_GeoChat_msg; +extern const pb_msgdesc_t meshtastic_Group_msg; +extern const pb_msgdesc_t meshtastic_Status_msg; +extern const pb_msgdesc_t meshtastic_Contact_msg; +extern const pb_msgdesc_t meshtastic_PLI_msg; + +/* Defines for backwards compatibility with code written before nanopb-0.4.0 */ +#define meshtastic_TAKPacket_fields &meshtastic_TAKPacket_msg +#define meshtastic_GeoChat_fields &meshtastic_GeoChat_msg +#define meshtastic_Group_fields &meshtastic_Group_msg +#define meshtastic_Status_fields &meshtastic_Status_msg +#define meshtastic_Contact_fields &meshtastic_Contact_msg +#define meshtastic_PLI_fields &meshtastic_PLI_msg + +/* Maximum encoded size of messages (where known) */ +/* meshtastic_TAKPacket_size depends on runtime parameters */ +/* meshtastic_GeoChat_size depends on runtime parameters */ +#define meshtastic_Contact_size 121 +#define meshtastic_Group_size 4 +#define meshtastic_PLI_size 26 +#define meshtastic_Status_size 3 + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index 1f1ff6a74..b06e9a707 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -836,4 +836,4 @@ extern const pb_msgdesc_t meshtastic_Config_BluetoothConfig_msg; } /* extern "C" */ #endif -#endif \ No newline at end of file +#endif diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index 57054a74e..998b64faa 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -127,6 +127,12 @@ typedef enum _meshtastic_HardwareModel { Lora module can be swapped out for a Heltec RA-62 which is "almost" pin compatible with one cut and one jumper Meshtastic works */ meshtastic_HardwareModel_CHATTER_2 = 56, + /* Heltec Wireless Paper, With ESP32-S3 CPU and E-Ink display + Older "V1.0" Variant, has no "version sticker" + E-Ink model is DEPG0213BNS800 + Tab on the screen protector is RED + Flex connector marking is FPC-7528B */ + meshtastic_HardwareModel_HELTEC_WIRELESS_PAPER_V1_0 = 57, /* ------------------------------------------------------------------------------------------------------------------------------------------ Reserved ID For developing private Ports. These will show up in live traffic sparsely, so we can use a high number. Keep it within 8 bits. ------------------------------------------------------------------------------------------------------------------------------------------ */ diff --git a/src/mesh/generated/meshtastic/portnums.pb.h b/src/mesh/generated/meshtastic/portnums.pb.h index 4fad85b86..88342e5dc 100644 --- a/src/mesh/generated/meshtastic/portnums.pb.h +++ b/src/mesh/generated/meshtastic/portnums.pb.h @@ -119,6 +119,9 @@ typedef enum _meshtastic_PortNum { /* Aggregates edge info for the network by sending out a list of each node's neighbors ENCODING: Protobuf */ meshtastic_PortNum_NEIGHBORINFO_APP = 71, + /* ATAK Plugin + Portnum for payloads from the official Meshtastic ATAK plugin */ + meshtastic_PortNum_ATAK_PLUGIN = 72, /* Private applications should use portnums >= 256. To simplify initial development and testing you can use "PRIVATE_APP" in your code without needing to rebuild protobuf files (via [regen-protos.sh](https://github.com/meshtastic/firmware/blob/master/bin/regen-protos.sh)) */ From 3b0169ba7a1b93f410bf924ab48fb1ceb7eaf831 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 8 Feb 2024 16:29:15 -0600 Subject: [PATCH 161/472] Adafruit display (#3179) * Use uint8_t instead of char in icon_bits * Add Adafruit PiTFT support --- bin/config-dist.yaml | 12 ++++++++++++ src/graphics/Screen.cpp | 2 +- src/graphics/TFTDisplay.cpp | 4 ++++ src/graphics/img/icon.xbm | 4 ++-- src/platform/portduino/PortduinoGlue.cpp | 4 ++++ src/platform/portduino/PortduinoGlue.h | 4 ++-- 6 files changed, 25 insertions(+), 5 deletions(-) diff --git a/bin/config-dist.yaml b/bin/config-dist.yaml index c48b0bf38..b5b105e4c 100644 --- a/bin/config-dist.yaml +++ b/bin/config-dist.yaml @@ -91,7 +91,19 @@ Display: # OffsetX: 0 # OffsetY: 0 +### Adafruit PiTFT 2.8 TFT+Touchscreen +# Panel: ILI9341 +# CS: 8 +# DC: 25 +# Backlight: 2 +# Width: 320 +# Height: 240 + Touchscreen: +# Module: STMPE610 +# CS: 7 +# IRQ: 24 + # Module: XPT2046 # CS: 7 # IRQ: 17 diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 82b511e6c..c0e55ea83 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -150,7 +150,7 @@ static void drawIconScreen(const char *upperMsg, OLEDDisplay *display, OLEDDispl // draw centered icon left to right and centered above the one line of app text display->drawXbm(x + (SCREEN_WIDTH - icon_width) / 2, y + (SCREEN_HEIGHT - FONT_HEIGHT_MEDIUM - icon_height) / 2 + 2, - icon_width, icon_height, (const uint8_t *)icon_bits); + icon_width, icon_height, icon_bits); display->setFont(FONT_MEDIUM); display->setTextAlignment(TEXT_ALIGN_LEFT); diff --git a/src/graphics/TFTDisplay.cpp b/src/graphics/TFTDisplay.cpp index b90328c05..ef3f6182c 100644 --- a/src/graphics/TFTDisplay.cpp +++ b/src/graphics/TFTDisplay.cpp @@ -354,6 +354,8 @@ class LGFX : public lgfx::LGFX_Device _panel_instance = new lgfx::Panel_ST7735; else if (settingsMap[displayPanel] == st7735s) _panel_instance = new lgfx::Panel_ST7735S; + else if (settingsMap[displayPanel] == ili9341) + _panel_instance = new lgfx::Panel_ILI9341; auto buscfg = _bus_instance.config(); buscfg.spi_mode = 0; @@ -379,6 +381,8 @@ class LGFX : public lgfx::LGFX_Device if (settingsMap[touchscreenModule]) { if (settingsMap[touchscreenModule] == xpt2046) { _touch_instance = new lgfx::Touch_XPT2046; + } else if (settingsMap[touchscreenModule] == stmpe610) { + _touch_instance = new lgfx::Touch_STMPE610; } auto touch_cfg = _touch_instance->config(); diff --git a/src/graphics/img/icon.xbm b/src/graphics/img/icon.xbm index 2b698e4c9..297f31ed6 100644 --- a/src/graphics/img/icon.xbm +++ b/src/graphics/img/icon.xbm @@ -1,6 +1,6 @@ #define icon_width 50 #define icon_height 28 -static char icon_bits[] = { +static uint8_t icon_bits[] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x03, 0x00, 0x03, 0x00, 0x00, 0x00, 0x80, 0x07, 0xC0, 0x07, 0x00, 0x00, 0x00, 0xC0, 0x1F, 0xC0, 0x0F, 0x00, 0x00, 0x00, 0xE0, 0x0F, 0xE0, 0x0F, 0x00, 0x00, 0x00, @@ -17,4 +17,4 @@ static char icon_bits[] = { 0xFE, 0x00, 0x00, 0xFC, 0x01, 0x7E, 0x00, 0x7F, 0x00, 0x00, 0xF8, 0x01, 0x7E, 0x00, 0x3E, 0x00, 0x00, 0xF8, 0x01, 0x38, 0x00, 0x3C, 0x00, 0x00, 0x70, 0x00, 0x10, 0x00, 0x10, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, }; + 0x00, 0x00, 0x00, 0x00, }; \ No newline at end of file diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index 71765c8e4..c8fcc3d13 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -169,6 +169,8 @@ void portduinoSetup() settingsMap[displayPanel] = st7735; else if (yamlConfig["Display"]["Panel"].as("") == "ST7735S") settingsMap[displayPanel] = st7735s; + else if (yamlConfig["Display"]["Panel"].as("") == "ILI9341") + settingsMap[displayPanel] = ili9341; settingsMap[displayHeight] = yamlConfig["Display"]["Height"].as(0); settingsMap[displayWidth] = yamlConfig["Display"]["Width"].as(0); settingsMap[displayDC] = yamlConfig["Display"]["DC"].as(-1); @@ -184,6 +186,8 @@ void portduinoSetup() if (yamlConfig["Touchscreen"]) { if (yamlConfig["Touchscreen"]["Module"].as("") == "XPT2046") settingsMap[touchscreenModule] = xpt2046; + else if (yamlConfig["Touchscreen"]["Module"].as("") == "STMPE610") + settingsMap[touchscreenModule] = stmpe610; settingsMap[touchscreenCS] = yamlConfig["Touchscreen"]["CS"].as(-1); settingsMap[touchscreenIRQ] = yamlConfig["Touchscreen"]["IRQ"].as(-1); } diff --git a/src/platform/portduino/PortduinoGlue.h b/src/platform/portduino/PortduinoGlue.h index 2cfd3fc48..f8da20e37 100644 --- a/src/platform/portduino/PortduinoGlue.h +++ b/src/platform/portduino/PortduinoGlue.h @@ -35,8 +35,8 @@ enum configNames { keyboardDevice, logoutputlevel }; -enum { no_screen, st7789, st7735, st7735s }; -enum { no_touchscreen, xpt2046 }; +enum { no_screen, st7789, st7735, st7735s, ili9341 }; +enum { no_touchscreen, xpt2046, stmpe610 }; enum { level_error, level_warn, level_info, level_debug }; extern std::map settingsMap; From 9d4c4f8bd145049503d2864ba27cb792669ba7e5 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 8 Feb 2024 18:57:23 -0600 Subject: [PATCH 162/472] [create-pull-request] automated change (#3186) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/atak.pb.h | 14 +++++++++----- 2 files changed, 10 insertions(+), 6 deletions(-) diff --git a/protobufs b/protobufs index 1a25fb62c..bdf9d6a81 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 1a25fb62c92e946cb386b602e0fe3109b92dfe42 +Subproject commit bdf9d6a81b06b919f4d01455a2eb766e30f1141c diff --git a/src/mesh/generated/meshtastic/atak.pb.h b/src/mesh/generated/meshtastic/atak.pb.h index 9a964702a..0ac6cb49f 100644 --- a/src/mesh/generated/meshtastic/atak.pb.h +++ b/src/mesh/generated/meshtastic/atak.pb.h @@ -95,7 +95,9 @@ typedef struct _meshtastic_Status { */ typedef struct _meshtastic_Contact { /* Callsign */ - char callsign[120]; /* IP address of endpoint in integer form (0.0.0.0 default) */ + char callsign[120]; + /* Device callsign */ + char device_callsign[120]; /* IP address of endpoint in integer form (0.0.0.0 default) */ } meshtastic_Contact; /* Position Location Information from ATAK */ @@ -164,13 +166,13 @@ extern "C" { #define meshtastic_GeoChat_init_default {"", {{NULL}, NULL}} #define meshtastic_Group_init_default {_meshtastic_MemberRole_MIN, _meshtastic_Team_MIN} #define meshtastic_Status_init_default {0} -#define meshtastic_Contact_init_default {""} +#define meshtastic_Contact_init_default {"", ""} #define meshtastic_PLI_init_default {0, 0, 0, 0, 0} #define meshtastic_TAKPacket_init_zero {0, false, meshtastic_Contact_init_zero, false, meshtastic_Group_init_zero, false, meshtastic_Status_init_zero, 0, {meshtastic_PLI_init_zero}} #define meshtastic_GeoChat_init_zero {"", {{NULL}, NULL}} #define meshtastic_Group_init_zero {_meshtastic_MemberRole_MIN, _meshtastic_Team_MIN} #define meshtastic_Status_init_zero {0} -#define meshtastic_Contact_init_zero {""} +#define meshtastic_Contact_init_zero {"", ""} #define meshtastic_PLI_init_zero {0, 0, 0, 0, 0} /* Field tags (for use in manual encoding/decoding) */ @@ -180,6 +182,7 @@ extern "C" { #define meshtastic_Group_team_tag 2 #define meshtastic_Status_battery_tag 1 #define meshtastic_Contact_callsign_tag 1 +#define meshtastic_Contact_device_callsign_tag 2 #define meshtastic_PLI_latitude_i_tag 1 #define meshtastic_PLI_longitude_i_tag 2 #define meshtastic_PLI_altitude_tag 3 @@ -226,7 +229,8 @@ X(a, STATIC, SINGULAR, UINT32, battery, 1) #define meshtastic_Status_DEFAULT NULL #define meshtastic_Contact_FIELDLIST(X, a) \ -X(a, STATIC, SINGULAR, STRING, callsign, 1) +X(a, STATIC, SINGULAR, STRING, callsign, 1) \ +X(a, STATIC, SINGULAR, STRING, device_callsign, 2) #define meshtastic_Contact_CALLBACK NULL #define meshtastic_Contact_DEFAULT NULL @@ -257,7 +261,7 @@ extern const pb_msgdesc_t meshtastic_PLI_msg; /* Maximum encoded size of messages (where known) */ /* meshtastic_TAKPacket_size depends on runtime parameters */ /* meshtastic_GeoChat_size depends on runtime parameters */ -#define meshtastic_Contact_size 121 +#define meshtastic_Contact_size 242 #define meshtastic_Group_size 4 #define meshtastic_PLI_size 26 #define meshtastic_Status_size 3 From 8130b1cf434513c8abd05c9781be901d75b38168 Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Fri, 9 Feb 2024 14:00:13 +1300 Subject: [PATCH 163/472] feat: initial support for Heltec Wireless Paper v1.0 (#3181) E-ink panel is DEPG0213BNS800. Otherwise, identical to v1.1 (?) Partial refresh supported, but not implemented in this commit. Co-authored-by: Ben Meadors --- src/graphics/EInkDisplay2.cpp | 57 +++++++++++++- src/graphics/EInkDisplay2.h | 5 ++ src/platform/esp32/architecture.h | 2 + .../heltec_wireless_paper_v1/pins_arduino.h | 78 +++++++++++++++++++ .../heltec_wireless_paper_v1/platformio.ini | 13 ++++ variants/heltec_wireless_paper_v1/variant.h | 54 +++++++++++++ 6 files changed, 208 insertions(+), 1 deletion(-) create mode 100644 variants/heltec_wireless_paper_v1/pins_arduino.h create mode 100644 variants/heltec_wireless_paper_v1/platformio.ini create mode 100644 variants/heltec_wireless_paper_v1/variant.h diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index 787b47e1f..09ea343e1 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -7,7 +7,7 @@ #include "main.h" #include -#ifdef HELTEC_WIRELESS_PAPER +#if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0) SPIClass *hspi = NULL; #endif @@ -48,6 +48,11 @@ SPIClass *hspi = NULL; #elif defined(HELTEC_WIRELESS_PAPER) // #define TECHO_DISPLAY_MODEL GxEPD2_213_T5D #define TECHO_DISPLAY_MODEL GxEPD2_213_FC1 + +#elif defined(HELTEC_WIRELESS_PAPER_V1_0) +// 2.13" 122x250 - DEPG0213BNS800 +#define TECHO_DISPLAY_MODEL GxEPD2_213_BN + #endif GxEPD2_BW *adafruitDisplay; @@ -70,6 +75,17 @@ EInkDisplay::EInkDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY // GxEPD2_154_M09 // setGeometry(GEOMETRY_RAWMODE, 200, 200); +#elif defined(HELTEC_WIRELESS_PAPER_V1_0) + + // The display's memory is actually 128px x 250px + // Setting the buffersize manually prevents 122/8 truncating to a 15 byte width + // (Or something like that..) + + this->geometry = GEOMETRY_RAWMODE; + this->displayWidth = 250; + this->displayHeight = 122; + this->displayBufferSize = 250 * (128 / 8); + #elif defined(HELTEC_WIRELESS_PAPER) // GxEPD2_213_BN - 2.13 inch b/w 250x122 setGeometry(GEOMETRY_RAWMODE, 250, 122); @@ -146,6 +162,8 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit) #elif defined(PCA10059) || defined(M5_COREINK) adafruitDisplay->nextPage(); +#elif defined(HELTEC_WIRELESS_PAPER_V1_0) + adafruitDisplay->nextPage(); #elif defined(HELTEC_WIRELESS_PAPER) adafruitDisplay->nextPage(); #elif defined(PRIVATE_HW) || defined(my) @@ -229,6 +247,43 @@ bool EInkDisplay::connect() (void)adafruitDisplay; } } + +#elif defined(HELTEC_WIRELESS_PAPER_V1_0) + { + // Is this a normal boot, or a wake from deep sleep? + esp_sleep_wakeup_cause_t wakeReason = esp_sleep_get_wakeup_cause(); + + // If waking from sleep, need to reverse rtc_gpio_isolate(), called in cpuDeepSleep() + // Otherwise, SPI won't work + if (wakeReason != ESP_SLEEP_WAKEUP_UNDEFINED) { + // HSPI + other display pins + rtc_gpio_hold_dis((gpio_num_t)PIN_EINK_SCLK); + rtc_gpio_hold_dis((gpio_num_t)PIN_EINK_DC); + rtc_gpio_hold_dis((gpio_num_t)PIN_EINK_RES); + rtc_gpio_hold_dis((gpio_num_t)PIN_EINK_BUSY); + rtc_gpio_hold_dis((gpio_num_t)PIN_EINK_CS); + rtc_gpio_hold_dis((gpio_num_t)PIN_EINK_MOSI); + } + + // Start HSPI + hspi = new SPIClass(HSPI); + hspi->begin(PIN_EINK_SCLK, -1, PIN_EINK_MOSI, PIN_EINK_CS); // SCLK, MISO, MOSI, SS + + // Enable VExt (ACTIVE LOW) + // Unsure if called elsewhere first? + delay(100); + pinMode(Vext, OUTPUT); + digitalWrite(Vext, LOW); + delay(100); + + // Create GxEPD2 objects + auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY, *hspi); + adafruitDisplay = new GxEPD2_BW(*lowLevel); + + // Init GxEPD2 + adafruitDisplay->init(); + adafruitDisplay->setRotation(3); + } #elif defined(HELTEC_WIRELESS_PAPER) { hspi = new SPIClass(HSPI); diff --git a/src/graphics/EInkDisplay2.h b/src/graphics/EInkDisplay2.h index 2529b1f0e..7bbf07069 100644 --- a/src/graphics/EInkDisplay2.h +++ b/src/graphics/EInkDisplay2.h @@ -2,6 +2,11 @@ #include +#if defined(HELTEC_WIRELESS_PAPER_V1_0) +// Re-enable SPI after deep sleep: rtc_gpio_hold_dis() +#include "driver/rtc_io.h" +#endif + /** * An adapter class that allows using the GxEPD2 library as if it was an OLEDDisplay implementation. * diff --git a/src/platform/esp32/architecture.h b/src/platform/esp32/architecture.h index e2c5fefbe..9fa4a5dd7 100644 --- a/src/platform/esp32/architecture.h +++ b/src/platform/esp32/architecture.h @@ -107,6 +107,8 @@ #define HW_VENDOR meshtastic_HardwareModel_HELTEC_WSL_V3 #elif defined(HELTEC_WIRELESS_TRACKER) #define HW_VENDOR meshtastic_HardwareModel_HELTEC_WIRELESS_TRACKER +#elif defined(HELTEC_WIRELESS_PAPER_V1_0) +#define HW_VENDOR meshtastic_HardwareModel_HELTEC_WIRELESS_PAPER_V1_0 #elif defined(HELTEC_WIRELESS_PAPER) #define HW_VENDOR meshtastic_HardwareModel_HELTEC_WIRELESS_PAPER #elif defined(TLORA_T3S3_V1) diff --git a/variants/heltec_wireless_paper_v1/pins_arduino.h b/variants/heltec_wireless_paper_v1/pins_arduino.h new file mode 100644 index 000000000..66d091691 --- /dev/null +++ b/variants/heltec_wireless_paper_v1/pins_arduino.h @@ -0,0 +1,78 @@ +#ifndef Pins_Arduino_h +#define Pins_Arduino_h + +#include + +#define WIFI_Kit_32 true +#define DISPLAY_HEIGHT 64 +#define DISPLAY_WIDTH 128 + +#define EXTERNAL_NUM_INTERRUPTS 16 +#define NUM_DIGITAL_PINS 40 +#define NUM_ANALOG_INPUTS 16 + +#define analogInputToDigitalPin(p) (((p) < 20) ? (analogChannelToDigitalPin(p)) : -1) +#define digitalPinToInterrupt(p) (((p) < 40) ? (p) : -1) +#define digitalPinHasPWM(p) (p < 34) + +static const uint8_t LED_BUILTIN = 35; +#define BUILTIN_LED LED_BUILTIN // backward compatibility +#define LED_BUILTIN LED_BUILTIN + +static const uint8_t KEY_BUILTIN = 0; + +static const uint8_t TX = 43; +static const uint8_t RX = 44; + +static const uint8_t SDA = 41; +static const uint8_t SCL = 42; + +static const uint8_t SS = 8; +static const uint8_t MOSI = 10; +static const uint8_t MISO = 11; +static const uint8_t SCK = 9; + +static const uint8_t A0 = 1; +static const uint8_t A1 = 2; +static const uint8_t A2 = 3; +static const uint8_t A3 = 4; +static const uint8_t A4 = 5; +static const uint8_t A5 = 6; +static const uint8_t A6 = 7; +static const uint8_t A7 = 8; +static const uint8_t A8 = 9; +static const uint8_t A9 = 10; +static const uint8_t A10 = 11; +static const uint8_t A11 = 12; +static const uint8_t A12 = 13; +static const uint8_t A13 = 14; +static const uint8_t A14 = 15; +static const uint8_t A15 = 16; +static const uint8_t A16 = 17; +static const uint8_t A17 = 18; +static const uint8_t A18 = 19; +static const uint8_t A19 = 20; + +static const uint8_t T1 = 1; +static const uint8_t T2 = 2; +static const uint8_t T3 = 3; +static const uint8_t T4 = 4; +static const uint8_t T5 = 5; +static const uint8_t T6 = 6; +static const uint8_t T7 = 7; +static const uint8_t T8 = 8; +static const uint8_t T9 = 9; +static const uint8_t T10 = 10; +static const uint8_t T11 = 11; +static const uint8_t T12 = 12; +static const uint8_t T13 = 13; +static const uint8_t T14 = 14; + +static const uint8_t Vext = 45; +static const uint8_t LED = 18; + +static const uint8_t RST_LoRa = 12; +static const uint8_t BUSY_LoRa = 13; +static const uint8_t DIO0 = 14; + +#endif /* Pins_Arduino_h */ diff --git a/variants/heltec_wireless_paper_v1/platformio.ini b/variants/heltec_wireless_paper_v1/platformio.ini new file mode 100644 index 000000000..7d7f4eb14 --- /dev/null +++ b/variants/heltec_wireless_paper_v1/platformio.ini @@ -0,0 +1,13 @@ +[env:heltec-wireless-paper-v1_0] +extends = esp32s3_base +board = heltec_wifi_lora_32_V3 +build_flags = + ${esp32s3_base.build_flags} + -I variants/heltec_wireless_paper_v1 + -D HELTEC_WIRELESS_PAPER_V1_0 +lib_deps = + ${esp32s3_base.lib_deps} + https://github.com/meshtastic/GxEPD2/ + adafruit/Adafruit BusIO@^1.13.2 + lewisxhe/PCF8563_Library@^1.0.1 +upload_speed = 115200 \ No newline at end of file diff --git a/variants/heltec_wireless_paper_v1/variant.h b/variants/heltec_wireless_paper_v1/variant.h new file mode 100644 index 000000000..4daf9a655 --- /dev/null +++ b/variants/heltec_wireless_paper_v1/variant.h @@ -0,0 +1,54 @@ +#define LED_PIN 18 + +// Enable bus for external periherals +#define I2C_SDA SDA +#define I2C_SCL SCL + +#define USE_EINK +/* + * eink display pins + */ +#define PIN_EINK_CS 4 +#define PIN_EINK_BUSY 7 +#define PIN_EINK_DC 5 +#define PIN_EINK_RES 6 +#define PIN_EINK_SCLK 3 +#define PIN_EINK_MOSI 2 + +/* + * SPI interfaces + */ +#define SPI_INTERFACES_COUNT 2 + +#define PIN_SPI_MISO 10 // MISO P0.17 +#define PIN_SPI_MOSI 11 // MOSI P0.15 +#define PIN_SPI_SCK 9 // SCK P0.13 + +#define VEXT_ENABLE 45 // active low, powers the oled display and the lora antenna boost +#define BUTTON_PIN 0 + +#define BATTERY_PIN 1 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage +#define ADC_CHANNEL ADC1_GPIO1_CHANNEL +#define ADC_ATTENUATION ADC_ATTEN_DB_2_5 // lower dB for high resistance voltage divider +#define ADC_MULTIPLIER 4.9 + +#define USE_SX1262 + +#define LORA_DIO0 -1 // a No connect on the SX1262 module +#define LORA_RESET 12 +#define LORA_DIO1 14 // SX1262 IRQ +#define LORA_DIO2 13 // SX1262 BUSY +#define LORA_DIO3 // Not connected on PCB, but internally on the TTGO SX1262, if DIO3 is high the TXCO is enabled + +#define LORA_SCK 9 +#define LORA_MISO 11 +#define LORA_MOSI 10 +#define LORA_CS 8 + +#define SX126X_CS LORA_CS +#define SX126X_DIO1 LORA_DIO1 +#define SX126X_BUSY LORA_DIO2 +#define SX126X_RESET LORA_RESET + +#define SX126X_DIO2_AS_RF_SWITCH +#define SX126X_DIO3_TCXO_VOLTAGE 1.8 From 54e52ae05fb495e07a4b1706d2ad73dc674d0d01 Mon Sep 17 00:00:00 2001 From: Manuel <71137295+mverch67@users.noreply.github.com> Date: Fri, 9 Feb 2024 19:06:56 +0100 Subject: [PATCH 164/472] Improved button-click accuracy (#3188) * IRQ triggers button fsm * revert change that causes raspbian compile-error --- boards/t-echo.json | 1 + src/ButtonThread.h | 22 +++++++++++++++++----- variants/t-echo/platformio.ini | 1 + 3 files changed, 19 insertions(+), 5 deletions(-) diff --git a/boards/t-echo.json b/boards/t-echo.json index 957ba01e3..c53132fda 100644 --- a/boards/t-echo.json +++ b/boards/t-echo.json @@ -9,6 +9,7 @@ "f_cpu": "64000000L", "hwids": [ ["0x239A", "0x4405"], + ["0x239A", "0x0029"], ["0x239A", "0x002A"] ], "usb_product": "TTGO_eink", diff --git a/src/ButtonThread.h b/src/ButtonThread.h index 66efd6004..20dc14cc4 100644 --- a/src/ButtonThread.h +++ b/src/ButtonThread.h @@ -54,15 +54,18 @@ class ButtonThread : public concurrency::OSThread if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) userButton = OneButton(settingsMap[user], true, true); #elif defined(BUTTON_PIN) - - userButton = OneButton(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN, true, true); + int pin = config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN; + userButton = OneButton(pin, true, true); #endif + #ifdef INPUT_PULLUP_SENSE // Some platforms (nrf52) have a SENSE variant which allows wake from sleep - override what OneButton did - pinMode(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN, INPUT_PULLUP_SENSE); + pinMode(pin, INPUT_PULLUP_SENSE); #endif userButton.attachClick(userButtonPressed); - userButton.setClickMs(300); + userButton.setClickMs(400); + userButton.setPressMs(1000); + userButton.setDebounceMs(10); userButton.attachDuringLongPress(userButtonPressedLong); userButton.attachDoubleClick(userButtonDoublePressed); userButton.attachMultiClick(userButtonMultiPressed); @@ -72,7 +75,15 @@ class ButtonThread : public concurrency::OSThread if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) wakeOnIrq(settingsMap[user], FALLING); #else - wakeOnIrq(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN, FALLING); + static OneButton *pBtn = &userButton; // only one instance of ButtonThread is created, so static is safe + attachInterrupt( + pin, + []() { + BaseType_t higherWake = 0; + mainDelay.interruptFromISR(&higherWake); + pBtn->tick(); + }, + CHANGE); #endif #endif #ifdef BUTTON_PIN_ALT @@ -194,6 +205,7 @@ class ButtonThread : public concurrency::OSThread { if (!config.device.disable_triple_click && (gps != nullptr)) { gps->toggleGpsMode(); + screen->forceDisplay(); } } diff --git a/variants/t-echo/platformio.ini b/variants/t-echo/platformio.ini index 2555032df..843bd88ff 100644 --- a/variants/t-echo/platformio.ini +++ b/variants/t-echo/platformio.ini @@ -6,6 +6,7 @@ debug_tool = jlink # add -DCFG_SYSVIEW if you want to use the Segger systemview tool for OS profiling. build_flags = ${nrf52840_base.build_flags} -Ivariants/t-echo + -DGPS_POWER_TOGGLE -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m4/fpv4-sp-d16-hard" build_src_filter = ${nrf52_base.build_src_filter} +<../variants/t-echo> lib_deps = From d246c47ae7f6b9dd3959b146d48b9cde33996937 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Fri, 9 Feb 2024 15:50:00 -0600 Subject: [PATCH 165/472] [create-pull-request] automated change (#3192) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/config.pb.h | 8 +++++--- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/protobufs b/protobufs index bdf9d6a81..99bd42baf 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit bdf9d6a81b06b919f4d01455a2eb766e30f1141c +Subproject commit 99bd42baf8dd2e8ca0eec70f05e1cf7f1a40a283 diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index b06e9a707..4047f7367 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -214,7 +214,9 @@ typedef enum _meshtastic_Config_LoRaConfig_RegionCode { /* Malaysia 433mhz */ meshtastic_Config_LoRaConfig_RegionCode_MY_433 = 16, /* Malaysia 919mhz */ - meshtastic_Config_LoRaConfig_RegionCode_MY_919 = 17 + meshtastic_Config_LoRaConfig_RegionCode_MY_919 = 17, + /* Singapore 923mhz */ + meshtastic_Config_LoRaConfig_RegionCode_SG_923 = 18 } meshtastic_Config_LoRaConfig_RegionCode; /* Standard predefined channel settings @@ -543,8 +545,8 @@ extern "C" { #define _meshtastic_Config_DisplayConfig_DisplayMode_ARRAYSIZE ((meshtastic_Config_DisplayConfig_DisplayMode)(meshtastic_Config_DisplayConfig_DisplayMode_COLOR+1)) #define _meshtastic_Config_LoRaConfig_RegionCode_MIN meshtastic_Config_LoRaConfig_RegionCode_UNSET -#define _meshtastic_Config_LoRaConfig_RegionCode_MAX meshtastic_Config_LoRaConfig_RegionCode_MY_919 -#define _meshtastic_Config_LoRaConfig_RegionCode_ARRAYSIZE ((meshtastic_Config_LoRaConfig_RegionCode)(meshtastic_Config_LoRaConfig_RegionCode_MY_919+1)) +#define _meshtastic_Config_LoRaConfig_RegionCode_MAX meshtastic_Config_LoRaConfig_RegionCode_SG_923 +#define _meshtastic_Config_LoRaConfig_RegionCode_ARRAYSIZE ((meshtastic_Config_LoRaConfig_RegionCode)(meshtastic_Config_LoRaConfig_RegionCode_SG_923+1)) #define _meshtastic_Config_LoRaConfig_ModemPreset_MIN meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST #define _meshtastic_Config_LoRaConfig_ModemPreset_MAX meshtastic_Config_LoRaConfig_ModemPreset_LONG_MODERATE From 74b90d35056e2577ec77bc8cfcc1058850f50e94 Mon Sep 17 00:00:00 2001 From: Andrew Yong Date: Sat, 10 Feb 2024 05:52:08 +0800 Subject: [PATCH 166/472] Add Singapore Region (#3165) Add 923MHz band for Singapore. Regulatory reference: https://www.imda.gov.sg/-/media/imda/files/regulation-licensing-and-consultations/ict-standards/telecommunication-standards/radio-comms/imdatssrd.pdf bands 30d. Co-authored-by: Ben Meadors --- src/mesh/RadioInterface.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/src/mesh/RadioInterface.cpp b/src/mesh/RadioInterface.cpp index fe39f9b55..cea3968ce 100644 --- a/src/mesh/RadioInterface.cpp +++ b/src/mesh/RadioInterface.cpp @@ -123,6 +123,13 @@ const RegionInfo regions[] = { */ RDEF(MY_919, 919.0f, 924.0f, 100, 0, 27, true, true, false), + /* + Singapore + SG_923 Band 30d: 917 - 925 MHz at 100mW, no restrictions. + https://www.imda.gov.sg/-/media/imda/files/regulation-licensing-and-consultations/ict-standards/telecommunication-standards/radio-comms/imdatssrd.pdf + */ + RDEF(SG_923, 917.0f, 925.0f, 100, 0, 20, true, false, false), + /* 2.4 GHZ WLAN Band equivalent. Only for SX128x chips. */ From bcbc2f229dadf8c8e2e7d2c4232cb74942a58e02 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Sat, 10 Feb 2024 00:36:16 +0100 Subject: [PATCH 167/472] Only cancel packet in Tx queue if it was already sent out via LoRa (#3191) To avoid canceling a transmission if it was already ACKed via MQTT Co-authored-by: Ben Meadors --- src/mesh/ReliableRouter.cpp | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/src/mesh/ReliableRouter.cpp b/src/mesh/ReliableRouter.cpp index 946a669cc..a1e9f281d 100644 --- a/src/mesh/ReliableRouter.cpp +++ b/src/mesh/ReliableRouter.cpp @@ -168,10 +168,14 @@ bool ReliableRouter::stopRetransmission(GlobalPacketId key) auto p = old->packet; auto numErased = pending.erase(key); assert(numErased == 1); - // remove the 'original' (identified by originator and packet->id) from the txqueue and free it - cancelSending(getFrom(p), p->id); - // now free the pooled copy for retransmission too - packetPool.release(p); + /* Only when we already transmitted a packet via LoRa, we will cancel the packet in the Tx queue + to avoid canceling a transmission if it was ACKed super fast via MQTT */ + if (old->numRetransmissions < NUM_RETRANSMISSIONS - 1) { + // remove the 'original' (identified by originator and packet->id) from the txqueue and free it + cancelSending(getFrom(p), p->id); + // now free the pooled copy for retransmission too + packetPool.release(p); + } return true; } else return false; From 1085b54069e426b592f7d458548de6e485f72c8b Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 9 Feb 2024 20:31:10 -0600 Subject: [PATCH 168/472] ATAK plugin (#3189) * WIP ATAK plugin message handling * Log * Update size and regen * Rework protos and remove compression * Track * Altitude * Protos * Protos and formatting * Add to column * Fixes / updates * Doh! * S * Refactoring and compression fixes --- src/mesh/MeshModule.cpp | 5 +- src/mesh/MeshModule.h | 27 +++---- src/mesh/ProtobufModule.h | 26 +++++++ src/modules/AtakPluginModule.cpp | 128 +++++++++++++++++++++++++++++++ src/modules/AtakPluginModule.h | 26 +++++++ src/modules/Modules.cpp | 3 +- 6 files changed, 195 insertions(+), 20 deletions(-) create mode 100644 src/modules/AtakPluginModule.cpp create mode 100644 src/modules/AtakPluginModule.h diff --git a/src/mesh/MeshModule.cpp b/src/mesh/MeshModule.cpp index a1e719721..9c6ca78ee 100644 --- a/src/mesh/MeshModule.cpp +++ b/src/mesh/MeshModule.cpp @@ -67,7 +67,7 @@ meshtastic_MeshPacket *MeshModule::allocErrorResponse(meshtastic_Routing_Error e return r; } -void MeshModule::callPlugins(const meshtastic_MeshPacket &mp, RxSource src) +void MeshModule::callPlugins(meshtastic_MeshPacket &mp, RxSource src) { // LOG_DEBUG("In call modules\n"); bool moduleFound = false; @@ -124,9 +124,10 @@ void MeshModule::callPlugins(const meshtastic_MeshPacket &mp, RxSource src) } else printPacket("packet on wrong channel, but can't respond", &mp); } else { - ProcessMessage handled = pi.handleReceived(mp); + pi.alterReceived(mp); + // Possibly send replies (but only if the message was directed to us specifically, i.e. not for promiscious // sniffing) also: we only let the one module send a reply, once that happens, remaining modules are not // considered diff --git a/src/mesh/MeshModule.h b/src/mesh/MeshModule.h index 323cc8595..ebe3af1a0 100644 --- a/src/mesh/MeshModule.h +++ b/src/mesh/MeshModule.h @@ -64,7 +64,7 @@ class MeshModule /** For use only by MeshService */ - static void callPlugins(const meshtastic_MeshPacket &mp, RxSource src = RX_SRC_RADIO); + static void callPlugins(meshtastic_MeshPacket &mp, RxSource src = RX_SRC_RADIO); static std::vector GetMeshModulesWithUIFrames(); static void observeUIEvents(Observer *observer); @@ -72,10 +72,7 @@ class MeshModule meshtastic_AdminMessage *request, meshtastic_AdminMessage *response); #if HAS_SCREEN - virtual void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) - { - return; - } + virtual void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) { return; } #endif protected: const char *name; @@ -135,10 +132,12 @@ class MeshModule @return ProcessMessage::STOP if you've guaranteed you've handled this message and no other handlers should be considered for it */ - virtual ProcessMessage handleReceived(const meshtastic_MeshPacket &mp) - { - return ProcessMessage::CONTINUE; - } + virtual ProcessMessage handleReceived(const meshtastic_MeshPacket &mp) { return ProcessMessage::CONTINUE; } + + /** Called to change a particular incoming message + This allows the module to change the message before it is passed through the rest of the call-chain. + */ + virtual void alterReceived(meshtastic_MeshPacket &mp) {} /** Messages can be received that have the want_response bit set. If set, this callback will be invoked * so that subclasses can (optionally) send a response back to the original sender. @@ -151,14 +150,8 @@ class MeshModule /*** * @return true if you want to be alloced a UI screen frame */ - virtual bool wantUIFrame() - { - return false; - } - virtual Observable *getUIFrameObservable() - { - return NULL; - } + virtual bool wantUIFrame() { return false; } + virtual Observable *getUIFrameObservable() { return NULL; } meshtastic_MeshPacket *allocAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex); diff --git a/src/mesh/ProtobufModule.h b/src/mesh/ProtobufModule.h index 1771f4322..d87bb47c3 100644 --- a/src/mesh/ProtobufModule.h +++ b/src/mesh/ProtobufModule.h @@ -30,6 +30,10 @@ template class ProtobufModule : protected SinglePortModule */ virtual bool handleReceivedProtobuf(const meshtastic_MeshPacket &mp, T *decoded) = 0; + /** Called to make changes to a particular incoming message + */ + virtual void alterReceivedProtobuf(meshtastic_MeshPacket &mp, T *decoded){}; + /** * Return a mesh packet which has been preinited with a particular protobuf data payload and port number. * You can then send this packet (after customizing any of the payload fields you might need) with @@ -86,4 +90,26 @@ template class ProtobufModule : protected SinglePortModule return handleReceivedProtobuf(mp, decoded) ? ProcessMessage::STOP : ProcessMessage::CONTINUE; } + + /** Called to alter a particular incoming message + */ + virtual void alterReceived(meshtastic_MeshPacket &mp) override + { + auto &p = mp.decoded; + + T scratch; + T *decoded = NULL; + if (mp.which_payload_variant == meshtastic_MeshPacket_decoded_tag && mp.decoded.portnum == ourPortNum) { + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(p.payload.bytes, p.payload.size, fields, &scratch)) { + decoded = &scratch; + } else { + LOG_ERROR("Error decoding protobuf module!\n"); + // if we can't decode it, nobody can process it! + return; + } + } + + return alterReceivedProtobuf(mp, decoded); + } }; \ No newline at end of file diff --git a/src/modules/AtakPluginModule.cpp b/src/modules/AtakPluginModule.cpp new file mode 100644 index 000000000..86e143811 --- /dev/null +++ b/src/modules/AtakPluginModule.cpp @@ -0,0 +1,128 @@ +#include "AtakPluginModule.h" +#include "MeshService.h" +#include "NodeDB.h" +#include "PowerFSM.h" +#include "configuration.h" +#include "main.h" +#include "meshtastic/atak.pb.h" + +extern "C" { +#include "mesh/compression/unishox2.h" +} + +AtakPluginModule *atakPluginModule; + +AtakPluginModule::AtakPluginModule() + : ProtobufModule("atak", meshtastic_PortNum_ATAK_PLUGIN, &meshtastic_TAKPacket_msg), concurrency::OSThread("AtakPluginModule") +{ + ourPortNum = meshtastic_PortNum_ATAK_PLUGIN; +} + +/* +Encompasses the full construction and sending packet to mesh +Will be used for broadcast. +*/ +int32_t AtakPluginModule::runOnce() +{ + return default_broadcast_interval_secs; +} + +bool AtakPluginModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_TAKPacket *r) +{ + return false; +} + +meshtastic_TAKPacket AtakPluginModule::cloneTAKPacketData(meshtastic_TAKPacket *t) +{ + meshtastic_TAKPacket clone = meshtastic_TAKPacket_init_zero; + if (t->has_group) { + clone.has_group = true; + clone.group = t->group; + } + if (t->has_status) { + clone.has_status = true; + clone.status = t->status; + } + if (t->has_contact) { + clone.has_contact = true; + clone.contact = {0}; + } + + if (t->which_payload_variant == meshtastic_TAKPacket_pli_tag) { + clone.which_payload_variant = meshtastic_TAKPacket_pli_tag; + clone.payload_variant.pli = t->payload_variant.pli; + } else if (t->which_payload_variant == meshtastic_TAKPacket_chat_tag) { + clone.which_payload_variant = meshtastic_TAKPacket_chat_tag; + clone.payload_variant.chat = {0}; + } + + return clone; +} + +void AtakPluginModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtastic_TAKPacket *t) +{ + // From Phone (EUD) + if (mp.from == 0) { + LOG_DEBUG("Received uncompressed TAK payload from phone with %d bytes\n", mp.decoded.payload.size); + // Compress for LoRA transport + auto compressed = cloneTAKPacketData(t); + compressed.is_compressed = true; + if (t->has_contact) { + auto length = unishox2_compress_simple(t->contact.callsign, strlen(t->contact.callsign), compressed.contact.callsign); + LOG_DEBUG("Uncompressed callsign '%s' - %d bytes\n", t->contact.callsign, strlen(t->contact.callsign)); + LOG_DEBUG("Compressed callsign '%s' - %d bytes\n", t->contact.callsign, length); + + length = unishox2_compress_simple(t->contact.device_callsign, strlen(t->contact.device_callsign), + compressed.contact.device_callsign); + LOG_DEBUG("Uncompressed device_callsign '%s' - %d bytes\n", t->contact.device_callsign, + strlen(t->contact.device_callsign)); + LOG_DEBUG("Compressed device_callsign '%s' - %d bytes\n", compressed.contact.device_callsign, length); + } + if (t->which_payload_variant == meshtastic_TAKPacket_chat_tag) { + auto length = unishox2_compress_simple(t->payload_variant.chat.message, strlen(t->payload_variant.chat.message), + compressed.payload_variant.chat.message); + LOG_DEBUG("Uncompressed chat message '%s' - %d bytes\n", t->payload_variant.chat.message, + strlen(t->payload_variant.chat.message)); + LOG_DEBUG("Compressed chat message '%s' - %d bytes\n", compressed.payload_variant.chat.message, length); + } + mp.decoded.payload.size = pb_encode_to_bytes(mp.decoded.payload.bytes, sizeof(mp.decoded.payload.bytes), + meshtastic_TAKPacket_fields, &compressed); + LOG_DEBUG("Final payload size of %d bytes\n", mp.decoded.payload.size); + } else { + if (!t->is_compressed) { + // Not compressed. Something is wrong + LOG_ERROR("Received uncompressed TAKPacket over radio!\n"); + return; + } + + // Decompress for Phone (EUD) + auto decompressedCopy = packetPool.allocCopy(mp); + auto uncompressed = cloneTAKPacketData(t); + uncompressed.is_compressed = false; + if (t->has_contact) { + auto length = + unishox2_decompress_simple(t->contact.callsign, strlen(t->contact.callsign), uncompressed.contact.callsign); + + LOG_DEBUG("Compressed callsign: %d bytes\n", strlen(t->contact.callsign)); + LOG_DEBUG("Decompressed callsign: '%s' @ %d bytes\n", uncompressed.contact.callsign, length); + + length = unishox2_decompress_simple(t->contact.device_callsign, strlen(t->contact.device_callsign), + uncompressed.contact.device_callsign); + + LOG_DEBUG("Compressed device_callsign: %d bytes\n", strlen(t->contact.device_callsign)); + LOG_DEBUG("Decompressed device_callsign: '%s' @ %d bytes\n", uncompressed.contact.device_callsign, length); + } + if (uncompressed.which_payload_variant == meshtastic_TAKPacket_chat_tag) { + auto length = unishox2_decompress_simple(t->payload_variant.chat.message, strlen(t->payload_variant.chat.message), + uncompressed.payload_variant.chat.message); + LOG_DEBUG("Compressed chat message: %d bytes\n", strlen(t->payload_variant.chat.message)); + LOG_DEBUG("Decompressed chat message: '%s' @ %d bytes\n", uncompressed.payload_variant.chat.message, length); + } + decompressedCopy->decoded.payload.size = + pb_encode_to_bytes(decompressedCopy->decoded.payload.bytes, sizeof(decompressedCopy->decoded.payload), + meshtastic_TAKPacket_fields, &uncompressed); + + service.sendToPhone(decompressedCopy); + } + return; +} \ No newline at end of file diff --git a/src/modules/AtakPluginModule.h b/src/modules/AtakPluginModule.h new file mode 100644 index 000000000..0470a3b32 --- /dev/null +++ b/src/modules/AtakPluginModule.h @@ -0,0 +1,26 @@ +#pragma once +#include "ProtobufModule.h" +#include "meshtastic/atak.pb.h" + +/** + * Waypoint message handling for meshtastic + */ +class AtakPluginModule : public ProtobufModule, private concurrency::OSThread +{ + public: + /** Constructor + * name is for debugging output + */ + AtakPluginModule(); + + protected: + virtual bool handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_TAKPacket *t) override; + virtual void alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtastic_TAKPacket *t) override; + /* Does our periodic broadcast */ + int32_t runOnce() override; + + private: + meshtastic_TAKPacket cloneTAKPacketData(meshtastic_TAKPacket *t); +}; + +extern AtakPluginModule *atakPluginModule; \ No newline at end of file diff --git a/src/modules/Modules.cpp b/src/modules/Modules.cpp index 37c7576f6..fd109b765 100644 --- a/src/modules/Modules.cpp +++ b/src/modules/Modules.cpp @@ -6,6 +6,7 @@ #include "input/cardKbI2cImpl.h" #include "input/kbMatrixImpl.h" #include "modules/AdminModule.h" +#include "modules/AtakPluginModule.h" #include "modules/CannedMessageModule.h" #include "modules/DetectionSensorModule.h" #include "modules/NeighborInfoModule.h" @@ -61,7 +62,7 @@ void setupModules() traceRouteModule = new TraceRouteModule(); neighborInfoModule = new NeighborInfoModule(); detectionSensorModule = new DetectionSensorModule(); - + atakPluginModule = new AtakPluginModule(); // Note: if the rest of meshtastic doesn't need to explicitly use your module, you do not need to assign the instance // to a global variable. From 514c19a68e8427d1be7cb713e4935d6b929053bc Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sat, 10 Feb 2024 14:16:46 -0600 Subject: [PATCH 169/472] [create-pull-request] automated change (#3198) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/atak.pb.c | 2 +- src/mesh/generated/meshtastic/atak.pb.h | 15 ++++++++------- 3 files changed, 10 insertions(+), 9 deletions(-) diff --git a/protobufs b/protobufs index 99bd42baf..1fa72525a 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 99bd42baf8dd2e8ca0eec70f05e1cf7f1a40a283 +Subproject commit 1fa72525a13117908a850d6754b5368eabdee163 diff --git a/src/mesh/generated/meshtastic/atak.pb.c b/src/mesh/generated/meshtastic/atak.pb.c index b0554c48c..1413b748e 100644 --- a/src/mesh/generated/meshtastic/atak.pb.c +++ b/src/mesh/generated/meshtastic/atak.pb.c @@ -9,7 +9,7 @@ PB_BIND(meshtastic_TAKPacket, meshtastic_TAKPacket, 2) -PB_BIND(meshtastic_GeoChat, meshtastic_GeoChat, AUTO) +PB_BIND(meshtastic_GeoChat, meshtastic_GeoChat, 2) PB_BIND(meshtastic_Group, meshtastic_Group, AUTO) diff --git a/src/mesh/generated/meshtastic/atak.pb.h b/src/mesh/generated/meshtastic/atak.pb.h index 0ac6cb49f..71c3c387f 100644 --- a/src/mesh/generated/meshtastic/atak.pb.h +++ b/src/mesh/generated/meshtastic/atak.pb.h @@ -71,7 +71,8 @@ typedef struct _meshtastic_GeoChat { /* The text message */ char message[200]; /* Uid recipient of the message */ - pb_callback_t to; + bool has_to; + char to[120]; } meshtastic_GeoChat; /* ATAK Group @@ -163,13 +164,13 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_TAKPacket_init_default {0, false, meshtastic_Contact_init_default, false, meshtastic_Group_init_default, false, meshtastic_Status_init_default, 0, {meshtastic_PLI_init_default}} -#define meshtastic_GeoChat_init_default {"", {{NULL}, NULL}} +#define meshtastic_GeoChat_init_default {"", false, ""} #define meshtastic_Group_init_default {_meshtastic_MemberRole_MIN, _meshtastic_Team_MIN} #define meshtastic_Status_init_default {0} #define meshtastic_Contact_init_default {"", ""} #define meshtastic_PLI_init_default {0, 0, 0, 0, 0} #define meshtastic_TAKPacket_init_zero {0, false, meshtastic_Contact_init_zero, false, meshtastic_Group_init_zero, false, meshtastic_Status_init_zero, 0, {meshtastic_PLI_init_zero}} -#define meshtastic_GeoChat_init_zero {"", {{NULL}, NULL}} +#define meshtastic_GeoChat_init_zero {"", false, ""} #define meshtastic_Group_init_zero {_meshtastic_MemberRole_MIN, _meshtastic_Team_MIN} #define meshtastic_Status_init_zero {0} #define meshtastic_Contact_init_zero {"", ""} @@ -213,8 +214,8 @@ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,chat,payload_variant.chat), #define meshtastic_GeoChat_FIELDLIST(X, a) \ X(a, STATIC, SINGULAR, STRING, message, 1) \ -X(a, CALLBACK, OPTIONAL, STRING, to, 2) -#define meshtastic_GeoChat_CALLBACK pb_default_field_callback +X(a, STATIC, OPTIONAL, STRING, to, 2) +#define meshtastic_GeoChat_CALLBACK NULL #define meshtastic_GeoChat_DEFAULT NULL #define meshtastic_Group_FIELDLIST(X, a) \ @@ -259,12 +260,12 @@ extern const pb_msgdesc_t meshtastic_PLI_msg; #define meshtastic_PLI_fields &meshtastic_PLI_msg /* Maximum encoded size of messages (where known) */ -/* meshtastic_TAKPacket_size depends on runtime parameters */ -/* meshtastic_GeoChat_size depends on runtime parameters */ #define meshtastic_Contact_size 242 +#define meshtastic_GeoChat_size 323 #define meshtastic_Group_size 4 #define meshtastic_PLI_size 26 #define meshtastic_Status_size 3 +#define meshtastic_TAKPacket_size 584 #ifdef __cplusplus } /* extern "C" */ From 404d0dda79543f39074abe0271afbe568dda83b3 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sat, 10 Feb 2024 14:20:04 -0600 Subject: [PATCH 170/472] Fix - Add GeoChat To field to payloads and handle compression (#3199) * WIP ATAK plugin message handling * Log * Update size and regen * Rework protos and remove compression * Track * Altitude * Protos * Protos and formatting * Add to column * Fixes / updates * Doh! * S * Refactoring and compression fixes * Fix missing (to) from ATAK geochat * Trunk * Explicitly set has_to * Fmt * Protobufs --- protobufs | 2 +- src/modules/AtakPluginModule.cpp | 17 +++++++++++++++++ 2 files changed, 18 insertions(+), 1 deletion(-) diff --git a/protobufs b/protobufs index 1fa72525a..99bd42baf 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 1fa72525a13117908a850d6754b5368eabdee163 +Subproject commit 99bd42baf8dd2e8ca0eec70f05e1cf7f1a40a283 diff --git a/src/modules/AtakPluginModule.cpp b/src/modules/AtakPluginModule.cpp index 86e143811..ffc4fe68a 100644 --- a/src/modules/AtakPluginModule.cpp +++ b/src/modules/AtakPluginModule.cpp @@ -84,6 +84,15 @@ void AtakPluginModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtast LOG_DEBUG("Uncompressed chat message '%s' - %d bytes\n", t->payload_variant.chat.message, strlen(t->payload_variant.chat.message)); LOG_DEBUG("Compressed chat message '%s' - %d bytes\n", compressed.payload_variant.chat.message, length); + + if (t->payload_variant.chat.has_to) { + compressed.payload_variant.chat.has_to = true; + length = unishox2_compress_simple(t->payload_variant.chat.to, strlen(t->payload_variant.chat.to), + compressed.payload_variant.chat.to); + LOG_DEBUG("Uncompressed chat to '%s' - %d bytes\n", t->payload_variant.chat.to, + strlen(t->payload_variant.chat.to)); + LOG_DEBUG("Compressed chat to '%s' - %d bytes\n", compressed.payload_variant.chat.to, length); + } } mp.decoded.payload.size = pb_encode_to_bytes(mp.decoded.payload.bytes, sizeof(mp.decoded.payload.bytes), meshtastic_TAKPacket_fields, &compressed); @@ -117,6 +126,14 @@ void AtakPluginModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtast uncompressed.payload_variant.chat.message); LOG_DEBUG("Compressed chat message: %d bytes\n", strlen(t->payload_variant.chat.message)); LOG_DEBUG("Decompressed chat message: '%s' @ %d bytes\n", uncompressed.payload_variant.chat.message, length); + + if (t->payload_variant.chat.has_to) { + uncompressed.payload_variant.chat.has_to = true; + length = unishox2_decompress_simple(t->payload_variant.chat.to, strlen(t->payload_variant.chat.to), + uncompressed.payload_variant.chat.to); + LOG_DEBUG("Compressed chat to: %d bytes\n", strlen(t->payload_variant.chat.to)); + LOG_DEBUG("Decompressed chat to: '%s' @ %d bytes\n", uncompressed.payload_variant.chat.to, length); + } } decompressedCopy->decoded.payload.size = pb_encode_to_bytes(decompressedCopy->decoded.payload.bytes, sizeof(decompressedCopy->decoded.payload), From 13c8dca6b47809110f5ae4c9936e1961429a5cba Mon Sep 17 00:00:00 2001 From: Huston Hedinger <1875033+hdngr@users.noreply.github.com> Date: Sat, 10 Feb 2024 15:55:32 -0800 Subject: [PATCH 171/472] [BOARD]: CanaryOne (#3150) * compiling w/o e-ink display * pinout changes * progress getting LoRa and LCD working * fix for bootloader, gps pins * add canary to build matrix * merge with main * fix build by excluding BellModem in RadioLib * fixes for GPS * Fix LED_BLUE and GPS RX/TX pins * Variant changes for merge * make GPS baud rate configurable * fix debug config * Canary v1.2 changes * Fixes for GPS * pass trunk check * bump protobufs to master * update build flags to use CANARYONE enum * use canaryone throughout for consistency. * #define 0 is still defined * add back .vscode/extensions.json * bump protobufs * revert manual change to generated file --------- Co-authored-by: Steven Osborn --- .github/workflows/main_matrix.yml | 1 + bin/check-all.sh | 2 +- bin/check-dependencies.sh | 8 +- boards/canaryone.json | 49 ++++++++ boards/eink0.1.json | 3 +- boards/lora-relay-v1.json | 3 +- boards/lora-relay-v2.json | 3 +- boards/lora_isp4520.json | 3 +- boards/nordic_pca10059.json | 3 +- boards/nrf52840_dk.json | 3 +- boards/nrf52840_dk_modified.json | 3 +- boards/ppr.json | 3 +- boards/ppr1.json | 3 +- boards/t-echo.json | 3 +- boards/wiscore_rak4600.json | 3 +- boards/wiscore_rak4631.json | 3 +- boards/xiao_ble_sense.json | 3 +- platformio.ini | 2 + src/DebugConfiguration.h | 2 +- src/configuration.h | 14 ++- src/modules/SerialModule.cpp | 6 +- src/platform/nrf52/architecture.h | 2 + variants/canaryone/platformio.ini | 15 +++ variants/canaryone/variant.cpp | 56 +++++++++ variants/canaryone/variant.h | 188 ++++++++++++++++++++++++++++++ 25 files changed, 361 insertions(+), 23 deletions(-) create mode 100644 boards/canaryone.json create mode 100644 variants/canaryone/platformio.ini create mode 100644 variants/canaryone/variant.cpp create mode 100644 variants/canaryone/variant.h diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index af40d95b6..d18fd2b2d 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -112,6 +112,7 @@ jobs: - board: rak4631_eink - board: monteops_hw1 - board: t-echo + - board: canaryone - board: pca10059_diy_eink - board: feather_diy - board: nano-g2-ultra diff --git a/bin/check-all.sh b/bin/check-all.sh index 1475ac3ee..cdd1ceb9d 100755 --- a/bin/check-all.sh +++ b/bin/check-all.sh @@ -13,7 +13,7 @@ if [[ $# -gt 0 ]]; then # can override which environment by passing arg BOARDS="$@" else - BOARDS="tlora-v2 tlora-v1 tlora_v1_3 tlora-v2-1-1.6 tbeam heltec-v1 heltec-v2.0 heltec-v2.1 tbeam0.7 meshtastic-diy-v1 rak4631 rak4631_eink rak11200 t-echo pca10059_diy_eink" + BOARDS="tlora-v2 tlora-v1 tlora_v1_3 tlora-v2-1-1.6 tbeam heltec-v1 heltec-v2.0 heltec-v2.1 tbeam0.7 meshtastic-diy-v1 rak4631 rak4631_eink rak11200 t-echo canaryone pca10059_diy_eink" fi echo "BOARDS:${BOARDS}" diff --git a/bin/check-dependencies.sh b/bin/check-dependencies.sh index 27372487f..52bc76089 100644 --- a/bin/check-dependencies.sh +++ b/bin/check-dependencies.sh @@ -5,17 +5,17 @@ set -e if [[ $# -gt 0 ]]; then - # can override which environment by passing arg - BOARDS="$@" + # can override which environment by passing arg + BOARDS="$@" else - BOARDS="rak4631 rak4631_eink t-echo pca10059_diy_eink pico rak11200 tlora-v2 tlora-v1 tlora_v1_3 tlora-v2-1-1.6 tbeam heltec-v1 heltec-v2.0 heltec-v2.1 tbeam0.7 meshtastic-diy-v1 nano-g1 station-g1 m5stack-core m5stack-coreink tbeam-s3-core" + BOARDS="rak4631 rak4631_eink t-echo canaryone pca10059_diy_eink pico rak11200 tlora-v2 tlora-v1 tlora_v1_3 tlora-v2-1-1.6 tbeam heltec-v1 heltec-v2.0 heltec-v2.1 tbeam0.7 meshtastic-diy-v1 nano-g1 station-g1 m5stack-core m5stack-coreink tbeam-s3-core" fi echo "BOARDS:${BOARDS}" CHECK="" for BOARD in $BOARDS; do - CHECK="${CHECK} -e ${BOARD}" + CHECK="${CHECK} -e ${BOARD}" done echo $CHECK diff --git a/boards/canaryone.json b/boards/canaryone.json new file mode 100644 index 000000000..d8f966a47 --- /dev/null +++ b/boards/canaryone.json @@ -0,0 +1,49 @@ +{ + "build": { + "arduino": { + "ldscript": "nrf52840_s140_v6.ld" + }, + "core": "nRF5", + "cpu": "cortex-m4", + "extra_flags": "-DARDUINO_NRF52840_CANARY -DNRF52840_XXAA", + "f_cpu": "64000000L", + "hwids": [["0x239A", "0x4405"]], + "usb_product": "CanaryOne", + "mcu": "nrf52840", + "variant": "canaryone", + "variants_dir": "variants", + "bsp": { + "name": "adafruit" + }, + "softdevice": { + "sd_flags": "-DS140", + "sd_name": "s140", + "sd_version": "6.1.1", + "sd_fwid": "0x00B6" + }, + "bootloader": { + "settings_addr": "0xFF000" + } + }, + "connectivity": ["bluetooth"], + "debug": { + "jlink_device": "nRF52840_xxAA", + "onboard_tools": ["jlink"], + "svd_path": "nrf52840.svd", + "openocd_target": "nrf52840-mdk-rs" + }, + "frameworks": ["arduino"], + "name": "Canary (Adafruit BSP)", + "upload": { + "maximum_ram_size": 248832, + "maximum_size": 815104, + "speed": 115200, + "protocol": "nrfutil", + "protocols": ["jlink", "nrfjprog", "nrfutil", "stlink"], + "use_1200bps_touch": true, + "require_upload_port": true, + "wait_for_upload_port": true + }, + "url": "https://canaryradio.io/", + "vendor": "Canary Radio Company" +} diff --git a/boards/eink0.1.json b/boards/eink0.1.json index 28862c5d4..cb636ea3f 100644 --- a/boards/eink0.1.json +++ b/boards/eink0.1.json @@ -29,7 +29,8 @@ "debug": { "jlink_device": "nRF52840_xxAA", "onboard_tools": ["jlink"], - "svd_path": "nrf52840.svd" + "svd_path": "nrf52840.svd", + "openocd_target": "nrf52840-mdk-rs" }, "frameworks": ["arduino"], "name": "TTGO eink (Adafruit BSP)", diff --git a/boards/lora-relay-v1.json b/boards/lora-relay-v1.json index ca4e2f0ab..b390b8404 100644 --- a/boards/lora-relay-v1.json +++ b/boards/lora-relay-v1.json @@ -29,7 +29,8 @@ "debug": { "jlink_device": "nRF52840_xxAA", "onboard_tools": ["jlink"], - "svd_path": "nrf52840.svd" + "svd_path": "nrf52840.svd", + "openocd_target": "nrf52840-mdk-rs" }, "frameworks": ["arduino"], "name": "Meshtastic Lora Relay V1 (Adafruit BSP)", diff --git a/boards/lora-relay-v2.json b/boards/lora-relay-v2.json index 2cca8ae9a..52b775e58 100644 --- a/boards/lora-relay-v2.json +++ b/boards/lora-relay-v2.json @@ -29,7 +29,8 @@ "debug": { "jlink_device": "nRF52840_xxAA", "onboard_tools": ["jlink"], - "svd_path": "nrf52840.svd" + "svd_path": "nrf52840.svd", + "openocd_target": "nrf52840-mdk-rs" }, "frameworks": ["arduino"], "name": "Meshtastic Lora Relay V1 (Adafruit BSP)", diff --git a/boards/lora_isp4520.json b/boards/lora_isp4520.json index 971512b28..8125aa666 100644 --- a/boards/lora_isp4520.json +++ b/boards/lora_isp4520.json @@ -22,7 +22,8 @@ "connectivity": ["bluetooth"], "debug": { "jlink_device": "nRF52832_xxAA", - "svd_path": "nrf52.svd" + "svd_path": "nrf52.svd", + "openocd_target": "nrf52840-mdk-rs" }, "frameworks": ["arduino"], "name": "lora ISP4520", diff --git a/boards/nordic_pca10059.json b/boards/nordic_pca10059.json index 214c2851d..b99e3c763 100644 --- a/boards/nordic_pca10059.json +++ b/boards/nordic_pca10059.json @@ -32,7 +32,8 @@ "connectivity": ["bluetooth"], "debug": { "jlink_device": "nRF52840_xxAA", - "svd_path": "nrf52840.svd" + "svd_path": "nrf52840.svd", + "openocd_target": "nrf52840-mdk-rs" }, "frameworks": ["arduino"], "name": "nRF52840 Dongle", diff --git a/boards/nrf52840_dk.json b/boards/nrf52840_dk.json index 8d07575bf..8a16e854f 100644 --- a/boards/nrf52840_dk.json +++ b/boards/nrf52840_dk.json @@ -29,7 +29,8 @@ "debug": { "jlink_device": "nRF52840_xxAA", "onboard_tools": ["jlink"], - "svd_path": "nrf52840.svd" + "svd_path": "nrf52840.svd", + "openocd_target": "nrf52840-mdk-rs" }, "frameworks": ["arduino"], "name": "A modified NRF52840-DK devboard (Adafruit BSP)", diff --git a/boards/nrf52840_dk_modified.json b/boards/nrf52840_dk_modified.json index 0462c55f8..2932cb4b9 100644 --- a/boards/nrf52840_dk_modified.json +++ b/boards/nrf52840_dk_modified.json @@ -29,7 +29,8 @@ "debug": { "jlink_device": "nRF52840_xxAA", "onboard_tools": ["jlink"], - "svd_path": "nrf52840.svd" + "svd_path": "nrf52840.svd", + "openocd_target": "nrf52840-mdk-rs" }, "frameworks": ["arduino"], "name": "A modified NRF52840-DK devboard (Adafruit BSP)", diff --git a/boards/ppr.json b/boards/ppr.json index 5283fdc4e..15e3025c0 100644 --- a/boards/ppr.json +++ b/boards/ppr.json @@ -29,7 +29,8 @@ "debug": { "jlink_device": "nRF52840_xxAA", "onboard_tools": ["jlink"], - "svd_path": "nrf52840.svd" + "svd_path": "nrf52840.svd", + "openocd_target": "nrf52840-mdk-rs" }, "frameworks": ["arduino"], "name": "Meshtastic PPR (Adafruit BSP)", diff --git a/boards/ppr1.json b/boards/ppr1.json index 4c0528245..35bf7d1e4 100644 --- a/boards/ppr1.json +++ b/boards/ppr1.json @@ -29,7 +29,8 @@ "debug": { "jlink_device": "nRF52833_xxAA", "onboard_tools": ["jlink"], - "svd_path": "nrf52833.svd" + "svd_path": "nrf52833.svd", + "openocd_target": "nrf52840-mdk-rs" }, "frameworks": ["arduino"], "name": "Meshtastic PPR1 (Adafruit BSP)", diff --git a/boards/t-echo.json b/boards/t-echo.json index c53132fda..fcfc8c50b 100644 --- a/boards/t-echo.json +++ b/boards/t-echo.json @@ -33,7 +33,8 @@ "debug": { "jlink_device": "nRF52840_xxAA", "onboard_tools": ["jlink"], - "svd_path": "nrf52840.svd" + "svd_path": "nrf52840.svd", + "openocd_target": "nrf52840-mdk-rs" }, "frameworks": ["arduino"], "name": "TTGO eink (Adafruit BSP)", diff --git a/boards/wiscore_rak4600.json b/boards/wiscore_rak4600.json index 9969ef26e..0dec90a79 100644 --- a/boards/wiscore_rak4600.json +++ b/boards/wiscore_rak4600.json @@ -32,7 +32,8 @@ "connectivity": ["bluetooth"], "debug": { "jlink_device": "nRF52832_xxAA", - "svd_path": "nrf52.svd" + "svd_path": "nrf52.svd", + "openocd_target": "nrf52840-mdk-rs" }, "frameworks": ["arduino", "zephyr"], "name": "Adafruit Bluefruit nRF52832 Feather", diff --git a/boards/wiscore_rak4631.json b/boards/wiscore_rak4631.json index 149492688..6dec3f7cb 100644 --- a/boards/wiscore_rak4631.json +++ b/boards/wiscore_rak4631.json @@ -32,7 +32,8 @@ "connectivity": ["bluetooth"], "debug": { "jlink_device": "nRF52840_xxAA", - "svd_path": "nrf52840.svd" + "svd_path": "nrf52840.svd", + "openocd_target": "nrf52840-mdk-rs" }, "frameworks": ["arduino"], "name": "WisCore RAK4631 Board", diff --git a/boards/xiao_ble_sense.json b/boards/xiao_ble_sense.json index 09a28c25d..8e0212b3e 100644 --- a/boards/xiao_ble_sense.json +++ b/boards/xiao_ble_sense.json @@ -31,7 +31,8 @@ "connectivity": ["bluetooth"], "debug": { "jlink_device": "nRF52840_xxAA", - "svd_path": "nrf52840.svd" + "svd_path": "nrf52840.svd", + "openocd_target": "nrf52840-mdk-rs" }, "frameworks": ["arduino"], "name": "Seeed Xiao BLE Sense", diff --git a/platformio.ini b/platformio.ini index 51106cdac..0033b6e46 100644 --- a/platformio.ini +++ b/platformio.ini @@ -19,6 +19,7 @@ default_envs = tbeam ;default_envs = tlora-t3s3-v1 ;default_envs = lora-relay-v1 # nrf board ;default_envs = t-echo +;default_envs = canaryone ;default_envs = nrf52840dk-geeksville ;default_envs = native # lora-relay-v1 # nrf52840dk-geeksville # linux # or if you'd like to change the default to something like lora-relay-v1 put that here ;default_envs = nano-g1 @@ -57,6 +58,7 @@ build_flags = -Wno-missing-field-initializers -DRADIOLIB_EXCLUDE_SI443X -DRADIOLIB_EXCLUDE_RFM2X -DRADIOLIB_EXCLUDE_AFSK + -DRADIOLIB_EXCLUDE_BELL -DRADIOLIB_EXCLUDE_HELLSCHREIBER -DRADIOLIB_EXCLUDE_MORSE -DRADIOLIB_EXCLUDE_RTTY diff --git a/src/DebugConfiguration.h b/src/DebugConfiguration.h index 59ce043bc..f0686b811 100644 --- a/src/DebugConfiguration.h +++ b/src/DebugConfiguration.h @@ -28,7 +28,7 @@ #define DEBUG_PORT (*console) // Serial debug port #ifdef USE_SEGGER -#define DEBUG_PORT +// #undef DEBUG_PORT #define LOG_DEBUG(...) SEGGER_RTT_printf(0, __VA_ARGS__) #define LOG_INFO(...) SEGGER_RTT_printf(0, __VA_ARGS__) #define LOG_WARN(...) SEGGER_RTT_printf(0, __VA_ARGS__) diff --git a/src/configuration.h b/src/configuration.h index cb7ee218b..d8b0dba5f 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -142,8 +142,9 @@ along with this program. If not, see . // ----------------------------------------------------------------------------- // GPS // ----------------------------------------------------------------------------- - +#ifndef GPS_BAUDRATE #define GPS_BAUDRATE 9600 +#endif #ifndef GPS_THREAD_INTERVAL #define GPS_THREAD_INTERVAL 200 @@ -161,6 +162,17 @@ along with this program. If not, see . /* Step #3: mop up with disabled values for HAS_ options not handled by the above two */ +// ----------------------------------------------------------------------------- +// GPS +// ----------------------------------------------------------------------------- + +#ifndef GPS_BAUDRATE +#define GPS_BAUDRATE 9600 +#endif +#ifndef GPS_THREAD_INTERVAL +#define GPS_THREAD_INTERVAL 100 +#endif + #ifndef HAS_WIFI #define HAS_WIFI 0 #endif diff --git a/src/modules/SerialModule.cpp b/src/modules/SerialModule.cpp index 42b109050..820e1fb62 100644 --- a/src/modules/SerialModule.cpp +++ b/src/modules/SerialModule.cpp @@ -58,7 +58,7 @@ SerialModule *serialModule; SerialModuleRadio *serialModuleRadio; -#ifdef TTGO_T_ECHO +#if defined(TTGO_T_ECHO) || defined(CANARYONE) SerialModule::SerialModule() : StreamAPI(&Serial), concurrency::OSThread("SerialModule") {} static Print *serialPrint = &Serial; #else @@ -140,7 +140,7 @@ int32_t SerialModule::runOnce() Serial.begin(baud); Serial.setTimeout(moduleConfig.serial.timeout > 0 ? moduleConfig.serial.timeout : TIMEOUT); } -#elif !defined(TTGO_T_ECHO) +#elif !defined(TTGO_T_ECHO) && !defined(CANARYONE) if (moduleConfig.serial.rxd && moduleConfig.serial.txd) { #ifdef ARCH_RP2040 Serial2.setFIFOSize(RX_BUFFER); @@ -188,7 +188,7 @@ int32_t SerialModule::runOnce() } } } -#if !defined(TTGO_T_ECHO) +#if !defined(TTGO_T_ECHO) && !defined(CANARYONE) else { while (Serial2.available()) { serialPayloadSize = Serial2.readBytes(serialBytes, meshtastic_Constants_DATA_PAYLOAD_LEN); diff --git a/src/platform/nrf52/architecture.h b/src/platform/nrf52/architecture.h index e6eebc45b..35cd4fd84 100644 --- a/src/platform/nrf52/architecture.h +++ b/src/platform/nrf52/architecture.h @@ -48,6 +48,8 @@ #define HW_VENDOR meshtastic_HardwareModel_T_ECHO #elif defined(NANO_G2_ULTRA) #define HW_VENDOR meshtastic_HardwareModel_NANO_G2_ULTRA +#elif defined(CANARYONE) +#define HW_VENDOR meshtastic_HardwareModel_CANARYONE #elif defined(NORDIC_PCA10059) #define HW_VENDOR meshtastic_HardwareModel_NRF52840_PCA10059 #elif defined(PRIVATE_HW) || defined(FEATHER_DIY) diff --git a/variants/canaryone/platformio.ini b/variants/canaryone/platformio.ini new file mode 100644 index 000000000..d52bbb24a --- /dev/null +++ b/variants/canaryone/platformio.ini @@ -0,0 +1,15 @@ +; Public Beta oled/nrf52840/sx1262 device +[env:canaryone] +extends = nrf52840_base +board = canaryone +debug_tool = jlink + +# add -DCFG_SYSVIEW if you want to use the Segger systemview tool for OS profiling. +build_flags = ${nrf52840_base.build_flags} -Ivariants/canaryone + -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m4/fpv4-sp-d16-hard" +build_src_filter = ${nrf52_base.build_src_filter} +<../variants/canaryone> +lib_deps = + ${nrf52840_base.lib_deps} + adafruit/Adafruit BusIO@^1.13.2 + lewisxhe/PCF8563_Library@^1.0.1 +;upload_protocol = fs diff --git a/variants/canaryone/variant.cpp b/variants/canaryone/variant.cpp new file mode 100644 index 000000000..5967a2a96 --- /dev/null +++ b/variants/canaryone/variant.cpp @@ -0,0 +1,56 @@ +/* + Copyright (c) 2014-2015 Arduino LLC. All right reserved. + Copyright (c) 2016 Sandeep Mistry All right reserved. + Copyright (c) 2018, Adafruit Industries (adafruit.com) + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "variant.h" +#include "nrf.h" +#include "wiring_constants.h" +#include "wiring_digital.h" + +const uint32_t g_ADigitalPinMap[] = { + // P0 - pins 0 and 1 are hardwired for xtal and should never be enabled + 0xff, 0xff, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, + + // P1 + 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47}; + +void initVariant() +{ + // LEDs + pinMode(PIN_LED1, OUTPUT); + ledOff(PIN_LED1); + + pinMode(PIN_LED2, OUTPUT); + ledOff(PIN_LED2); + + pinMode(PIN_LED3, OUTPUT); + ledOff(PIN_LED3); + + // Turn on power to the GPS and LoRa + pinMode(PIN_PWR_EN, OUTPUT); + digitalWrite(PIN_PWR_EN, HIGH); + + // Pull the GPS out of reset + pinMode(GPS_RESET_PIN, OUTPUT); + digitalWrite(GPS_RESET_PIN, HIGH); + + // Pull the LoRa out of reset + pinMode(LORA_RF_PWR, OUTPUT); + digitalWrite(LORA_RF_PWR, HIGH); +} diff --git a/variants/canaryone/variant.h b/variants/canaryone/variant.h new file mode 100644 index 000000000..e31ba3c58 --- /dev/null +++ b/variants/canaryone/variant.h @@ -0,0 +1,188 @@ +/* + Copyright (c) 2014-2015 Arduino LLC. All right reserved. + Copyright (c) 2016 Sandeep Mistry All right reserved. + Copyright (c) 2018, Adafruit Industries (adafruit.com) + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _VARIANT_CANARYONE +#define _VARIANT_CANARYONE + +/** Master clock frequency */ +#define VARIANT_MCK (64000000ul) + +#define USE_LFXO // Board uses 32khz crystal for LF + +/*---------------------------------------------------------------------------- + * Headers + *----------------------------------------------------------------------------*/ + +#include "WVariant.h" + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +#define CANARYONE + +#define GPIO_PORT0 0 +#define GPIO_PORT1 32 + +// Number of pins defined in PinDescription array +#define PINS_COUNT (48) +#define NUM_DIGITAL_PINS (48) +#define NUM_ANALOG_INPUTS (1) +#define NUM_ANALOG_OUTPUTS (0) + +// LEDs +#define PIN_LED1 (GPIO_PORT1 + 1) // blue P1.01 +#define PIN_LED2 (GPIO_PORT0 + 14) // yellow P0.14 +#define PIN_LED3 (GPIO_PORT1 + 3) // green P1.03 + +#define LED_BLUE PIN_LED1 + +#define LED_BUILTIN PIN_LED1 +#define LED_CONN PIN_LED3 + +#define LED_STATE_ON 0 // State when LED is lit +#define LED_INVERTED 1 + +/* + * Buttons + */ +#define PIN_BUTTON1 (GPIO_PORT0 + 15) // BTN0 on schematic +#define PIN_BUTTON2 (GPIO_PORT0 + 16) // BTN1 on schematic + +/* + * Analog pins + */ +#define PIN_A0 (4) // Battery ADC P0.04 + +#define BATTERY_PIN PIN_A0 + +static const uint8_t A0 = PIN_A0; + +#define ADC_RESOLUTION 14 + +/** + * Wire Interfaces + */ +#define WIRE_INTERFACES_COUNT 1 + +#define PIN_WIRE_SDA (GPIO_PORT0 + 26) +// #define I2C_SDA (GPIO_PORT0 + 26) +#define PIN_WIRE_SCL (GPIO_PORT0 + 27) +// #define I2C_SCL (GPIO_PORT0 + 27) + +#define PIN_LCD_RESET (GPIO_PORT0 + 2) + +/* + * External serial flash WP25R1635FZUIL0 + */ + +// QSPI Pins +#define PIN_QSPI_SCK (GPIO_PORT1 + 14) +#define PIN_QSPI_CS (GPIO_PORT1 + 15) +#define PIN_QSPI_IO0 (GPIO_PORT1 + 12) // MOSI if using two bit interface +#define PIN_QSPI_IO1 (GPIO_PORT1 + 13) // MISO if using two bit interface +#define PIN_QSPI_IO2 (GPIO_PORT0 + 7) // WP if using two bit interface (i.e. not used) +#define PIN_QSPI_IO3 (GPIO_PORT0 + 5) // HOLD if using two bit interface (i.e. not used) + +// On-board QSPI Flash +#define EXTERNAL_FLASH_DEVICES MX25R1635F +#define EXTERNAL_FLASH_USE_QSPI + +/* + * Lora radio + */ +#define RADIOLIB_DEBUG 1 +#define USE_SX1262 +#define SX126X_CS (GPIO_PORT0 + 24) +#define SX126X_DIO1 (GPIO_PORT1 + 11) +// #define SX126X_DIO3 (GPIO_PORT0 + 21) +// #define SX126X_DIO2 () // LORA_BUSY // LoRa RX/TX +#define SX126X_BUSY (GPIO_PORT0 + 17) +#define SX126X_RESET (GPIO_PORT0 + 25) +#define LORA_RF_PWR (GPIO_PORT0 + 28) // LORA_RF_SWITCH + +/* + * GPS pins + */ +#define HAS_GPS 1 +#define GPS_UBLOX +#define GPS_BAUDRATE 38400 + +// #define PIN_GPS_WAKE (GPIO_PORT1 + 2) // An output to wake GPS, low means allow sleep, high means force wake +// Seems to be missing on this new board +#define PIN_GPS_PPS (GPIO_PORT1 + 4) // Pulse per second input from the GPS +#define GPS_TX_PIN (GPIO_PORT1 + 9) // This is for bits going TOWARDS the CPU +#define GPS_RX_PIN (GPIO_PORT1 + 8) // This is for bits going TOWARDS the GPS + +#define GPS_THREAD_INTERVAL 50 + +#define PIN_SERIAL1_RX GPS_TX_PIN +#define PIN_SERIAL1_TX GPS_RX_PIN + +#define GPS_RESET_PIN (GPIO_PORT1 + 5) // GPS reset pin + +/* + * SPI Interfaces + */ +#define SPI_INTERFACES_COUNT 1 + +// For LORA, spi 0 +#define PIN_SPI_MISO (GPIO_PORT0 + 23) +#define PIN_SPI_MOSI (GPIO_PORT0 + 22) +#define PIN_SPI_SCK (GPIO_PORT0 + 19) + +// #define PIN_SPI1_MISO (GPIO_PORT1 + 6) // FIXME not really needed, but for now the SPI code requires something to be defined, +// pick an used GPIO #define PIN_SPI1_MOSI (GPIO_PORT1 + 8) #define PIN_SPI1_SCK (GPIO_PORT1 + 9) + +#define PIN_PWR_EN (GPIO_PORT0 + 12) + +// To debug via the segger JLINK console rather than the CDC-ACM serial device +#define USE_SEGGER 1 + +// #define LORA_DISABLE_SENDING 1 +#define SX126X_DIO2_AS_RF_SWITCH 1 + +// Battery +// The battery sense is hooked to pin A0 (4) +// it is defined in the anlaolgue pin section of this file +// and has 12 bit resolution +#define BATTERY_SENSE_RESOLUTION_BITS 12 +#define BATTERY_SENSE_RESOLUTION 4096.0 +// Definition of milliVolt per LSB => 3.0V ADC range and 12-bit ADC resolution = 3000mV/4096 +#define VBAT_MV_PER_LSB (0.73242188F) +// Voltage divider value => 100K + 100K voltage divider on VBAT = (100K / (100K + 100K)) +#define VBAT_DIVIDER (0.5F) +// Compensation factor for the VBAT divider +#define VBAT_DIVIDER_COMP (2.0) +// Fixed calculation of milliVolt from compensation value +#define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) +#undef AREF_VOLTAGE +#define AREF_VOLTAGE 3.0 +#define VBAT_AR_INTERNAL AR_INTERNAL_3_0 +#define ADC_MULTIPLIER VBAT_DIVIDER_COMP +#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x) + +#ifdef __cplusplus +} +#endif + +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#endif \ No newline at end of file From f11def4246fb3ad298e6f5f5c77ca32718aacf1f Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sat, 10 Feb 2024 17:56:04 -0600 Subject: [PATCH 172/472] [create-pull-request] automated change (#3200) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 841be3b27..4d1f50ad6 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 2 -build = 22 +build = 23 From d52cfc294b49a484ea41e13d0e3f66bbe53fcd5b Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sat, 10 Feb 2024 20:01:29 -0600 Subject: [PATCH 173/472] [create-pull-request] automated change (#3204) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/mesh.pb.h | 2 ++ .../generated/meshtastic/storeforward.pb.h | 20 ++++++++++--------- 3 files changed, 14 insertions(+), 10 deletions(-) diff --git a/protobufs b/protobufs index 99bd42baf..6cb18782b 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 99bd42baf8dd2e8ca0eec70f05e1cf7f1a40a283 +Subproject commit 6cb18782b1c446a4ca4797dcf5bb2da765b6e5a0 diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index 998b64faa..a6b36a875 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -73,6 +73,8 @@ typedef enum _meshtastic_HardwareModel { meshtastic_HardwareModel_SENSELORA_S3 = 28, /* Canary Radio Company - CanaryOne: https://canaryradio.io/products/canaryone */ meshtastic_HardwareModel_CANARYONE = 29, + /* Waveshare RP2040 LoRa - https://www.waveshare.com/rp2040-lora.htm */ + meshtastic_HardwareModel_RP2040_LORA = 30, /* --------------------------------------------------------------------------- Less common/prototype boards listed here (needs one more byte over the air) --------------------------------------------------------------------------- */ diff --git a/src/mesh/generated/meshtastic/storeforward.pb.h b/src/mesh/generated/meshtastic/storeforward.pb.h index e6cb51f61..151f6211b 100644 --- a/src/mesh/generated/meshtastic/storeforward.pb.h +++ b/src/mesh/generated/meshtastic/storeforward.pb.h @@ -62,9 +62,9 @@ typedef struct _meshtastic_StoreAndForward_Statistics { uint32_t requests_history; /* Is the heartbeat enabled on the server? */ bool heartbeat; - /* Is the heartbeat enabled on the server? */ + /* Maximum number of messages the server will return. */ uint32_t return_max; - /* Is the heartbeat enabled on the server? */ + /* Maximum history window in minutes the server will return messages from. */ uint32_t return_window; } meshtastic_StoreAndForward_Statistics; @@ -74,18 +74,20 @@ typedef struct _meshtastic_StoreAndForward_History { uint32_t history_messages; /* The window of messages that was used to filter the history client requested */ uint32_t window; - /* The window of messages that was used to filter the history client requested */ + /* Index in the packet history of the last message sent in a previous request to the server. + Will be sent to the client before sending the history and can be set in a subsequent request to avoid getting packets the server already sent to the client. */ uint32_t last_request; } meshtastic_StoreAndForward_History; /* TODO: REPLACE */ typedef struct _meshtastic_StoreAndForward_Heartbeat { - /* Number of that will be sent to the client */ + /* Period in seconds that the heartbeat is sent out that will be sent to the client */ uint32_t period; /* If set, this is not the primary Store & Forward router on the mesh */ uint32_t secondary; } meshtastic_StoreAndForward_Heartbeat; +typedef PB_BYTES_ARRAY_T(237) meshtastic_StoreAndForward_text_t; /* TODO: REPLACE */ typedef struct _meshtastic_StoreAndForward { /* TODO: REPLACE */ @@ -98,8 +100,8 @@ typedef struct _meshtastic_StoreAndForward { meshtastic_StoreAndForward_History history; /* TODO: REPLACE */ meshtastic_StoreAndForward_Heartbeat heartbeat; - /* Empty Payload */ - bool empty; + /* Text from history message. */ + meshtastic_StoreAndForward_text_t text; } variant; } meshtastic_StoreAndForward; @@ -148,7 +150,7 @@ extern "C" { #define meshtastic_StoreAndForward_stats_tag 2 #define meshtastic_StoreAndForward_history_tag 3 #define meshtastic_StoreAndForward_heartbeat_tag 4 -#define meshtastic_StoreAndForward_empty_tag 5 +#define meshtastic_StoreAndForward_text_tag 5 /* Struct field encoding specification for nanopb */ #define meshtastic_StoreAndForward_FIELDLIST(X, a) \ @@ -156,7 +158,7 @@ X(a, STATIC, SINGULAR, UENUM, rr, 1) \ X(a, STATIC, ONEOF, MESSAGE, (variant,stats,variant.stats), 2) \ X(a, STATIC, ONEOF, MESSAGE, (variant,history,variant.history), 3) \ X(a, STATIC, ONEOF, MESSAGE, (variant,heartbeat,variant.heartbeat), 4) \ -X(a, STATIC, ONEOF, BOOL, (variant,empty,variant.empty), 5) +X(a, STATIC, ONEOF, BYTES, (variant,text,variant.text), 5) #define meshtastic_StoreAndForward_CALLBACK NULL #define meshtastic_StoreAndForward_DEFAULT NULL #define meshtastic_StoreAndForward_variant_stats_MSGTYPE meshtastic_StoreAndForward_Statistics @@ -204,7 +206,7 @@ extern const pb_msgdesc_t meshtastic_StoreAndForward_Heartbeat_msg; #define meshtastic_StoreAndForward_Heartbeat_size 12 #define meshtastic_StoreAndForward_History_size 18 #define meshtastic_StoreAndForward_Statistics_size 50 -#define meshtastic_StoreAndForward_size 54 +#define meshtastic_StoreAndForward_size 242 #ifdef __cplusplus } /* extern "C" */ From ce8673b6dc5d99b8b6e52fda0bbb64cca30440c7 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sat, 10 Feb 2024 20:09:51 -0600 Subject: [PATCH 174/472] Added RP2040-LoRA target (#3195) --- .github/workflows/main_matrix.yml | 1 + src/platform/rp2040/architecture.h | 2 ++ variants/rp2040-lora/platformio.ini | 16 +++++++++ variants/rp2040-lora/variant.h | 54 +++++++++++++++++++++++++++++ 4 files changed, 73 insertions(+) create mode 100644 variants/rp2040-lora/platformio.ini create mode 100644 variants/rp2040-lora/variant.h diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index d18fd2b2d..22ff92feb 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -129,6 +129,7 @@ jobs: - board: picow - board: rak11310 - board: senselora_rp2040 + - board: rp2040-lora uses: ./.github/workflows/build_rpi2040.yml with: board: ${{ matrix.board }} diff --git a/src/platform/rp2040/architecture.h b/src/platform/rp2040/architecture.h index 61eb1bbe8..d7d7214c0 100644 --- a/src/platform/rp2040/architecture.h +++ b/src/platform/rp2040/architecture.h @@ -27,4 +27,6 @@ #define HW_VENDOR meshtastic_HardwareModel_RAK11310 #elif defined(SENSELORA_RP2040) #define HW_VENDOR meshtastic_HardwareModel_SENSELORA_RP2040 +#elif defined(RP2040_LORA) +#define HW_VENDOR meshtastic_HardwareModel_RP2040_LORA #endif \ No newline at end of file diff --git a/variants/rp2040-lora/platformio.ini b/variants/rp2040-lora/platformio.ini new file mode 100644 index 000000000..a1d6bea9d --- /dev/null +++ b/variants/rp2040-lora/platformio.ini @@ -0,0 +1,16 @@ +[env:rp2040-lora] +extends = rp2040_base +board = rpipico +upload_protocol = picotool + +# add our variants files to the include and src paths +build_flags = ${rp2040_base.build_flags} + -DRP2040_LORA + -Ivariants/rp2040-lora + -DDEBUG_RP2040_PORT=Serial + -DHW_SPI1_DEVICE + -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m0plus" +lib_deps = + ${rp2040_base.lib_deps} +debug_build_flags = ${rp2040_base.build_flags} +debug_tool = cmsis-dap ; for e.g. Picotool \ No newline at end of file diff --git a/variants/rp2040-lora/variant.h b/variants/rp2040-lora/variant.h new file mode 100644 index 000000000..1f42c4db7 --- /dev/null +++ b/variants/rp2040-lora/variant.h @@ -0,0 +1,54 @@ +// #define RADIOLIB_CUSTOM_ARDUINO 1 +// #define RADIOLIB_TONE_UNSUPPORTED 1 +// #define RADIOLIB_SOFTWARE_SERIAL_UNSUPPORTED 1 + +#define ARDUINO_ARCH_AVR + +// #define USE_SH1106 1 + +// default I2C pins: +// SDA = 4 +// SCL = 5 + +// Recommended pins for SerialModule: +// txd = 8 +// rxd = 9 + +#define EXT_NOTIFY_OUT 22 +#define BUTTON_PIN 17 + +#define LED_PIN PIN_LED + +// #define BATTERY_PIN 26 +// ratio of voltage divider = 3.0 (R17=200k, R18=100k) +// #define ADC_MULTIPLIER 3.1 // 3.0 + a bit for being optimistic + +#define USE_SX1262 + +#undef LORA_SCK +#undef LORA_MISO +#undef LORA_MOSI +#undef LORA_CS + +// https://www.waveshare.com/rp2040-lora.htm +// https://www.waveshare.com/img/devkit/RP2040-LoRa-HF/RP2040-LoRa-HF-details-11.jpg +#define LORA_SCK 14 // 10 +#define LORA_MISO 24 // 12 +#define LORA_MOSI 15 // 11 +#define LORA_CS 13 // 3 + +#define LORA_DIO0 RADIOLIB_NC +#define LORA_RESET 23 // 15 +#define LORA_DIO1 16 // 20 +#define LORA_DIO2 18 // 2 +#define LORA_DIO3 RADIOLIB_NC +#define LORA_DIO4 17 + +#ifdef USE_SX1262 +#define SX126X_CS LORA_CS +#define SX126X_DIO1 LORA_DIO1 +#define SX126X_BUSY LORA_DIO2 +#define SX126X_RESET LORA_RESET +#define SX126X_DIO2_AS_RF_SWITCH +// #define SX126X_DIO3_TCXO_VOLTAGE 1.8 +#endif \ No newline at end of file From 36cf9b9ef4161a3b0721fe5d68a66193b886c5c3 Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Mon, 12 Feb 2024 02:27:22 +1300 Subject: [PATCH 175/472] feat: E-Ink "Dynamic Partial" (#3193) Use a mixture of full refresh, partial refresh, and skipped updates, balancing urgency and display health. Co-authored-by: Ben Meadors --- src/graphics/EInkDisplay2.cpp | 237 ++++++++++++++++---- src/graphics/EInkDisplay2.h | 64 ++++++ variants/heltec_wireless_paper_v1/variant.h | 8 + 3 files changed, 261 insertions(+), 48 deletions(-) diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index 09ea343e1..51d7ac5f8 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -125,61 +125,68 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit) // No need to grab this lock because we are on our own SPI bus // concurrency::LockGuard g(spiLock); +#if defined(USE_EINK_DYNAMIC_PARTIAL) + // Decide if update is partial or full + bool continueUpdate = determineRefreshMode(); + if (!continueUpdate) + return false; +#else + uint32_t now = millis(); uint32_t sinceLast = now - lastDrawMsec; - if (adafruitDisplay && (sinceLast > msecLimit || lastDrawMsec == 0)) { + if (adafruitDisplay && (sinceLast > msecLimit || lastDrawMsec == 0)) lastDrawMsec = now; - - // FIXME - only draw bits have changed (use backbuf similar to the other displays) - // tft.drawBitmap(0, 0, buffer, 128, 64, TFT_YELLOW, TFT_BLACK); - for (uint32_t y = 0; y < displayHeight; y++) { - for (uint32_t x = 0; x < displayWidth; x++) { - // get src pixel in the page based ordering the OLED lib uses FIXME, super inefficient - auto b = buffer[x + (y / 8) * displayWidth]; - auto isset = b & (1 << (y & 7)); - adafruitDisplay->drawPixel(x, y, isset ? COLORED : UNCOLORED); - } - } - - LOG_DEBUG("Updating E-Paper... "); - -#if defined(TTGO_T_ECHO) - adafruitDisplay->nextPage(); -#elif defined(RAK4630) || defined(MAKERPYTHON) - - // RAK14000 2.13 inch b/w 250x122 actually now does support partial updates - - // Full update mode (slow) - // adafruitDisplay->display(false); // FIXME, use partial update mode - - // Only enable for e-Paper with support for partial updates and comment out above adafruitDisplay->display(false); - // 1.54 inch 200x200 - GxEPD2_154_M09 - // 2.13 inch 250x122 - GxEPD2_213_BN - // 2.9 inch 296x128 - GxEPD2_290_T5D - // 4.2 inch 300x400 - GxEPD2_420_M01 - adafruitDisplay->nextPage(); - -#elif defined(PCA10059) || defined(M5_COREINK) - adafruitDisplay->nextPage(); -#elif defined(HELTEC_WIRELESS_PAPER_V1_0) - adafruitDisplay->nextPage(); -#elif defined(HELTEC_WIRELESS_PAPER) - adafruitDisplay->nextPage(); -#elif defined(PRIVATE_HW) || defined(my) - adafruitDisplay->nextPage(); + else + return false; #endif - // Put screen to sleep to save power (possibly not necessary because we already did poweroff inside of display) - adafruitDisplay->hibernate(); - LOG_DEBUG("done\n"); - - return true; - } else { - // LOG_DEBUG("Skipping eink display\n"); - return false; + // FIXME - only draw bits have changed (use backbuf similar to the other displays) + // tft.drawBitmap(0, 0, buffer, 128, 64, TFT_YELLOW, TFT_BLACK); + for (uint32_t y = 0; y < displayHeight; y++) { + for (uint32_t x = 0; x < displayWidth; x++) { + // get src pixel in the page based ordering the OLED lib uses FIXME, super inefficient + auto b = buffer[x + (y / 8) * displayWidth]; + auto isset = b & (1 << (y & 7)); + adafruitDisplay->drawPixel(x, y, isset ? COLORED : UNCOLORED); + } } + + LOG_DEBUG("Updating E-Paper... "); + +#if defined(TTGO_T_ECHO) + adafruitDisplay->nextPage(); +#elif defined(RAK4630) || defined(MAKERPYTHON) + + // RAK14000 2.13 inch b/w 250x122 actually now does support partial updates + + // Full update mode (slow) + // adafruitDisplay->display(false); // FIXME, use partial update mode + + // Only enable for e-Paper with support for partial updates and comment out above adafruitDisplay->display(false); + // 1.54 inch 200x200 - GxEPD2_154_M09 + // 2.13 inch 250x122 - GxEPD2_213_BN + // 2.9 inch 296x128 - GxEPD2_290_T5D + // 4.2 inch 300x400 - GxEPD2_420_M01 + adafruitDisplay->nextPage(); + +#elif defined(PCA10059) || defined(M5_COREINK) + adafruitDisplay->nextPage(); +#elif defined(HELTEC_WIRELESS_PAPER_V1_0) + adafruitDisplay->nextPage(); +#elif defined(HELTEC_WIRELESS_PAPER) + adafruitDisplay->nextPage(); +#elif defined(PRIVATE_HW) || defined(my) + adafruitDisplay->nextPage(); + +#endif + + // Put screen to sleep to save power (possibly not necessary because we already did poweroff inside of display) + adafruitDisplay->hibernate(); + LOG_DEBUG("done\n"); + + return true; } // Write the buffer to the display memory @@ -188,8 +195,16 @@ void EInkDisplay::display(void) // We don't allow regular 'dumb' display() calls to draw on eink until we've shown // at least one forceDisplay() keyframe. This prevents flashing when we should the critical // bootscreen (that we want to look nice) - if (lastDrawMsec) + +#ifdef USE_EINK_DYNAMIC_PARTIAL + lowPriority(); + forceDisplay(); + highPriority(); +#else + if (lastDrawMsec) { forceDisplay(slowUpdateMsec); // Show the first screen a few seconds after boot, then slower + } +#endif } // Send a command to the display (low level function) @@ -329,4 +344,130 @@ bool EInkDisplay::connect() return true; } +// Use a mix of full and partial refreshes, to preserve display health +#if defined(USE_EINK_DYNAMIC_PARTIAL) + +// Suggest that subsequent updates should use partial-refresh +void EInkDisplay::highPriority() +{ + isHighPriority = true; +} + +// Suggest that subsequent updates should use full-refresh +void EInkDisplay::lowPriority() +{ + isHighPriority = false; +} + +// configure display for partial-refresh +void EInkDisplay::configForPartialRefresh() +{ + // Display-specific code can go here +#if defined(PRIVATE_HW) +#else + // Otherwise: + adafruitDisplay->setPartialWindow(0, 0, adafruitDisplay->width(), adafruitDisplay->height()); +#endif +} + +// Configure display for full-refresh +void EInkDisplay::configForFullRefresh() +{ + // Display-specific code can go here +#if defined(PRIVATE_HW) +#else + // Otherwise: + adafruitDisplay->setFullWindow(); +#endif +} + +bool EInkDisplay::newImageMatchesOld() +{ + uint32_t newImageHash = 0; + + // Generate hash: sum all bytes in the image buffer + for (uint16_t b = 0; b < (displayWidth / 8) * displayHeight; b++) { + newImageHash += buffer[b]; + } + + // Compare hashes + bool hashMatches = (newImageHash == prevImageHash); + + // Update the cached hash + prevImageHash = newImageHash; + + // Return the comparison result + return hashMatches; +} + +// Change between partial and full refresh config, or skip update, balancing urgency and display health. +bool EInkDisplay::determineRefreshMode() +{ + uint32_t now = millis(); + uint32_t sinceLast = now - lastUpdateMsec; + + // If rate-limiting dropped a high-priority update: + // promote this update, so it runs ASAP + if (missedHighPriorityUpdate) { + isHighPriority = true; + missedHighPriorityUpdate = false; + } + + // Abort: if too soon for a new frame + if (isHighPriority && partialRefreshCount > 0 && sinceLast < highPriorityLimitMsec) { + LOG_DEBUG("Update skipped: exceeded EINK_HIGHPRIORITY_LIMIT_SECONDS\n"); + missedHighPriorityUpdate = true; + return false; + } + if (!isHighPriority && sinceLast < lowPriorityLimitMsec) { + return false; + } + + // Check if old image (partial) should be redrawn (as full), for image quality + if (partialRefreshCount > 0 && !isHighPriority) + needsFull = true; + + // If too many partials, require a full-refresh (display health) + if (partialRefreshCount >= partialRefreshLimit) + needsFull = true; + + // If image matches + if (newImageMatchesOld()) { + // If low priority: limit rate + // otherwise, every loop() will run the hash method + if (!isHighPriority) + lastUpdateMsec = now; + + // If update is *not* for display health or image quality, skip it + if (!needsFull) + return false; + } + + // Conditions assessed - not skipping - load the appropriate config + + // If options require a full refresh + if (!isHighPriority || needsFull) { + if (partialRefreshCount > 0) + configForFullRefresh(); + + LOG_DEBUG("Conditions met for full-refresh\n"); + partialRefreshCount = 0; + needsFull = false; + } + + // If options allow a partial refresh + else { + if (partialRefreshCount == 0) + configForPartialRefresh(); + + LOG_DEBUG("Conditions met for partial-refresh\n"); + partialRefreshCount++; + } + + lastUpdateMsec = now; // Mark time for rate limiting + return true; // Instruct calling method to continue with update +} + +#endif // End USE_EINK_DYNAMIC_PARTIAL + #endif \ No newline at end of file diff --git a/src/graphics/EInkDisplay2.h b/src/graphics/EInkDisplay2.h index 7bbf07069..91261c865 100644 --- a/src/graphics/EInkDisplay2.h +++ b/src/graphics/EInkDisplay2.h @@ -54,4 +54,68 @@ class EInkDisplay : public OLEDDisplay // Connect to the display virtual bool connect() override; + +#if defined(USE_EINK_DYNAMIC_PARTIAL) + // Full, partial, or skip: balance urgency with display health + + // Use partial refresh if EITHER: + // * highPriority() was set + // * a highPriority() update was previously skipped, for rate-limiting - (EINK_HIGHPRIORITY_LIMIT_SECONDS) + + // Use full refresh if EITHER: + // * lowPriority() was set + // * too many partial updates in a row: protect display - (EINK_PARTIAL_REPEAT_LIMIT) + // * no recent updates, and last update was partial: redraw for image quality (EINK_LOWPRIORITY_LIMIT_SECONDS) + + // Rate limit if: + // * lowPriority() - (EINK_LOWPRIORITY_LIMIT_SECONDS) + // * highPriority(), if multiple partials have run back-to-back - (EINK_HIGHPRIORITY_LIMIT_SECONDS) + + // Skip update entirely if ALL criteria met: + // * new image matches old image + // * lowPriority() + // * not redrawing for image quality + // * not refreshing for display health + + // ------------------------------------ + + // To implement for your E-Ink display: + // * edit configForPartialRefresh() + // * edit configForFullRefresh() + // * add macros to variant.h, and adjust to taste: + + /* + #define USE_EINK_DYNAMIC_PARTIAL + #define EINK_LOWPRIORITY_LIMIT_SECONDS 30 + #define EINK_HIGHPRIORITY_LIMIT_SECONDS 1 + #define EINK_PARTIAL_REPEAT_LIMIT 5 + */ + + public: + void highPriority(); // Suggest partial refresh + void lowPriority(); // Suggest full refresh + + protected: + void configForPartialRefresh(); // Display specific code to select partial refresh mode + void configForFullRefresh(); // Display specific code to return to full refresh mode + bool newImageMatchesOld(); // Is the new update actually different to the last image? + bool determineRefreshMode(); // Called immediately before data written to display - choose refresh mode, or abort update + + bool isHighPriority = true; // Does the method calling update believe that this is urgent? + bool needsFull = false; // Is a full refresh forced? (display health) + bool missedHighPriorityUpdate = false; // Was a high priority update skipped for rate-limiting? + uint16_t partialRefreshCount = 0; // How many partials have occurred since last full refresh? + uint32_t lastUpdateMsec = 0; // When did the last update occur? + uint32_t prevImageHash = 0; // Used to check if update will change screen image (skippable or not) + + // Set in variant.h + const uint32_t lowPriorityLimitMsec = (uint32_t)1000 * EINK_LOWPRIORITY_LIMIT_SECONDS; // Max rate for partial refreshes + const uint32_t highPriorityLimitMsec = (uint32_t)1000 * EINK_HIGHPRIORITY_LIMIT_SECONDS; // Max rate for full refreshes + const uint32_t partialRefreshLimit = EINK_PARTIAL_REPEAT_LIMIT; // Max consecutive partials, before full is triggered + +#else // !USE_EINK_DYNAMIC_PARTIAL + // Tolerate calls to these methods anywhere, just to be safe + void highPriority() {} + void lowPriority() {} +#endif }; diff --git a/variants/heltec_wireless_paper_v1/variant.h b/variants/heltec_wireless_paper_v1/variant.h index 4daf9a655..7a4e54ca9 100644 --- a/variants/heltec_wireless_paper_v1/variant.h +++ b/variants/heltec_wireless_paper_v1/variant.h @@ -5,6 +5,14 @@ #define I2C_SCL SCL #define USE_EINK + +// Settings for Dynamic Partial mode +// Change between partial and full refresh config, or skip update, balancing urgency and display health. +#define USE_EINK_DYNAMIC_PARTIAL +#define EINK_LOWPRIORITY_LIMIT_SECONDS 30 +#define EINK_HIGHPRIORITY_LIMIT_SECONDS 1 +#define EINK_PARTIAL_REPEAT_LIMIT 5 + /* * eink display pins */ From 96bd898a382f84bed475190c68a80da234266373 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sun, 11 Feb 2024 07:43:07 -0600 Subject: [PATCH 176/472] [create-pull-request] automated change (#3209) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/storeforward.pb.h | 4 ++++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/protobufs b/protobufs index 6cb18782b..20f2783e1 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 6cb18782b1c446a4ca4797dcf5bb2da765b6e5a0 +Subproject commit 20f2783e196da1429de4b0fcf05c7ffea98d7901 diff --git a/src/mesh/generated/meshtastic/storeforward.pb.h b/src/mesh/generated/meshtastic/storeforward.pb.h index 151f6211b..55ab0b510 100644 --- a/src/mesh/generated/meshtastic/storeforward.pb.h +++ b/src/mesh/generated/meshtastic/storeforward.pb.h @@ -30,6 +30,10 @@ typedef enum _meshtastic_StoreAndForward_RequestResponse { meshtastic_StoreAndForward_RequestResponse_ROUTER_HISTORY = 6, /* Router is responding to a request for stats. */ meshtastic_StoreAndForward_RequestResponse_ROUTER_STATS = 7, + /* Router sends a text message from its history that was a direct message. */ + meshtastic_StoreAndForward_RequestResponse_ROUTER_TEXT_DIRECT = 8, + /* Router sends a text message from its history that was a broadcast. */ + meshtastic_StoreAndForward_RequestResponse_ROUTER_TEXT_BROADCAST = 9, /* Client is an in error state. */ meshtastic_StoreAndForward_RequestResponse_CLIENT_ERROR = 64, /* Client has requested a replay from the router. */ From bac7c708bf517634916f7245f1ddad55962184ba Mon Sep 17 00:00:00 2001 From: rcarteraz Date: Sun, 11 Feb 2024 13:10:08 -0700 Subject: [PATCH 177/472] LilyGo T-Echo Bootloader UF2 and ZIP packages (#3210) Built the LilyGo T-Echo bootloader from source to obtain the UF2 and zip package for updating the bootloader on the devices with outdated bootloaders. The UF2 will allow drag and drop flashing the update, and the zip package is in case adafruit-nrfutil is needed. I wasn't sure the best location to put this but since we already have the nrf52 flash erase uf2 here, I figured this might be the best. I will be linking to these files in a docs article detailing the process for using them. --- bin/lilygo_techo_bootloader-0.6.1.zip | Bin 0 -> 190873 bytes ...date-lilygo_techo_bootloader-0.6.1_nosd.uf2 | Bin 0 -> 75264 bytes 2 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 bin/lilygo_techo_bootloader-0.6.1.zip create mode 100644 bin/update-lilygo_techo_bootloader-0.6.1_nosd.uf2 diff --git a/bin/lilygo_techo_bootloader-0.6.1.zip b/bin/lilygo_techo_bootloader-0.6.1.zip new file mode 100644 index 0000000000000000000000000000000000000000..34bd169f62a0f3913e2ebbc564455a2bef8098c4 GIT binary patch literal 190873 zcmbrndwdkt-9LV2c6N7mvq>fwAV5N9b0L!mx&hQ+DcuB|B&a3cT5WCJ;H4Y2vRsr6 z7uf{F4VE_afeN+OMQu&6)NC+5M2rN*s%>p&x%7*dmcd6^ls#{zvY9^uFaQnwCC{4A+%c&oD|Gc`KIQzw+Mu9&NhkzPpz!UApq2rH%LA zxBRl|MzJML58r)%(?jCzMT0A8)95ckEM>(k^{`^o8-*b19F@EbNOjmd!4pr z%Oa$;$yDFcxL9L|u#kQ$%_f9-W!fvGCs+GZf_a76u}NlLXS$~K5mKVP@S3k@%8h2( zCW^jLKG7ojonk0ZE{k&CX`h?d{<4qP{?9&Nk3-I?xB1J%p#cx`!*c!zBj%_ciBp;+ zR#|YCAr4jiv;EuKPG=CynE(l$4>Xh%Dth2yN$#o@J-$9hq`2^ehMeZ4=0Dt6LRIZy9WGA*~4=dzHpv!<#iirnNp%+1hoZvUAVOOl^X6yX&v$MD(dzT z`pg`PyizlC#EH^h9UhDdW3VVB)8WZ=oB@ky#rk3`Q0)p&L~Ty}NezeAO==Em>4%9J zpd;2N^oZeP>>o)!%!mS@kAHdjk}rH6Ur)TiJ~ECy@qnkJU-@`wA8*6+#%qZ`QcQ@G z5$P-wXBysfbp)hWuU4SXBB3YOn|VX#B7XK1Pcl}Pbkvao&Li|;WNYiKwhSV1ACUo7 z4Co{mGofXY)UVtEIxnUnQX`mIHv>{h)B$5pwTEf()z17pwt$m=-nCVBdy}zcNq5+T z_oGR%*W)LeiLer*pm!<}2fpoEUIz@PCiB9AIH9ZWw6>vMW<*B&X@W>!MVQhpdQHRP zbNvl_bT=VILZ>8KG+UfVrz5ExsR3({r@6IqzSAqeujdC!v@i8%^nAka7J;!lU(_@r zxVGSn=-;9jkVgMA`ZUrwSVP>Hy)8&TqZ4B9bZabrVG`Q*=q|EHpXKwkSzq3x&mn0~ zdA!2!GTQCiylDURAtH4|`gD=F0u+myuNaYHK%vq$EhK<8Q;=EYP*`(FP6z6D()zzb z{h(3b7pN?#lZiGPU!E{}RP)tu4OkcZ(q{Ap5E{PTn`h7$+FlY^7Z|PEJ8A2*SAqQT zer?egHjMY|{m<>SS-=B0HBd~xi*|P!m}mha&X3LqS4I_9MZ?N{#TSjat8WzR%pauPS}ON7U5*z zWR&S??V_Vg$lY};+IAal$KtdGTTW0rqc6XQILTJliBba7o{Xg%J<9L9weA7AdaO+` znW`~}8u@*Ro*Qqp$P;97b*9{JH7h)D{qrcL&O~1(9(^YBfdg+BzW0yj?H7Ygr&-&F zu{jrUfx66uez9maTwI;xHErNmd8bPHAMGK_l}G8gUymQiIwov0S!3SVF17 zLH6hZ$?Pz2hJu(R#=l^Rv_BTsd84B%&lwI7C+ff?9yg z;1y}LNwO%?npDmt(bJ;!b+nB{XMV2LZtBXFx9X1ej9;e9y#q{Unj$#KnkzR4WwT^e zEYfVivQWBMTk~40?;K>Wj76rinQaRn`X(44(RPqaNkRM=8%za>qk-Zna3UE%#9eMN|6tcigQZGfCbZ(wB6oP zs^%HAH6uZu@&y;j%_$J6$7|LyRhOIn;|w74HFn#WqaR=u>PeTiq#1|5@=0cUd!?-?Y_ zlEG@Gm0vR0%DjocZ!xTG$sm_igTL2jwc_ulEa$R*n`c>{ZUtUNa{7SH!0T+BV#ER? z5+bTqy%eiMhnu4v11#CtZ64t@GLYeTUMKxm7pGx7eyiNxvaN+YwV~S=%$P;{|Kr3G zjJCdbnrwf@A-BjCVb5xEKHyUVYMaoq6RW^cM)$JCT82GcT5Oz2yi(N7+X_8HGNa>)y03g_n`V4w3u1Pb}oX8>VFw$nRYQ>ME$rBGosRU}48SSMJ zF--hL5_gz~hMivrk!fv_p>0cG7_<_ug)%K+v9! zbFwwSs@7j|rTiR6SPTkb)68;Zh6;F2+Uk)Z$~#$^eW_e-kU@dNR>DL=`E0v&$92H# zU97hb(5|V|EwfMCwReY(hwaj&!$h^Hl)9|8+*~0oJvTQyN6bA%#Oza9qHu~AGfpiy zYa(ftcT3MN0Sy{>BsjQTmNnw9Cm16}-h~(~1p14}&dXp#2 zPHzI8 zPr(oAp4l0kRL&fpR76y}Ol5`E8ukN5W>vE~sr>CDbfm9~D_A)$=yCc6gQnTZVRnSk zNCB1C1?Yx3J!D5+n3QHFqxPAZSsd`U(mGS6sDB(P4|H31XhJ@Bh~?1fn7Ip!&6`$h*Z6&Omk-DcdYTTtikZ~i1&0@7J+cq4$(75!RbD}h4$lvBBbKw-1tz7* z`0|fovnXfjEhqkiH*>*PY>5)bRiMc+O&Ti@Im^bG~A1&@Ejr=zLeX-&T|+cAv>AToROZH%pGm~nSKT>2`(qv z6v&KH#naNGXS9>D0+l=S4qv%8sAmWRZ5>zx@9U)98{~?)-R0PWt{Cal1)&3vZGgiL znJui(FB}dGbs&|JQ~q&0{p5H{pQELNkj*&af|NFgNNeovlC`KDP(@Y!E&9MJF>N#hVsI|s|#3lftv`7dQ| zu9h;Cu^D?oM;jS%7^8LV*l5kbXq|2&?Ju=qT!3A9(|6R0I%7+sPJbGig7ATIlI7=c$ZyFnT$bcaAJYyQ#e?8#o!Td^hf;SiPVNnEQ;b zjo^uQsiMlNmFirz2IW)xm$Vt}`m&AwYz%W~k=CNEmTz{pdeQO~n<>88ER{TKhp$7; z)NXgNrFnbJsP}?yH(H`CmVIp;?;4)=wJ)!ZOi<^j-@w?UdcJZmsI;9@=|;e@s^Dp= z01>}@HB&wbV@_qb-B`H~LD!gLNORBzA5#6_NM z(`LRgp1bwmg-%|*{4*J7;vdoI+@ zCN}NVsKLX`St?UNf~KMcc}{~ypM)Nlrg+x8)a_l++U@buJ=`?p@m2>(`R5T|pRXqa ze8HlAFTXD!ULtR}To6Lgx<&gv`I5m(;{0sld+v6M9PgoPkxjs zTYOHu<0oO0h~19}pfrJ4p*>l5i!#@lrTu5pAGV5VhBd{|x*M=3`e<3~kRI%e0f%bY zvCGe_bOsN$&^)Sr((g3?0hx8y$(E;+v9^(qqkIojv_)s3-?8i-orreXRNRCWIX}+# zUCc9$<#9%y3wfmHiLT}_i@K;o_h+%5?$5@aY<4DN-ygAd5o1rbg{{RCKeZaxyr9uv zi_u>v`kN718@7lPyD{wDmZu+(dFRJ1lq<{~;kzKm8KXeUXi?hgoq&hZSV_ES+Dc^r z8`>)#`9o9?4?zM5b~$8=OiJmPemP8}k0TaCp0a6IjQ%R@^jpfE;J=I}n#~hUd4Xwx z?*3_?1Owgn@bliO;no@x^#3;jt3S$>b4n=K(95V6u{X+;=O}EsS>ej_6?1uoVijMG z+6>&NwPf5*67rhbi&gu-`ED;YwNF&jF3F+x6}zE3J4nczR?4+oR7WZwQVvfXr4JbV zkbLtoh@jY{4ApJ^5J48M5VBK}!r3%gKV*yDQ}inQY6{J|EQ~ zS7*t8|D3Iv7dDlf6jJPZo!92sGIrGnU4drpoAJ~dWt?VBetof~ z7A-zU+{F2&9$*d(F8p1Aq*j5`F| zMlRAE(!L&Qi|rfY@%Oc%lx6lP-t@OJbnZr`^ghpTJVZRCyO~4!LOgX0ty{1e!iHQ?)A-Y+*(h>d2@LWE7}Tp&z5>lbm7;Nb>E!Bd3f<5 z4>S$k#l53*COX#p^$qnM+7p+~_$fCrK_z&yMpeNemv-QSsDCt48>>V);xQV+q8_T5m=h)y1U3xjOau70(6b<|?(DVq-m_q;<1W_Wsk+fL z!jY;QZaf<+S+L;y={Y0ZIasSiTEm?!_;_#LLLT0R8Fg-qS~>7Y;YB3dM?@=R8Ru5F z+ZHf<4*fdGg3m!p|2H{-tZ|+|OZ>aKf$aZpe+GOXg~V%LlwO}*kOhtczR-nr-$UH) z7UEtQPVoa0!0*S2dk$oxTr=y2qMuyqUq#_r@A3;m)UXL;W#Ei8}ooH&X6G z7^W0j(5&eB~F_g2=ud{WR!BZ$FAy}t^n|__UZ-#+kMg0{9hGq2;3JddvY9J*1rEg^D*vQYS#&8R>_!e zsa?-aciVim+%fQb1!IFTrekYRu10(qJ%%~ozifQQX|Jnp2o!D5NlCRHaA4kgSeX;& z)SFc1OuuPr^A%zDwEk}WaPmYFoUvMWiTKWtqD9L#FJp@A%Sc~2_#JzupD@cP4Rh3T zb|iVCq>h|9#EHZz81Ghi6shlxGiZg!%*|FuezA1*b>CW;JW-=U zQkT93tI9XkSL#~)=JL4;0cO`IqQ3-tP^na@6iZj3Z!=M{NUFdu>3H(QbmLbszB`T7 zG^GT)>U3#}QifiYOB0cki=0yIx5*QkM#_N{Y@7IIMaqnnbYav=F~ZcR_5l1ij5aUv z3N$fRH2i1IR?xy8_{yNAiK#S)G%vK&m?DeM)j{^>iC50ha)-=Xd(!Z}^-zzBMNY)- z)bHp`5C5iy`nTX6FX7ei=p`f(yGf_sC12mY`JZ?|nO%XjBXb#wDyFy=5$8hAH){_NzeBphSfdpd zTSnHz$@zsvjvniY_aAEYuc|<{$T2%}1$aoK>E}x(e-8*Yyt)=vY(9l66+mjA|8MjRI!iDE>|koQSd*<;mouDCk@4jG}Y{$~LHL+`Zyj zSFdNS*c)0a^r~z7EsSCjcc2ytVI(kLEOb$(J>+HExq(c=X!GM+;2TKBwkEdd>G1L9 zWA-!fOoYy!*PyQBJL%rOMW14Do(Z~HyLHqT)p~x0vE70=ge`h5o;eK`jIY$dY-hKd zwsYGjhcn+}ezy@ZPAhK=`OTmW4w5pnqY)7_BqH{jcAP}Y6cNI_nAxTEiR*yrvBEO! zL1o{N(|4OYO&u5+tdTDxq0I-atkQ2GNB@O9`))@kgS=;ucM_wPOZu&hVi!M(hBjAQ z`J=nmRfeC@C7}&<5ThjiHA;WIXSFGAtM#ZD%nL6(+t7$Oo)4_zL5xctu%GOq{>(k- zBeTQWZs|zZ_9xBMYaw-EzC@I8qJ)4FMZ~nj*3P5EdnoZ2lz2A6>?tYOj-Jxq67eZR z3x{5WJ!&-e(WnUSOLc4>{tMB6(Ao)pnk;9JnAAe7IGdbJ3S@Ebsi{Aqb_4hGl{p%J**dxA#- z?)>M2{oS{=u#$E}T1O^VinQCR6fSJ@+!jwl~E zFl^T5Vx-zImV#%Cp4Fg&va>OoxeXjfk{vN?<;V|4L_eKN=r!nhGPZw&h>fr{CTm%7 zH7R+H!Egne@(jc z_tpIFxOrxl!W*q{B(%z;X3eBrk#Z&r@oh5CD1DjNLHeg1m7n{+hJ!Cn{lYLZn2z1EVOAj#bInbofqb4=r6k_>5w$k#T(Q4^T*+ z=K?K z0%~{hKGuSfz75`2Q-o1Z`(yB+!7kuzfTT5V%-UOI%=}-5T?Uq{xNCht_6{=4u2rrl z#TMU_o|djBLoFNiqV_F1AK2$5?K-&Z1G340GC4{6xDQk>kbPL4*@W9|HgX&navVgb zzE5J>%^5k#1g&FnQV$@bJv-#y>uU~J$+6^#WzFh3Dlw>!{0$ToYV@^*HqdeolzVbW z3vV~%WRD?Lcznn7>BOSWSFcfjtlq9JQfH`c^$=FOcT2Xat`i|01oA1QY(UaBe-QOx z#^^VXPxI1puFYy-AEH$_W#0e`Z+P-VHYA#4?C4NNRD%3WXF3bNKOM3}EnPH%RI6pQ ztNYB_jQ9lIl}RNvvuf5#$9{1{@(rAlAotsp3DWV%MAZGmkcIBHwPr2*^;{7)JVND} zPRQss*kk_?F>97M3oc5_Bx6tYl4d%ur~Qof2kb}shzVSj;=)F}k1^WodX{+9@M9wG z$`6jo6Wa;BzhkTHkYz+4Jpy~vN_ckdid|X;>^pVh$qgeyByd00pXt*kFH=T&m>qRl z2PE?qlPVrlGCt0&n59@gHdlBRTZNzq6^}$jbwb4oWn#rpL|5~!<0~FACuZ4{SymV}mUjb^G>p1k?wPfkWxh>zOgGi*n!?uVelL!aARhd#Gv z2coq18=^C&FV+fpG9#v#<>v#zH5I|k0>s_06-c{zR((dbo_s^~3|1Ro0*J|JHB!C# z{Ybxs^uE<3%bo8To$8{@wY>*sq7H)|m%vtaV@lgP9wyTEl2{y0p@d_d?yf zQh%&trGNG5l~wDdNA|7pK2o*$bnAzZK{^`ut-eKmO6NoUgVk9KEcL=q8m>1TZk27& zQUz$PCPfO0ng{Y?!}VMwm3F&WRSLTCRf4y+By@{x9VlQrntq{Xp?@O!_k{91#-AIo zv&5JKvc|K#$@^qMT{E?{*ADBa>?r9($H^$Slz$x9HF>3?daqO4GQ8qcF1}C2_n#VAQ~vy#QnviV&#eOR6z(~- z2vH0kRa(seQx;JW$rE=PZ5N_Wo8rZobhL@^)q3E01$LX&mQBmFkJE~JUr%luhkEHhEmwU&( zlsQGo*kVMcXw?&C2SIEK_Au8aJGtO;`9wdJ_*lcv1P<3iBSU5(zJ``HVMl`$FtiP_ zC4bE({7uvex~s5SV;II4jncCDV`X<4F{7lcrG|}s5`?EqX@NaK4Z6c-?fy$3y!^D`FGm=smRanGSo*2qc*NTTY?MBF7RS{Ce7iS?7BU>xc&5{eVccn^osap(7LRDX5Pz*i*S@7)< zPMeJyh0wH4!}5W+-oRuvgt&5s5rgU4sgVp-^fKBF3A3CIy9vG%hxXq?CY3@+*F@CM zNorARDb+-&|2Ks%8MAVTGp&kqX1Y=|GfgR-X@dmp>l1^!@*P@en9dESoqNNAZ@;T6 zb@^)fo;l9lbx!R+hZr#tdoYoOzk$SW>b>&xO0#yi{(K$ub5YPs3zrPmGEQU6iL-k7 z;&YA5Lb_F8oh{1~v2cRQ6{E2q=!~{;h=&c=A-f?jIJKrBDqET$^@*?vQu^4a7Zccn zp`FI7t#Ul}Sdzw3_nnTn1ix(=C}sYJy_>YZs+U8b;~IXUU*X=OTijKUw?2VX^+hBR zTMe1!ltOmOz^W(k$}$!9T@H}eRt8X2CBnT^LD zG|J8I%MC9$%aQqg57Y&qpP8VaF$#}(?1@F z`KV(VVC;4+X@yk?I8GqrZis20aT} z|9IbNyXganW!2tI{yzL2{7UIvLXle*5rg2B)3m+D_@yv8dL$8>jd|J%j=*T4_`hHc zeH^jk@z_m?yk3tt9{YvSb2Fl`J;6n1_hkiZEXPH^eiQW+Qr{zowen>&5nD8xr+WPK zH`PI@ec{vS?Vj|r*S51`3%KWUWPSJXXtjF(-uJ&k6=YJu=tApJ1`P-M$-ov zNTlD3QyuV!!?dTO|8ZDb60v_IJV8&ma*VEX z5;%9_tqR9uGmPkep^vt6Rs4^2E`3H}W8k2_(HHR3)kQ7&`hr|gg$4bNjfQ&b@Sc(g zAj&=-o0#zQ_TAJ0UP~hL!j=9cY~S_98lbUqG`f(%3gE<8^v`?Eu;p@6rqYBHQHfXx zboI}Ob6tIyfjr9MG2yX_pG0|4jlx?2Zz8L*h{`h+1>|CR5-hu9XCn3n>M4;>n-mDG zIsFKD9qDL&nZ5-ZteCsnD#N?l$^-pYj5H|6q6VBX*mV-IviK&*qVIj=LKEf`YMG}|!1sLy$|OrZ3sG&)IzP-@MZE}> zD0ee7#V;ewRiNpsrhrBzdGTk|ix65@2~RbnWQDD2mU#VVUO?Z98Tug7glIvF_Ry%A zoQ^Qy(Vw9#MlVtc%ZtmfE?v1dL!BNDt#@0e9VJfK;}ElH(N>_wUn8MM$d!LqDglFl zYntUO>Fr2peYN$?qm|x;dPd9^i@P^SP&IO{W^)*{889wm7=kj zrbKM+Sah=hNyHk-y5VU*a|Hp;bf$&AG_4r1;{tZEt%$xL+Rd+#;wkcEw0t8@^jVC( zFdn-tj&mhg@sA?*om&2>E~Vd8@mN*`r{q+SBlBT%8;sJZCyZ*s6aMe0P0XoCS8^-T zlwHAO`DaHaV6NlCL_GRA$$lGJ!pG5F!NT$nj^rTbJiq6&Is)yDT8qc$neu_cVNR1l zVdo-r7yUbG=Tknt_=N6#zD3^J^-G)wc^XkB4mn3M9ZAMM!fsI*p(`^!a(cgnw?6Xj zei1qsW9^5ni!jvAb)ApexvmpLe{jscMGX6vO*qJ#um-cJPWZE~y$4}8+M?ThErw0Y zCRA%IgWp2R#$_9`aoJ$sw2>CrfZZCUdK zjWVoprC4#r3gsm)jz}2ML(wF7mCbiNx)W>K&GQN(1i(S9C}%b}=3eBp0g5^6tCLf^ zn#tJJtf2UhVHslxan_*KYH~&Jt=0#F8#cTYT(I#>(DZnH{+o}#*WJ3wRQ}}=YA2g# z?1Me9r9Tm&V|Y6#jIObks6|ZIev_yQkK>u**cPn$718am84~GR=N^7J5t}&-x<8yF zdZTxMQUshCdnWR@KDmp|+Ix_v9zUSPdT*z zM9J@<`J=X zVVF{6%)sYM?Bk*b=VFc414iqgMNOS9K>qWn5azVM4E;Td)?pjYC410*pFR<98ksBL z$rh-s5(+& zCmz3Hz4N=Ld3>pyt_wM^2H;zM4@L-Ujdg9&O~MwP6Dbz=j&j;nz{1f}{@h`38DN}E zn&B5a(;&b%)W`a7;W>q=NJ${R+C(hxwZfhUpzS;l*~g(h4{nn=l=6T&h(%7vzPAH5 zSc=nc0}}L333{g&+HMDQ;2=MIP#cx=D@8CN*8&>7`f5pFrG%>xkO7OpB ztMlJ8SWW7DIsSZG8ujz#q#^wge-G@^b-o6F-7*T{ke}ueQ=0FP|6cyy!D=J*0#dC; z>QkiNLdw*f1$czXLhAc~QEjB2MyeGl(rj38kfL!asa3*hHw;rPHxIE`<9cqW5<1pY zC#26qW17^w*Jv~$)v9u!4}46u+**swceKgvr(GQNF6Y8tENc7+asClf&pvq1ObYd( znIgGr6>R-k3f-rQhWhu@JZnVsX1gSh=*@L`@wda{^wN4&{(!XvUb}egilMyyw7wH@ zEYpS`yIe}?A$T5dnY7Ik8eBlHdmO+gj6=P zNV%X9=M8KRw-1{D?A@$N-!9nQ&qQg;?HYp5Y-<-=MmeQLzD@>T z@Y$TEm&_WcbL~VDAbVnUV5KlVb&l;9=55qBMNb@OYG(~Ch{0~BVcuy3tbHe4Rd0p! zyzhhW+=0K8)7V9!$kZWfzaOG&q-DsYt-~&BitJintqHJI^IeqsXpK{lv-HIlIj|Wg zX1ZI!cZYONcKJ`}FSL>}*gb6>10tU(`3xWJ(zDm{RqKB8?tu2?;N63R#E`n+@wGvQ zBP0O5xB>Fr%OliN%)r-u9v1W+`d#q4vC47XL()`}(>zds^CIf#F`RYYTHiG?aF!X# zCU4`H&+GkBm$&0bG+u&Qlm7@`Ny>(QIsEk_mP_E%SOE5z(_aePAl=PfK62G2UiI z#PC5CllCdt2^+w_3X@ro6sRX@H1^wsYxPFZ&Mu0h(N3;D4Hk3ScC_`y#%SX~8@1zC zBaRmqSEkYDTCMsvU+B^0 zLyZ`nz`aqET5|IH>P$#M<2YL{8K<|0^LpuweuWvGW%K}}y!eaHXwOBzQ`+?b^@x}v z>UxT`x++yB8T)XQdII#t#m>>#>^EjL?+%y|yKjSMgVTPJIPDR_W?)r%p(mHl&6Ah) zgBw`Fu*E_VUkD9i$m*+XuJ+lYxV}Sl*JNIx#7pZxh<)JVIBeH9Vr`n>Rb36aoN5c| zdI6qP7Wx4fnXPWuLy+;WP>$)IEa%?s`Ua6-yJYYQ!mr%5{*N~LbqU6wUrAH5+dbpifeWAJ|p z_;+0b|DB{{M8}x*ytMHaLN@lQg_tLL*4d2Mw|2A=u-cAo*VmF``n^s!Zys332(w0G ze}`Y6w9`>Q#1Y1U%AUXpJ25NJzGGL0Z?pkcg9XEM1)3En=#$QFk!1RS`n_Pq8y%+& zs%4F@q4yw3e(T)g-zQI0pJHePJ+v&Jx7K&vspN?&NQH?TN$E!Yu7=Y4GqfKjXk@Sm zkKu=jjffhcF|X->{6-=rM=UZ^$1;>kO4w!@7z3|6#L8`LulQa!~SLUbjHs@VQOe8*ebM`Fg$7 zJ2@Kr{uq1%YlbanBh(iPs~_64D_(dsZDG{tlqO4UOR+QBM3g$`~Hf@ijxsL|}WlxMoU?S^sW4bwZ^{PR+o!QC50hA<{0u zdKR<&7hro`;+NFZw&01bo$^FEC|fZaN1>_TU})-fM~Wp`QNi059398)BG0NqyW7z& zt2hikJYK?#IVVLlcb#sA6%w~4X!%2A2bDCh50f40)#gS@ofeD%tX3-7iKxLwlbXUh zK0>Fay`eMj1ptP5U4)HZ$X6BBAwK z?8aAJ*v~4|SM(pk+rPx(TFCfoa4QbA@h4-s@vh$YPC@DyZIE`@mpCmyZo+;JUjg=W z0!trf(CPU&wLVaaqTCEKH}FGPwht#>!Tw0?L@y#*#PE-E}P9o@X6#nRo z^JKZKg+s8dr2OtiOzYiLyCP-8-!3z@`Dl+%drfA`*C|#+d)muw5m^OgV$C3yvfPC= zb0y|=|H<64{OM%Ig9`OTj>i5KzxxYfqf+%weG>Ve?B;C)dCX|6I}ZP4o7mdqy;-*) zYAu`8!CO3$gdU?em@w)L%AdgtLyzv%r$PG`nVZxpWp+T0DE$WHgJT~3JB?AS8F}oa zBi!+1C?Ks)lh(n{%1CPk6f*$!)u!XuWjs&N4h)z)mY1(-LnKGFk$MlQR^U~A@~ld8Y_`V1w~&*<&ds#x(}ZuHq!@n^%_&O< z{M`ophvO~s*J&dZbZB$o!?-vP6bf2r*@_0myR^lR^~Esd&eb<4)MwyazQIqW?P?=M zrTA7OHPv;@o=35Y{Qf;JuZrq7Lza2L2ML4;kqsBd zkVg2@{ezC-Qwd62sZl%!`Qo%UDq!W0F}PFXX#?^@ACx)okZ)FT z3Nv)SI-x9c`dwk#!qX!-V^?&ieA>%ve;S4jZ$(J0R_o+>>O|1Wr+cL};_`2+(wfO- z8Pk8a7bh@6F8~6KGG(#fQL7ELT_#V!w zoKKY&Q%J~lgv*Q=1aPQlY46C4PYo)(V&vb^U<~%hi!?~(YB~nIwrF^xo)P+6bds@7 z-ZCKAF+%?i#<9y_c%f-A$5`0JFy>erbT+#&=66Qv$dMV(7_dGa9_I<;BMJX>D74y* zQ3}x&CA^2#)oP>*MfyAYi%6ka*{O>HqZKkj`4w29d@5h?tfngwUij6iRr6egT1!2~ z%A_lrl}@jos5sXk8UZxDd$osBH}S0aV)ZS?D!@tG)%C_Y_pG?fklPPO8;#P9C@mVL z#S5hyFO(KnTn`UJ;zpc6lBp~wl0w9+F(RZBVpuXDEk#DZsuz(3Hptq3V3IBHe#CxX9!BT?F@yl!!87vEfr7enHD*sYL@; zh6+bSP>Buk#`t@Y3R6Bfcr0saw6U)ie#%<2RAFdfCTr%TLc&A7Op<9TeP6s8YvN_U zMOVgUzg;fNWxw676m;4Sc5c|(>8VXp#>*qIjYA#1Zcy$ZeBLHw2cHn(;L~CWPj}6h z>w96@wwR8k<^{JWz#bf0f6&4lWuS|t!>;^A^yGT#-AG65eyWr?QW~aqy(LL2`6wlU zV@}8SSvU5y|G*i0R>=g-od>j3t&FktM2cvMW|Xih<9XDt!N6C=iF>1^xJ#kZ@X~xI z*#v6@(X68>NrCJ{#L$4s*5S-aNnlYUVvt*&ThAI?I$vQ#ewjqQ%Pjxcl0k;>k5<6q zg!^TT6y<<#8L7iaaRUEn2_&L;>@UgL>eYMsWv+r?BO=yq{3;(TKyFgEDg`UJp27;Q zdT#w;+)2}l)F=4z7T(MK6i#qehyUGG%z%@HU8FJ*D@dAD6EHE0{G(KQiN~HvhTt)F zLw003$&L)jZsSrzl{^oUR&w#Ji_+ztUB8sAf3&|u$~K&~lF2(pV^fAKh=O$ar$Z{@ z#R588Kcn+D6z!rTYU@SpmR+9q*Wkpkb0Qr5wSpM z7n}Emzkf1ICAbre5&sE4*B6K)I~_HPry!Mn3QyW6@It6jJ0w)A`0Hqv_^T+z*`)kt zsVNd#%BuG*9gcdI2IN@^JOqSkhmC@ec4}Ro`pZP@yNRhg2%S%+1Nt&z=zZb!DK6CE z8(2>{Ooy)#Ih@ep6ESm=&t%9b55cwvOETur>zleG;6II(=UpZ(GpVe|v@;@U@9^({ zrqn;!PYw?DGrSwTFKwpMAP>hvN&o&25j#B`dpg;GR6bI_NJ_@Hkca+OJs#9%#F{S} z7;=EhA|9Ust($z2l|`dWJ!nr{MRr;SCc&>twH>RPs>7nrXVFm|&MRap!-(oc($FOW!lrnFG{w+GvAEZ9an8 zV619`Oy8eHxgF=D)OW)Tyf9X`3w2wNmoZlVpYZ6t3+sKrI_K#4*ak4R0ft|2g;I|3 z!d-s5DHaxG79#l;kPqEhwN|@2OBci&@GBd?pd(zB1`R$E5zmnF;83oDk*9WcSaRtt z6W>HYyIG#5l_lwn2y{lQna8N)A^NNaPAT1t*`BUV2R13~3|>$8zNoJ#9$T8ogB852 z+zCq|ZN=9&j@3Ayq_%?Dm(5408S_QGQ&x+T@_r>^EWAaTDi2>Q)%G%^w8IyzT4~xZ zldvWDt_LUZ^=09q{xoWb=h4fDjXMH|W9`Nrfxf=qo?q`yR%Ix3ltuXds{KXs4SY*} z9)6!5wT@v)Z8qny&W0j_Q!U8UN=H5^pd&H~JmQHV+78|MIhn@L1dY9aIJOBb(Q$1B zu7YUqvV2PSqkoOU=8Ao#Oqwz_1_P-b<&r&|&Py1&@sS<61_!L*H;vPpSO!{L zAJu#4eF!u{>&F-44zRQ82DRyZf#Je5XvK zw@Tt!(gau_1|#K&D%u69fSxocU;7F6Cc=J#R2vUVu&`^rQ**;oulMbO95r(EZ{X{P z^lJ!>^gg6tM_j?sCIQh-)Jir@du>!&Tg|J0Q4QN``C2MA@t|S z7)7UrA@%jeVbGKOuagG&6Q-eACCO**m5c@IUgnKM=0hZ zFi%>3cjp#$*?k~~i7^@&h!U#<(AKLDxvc}PqJ!iBwuB4W{;KZ zkx6RT`M~;Ig@;Xp-pP;&jT1NFflJtt)3P3t?fHPuRAmAW2M)mWlYbbTtdN*KEY|1ci_K6pk4WmGdb)4iD8R za5}Ws;AOSOSwvEeD5qrXW!Q2jM-c5OP=5ntBCHHA;{I|lt#cEa)VlHT(ls5<8G(mSRUIa@H z%P#V{jlSdT+Tfc6CoxeP`U&(x1~A@6zM+9F-rki?TIFoqDJo&NS{%oTgEi*e3@ja1 z?S7n#pDtf3(;I`9o)hm}0eYNZNcZFby{{PdgGisAFH~QjrevM55j$vz-jw1{xEUFW zc}6BEgDD{@Thgab@$jmt#G-OE?Zd5c_->(T;pXdWBQsXMu@{mXFYI2dS?%wC&bC7K z>qsA%XA_Fw$4y~1(6cB;iq7xvgH&H3_je1O>00&3yS=|}`D-{;ns?ZL@0NdZx|+>F zZ1G&9#((PWURq-yzaJ<0D+<7GM{pOS_{*qW?bFN2=@!cjGiYxb=~#}w5UGWTKZ%+< zEZQJw;7Ry;n-d$U)Kr^~TWD5^u z*i~@H;x};9P6NCT-yV7ozxm!5^5=O7bkrR2zoObJxq!>vvL#H4bHnTm8U-|dHC{M5tFgE z5U+XZt%$UTo4Q)%jE;7A(7Q;Rj8j552e}10-ZYuY64ZaVCTZHqgc;{tACdARL-pK1 zF3Y{ddrUjbJ88)p+#BD3=(I24*|14j2KO-YW?)Ct7fhb|Sp`rjBV^0c<6#6DRuMNpcXJ z>hs||pXc82bN<6PYl-ut#?41lj2ndWNXTo&sY$Z^{m&VpMmBZU$q!YrNL; zWEUyHy;0k&+pJ~$Hgkt<8?%i(#cq55bCWw=7K)3oCs`n$`g`pimd*=#h=|E`5$uOF z_fAMWI5!YmGMWZIxkVeoZJ+UKhjAk$t9>$LmPLQMw9Xij*R45wOZ)2U@7eJ3_NPe) z?tKv#=48QaidaEM69gjxq_Ql!hE7X&;rhqbn z&60V{3VFmrPbjIl7t+9jjNL>S3TiFv^!HJJ(pb*m$OZg}Me7-9$NzS~M$~3vsXJD+ zmYq)J@~V}zMS^o+xOc9NrWN}N9v{pn*(#mv|%zO`Z-$7l1x+5{i5SiJJFK@ug zOCv_&E%SRE#HKLvgScH7G)ZN2+6GZDaTC2)+8EwX{5L~ z_LXwfM9c@B#DwxR$7AFiw1o^U->5CL8CHIp=7ct!FJ_I{O?q=Y-RY?Q9m38t--vrb z43T{E7gT0>B+Sc0vGbrc1~R9wFGXF~Lg%A0$E;6pLrm0A>@!1a_ThH*R1C~^M2k_m zI)1kUkuR_kmoa|6h^(G3)0-k6gKT1F$X0u0>oiy{?9>~>Y_*Nu75UE-=5u9bt2^Jv ze=xu~(=Ka7b|ztmAkvBmJ!>Q3 zj7>!C(X-pFQc2|W8e(xCySdB;PPnO?%s8ox*LVUoz89f3=#9E1L~8=x3Td<0`U2{9 z;I=|<@CLcFiTNc?VvKaC4S4CBrb(7y$bcTGR`;hW2Hr!(kR_VgR~()Jn< zFHBpJ*4&8|d2;wlcnfwF3`G<59c}e(Ej8xIZDp3}zcTFhqIzpt8d{)OsyMxpYQr^5 z{gbzs@t7kmLaq5(>US`AWQK0c7;Zwx$u&fr!1nodYk&ON?;0il%P8qx9a{FUsBudn zv4yJ_*b3-v=Je*)j}{?zY}xqzt!Y}04q-L&x6AHtP3f*Q-tjI&p7_6ny$O6%W!gUc zoRjS&P1}^Ug|?iuP*OIFq867iE#=TENOANXb@Vj_by9t249kou>TuG6q%1E*MGNW} z9MBeIY>GHkWGs&3xQz2pSmp&4Jtz>ME~jic-IDLRPYUXM@BjPy`(_1W_-W2HAxbq9x_R^GVXxvPCE^!C`Y*bCbgvZQtXyVoeHn&RXW~aU%WP9V#6XX*qz58u*2%q zq-!_rjBMl%P<)(#>~{RV13tQ=;_2`#s(AK`(--s^FC;(WgDbwoueq%`3Wlhw!WE_mhEQG(bJ|O7zg$V z{6%o?ifF~u=g^9~@btr8oO?j>g|%u5{EVjzix{Vn{ma@$)K6VUbH-eV9^D8I0w+B2 zDpdBozHeh*@c6*3@txA!zY#WW;xk>9Xra7A6Y&}=hY&T56@^zeUX$>0$*hj>>wr;183uKyty! z7$OSLbF$a}0}{;_@c)23ajuNC7~ni};3riIU9+pUC*IRv(qU>9YmGY19fp||m1MjY zPyID2)}m}^HD1()Lz7a2XPMAo8JE|hu2!54wrA)6;24AoZSiOGXc z6zWefWsH&^QM{09{gH4kWW~&FHMxY;BKJ@nWX-uuu^zY_w>dhb@{0zR39rLy#O2(? zXSce%cC{W_C5!kAAY^#h@K&1l&Rop;dZs4RSYg^(u3(-t41D;5Jt}zq+nK#-plU*+ ztCl^5ySRrN_iCl0%WK|f#y;ZM@1x|s&)dizgcctHB59MSwz|XCYHmr!y*<=l5vREu zxlM|30=t;d>Q+AhMRDPEn-3VJ4r-ra8(I=V4Ng|*K5Hl#*20v0#fDl6P|GdR&nxFh zLg_Do0kA{65qT#dt2BM08S!$!Dqyj)0_q9c>j0JUnbkRn!Aiz|p?!VwMMxpcJnm4j zL=sr0lWLuNerz?>iq=-oM`js2jGkm+B(8S8pIV~Z8TJ3sveVqSRGZA|XW-|Ih5tY3$+~Otnd&X4_f~9#H0vDnhvYq8>vq&B zqaFjKkroqr{VM9Y6Jy(HDUMJpu@XAc^qT&H+%l6dkLhHL=_I}ER6Uaz=3KAC()#}% z(=?R46eUlL!VP5Sk4FT#K=h{+FDvBXSAVDI#`|4N@s8N$27S95-&h^#wiRzD{=avS zVsPW;p63_Qdbt(l8X|URz2Uod(pPD43Z>k_{|K|j5_zvSmih25vNpWuGAP)^5%3n{ z#;s}_A*ErrL#Br0Z&ZMWfZRc1wL$-evw-G^{Sw&a9>kevjx}x*TC<_G8G|?%i&%NW zAxbBVtuJb#czY$NkWV!GPLkm$!67nbpYIozB)b{w?5mg~b zQNr|*&)DiVOB|woc=*o?Vqx3l6CWWSn2><9n6r76gzr%cY`2`~1VyN1*e96b-=G(K z8tsc6+RgF~?Z4X0>(^?F+`PhAGx*Qk)*Tvrz1L&6$U`v8l^Pp2MY=*t-)<=wf*b{A zwOsRuZLWKx8+QKp&K=tQ)jPBYJukv*3Txh-^BU*6Kk~3b<1+?+4|kzwrH;F1j)`Ws zSRv8rvYsP#wqK*4?Ns7MtqqjN!zen{?7A7xjCDAh1LfC6GsUN3*MXb5n#%bJzc4BK z7PO^%wQC%DwyyC^VdG8VKZNPIe5!5RU~MARM$#o&na%0~jdk$wguPWt!&rN8Ho(G- z`~aQpBez+>SNx;58hpkzO;5sVd3(&%I&JVUB^9b?L7j*=Pv0`zZ)QbZgp3Du2EXqR$7OcxyvV{1*^lj&Cp8s{T!Uj zMbN2BC!P&wOS*nenIa-iJfOToKYJo3f**6%k`7@3D7!-xy#}=13vMbA-#u_BHX;mZ zo0Z5$u@t_VpFl@Wkr#GIam39L&MZRn3`TcD$t^Qi5g z@M|T+aZX(^$T4#8$@u|soaGU+j=KaxCwk7QzXh_eQR0eIt3&6voxLgSfw|AMf#b5- zSp#*jf`Q1)qD*0V8yfHubOY>o-LW z&^(URHIKm1(fj@9eqBZ}hY(Xs2oM~!!QaN5LCdx~!ADyYC3}Esu4W}1`e%Bg5)yn7 z)~|_nF|q}YoySk-BXiGJSMQH0-Zp3u`4H_$6V88Q$oSODL1z#%UqYol+)u0UxBYu# zo4vFO1^Gp73?tnNFuvUFv9#vW@Mb@Q&fXM}Eu&!1Xo*!yuf#enJ&;Pt3!%k}F|dZh zwU4JVwPX%vYO$&B_s9~BfLS44{s#C@Ga1%wD^3!9mymow-}9?T>mXEsCw9PYVJ8f+ zOmRs}#2C8SuvT5WwSIu?=6^l*S~aWgpfR#Uy^rr~_W@nLMPCbl=wad= zkVGy;&n4pTK|V1>Q&vNo)y2nQ5j;V%|L@?Z;M=9=&w}2hB3$F08b(ZX)rUb~Lt@+^ zbKxZd$?;{B(Gw*<{1gT^I8I10h&q9PNNM={Dl4SfpFYv3KS6dGs`Fnbs6|gg<2Oul zNE*(|2zY7@`TyGXq^ysy2g0gzEGfgUhvNQUgxqIGKOK%tQ7FC<`ZZ1!%=oj}1hO=c zL}-8%1ne;fS1e%mnS*R5XUS%ATeSSU$cvCIx#DzOL58>su6gES%YLR5Bg+kZ!VE@( z!SFerw&9*k+#}%WvG*N_Y`(~6fy1Bo&j?ri4_G6(=!eiRdA$A(R%qHrS{swv2Wuv< zG5g-u>9Y*Z)Bz;Dnjl5ol6>;c!0RNH%m{#j1_yimDeR48S%zHGzzWUV%8<9or2Y$8 z58~{LqVLBxUyv7b*S{O#CXR^?Rk(?JBmBfs5yQleh;iZw zV0UglYaJp?APqOKrWuV6{28~$_zA5Mi^5HKC1O;rv@qqYnN0|N`bj%ek0q+Z&G4TG zZ)oamER?2WUK89>L;=DJuTOc}j zF=n`eMG+}=F^ zF5;&mX`(+y|5NSAFB0oS+!Rr}JWzoksK7|vIm#jGnj-o>68tTLrU7+$44vDl0Jmw>_EqvTC1v64~FSNH>e8hmOqcm8XFH~r8hdvMA#@@fV4K}^2(wa?(;HS~XsHdfO53`kmTOAEu*tA0_`I5DLq6wrM*)#(@ z3*BGU=h?q~Ze^|e0)l%NFo)B6y2Ks*3Z0&LnIHn`7AIV)`H7VXD5E3E3eehs`FAuMFTt1?&JI>2C2 zm>lL{9i#{%GwLuwgHD=C${06PkN8Y+RB{Po(tX1Ua==vzELWW~04cWr+DfBGkE)pU zrFOWfD$fjb9|JcM5f(?Vx~)2T1g&4J9^q=wR&Wr`!7KN{!*+{7>54G?)bCA=+J4|wUt?Gh-0%@U_zWwLGO;nbi z5i6|!at9*)tm-ofAfV&3IYAk*fQ$x?QZ2Kpj=lH{kY*P9uZKoFrIj6se}sI~L{~`H zMLq%b!N6lV;j+f{#HoLMguV4EMi0 zbG7~qyyXr6J0H(5#LE#@dMRuriMjRCYN@Akn3UFS;3Lo+Lhs=yK%c#^csDI%Pg&K? z{bz3_E%#Yyxz~HxMy`Ubzj~Ren==`sr+^=`sgL>spWiN%qcc~;tg!X>boiFGFLhMB z3(Ok9SF%QKH>$%^I5W*t9}+4U{6@WyM1Gr;CDyDzg(29v^z71wOO0WM(Yt4WZT#WB z)?~DjjlU77N?em&f%KwY57?i8Uk>)fXZI}h|2miTagTo6K4+#H{h>T6X*$-c)Po46 z@l;x8<&VqAK^gl{Mj~$Q|Nkx{5$F2ZMxsnq%AcVBn&r>X+YwJ7hWD|Ouo-KWQ*)Aw z{H%}P`0Lzn+xM1#_it^ff-C{N$shIW^#ocAIl_Y8e+t?kK$h)LR~mXh~61L0|Sv#F2YiF{|PFd^9GB~+~DGwz-GWWWtiGJjm7_Rt*tD8DP zIZfIr1XgB5LjFu0)n9~7BUk;h&+C5>UMgN6Cn`P{eC%nzT#9!xIh&-PNfen)vXEZcpX>0SkCV^ia_Vzd)+Pf`tSDgT_)tznCCNy5qYH8By(cK*97Zi)8adk zTi{OMw>nBZ9)y;IvYDmH$N)3bZvmxb>IKA$h0BeR6vF$3DA^(7yDWMnyJKe(aHb~d z)o#%&!p3Eqk^_FptY%J}ID8az$zKhmhim=NkT~6=Hv8pvp(5!L4u^pI5DN0Hsrz}w z6CCN93_OFxUU8`su0aMu?Z9TdUpTP2juoGc9K-wf5x2{DuHH05!~Fs~WlTLn79@cPYd($#)^d7wk|^YC{`#(mJWorb0}8DER| zDx#XEDdhhI-CbISki}rd@`Zw@`xMYby;e~ZtG_ftMIP__8X7DV%(@=zWF2E?sV zuB#*IpAU6ii4vGPda5{e>iF@6<0em?T1-hGugGL2&@~!9&v!YY4fD;quGH$v)$biX zI&(DrVPD{P!rr;$Geurh>3ESx6@2Dq!C!OMP`t>qioC9XGXbA$#1p97`$-0W8z(VC zE*J9bvf%s`)bI7*+w|X4cfO?m@@gz&7w6}2LaxP5EF1jBIXL)Rx$zs1-%{TU_^nY` z3t6d5|1>!Q(B7FH`|xgYkY*Ov7I^Ax=uO6-NM>MfXh7l78W4|L1giSz7=;s=T0g)6 zd9?yKd()-Ec*3gMdc7X9VS2q5)!fqt>8>|^sE?@KB5+gJNwwb8ea_xzdQNjj*Jqz1 z5083Jp9NmbTa_QKXZ4;X4$q%YT_LJ)cNo9{=u=I!f$VYz`R?kf3GjKKz za570(74!fM(IGr~{oz18_;D-jrymjDi9UadPb)O~ke`}3A8K$^OWW{{$kPPfiTo+J zs~ThR4XiqwpxPtSiPQ7_zG9$W~oUaGYY8PtgwPC)PtOgef0D*J!d$? zn|(&@=hR)$h`k<7jim82s)NU=%oU|*w{d^!?sqQU{W_bn?0muN6ishH4_<-CpAa=zu2oNq-{nTPx+P2iE`YP%HCwm7PCP0@(f;`nfe z)o8V+MXI&X7+P(`zA~@VBYP2#<}c|0Zv>9XuG+CWTs}{oTkT{X@JYU1DCzceWJHot zQW|m|Eyt$?pFw;Y@VN$`_6S|)Jan}T?*Nv;`x?hS53e|!cJ&xCA~nJOL(e~hPkO!? zpY;3-__RiD*P1e2*u`ECv{N1hyV(a+Aks_F^ZVYOQ_1R1ANTFLWwzok*{Pou4);>b zE4b&T9y%-7=j1WU#^Dqhyu#(I$0_2@58xgChI*bBoF>t6z7YNk`RwYNz7swlcv>HD z5>3EtwyIT>KNfTHD12RXtb0+_VRc8#aeD7>7v1f){wV}NeaP_+b$(b_3|dAxY8s%7E)4B%Hx%^YbvXThVKCx zPcGu%T|pzUOy>^CHfjM^{Ja0lGry8?|00*yq!7LR26R^&O7*t{L-j={M=kqhY}u}4 z{P3Xmk%z808BYSijI_pxYX(Xct0uGnXj~Y}+ksU}S%m2uaN?lzBAhq@R^e3C@iIDt z@9ViW02C2I^+ydaRZ8*rReIb&Ja&Gz=odPY@w@srFZC>i1+U^g$mB2ghRQAb#Zmj( zC&2eJ8Gi&)n^X`j@h4nk4!hu;9gA)0M&yXgbXaM> z4qlctH~Gi6bi4K6D7uY)0jls@Te?H|&3KrJp-G0w=1FFpDIdh9>SsmmqkoM}^;!$G zV(!3dXc8RKp4h{W8=yZ!p0nt~tN-V!7uwg9pF3PUU)Oj+1C)UXgLr(wKqYVz;5e04l`G@@ zkI?E;BuhO0-#9H?_-xZ9aq=ZgX<2Q+>nA#3Q=b`lubuALJ9x*{VV8fBFFOps70fPl zy6`i+KLNbNsEy8S@Daq{f&aksMrf;2vv~JlJ&zBT!ef0nKv%4|FBKtagN&+sXy{L- zaGv7G16r!L&x7Yhv|{Pt^Q2cG-~NUAGt>@3kd4P@_q(7`_}N~fDa6Z>-_HjF$#@k` z^mEYun5l7~7lc`6V`^BR zk?zUI!C4AGl%@NUarLbb+VK~(`(RWA9dl`C(b5!3ZajV%HPc?rI!tr3eXwS35+bTF zvIdN-aS|5=*9Y`X-`>>z?KymDc6;OPdj$1WWY#fCkQ{+bz?qJ87}aTg>EQw|xb1>} zRF?TWy=FBVIHr!0PH=7vdl@Y zRKWf2LLO<1*qDOzTBlzQBf{{){mZ^q1GwtuEmsOZdX>pQD$t_Vt@QPc`X}lc)4$ZdX<|jwq>Vta+z8|^ zpe6YDibL%iwKU{;XKGRq^szjd2t4NYXZ5iMX>Q&wKOe;tz*exa;)>#mvI_8=$hlTh zVL3so)eU-05v63$O9TBW-Rtq*8IH#v?Tx^C5syFAD|QSAa#}p@>zE75Fk| zqD1K_TA%!>;0hL|dw#CtC<6VvQ7cYAEW#(t2BbXP$EQ_t6U@>7naV%Z2rNFzgHyWq z8RRBl-44?VeA+sY6R&}yLKu7DM{?sY$`~87gR#?BFm_cr$7o(Gu-gPdUpTb@V<>b5 zS#CicsrC( z7VusBxQc8MZ7>YD!_4UmJ^&vJ&$%&WX5d6$(`yw)-<6=ZrTRI)K`((~&)8U~5BwvL z6Mng25z6|jVgEf3!ISBUL7c-!^|^k$n7}EpF95kT-8s#ZG!*k>5RuVA!AsE_2aNoQcr!O=XK$l&FUJ>jEEg>Sye9g zs7bf1lcb&@QOy=eA+!oHu4}*4cCTRLvSGVotPLJ4r6~Kx0gGO@wcE&*N{#In^$E1b z5h)#P%Lf`XqE2{G$N_l30rM4lKGNbjl~gJ4uj($cOw*=~!D-WL?#Vi11%*Ukf?T2d zj1{&>Tfy`^s_DUAv(Kzt32pc^L|GQGWc;3_%^8GTLvoq6E65*d83cXymuf>0-j~DNhUy#jI zBF9UnLgHYO@!{ATgczTgL6IO83co$0z=EiRWV{k3lp)_*Zo#koPx{}Ld(_&&Qm4>o{t0YD`uq9`b%x<&yTJ9di>vazZ=aMLQC(j8Mc6ja2|+MKtT_ z-pEdVyMQqxDdWOj?YKNn);s_rb&0C_mvt zhCz%L&AC&Ts-(fOs{PSe83t#4zIP|kSBB&z;{yY*oY%RFX{@|x-?_OBZ5fh`=u<+i zW59-5=*<<^Yi1eLpJ!d~GJAFzW}j1CXhF#TS71yMZKtSNWG?TqNOJJlYWFC)osA3Z z+$K3!Lq~g9K%aT6E{oI9jO_FYC=()YfpfrFxM_EgALo!)OJA*??rrTt{)%3?*H&SG zmzMw?!MAyA(_PZfCAPt$u1G4Yt1IMorJ*AjEJrNaI005tITs!!Ho5&nSTTi@`Uq?& zTx9_c7}fRH0R?tQC9pP}(n$Ec-9Q-2>f^gVY7f+Mg&8G+x>A!hCNoiKSmgapRf+Tz z#%1Av&l|wFEIYsSbx!WC6mOr1ZVis}jY6(ie~w^&-fFcq_MSImcf zMO+~(nyJtB3q6N-(vB#r!-^Z+4c+W zp*2V|j-B4PPZnrjm?;K28Lu8l?dF!o+D4%QF|juhEl>T|68KGEzIQt2`!@8;g!wK* z4|eHmvSincH8WTL_1xc$tZ-(yVfFp_-;Vn0s$b{lRcz=xckX!mB>0t*yu=_S7%E6M zZ@?*GkcP^3UkP?TW!j(R>mF;UN! zQ|Cr}CGCP6F?J?>?4*U%m-~@Lxj#S_tVU3k;Zk*w==GGI28pzLZdb;Bw}`WoO=3*k z7h>%H;B^!)?k!{i?O@DZN~o(GEZm&>75Jy$M{HfIz_*a5f;bnu&M$P~%A-+O<=L@S z!SWjpZ*Gk4tep89Sh?rvPqu5$HJRB+fZjpK5AzS~23PE9sKLEOhxww`E;Fsup54Kh zSIeWAYuM2$DKL|LDo73O-e9elUq9VztHAtRDX50tqwu%Bn8%)H&sx;)2R5(fa5l;9 zp@y2(!E(zHZ_vO-@IRoqe>-jDJgZv*6k&3^mTKR8 zjg!zLa9qT98Nqc~)VmP%7;5k|gc^}MgLmg6GfRQ}4yNUDv1#J-*QEU1RmPb?wXKfJ&cse7e5dC!ju`H&q+)coy}W1Yy{B61p@Z zJ;_6k=IL(S#|HUT_&}mph)zKqW%Kb>t5W~{9XiI;y%oS9v)vP{v*ldl~6w>@o94XgacT4239g7NzgUqjOb297;0&0%Yp55u8&_Qz7R=RJeYQ zc7pzQ!nPgK?DBk^So)bH2n9~%6+iW{0#+(IfhQIC^)V0%q`T>)rxF*V#1B!T1*Z#@ zN9T*+Tp_+ zlvGJGtiv-MMb0^2dtwF zbx)yh|ADN$E4VQ_w-3E#n$TtDvieNjpht`NGyAO2t#QNq%vn8iadng%vi^@cUieW4LArq z>+wpyk&wx5lgetTgn0vZOEq5lHhaJzT2!E)O7yu-_Xyylbj3Q5)@5VZ%`frLV*VB zd^~W?GNepOdX+gwRVCuGm zTNf}d-}Y523&-2>`!6Dduvn!m!E-O{yz~?(J9d6_paGhd>OLM3lhra&?__+Qc9rtm z@wTFG!W1DoS@|7oL%DDD36PfObddD;t|X<%T8lB+C6Oyoac zTc>(n#1-c6G@B36^;O7P;|*%So*~=(r0{roi)LQCcb`>ekETRisFXP7pN$e z@fb3r+9ug_t&~asvs$edW1&GY7jk6#EyND~UCJ{G{C`jJams5(7MEmcNrcwVnoD@V z_?`v+aX5U~AHs}SC?2ob;B3=OZn{sR9IVjyxhI+SyT=+8wp0d3UAotO!xnh-G1UZl z9@zxJW&KRw_wKuq-6q1}4m$TSuX9a^)N=dyyjG;b4OM`h~1e)9`#%rwm~#wjld zE|3d?0q8+YQR75g#56H4VxBl0dxuV%Px|y2`E?_tv3V(ZKOVoSSAe!P^^yl1c+rOn?|{t}+#EH4}~U$H4l`>Dj|h2JY_KWIn)xrg=@?I%Hx zC$}+gZ~{29p7;Y=eN4DQj*f4913SZgMQT61iv1wB%Q%tg%$V6P>|E$2jn5>EednB3m&=G?I6SjC%_j_#4*bVgzn(!?1G_{#{iGM8(E-$1cpu%1@r!oCuc zQ6ip5;52tljDRvhe`M?WE91MEz!gAt7w6Z(Y9ji)1&!{;-SG1&mBy|z6i!^Ut^WIf zt9~om@L%-;dREux4YX*(np!l-*jk3WMRT+f53!(c=SibzauzSzs@ddI0idod4pl`@ z8=V++XAOBjbB>5jA z8UkmS+x1?A7aI($DYf#MI=`S(Or*g z;wnp%(#V>8-d8V=Km*3!CL;=_sS-Wx@AU>O&F(NSTArsGtMr*J?z{HnZp=kK<|6k1 zWdB91*^4pTigCfH$=0q$o>ss@FWY3#HZ^b2hJmJKw|x~5>uKEn-fM>T3|fRY|<kvAvVhe-R9h>uFbR^|2JFb>tw zX_`9wNE>+R`M><|{ErZ$EsG>SO?;D~$=F18cK9P($LvXd=~POkv{vX&RAYjo8kxGxWSdO#q9+F$vwZGR{a17P zp$U?`)zXrPXC-)rvDct0&e2TpMX=)iclj6FKLys>G}b!@x~sG=wNrmIc2BUFn;goW zl6fOjA0kh7pH0`}->ntFq8OZ|tm(YBtsFL&wanEOC7$S;Ik!r#t1}d;iL8}I>Dqhm zKnx3UWB7!ZpId601wUOVzQ2iPwG|=X42^dY#)~wBmw2QG9UBl76aE_HiAnbi>xJL% zGP0p_@DCylU?VuJdi|Oic4{L|tPAmn67G(a_but%D)Gz8LA$!&>q35DhNuqih!v=) z9U5b~W3$6z&IkeN571LW|R)_;n z#GMH@+B&TVnTnym^n0DF-LNFEBZ4G0yn<+Wqgb+tO7sPkMqhn*KwMo?A6nH0O&x4C zJ$~=L!SW1)<=u=}yI=ljSNyyO*mV*2WaEDKxYQW?_PTG}(GFdtI;`i;F!A-d1u4l4 z{+FuQlMVj{*dOt_M2T*PPjX7uONXu@wcf|~V7*VqSuqZ01oRv*8 zaZxKx`Ah_8PxfL4wAfY15|ffP{m=ub(KFyV+!&8%Awi!e`J?QIy1J3Q<%hanZyyV} z@j`s=Kq(>`sl;fk#Cst=OP8KMj-_P9S2RzUWX?-{o0&}%Dy&iOI?#eY$J&Ce&?Qg= zeHa$=Q){X&OWdu4W%waUUy?V;a$-hy*MAL4+`WVCeFNjYp4vMrU81Z&0ex))lQh+0 zaJgG?sz2F&LwHWO6s;~DsD_Oh-0{lPSa`f2gh^@~tB@}QJPEX5m?XuYw)+mvjdp(> zOX*zR1066S-efDz>$7MFMSAom#(at3i2zFF`3-Cl!#NT1>C48OaUgG9o*_UXT`Dz_dXn@?a+ z$K<|82;+>^?T5^7hPCe}|6#wUuBmU}8FTLV3fM2+H&3fDzGx~c@_j9jTd2OBi2wIn zj$LJqS+M&Y1>y_?jUYPV*tKs>y+7RbZl>|bKK<%He{vO)sczXYL;h#L{oo4f-RoyK zWkdkH!FSc0a*JleLi0D1rEtL=w|H~w+>;E^QF?uBFX3A`c71=&A%n9qE_$;Ew(6?f zGM}3)mheKrzMjOQ^WSvfWH^hwkCh$VxUIe<5OHkS8zS0hQ_q0M@a=`qnEQkelK;=i z9yM5^Y0;Y}X2S{y+UbD?f)L__4jXm=n@pwp_8zTt>MA=CxjJ9F z8go&Z{8f#=s-#XtPf&luQOs+~3WjkipQ|QI-qi#olzCTUS?_8_yzF>6vb?ivd{{Xe zd>q7(&*OWrl6g~YF=#1GQ%UT;O13n04wAh+d7q~eUYGKHH{Vw!VDy%o4{8EO*6M@W z*enhRXsh6jn5%zl#5Xa^8s_v^?}MnDuCKup&vm&-$ z45R-w9DG^VB}w0JM9;_8Sn>bLB>6MZ|G70b{J$(Y9`}khY4~23yb9xDRlm@^+`rV` zYvRU}pMe8+3yV*|=l45k4y@_}N!L<%eMSx7%6KQx=N#i}49x<{G1lQwA2_^j2z53@Y`Q>&T=eV#A}$FH8?RYngJ) zTQ&+gbUw`@4Cv3(!(t6n6p!xxa1v$SsBHL3bN~N))C+^rit?KGZ>li{0omzEOC4Ek=OqFn3K9Bz^FJ0@al+|kpb?ZJ20|$(Q zHwW8$S0EeQ={LzvpglIDCL?QJOrIP+8Lrnqb{k5vhTW)Zq+T-c=-Gx?}hBu^uvB&G;jaYwQ4S9CsBcE-wO$$3DP zVucfZp!1z3r=egBwCud??e2`s-$BD=S9`4Eu9$WI!;j8d|MVNt!$zPf!&9|!^<&Rl zesyT1>*fP#jSc0q4m387gr*=+ULIYcvCvkHV^_-1uR^C9c#P2e0*l{Q$Wkpf(lrm> z4Q#6Xwj!>Y8tlx2hEXe~^ zOmDq5W9Ib-c6XaHOAlleOz@?hDdW%z$JbsDG(-zAV+RuO5S8y%+$hV_h<@az`XL^0 z`4>WWdlN%8$;++8vphZdwKo}mQ-9J01lsEl(r5Y66G_w{l@V(DkJ`_ zjiE*wg;ec@z-f9~FXf9^Hr=<>>mz^Fq0s2tf=?N_gQoGh%7?)MM8pBPWc&yv-&yP{ zfv%nlI?uCtoJ{K>Em9No1LK3@D1y+CBg?VRtXw4<#_RWCeQqffyccMYn7pgImA^u8RB`v?2p2Gu_*)}M#RbJe&Hq1|8UF)jp0qq?kbMhJ`Z&x z?!&b}*Iy5rKYaeE`FZn2HpDeHV*EVAH5xc8pG8M2BY=6F?fO@Aj3N?tINseBpznP8 zJ-#tZPfUd7_#)nAWOc+fvx;|S{uT%fou)H*cbj5(XQt!yi}4uUX(>Krm^_|Z*!Cvc zR1cKmD$AHd=E->n0`0!R81|9CHvdTBMVxn{u>kjqi>NoEoJ%Of(4C4;wU^IWRc?qH zo+C}=tIATnMUNh8Zm$<`e`p8pZtJSg{7sa{9cIU~sOLlTuMY8(A3!~+JY7C`IsNAW z_70Vq(s^Dg_vcY6^)c$Tc@DBr8mQ;yWtcUTts|)F76%b`IlNS}dEp@|{-cbc44O)_ zgMaQ`#Toq2^Z;sHfEsQ36(4f4-*e!7ePr%D#7+K>XxfiTtWcavkun0_2{dMvhfI^D z1NI+Xe-kv~*JDs;HEKXDw$KFSYK2DjN|aR+P1o;r;uqOie2_+0L8g0VDa43750vP$ zKiZWY$<*(|?3`!SThLy*6K!YT=A&GcEwmY)Lyo!T3-Nq-;|q}yN{0T#nV4mqLlMSh zD3{8zM)F+9*(91a;w(y_)hJO!oo-}_qV;bZ01c0Z9uq;sfoCZ#KRIR>kmI7Hr)DhJ zUW@bgo4zsNA%1!$J=^=^Gs&d>F>&ck%2tIWok_F<*S0;6b8Pf4j%tsG;LkkK6j5q{ zn%YCs>VCx)v^vQG<&sx{=J7=%m1DIWq>is@fnhaoy?m@TxJaobL_;p1)G}vau`8H` zC&a-gj76n>Tayj`F|-Sf-Pvr8WN+fs4Sj7=K-tsnK$Z%AvOUrYPjfj}Zs(zCWe(H! z+ob%B>F^luTw5Z0b=PIL%Vu6$;8E>Y0J4ITF54W&Bai-$^)tR#-9{+Yy<&FSD6&)kXj#AibGWKkh5_ z`NEy;4VV+kd@VLyr`TYZT$OVy#t&v@-wWMcAcuoDDnB_rg19NMe5M%~9wK5*EwHyG z!Cm85d5p3O?;k=c;QS`!Po!D`(54Ey2ZITpE835qwxhq9z$DG+b9GSL%SM;YeCOiA z*ZIjqkpsk$X^*BxC(zD|M5})o9Sizu0&f8CBj_@qWt;JWB>Z70P+Hp`-n6r7%$oM@ zb(=3No0+`P6uBdNN3gh}F>h@<=<2xQoHw-_WMOLAO!4r9inkGKP@wUn-$pKL`fQf) ze#?6JY0vMOtJ>{l(#=w#^a-8iu)bbc8Ge|F#T8rfoE3s>P&ma338i5?*&ek9pg;we zuX~}~eq{N>O13dr5ndh~d!FI$!iqH6;UVc38GT7=owcfsjiZbq^|0h*S6jy4qL`Y^ zK{?2b(m}G4S$>2+GWR@N%-~s64Nr_7XdrLEXl7%_iOke&3xklQewbTdi&(^LQfRK*vtTzZ^hJ6=YwshF9Y3%~m%IkiE4+%gs!+QmLs~ zE-v4?e59x>e@2_Yh=W~@&mVYL>@4-#w@Y@d0K%vVWy;CT|Lu~BA*E8^smCt?sa2UT zF7PZc0r#p6C__H**>^HT1#6N>9Irb_9Phc9S?rFbe*5-NNULz1iKVz+8#q_wjaH%L ziVzO;M<(tNak#7WPl4U6e>#}e6vgi%`)7=SH%3XiroasD_m5h+gZShBNjlV@frEV- z*QkUBd=Ay5OyZNXv8&i#s-HOJtZj+yX#a3{R_#1oDuik^7wiStjKd*bX9-T1^$PkjHxcX)r|iEr66 zn&jAp6RZ(fB8Dk^1ogBPe2qOn7v`zYNjHlPJ;7idOJgAgW- zDkm;G20y4pVgM`JCoUfWdJ4Z`u@UDKFY-+dl5Kn5rV$%QPS~(^36>=aoQAxi8h5(gB&y3uD>4^t`dT4jpwx@M*M3wva z=DbY;JRSKaY9~|BCbbOOsy9K4d0+*+3ZCodUlAvg&E|f^oQCz5DarG{di^IOBF=B1 zEW(ez-c)|m#U=1!3@zHFnV1;B=q$!Lsopl=@A&^aN!2mp^89Ace2eJ8NHXLmvgjkp ziALC#$bVx3po#Oo`s1gNu^4G9}x1mE46YRG!vkaE=E>sW3yp9`rUS^ z*Jt{S%@ki^#K|`Sci8p2OwH8qOLN53za?EAeDm}m%QH0v%A@@J`6} z*k+nyiFCHt=6zLbL7oBTT6VtT_0+oJTFu*rwctEz3!GYEaQVq=;U+`gCRza-`syWd zHLXnf7$+L0{59%!(i;AuX4^K>AtG`H9u>U7_*7o=Cz?@aO{GCr;LdMo$E>R#Bx!z| z_N3_}PNR4&xDC#3n(};9#>iJ=-BVA{3nnh7{B?b?PF9Y z)kQKMe+WBL;T5X!28MAH2-}z!@}CD{ten@(J^f0zA&oVS>0N!U9D4({rU7aj?v{)F zRj@IVd|^H$uEtrXV@g6lD7%5Hn=OB(G(bN`68qfqvX6R8n5JUG7ENrU6=}eV9P0ds zV#3Nlv*S{$US2nU=gSwC%}8ADiU^Q5ZV+iUO*G2a>s%MC$$6XPc8qo>xaJw`DOv;6 zvRFUvZUeO;`i7NQ?P!2Bu7x)f_u@{JS|Xn-X{iz~CKkQCa(`?K?%%JlXC}froUhNj zjL6<>CSWXY!K$a$-Vyupb)SCy)ShGOLJtcSfxNY+>J2l3^+7I3t7buez2sFkfLr6I z_@d-D#e|x5a3XNsDlG!@CxhFmvv0s<2(eH1OW-!uEI^;SRp2}w9632jW38AO@K z_0tqlPyP*UoHO8_d)CUvzQDP` z2bzzJmM1|OvNzrtPMC0)6`t_-%-g=<`ZS zfRKO~a2eMf29Yl|MyJA#b`v*x>Qv~lB!|^<*CEq((r_Rzu9M$Ze=3bx=mfIvMGitd z>*xgaUGckUUWMi|*EINt~jt25Vl47my&XpsZ9LbSsStVjl3`Xsbv zcl5uGIfJ|5ca)`{yy$ggq$~Hp8=4!EMK(Sw94U?1kioWnm^&338sHK;si#}C3OdOV z?aYHKlh^~tOyhok?9pRlQ0Nvc?0mvQ{IUal6Lb@5Ct?6fg9WRb%DbW)J9Yz!*%9gR zQjhpB_GlaM(y?Rvf^P+<2dPiP;Ai@;XkjzSIqqD!_*Uezb`+;a#NxDwyLe@EEHW0! z%YGA?H}m(%Xe2-KT=WZQVmZkBq=BfH(pxRtOjNp)FoSns2Y+(f_$<(}f^;JP90-$6 zX*l-c8(Iqx%5p`{IajsW*o5b!sZj^Trl%c0jJfe?qNL8%sWJZ!J2IE0i6uTAckFT* zc9c;N9jedVPs=bqO*2=pCRGac@gI5_>3SKnL4h%K_`62mz}@u zb+i%te~68_a-*JyTEaAfH=UPWXV_hDrN)tH-H*nRYFOAytsIIPIFU+!T1oM~(}N=7 zHTFkSrH(+Upi>cLC!KiAc^@Psp^a-AuXw{9{tqpGi5^>*zFnxO&oex`_LQAZQ8KGS zZFoEKmN$KS>i0dtUd&w*xo=JEKO>gOiz2^MxF*xK6fQzBY-(Qt^^n7Mk?=`69OYzmJ8po71;5 zq9&{m*@O&6oaNKShgs9t4~^VJz3)dJ9@58@vQ){F`&rl|ZPBK+(SCGWY`P{V)I-vS zF**zq25ECdUp98rGzSL{_UBJ9$V>+4by7aLq}S;IhL)*~!KPC>JI!C<n)8x53Fu{I$*8M zs&N9r|FgaVFX)&n%LlD1EOh}$d z83lJ}+3qYz#4PBNP0idhfjsQgGKN;!QE#cMpr6<~^aV7TP9}(+IIs|I1#Z?p; z66Pk12ZmpjpAZXpeC|8b=$pmkWpt(QuMVdxCioEnN!=wJ zfPXD4cm}-4zCwK?6r=!No$dAJH0YTvhZ2?Y(y|$y$XF7ApC&Mpq|}|T0S43LG=DD8 z_b<%evUGX5@$d|2%LGV{zP%gZ5oT?4&1vPP~kwE=Llex~acEYb(L8L%Q4 z5Oc{#o`gm~4g7r$ETqyD&+D=)ux-&Pd6aTGSe1KP4w#1>Jm#nP=dv?Q{1Ki%!qo`X zsu(^ea=R-~I;x~1S8&Um}0+E`!K@8(EHwb}Ai$&B$` zn<(~9fPZeyDEm~dBCBG1u(5qL5YCpvvQio|Z~Uaa82Joaaf+J}CxLQ1?cJPxOz)ch zR(v0}(Hh_U0ayZL}=I=%&UgR2vOojR8CU}P$wEMD$e zNPkVnXHN$aOZmL83DM$+UD^^&p#gk*fFav9X&7a!y8VRr8(~Eil6?+FqBuw4Xx*g{>GBNXIXZV8lzMgZ|zM)Qr_01B51Qr{8i_l8MR!&UiC*$Di~5cd8hZ>IfKh;$Bq6l}ukA)Tic_z`Z*ip*Eng%(AE zVqm@Bae0k}0wMn~#I7D35Nlvp$Q5Ob29@RH>UG}{Sj%t{`s<}XYD}*5jzRRF42zDL zReI@cGJ=Axg}1t}${q|MR?sL-sxMPqtK7M+dS6~G`ZRZ7_nzs&vYA}elV2($9-;i2 z17Uy3r4|%(tv(|qERJ&ak zz)yXR39?5j@l2?{*l#rphkjc{6w(NKlGgUG6C5z4KRRbMlmC4(UNit)g=UK@7kw)R z9r*%2?p;xmr-wq4Sc{b_fNt2qs}m*3Agba4MRD`c{`SP(&;uQe7W+?KYO!;h-&IGe z$9;wu|6`^_&*W)5QiGMk9ZeJe5_?jo8E?hp(JR`4C30k(MBX%9WV^c1NJ8~v~ zdYAQ*+?XEuSw$rfLq@!0RCf=6%H_S?ex)=~V$T@WzrhppIa<+(`pknbCQ;J|(Z)2y z#v9ebekXcvIdqNQa|3!l1pRiLDA0YUU+aG${9}4YnhNeP&KiZm#>>S1<3BC;y36Ip z`%>kKm&-kQoD+{9PnG+p{^aCgk-?Jn5y0*$020bMzHcZS-oZe15HajyHV^i>6E*$) zIO)QfYDG4MeL<(}uKQuPSgI(ShxLFvoZ2OisA)XkB_rw}b=Lkrl)Vdl6J@$T{?25Q zOxm=aUVyf=WzridatYuC(A6}A&>~7@T^Cn(O;Ox{uBIv)1SEliDdG|kUGQ?YbzQgY zs@oLVL)C7Jt1EhRPXfAvuIm(mB3*GRVyD;qzt5ya_nbZFe}4UZnoMTi_nr6pJn#El zz7MTKX+Mw#2fpsB92C{-`pI%dRP$bO*e~utYrwH(TrE)>UDich2`osMVSuTuBBulP zT1MEu7%!x#6sqYtSIi^DK`j?gn1R(K5h8flnawb!D^K72T(85FGMzs{RzI-OL2Zm! zze@{b_hI<8oIT~<=xHx<;MaY|3MKIZzz5r@vH2d-x2+~mhJZ%skq zG3~a_1JO;|qt0JxKbJOX+vH8!R{v|5GuDnxTEvV0nlGz@paO#00Nh1H!B!`=(XM$k z59He4=E7&sBNtoudMJF==b;FeoT8tYVt<3CdqbhP}^N&##6KYbQhimwVgGb zUQ!P3vEEgjTr3w(P&+gZ$RrN<{`qQNt!mNklpD2Oa;xwAYlGSoKv&%} zd-uzbl2H9^m!RVMou_;2?nf62be07EMX5AQkK1l8V; zT?{-gH`s!RsgiB0theK8g~Z`=nH1E1TqCL*M|Arvwd%lbvJ3*sjdgUU?b6?0%sS6G znSWtq^cO5k@$1nG&zPiJO3e=g*Oc?^fNgzLEAH$(7vz!8kPoYCj`8ky&oRln@3r3S z3|lPqZ?8e)$9Jr+a$p~W@!9lRZ&n6kBP*};> z)5NAf5TkGY{IBmh8x`$BN0G-l8Bu?6HQggkhL+rJ?!d{@Buu6nh?8OIEs8x4Pq@-O zkxry0s*6zaX7~Rw?*voN!=_nozV~U<4sC@jsn!g!gB8zm|6lUI1uPhI&qA}QXCcbi zJ&W2i8UB%Chf_}0`67=bU#PP|kWps?q#->{AgeJc*Uh^ZDc2~#A~rGE3+`>diDy4= z$Yu_F%lLnPB$1$+JneCoCrf<6Bb8q$(JGXqM5|a1yYcZ2+pRrYtjpa!74k9nS3j7V zI+Gi;_BN!6&|_14Iaq6A7Ez5v*cQQ8v^N(u;_;oVQ&2L1zOnPa_H%=<-T7*TK9^`D z{;xHNLOL~8hrj=qI=qQGbfOM##b56psd9c*hdowsRn>g|!U27?T!J%rF4h*=X!k9a z*YfyffRRzrlowKNq_0xUC;zIdcF)I#fGvp=k?Fk{~Sk+pjF+k3bdBn`nOm*C} zCL3}x#Gl4}!X00>h51{DtWnbR4YB6RG~iXm4M5D{El&*?R;8Uo4{#WC|O z^qSPa;H?L*L8+Fo_i@}!Q?G~j%H!G$z1_OhIF`JhG2n|nj#fab)bTi#4qxn*YmL3> zjH^hGWhr;vyU2rIoD(>n8~c$*qGxGp$*@Inj@E8wY%Zl?7PT2v?ydVHqqP%BNBl6G zoP5*Ifw+{sBiYi`#W=g<>d$50JotncaDTp^utIB40{!y((p5rtK?w^vq;LLX8qmFx zb+G_R;+^g=tSYnD8vKW`ZxX#VTf;&B!odDb*aL^Iajq5bodQcR$?wHZmEjZ(+Q$(U ztUNOx-$8tD!gnXW|AcRrjT3Svp5uEyzJpTbnV?itudGMh#12kh17ZhXPAB&q&~&lf z4$ko-ulJ$a9UtvxsL1&G-sj<9><0B7Tf38?CZ_ zx+>Dwo6fnwohDxR)rn{H?(zDaoAAqz-B!`cM`?$M+>~woXo6T66 zBPy!ufLT2-B%}9d*ATyrXqQPgJ*F_>^?&$UM7vGm_OZKQ!J~LV162eE!Z|r zHNZxF9D3OZ*|!n$ED?N(6HPHep?M8mmdN0I@fMHr{b896b(GSg>N zWgawm(z zSE}HOQ#n^D)aJ|M^lVP-f#^&h~VIz)HozNq^)i%>dt)y9BwTZ zySbX43=KPcm22th=Aj&vm>YvvmP8sE*gO#3=FPE!nd$23Va`UWZWuBvd1=bEO@I`e*2{xSOK+Tk3G7xfG{8&(Xkkw_Z%Fjkci=O)`7f9fIz{-Q#OfO3F zZt(}T%e)TYsugQy^*F6-&>Az4UGu7d9W|Vb&%p#d>eO)>t@%>$N)GQYlg;Ww;9FL3 za#)Vhh<23At7B&M-eF4jBZ*Q3bm}tIYgWHVB=3R_=(HpYwB-9I_T5#0y;2_j&Fa-7 z88##G9F=-k|@ z+DDrI3pX#jz|F_U@?oV)yM~;O$#UY;P4W8fd7iuPCGK8@zI<%>Tkd{w|F_(I96Y~? zy947_Z)I}lQ9Am@UjZ?%C??s`)LTcK(L5zh{eJ&Eea9dIcjZ*~7_QNkE^ ze{O)Y5tn~;0B5DO=?=5{Bb`DolWyGCg1EC}fyModyA3@lK^C3)d7HjsY(@*#OAVpA zeh;ywXfAf1OJ&V2Ax_t%Lu1TFYYeBK+bKeARujI7V=VL1c-|<@jJ9ZtrO?BnJ43ey zwHtA=yj|k;m9UXkg8Zqr>-9|ct>B}V)3SyV&6_}rsMKx&9*}QY-pglJ^#@YTsfQE3r)>V#Ccj zC}q2DTXw}|u}RRBV!vW@$FlHkvN_=wb@w%1AB}aodaQrtTI%^;?6qiblG`z^Vnqy8 zM&|CM`y>57QO4nJVZ~>#%HWXW$$r?<2P$>iY4dH464iSH(UB?j$NlkcpyR3G@1!}@ zO>_|PuRsSW&D;GQ-RbHB{jVWqqVI+w;4lR;)vGcPt9(tSDrF#Y8R8?C_;}A_*e@N# zuIAu5r_~F*H4YMG&ia@(b?mOuuHO~iFZ3{Wu=O#}c*GMJW)VY)P`na-k*><nE^lFsmuUX$n!0#e=82&4_As64r!2lEZ3hXs+b={Yfw9R))|f~jCuT(7_+Id$rv-CL!T*|vWVVwV1y-RH!Dt8hJI!v+CzI9 zqL#^YG?&KJL9H&|s5WSM)Xcme<57_xfnrEDiuD6ZY zd~DjGht|awZTp_*b#NG>y$e;*m<6hx+p$1(8ks$>Bd*PfM71k|am|TuH@q;+Hghl? z2%Jox2O9<|^xl7XU>tbeIP@3R;Que5qw%U5pwCjASvq@1uxf9Rn|t7G175~?{+=>VY6C^|GXiy`imhe?n(RK z1AiRj?*$!=@P=8UUcqPKyqes};7?y=yqx zBeX98HeQDn!ZpZ#B(wSfIIqV~`}So~llmVcRO6e#hpmtyI^_jeC7e#-E=IoG4&tCx z(oNV=u8>CMBDN=x>IXxRxsLW8)eEycYhzTZxC%9y4b8eqeP+aobRX%fs~GfB$hb5% zALCgnWA!_pbWMqavgvc0T42;E0JTQWcqlg3l0;uIYE!w5Q=H1h3Z)aU`kWlAFeCR3 z64AyTF8#b3qP0ae!G9&rZ?bSQf)gDF$)KS^DqEnYbNZ^+`{(a^t;X8;n<1vRsR#54 z0Kq6@v}^`j(-@VH!XutobSP*0EFOnXiB68xtP z0-J1*^1@SF{ox-&0lgf#?SxM0Fz3eJ6WkthL9(FFuHOwIMu1{aY`&@sZAtW9iO3RH zAOh|s`uw_Bs*YX?u6z?v18u$ym`#^r#4p!dG@Bt>xH@IXq<%FlV*lG5{gxuGi8=!$ zPr=R(y^}!vJep;!qNu|e;OvP{DTbQlO!S%C=wy|@I0HxzHs66>Lq^p$u>&*7D8eg? zGw#r4>2m{PWFhN7W-+Ue0dbvDTJ;kao`{#6v5ZO;s0OoHBx+U5hUWM=AhTP6vD#T+ zRlgZDC}Xs9PQa=b51Hl@KLel1viVZiKj{LRS#f8#DYc%3X}EKq0dP! zrbhFXzqE~1VYcY)axNGb|87}79TZT;TPTZS$MgXogUUJpKft8^koFn0KUSBVy~ga> z)MEFs^0A(_`+EhyBV&h<(jwFjd${zkZ_AfRT_% z{dfJUKa{|}=eB*HYRfhuA}4TGO;dv^+eoPOUw-+e;mf{9v7=fE47@~NiJs#`umUUg zVj%ACK>V3l)DFxMu3|CpJq7TEG&MLZVz)u>YJ$~FnnYIzhV8zM+e3HI^_Rm;y{7FM zlp4}@H>Lza+8#M!&w%XfDgMcsR#iY7NUm;2?>{M3!uKYK?=;2d;{&f_N?Po2@ds&>wCwvqPJSB zRVn2bJ}`*(6VjGnSx9@Z$W|zDbLLkQObM| zXJcxxpTlWOz-h}gdfMV~+T!<8=`W5X-}Rp(7XvwtNlAW$-bQ`rc}Dvf*ElixL)*8L zF2P1pq?w@3YoNWR6}n9^D`{PrCjn-6s{KL4K|4U>>`ShWJoK-`?V#R;Js3vch|w=a zUc2w!SO{zSo*3%d_yGca#2~|ZLrVvx%$905R<5_L4y~_U-J(s9x;C~zrd1nk(I!ew z_$-vVf~hD(O)6eg9b;mAG3Px zhv*9?HT#%)Q$G)i_jk-~U@|zfQ2&t*8*)Av;)-yO}Y3!{0@P;#`_ z4gvA5IN6tm5wqF@3ZU<>ZChGY-6fMRX;?|%qdvNW7#g8|wLJOoL#0a#h!_HqR@N`9wB z{qq5nde4RXKe}-Ll>-6N;M&*@(h5L(<9FK9bp6bduRHvbEvcK}U>hjdxL!LGZA%OJ zLC(0mie?Ez-EWqcpEGims?&sd?WL8)+3nB_OoQfxMtKJI+2v{w_AQLP(IZHtbu9u8 zC3LTYf^c0`y~~bNHC2s+g47Pl46}I8Ss}3@+v21Ygk&IrcF02@xl&LL&;AN4o#Zds zAt+2~o|jpB zKdtLG5IdMwHjM9mg|UM_?Run93reil&tF&M00(lz`e2Oy-aSfx@0Msc5yLv~)b5um zw>D}IN{74O`YCeyYaa?~cT4Z1R8BAJK0U3MG5L)S18WF}!(71WtB6LloXm)JFPqcG z!Pn)z_PnToohQkHNghq!V8F1o@z`B>y(FVHDQ4i6^5EKDFJb`7vLET%VO z&8L{$pMfW>j}tekLCodJ{VlF_F&k!C3eKg>es6plBoo~uEv`EKZnioZ+{G8?o_Sn5 z%8C_E=hmblxeRup9DKN$MTI0~4hx#|Kd9HZNIfKXWLb48__#J#vfZlG#WtT8`V4r@7*^kCP=yssa*3k$9dhCpZGfE|8Ko5N?D2Gs5<78kA^6*D6 z>j-Cb`n18qf>VE-I1r__ppSL~zlEy|M-llf2-%whC$`grRE`zpBx_W$!FCU!KX2A1 zMrf}v1V6yR?t=Z)FF(|gReUJ3ba)V&+6G^f_7N+fzN@4;Xp(ug5W5&NzVim{h!exg znmt##C%}FdR@bd^5SDvKoUkor!C>nF#5Tq6!?YI}3Q_r!(eGM};_bcUI(Zc555FAD z0)pC{{dD~z+K{H0Y_wK*_50Z2m`AU#8MH?An6ow?N;!a1dSY{cT47dC4W_E^4aFBD z|NX4&_D#=k`p?EPKj&j>p6hk;EBr3aHL0mUs`D0Pt1AY}?wJT|izQz_SJxC$Lbi%EfMHW~e%V0)F-Ve~)OD>3>-XetL56Pmf#YXhB}jM$040V+pl z0vaRry~O^ibamZ;E#UQKtH%c9K#KbQ2uZJ`q2E`H^a&b0Nl{(>K++0iV_!uyELFYt zHEBOrnt~ZCwc8MV9agTTvPWv?!ION0{j}~E3i>!dS;gB593iy(3Vn2*xW**!*9w9> zPPZm~B(5KDxc}VhhlIEJkrtO7=;>+d$WTjE4&>Ueio;IOenngf(<=GJK(b6ZY*zm^ zAnW&jIpExv`1B&gTJi2Hb3HfNKIu9qzj<5ksjH>^Uga z7gfS$l=-s(XOyA5mj{x+AJC(=;k1AnFBloykMg!E{Qh`EYTNrr<$~X$G|+~H+3Ieb zP&u^$(VpnEnyStlq8=gSDK;9zGYh{dg&a*)KL(l_rITUfbm`#nLZNqpp|*fd2&wAp z=uzN;04H-Sja|pTNg#quvW&vP+JaQ|Z9Lac%T%tMstykJ!AdR_dyC|K$LRYxb;(#s zh>P)*e!`}@y7ihoFa{}RVZpaOBQuuOo09?EDJ&~8<0(p3uLx~QR<8iL(;^_r9Vs$iWIRfq z7_bM1J~1VhRc80BYnNc9{F8zHZpj0Qf_A=JL<9m_VfUk6eAyS^DU5NuSy@o~q4N~l zmkpmBt9latyvg3pRQ*FnV47misXu~^rqq5XXzyt=^jY|u#29Oa{Mssig}l_OZzHad zRqpAAHyh5+Q{g3hQhy?;Z;#YK(>7%oClSQ@f_ydrDIebRLAO;tGMf9hdhU0Tn?vq2 zro?=D6hSgh}{2=1h z9Loaguc!_TdD}8o%TN_CeTX{j9hPw>GO6&h!E-DAiF$`g*YBqBX}le_=l;7*hq=kr^KC=9 zz*lTInI%7bQty5BAN}0ZVsz+YP7%((c3<+|@qX^##OUy)oMQTF&3LNsBZ$j}o|NI2TWgXcfIEH zhI|!XZf!-~F8JiIit}-X)PD5y4($h!mE7P+!)RMGSe%vE8XCh^ST3ww6>=3GcIG<^ zn!--elE1a}*`TdK%$GyAhaZPrT>@{vWM~U;3LGA9@D%R-K$07*>P4gX6wpT%z5zO3 zDQp-oh0WqLa8@e=H7OSMV6kY69D^58bcm?7*f}T;J^{s?qx&;`+AH`*GOa{v$wVwKU&+OKN4Jv+2hna1<+ z)s=1e;I3)<9S81gS#62Vn_Q}Ng;xe^!=Iyn5&Pr_=h+)>Vp)R<_;9C~ncjcFQD$VEEMnsACJ=u<{R`u6|wZ7_AVIWy>vUZYi=b8NVNs<9h@N5kfLF(d)j`JJ} z%!vw~m1ffiQ=*(rfG^AWZgc53kkc14jEKY)MS<#;^n20p8uP zKFX3!Ef1Z%!^8j9<}oxU`s%U2I8SrfL2qUk2~U|~o3s}*g{L0V24>#zYN@hGo1p)? zV&>&-ba(vBiTd|?M{0DQ3|q>lHfiIL;u&BmY|?V|D~78)Ts4J%rR8S|dqUa-+w0ww z`-Ojz`-Ka+U%HU{_oKO6^xQAnex;8*lbZru8z&zRq_jb^4$5#R_TmPe!%EIjcP3)g z6kzv)-LRcQTm9{M9tjj?rRIndnm?!BrP2I=y(s>PTChMmqAUn8&@<#P*eelfF3C%i zzvsr4wNhIn(KjTzHo%Nx4FN?ldk8H7~d?Z zOF@4Q#C_n#%e4=&%D^)rv0sMPj*Y~#-HT7~0d5KxdnKByxB~Ow8-&=FQ?lX>(NK6z zlqokxE5p^%V0ccH5KXJ09|*E&4+8=@?H@35IPcKtq+xU{&_!+6jPMMS)H2Ly7PF#n z(o}UM98FXCL>k&gv$!nk4Wy~taQ&rD`DphkskT>X9*ouUWjqx|=L=_hw_6~a>xE|M zC>GZY$~&>|9|R7x5j1<-mILUiX3#7nqRRdN@yLJ$I6^*gNjett{JXa30*xp9Y}ooA z7LfLONk-ZSkX9N^i(U9V6A{%j0*t4L)5>By7L>%!2cOr($bG?<;8MgFabUhQ4sq~% zQ^OPIC^|l@|H74{0kk)#@%(dsyaULwEx_O!y9Ql+7#?7gKKb0Z!uicw_itR;hqq7q zjY~QlcBLO}JwLD^_3*DSYf2|Ix=e?c7A%_I+OsKx`{*TD#N%L&eW9wK7Z*O*0IazQ znA_`Pnz%N;OPj~UHg3lKaXR-*_w<_^aQ@4S$y={O>pDl&eclGTdUNE^K6z^`Fq3PK zHvL?Alzd1_9$mhz=@DgX0&z8K_Hktg%;_HpJqy^zpC6>>S%ybl+d_|Y;`y`KWjA|% zRuC{3Q3}&_9>-Ru?idL~{d(z7V8`XyT8Gkqay0sLRWE(^qxWoMN{SMFL`4aqggrVP zC6Kn?5OXLF{hX(n&9MNyl7$`*=WVD){ww3fTRGcArE-BGCiGM?wv~6&_n)?I*}Bg) zBfjYo&m;R>Oqrro#OH4_ZQJK6iyI#8+_uSOi&q!C-MZJ+b;R2capfPuSqSuHd^}BQ z4A5K6G2me8yHu8yMME;Bzh?cD9WynG>+LS=G!$5`T@yDiB)|rwleD zPH*rE9{Hw<`|Xu;xXAe`K60+gWRvC?BIagJRp9M)Nz7nNRbL%!+xncgNE*QBVtH^K zd+Zg@tLqSzPkj}BlF-71O^AA63k$GnVCs_L&l-i^EHm>#hm8HE0DBE4uk@tcJnwp< zTLydok>*FdLEpB`nSknr!r(>-;0CG%4vx7VPcoX(}3AzVzc8bALNkp zQBa4K558>{V?NN`EN0&dZ#l-45`~jjKDZS~H_n1;v-tz^bf`oM;9?;KKc@7jPKn}y;=gwFUDvzZyBVMFJhMt()c<&Cr@$cZ=NQgQ!^wGtIAkc{ZEzIKFjxf5X-BL_lr(RU?KasM=E{(M>Xkin+6(q? zY^WsM!Yo6>>%e|;hQal4DnqnRaM%KHSVA892WW13+^*N-U7X5cL8ty?NRGY_`3)DC z327I}tlrlaXIcW-J>uGE3)SIiCX>YweK#Y14}G5whxKoJ!y)?Sc)T6aLXU1-BTnIt zZiROj(fW#TWsp)s3Qng{J+^eJdiPLEbXpZx)(Bb20)L4Q(vqu6)-YRkU8R2|q&@Ij z)!RiU5~W{?rYl*9M2)?pYbiQPPFYVVHOscc0mQ=~3_6@9uS`#}@(fDY@@40_P5UTzhG}%4~k$yZ*cB z^5ch0%6h{GoPAteQnD4=YZ>erxNCWz?0zY_FWte;^Pvp8;i&S^*nSLi3G+!y#@Zxn z3(OU(thE#OqsX59@!`I^2JHTp)z`Nruzw-F8k2_+={Na3e}EzjYKZ0i3!ITZ>Q2f; zv!atK%tx(CVybX-s82vtvq@9w#EjUph#!0kkqoGxT==J5fHN#bhx@pJ08XN{VdztN zZva*Wc)JmA|D+$$!*DV%LrOrB6bZ4ehWoN{LdErH?xDUnM*RPj`&Hx?;@&W&?S+R} zGVeM{A8?hy68dOkV5qNY1gG^t7Jl=w2=t=s+K2lL19G%6Op()r_VY)F`}hGbb}G)JP5P;8qRa;LGdZiEJy{0`#$ZD>@%yqID?*x5A|I>l3cxCpbc*A`LOFN z$?uup2-(6j{X>2Cj%YZQAc_>Y!7zf>HO<5u*lFSo zY^cvW;*HuL;cRKp@?_z?hzJ6ChI`;BBxsA3;lAI4hT9)8!|s@9IV&bP#G-+rKKDoq zYDXUSR!Dr3bUhc;^~?~_b@3R&TQSgl{nG;{bQVnksJ|i zPl5KBQ$!_`qAwK-=i@q+FG2Khca&({7n%&|9H+MEC6XKf=Pb+(L`lZo$M7~oY?ro{ zlcFg)rP-yeU^$qfy}2#xCHt1 zGA?2249G*C4ZxxU(IvS!&5#X!}j;P60FtRN`Mz zV#;WVR+K`z2jVECM<{3~c?`+fM*3byI?HG}O`~*Ep(~=6C*?CZKj?S8QiVUF)uP*y zvKWdVVYb2VH<7z96y{3*1pEQ)xP%v66OLkj-goQ#=cMKH_YHpa)zYF}txLWhxMvsm zevSwJnTMx(stax_czLk*t3~sd7VT(_XfNCHM=2^-KU1fChn5CAh^6G3Mmiv0Go{(61)&mo@BiYpjSoJeJ3 zGE;BU9B$6`grnYNI>vgR;N<+4!Cuu_5NfSJD@dwA?_}!FaWbX3#n_mvv(aZ!fdU=? zYQ1DpkD|0Mu^+V{1_9YsoyYmws9pqF=85j)S$ItEq*G7bBLNcO3P=$ujIe}~J+bai zR^#B5Ae-u_Z~dk_6YE_7hR%I;&=E=|1sLnGPUhEBT;U+J25G;f{;prZZbMRk({IEK z0(M$AC;txbPV}jeWWW|fv$vVmEue}+eSZLV;N+)K%O~{|pCW<~tdMa6+=(4m1X8h) z`K*krWKzlnNLB<@(VU<(6Eze1?d8^;l1-^w^HP30q6r?CQKfj;ts<)277w!pax0q z-nh|zWlQUd2fRV}TrZ&$bZyw!dj+h^D5WrA?8}Ze^Rea zXgu6aIk})Kh+i%5f}iQ{=R3ont;gG)7eysEAD$o1c0Ypt!uYncvaQfaa=`^bQEAAx z2o`H)&=6}ZWNHzt8*bge!s6^)cc^uFxDn_AS0zra#yDXQYoK-sZvyWX<$B89%@{4% z(r)y(?{2sRaw*dh=fu_FY5B7I#n#RuqcS!B*R3~iklhZqv(OrT0rMv<_;f>Ql$GZA zE#W-m<4XI->dWb+Iv3>1TbaEq)}&*VG=?g|tHPP?WdGa4h%i+yx|?uH&x$v$3~sR3 ztqkWyWz_uO0M#5(JV$FTqvpp)o)498q`H&LwzA=2|YU7jtXMz;x7{a9M59t$9zh>hZo%+vTY3p1g)uLiJb(j0d^Fi)c~r zc89{9kb!gYvDLvf1pn!`fB)w2pTaa2SQoAm)F8+Gj4MC3slmAQCwXPzTf_gzecqLG zBs=*l;-w==x6HHc{AC9`*9CS*np3Qj_(F~%X;M+?Kr*{jc7_?en9 z&I`;vCJT7X0J8;N-R}~PE#J^QF__N~qskjzj#(PS{4II^c*F8&8+b(kfc%z78pL}Wch*a?nHO(M#$Jf zvHO-JN2)U%rZu$4yVcl}ViKcH;NsFs8riNi1frLP|Df>^Gi-(-2_SB>0qZNZ=8T0i z#lrh8hb*CSLz~A@_f>aS!;Mkzh6wgYNnT;Eq1&t3ht{0&%ZroU}jc;Kc=#3Uy!JNDuWm0(#)bKf! z9SqcKHg*=gEkvVkz^rwbxa+sR9&SRM@EtBG7HX(#+qm+csDv4NdZeaJYOv3uwJ*8z z)-Y%hX_Te*T`{ zKQ3yFcEXw=;>tM|%!hRGW7+d?>+alnz;Vr1aRP&!OPN^TdcX~Bl=4Nvi>==jo$i(} z+qk^FF4IwmyBH}k+LhVr{Rar2VHprY^mhr)4Mn5xf^BtpiT<|8=-aaJwidk2;o01} zCwB_;C)w&o%|CHVYqS2QL_tUEiJ~+5n?iYQc#|!6mY(WvtvPRVtKC!j|NNfacn`Je z+W+-EvU`@E>hjU|s3)C;#547I%e|hYlJoQ25$q+NZ76Ol-kR0+>{cMl=wm@WK2xV$ zw_(-Dpi)wMk|Gf0CF-?l=qtzo4~Do0DmNZn9a`;QXb5KqUvF?lUk?`(8fUK^KKUu$ zPQ(Ktu1#+aZcU!qd16 zg*R@cb3zbvlu9RBgc;?++?)TT%N%EzT^uM6@?ejZtbv2t9)_J7o;B+n(-sEDc82HM zf$Qb~2LUQDv}@v2;--bsrdGQT5w|tD5K?-)#qQO)la2Qol*htZzC3pW5IOoG*PM00 zzn_(-fq#n?lvnnNZAFRzi?~pDFL1G7+fvaN4~0#hz0?LD@WK!y`!QfU?g2uH-CaGA z_lANtpT%eMa$ecX6jttl0XZv4^==LFz7*U=8%pMT`9dzl<67OH;o%^s8t1X*7J0zC zj@&lU0ggv|g2ue$_nbVEh^v)h+Ubv`oiv(u&S+X?G_5~8$L$Y_Jpvo!Ax88SMH8-{ z81}q|@~?1D1;UTRePHw*$#1&j)AJqIwY#QpA$q}|2ef1lC}Z#dWLcm*K`;0(^^89+ zna>MEeJ}Ev*q^%{IH7UjcXM%SI`Uk;GrZfyj$+@F=g@0^2$pmaPc!seSk<_1?Ac;I zu&M@jq;$SM06)U^ z)2i=lHpl$vqJrhYreF|#Vgo`JQPS#y2Evm$S{pRt7fCM>i2>y>y&QkLIE_1E22U-+ z3D+C+x2NltWI)hEkCHb34e05ZoDRO5u1kwVJ@V)6Rgn5Y3W=FfO8WaFkWeK)yHG9Kfhn`>Bg9q=BLlz{3XK)?DN5F;siVqz{I zOZJI+YHBrE32Y5K>(Y*KJ)2FftCnh|em0{wHo0o9M|RX`WwPvvER3$Qdn&ckAY}3y z54lGR=H6uJ75?*7VYPGSOicoY%urotf#{@mYxBon8^%myrFM8M(7dukYL)2wJTddf zRrAR%5T`PnF{bz+*WNiR3JZP2mQVEUAD$F70kw=F(xnLzwAqtey%oOO3PksbR=Zc6 z`r(nDQ;dlsg5E;D>ffIZG^b3=L7a~DvjoElS#~o}FluuIZ5Ckv$V^gIu;-y!DIj+9edNXfM0MTXv7vizk>cUg&$G!-!sr7Oxl{+jSRW$*LiqIb~kEUT9gX z8Qu!+^?I*lwC821*A0zR6Py^UE_%B)D0{Cb%RIj`OMT-tLXa{lHx+%{`tHpi+|7KxR&c!8~9rGJnih!^vt-&loz>MM; z51P?mJ>2)okOYiG>fOI3ppi#Z`g4osdZZF*mWX?AC8XlHh#ZO->^F}(Tm?EiXjVF38`(vkTm_vqq(uKS}XM@4GF1a5uOOm ziN0Upy4WM^r5rmh&E{5HL7^L^f zzW?cMc0Bpl@2bI@t{7Z4`ku=Mw|w_Kk+Jv4cn?dI=<8D5|CAnO`d@j$5 zfhxZTYp)i~2#YUkCkrIolFs59$KKO2;LmA<_eeGq19_h0vvEv9+sCsAY&mjST5lec zinG*j251ZOpj(s5OR65bvt+MBPBYK=as<1uDWjEvtcdrS0E8entw$>-_jG|$|C^l#+% zhZBJ`GqB5(yym1l^dc|qL9I>Fo;B!oiNhU>6vCY}DTq56Oe$IBsnzG?H6t{0g}u-> z4E`0pz#@Op`#@kH>V0Bj|E~W|!MZg>D4$KwH}gV1Y0!e2P1;}JW4mthagSyD_{Wy| z3_EGf(TZS*za;Gsqu!EFh}8Iu5!lH`%n{MEN`J39&<;8$2SvnpnY2F(wPbQWK6x4T zPdoXY-izs)VgqEWPwTt`yJOvoC_83^tj%K2 zj;AY)zS@<>fFK*x)&0h4DLPWJAlI%msDIK7O7hC5>o0<6o~kYz89Anw!@YI~UcZteLnb-~-E~C^Xz`xZBWV z_=BO(kSlnFox(4L9-+cG+jyPvX5$w|hiSHHx#=O3W-2hBG@UW!K#Nsqp8_4G7$k)L zB{(VIP0Y87FHVa*3jb2VurFiHD^nuP&~2TK0UKJ{5zVNO4zJfOO4nsq|9xn1pkM2o zBR>7jc?PeOcqvM?l1#Y#>}M!Vey2;2SFSR^U$!}HhCKz@)chksSn+h#oiNzV$LQ*K z!ffXcbF%Cg6gKsMt~dKIPMGcoC#6*I!27IK{?ygzha6YxT2AQjwk^A%cddsPB?sI^ z19G|*v%MXWeD)xB8f=?(!wY1WHbXvmu9Llfu9KH=8ZyBX!YntK&3I~*I3R?h6ny^$ zI;5F0-ILGoe5UKq_&p21O;Th&=jymnlUEKi#dN%OeaN-$DAlFbtJft&b!ohZYLbqc z7)E>&@c$FUTIvv4EkO| z;!lZHeP-0_V)rAx_uZ~~jWy1K77!8DyE5&s>F+GRP=`EyM2Zq7Xi%w6neoQ;yl!tT zD*vI>EB>w}UBz8|*J&kBd8rGilZj0GlW_@tgdBX`t^jx047~(rzY8`pvY$%uqBhKa zD8||U9Q%=yX^-e{{9**YPWrn}k7V1oAoly6poCP43AF51O%90mv>4g+cLfe%k6tc@{id_P`6t$bQ+Ly%-nX~ohh0sB;$orq0Y_mP-=#2-!v(xt`Yn84YiVCu; z`~A-?Su)~On3>Q!)i4X`YVQDV8~(i8d&j|ZZmznB`3^ZrU*m+o)Q8=2zyf*wX7o9F zFEZ;hyT9i%3;a%=M&IqxTM`~g`KR#dpQ4|kTPd3FVZeDWs>;|>Q zItS=0Z+~1bWfFWJC4Fr2M>u=Gel>2yYX3S$Q3Oj_GDjKv$?;745LVg%R@wwa^Q{ed zSMi9e1;09ABW+DnQ(Ez+=xZMBMNzV3Z0dI8&&No5SE0Q!7g&C7 zAuyF{R~-d^snoa`2gu$dm~7LU;h!Hj%h{*qVCL_N=N1dSIc$wDQ*|elH3vmdAI6=D zaY~@}9E^hew)L#yzPK%5sIbI3&1EqI=mpI#TFaHP@R@ggQvfoXVhp9AUtXLuG$N8A|)&hm-4rt$+UC@w|wchC}lhQ=LSYJ1#I*wFC zksu9&K2xbO02=_ViT1z78gDhpnWtzBs0X?NRi3xamRN0ouQ0@$)+5duPU}tU4dBdX z)M;iH_3*24IbgOI#fY9#G>hbFqTWWYHBzq`z{R@)@0c@U&#vdEQA3kU`^~otEeydipjA#N^L-F z<|@WR>vAXeZA}^Eob3Y?lh;s=Rt9O7Cd>204x8zyA#wj zry}hz_Aj+uPm8qVOp90X(-?6vN$xmdk`t%s*HvF1cp*hzda?_4l%ifALp&946XY3+ z-9Jr9$2C^}9h`jvYL=vzL@hr<1n5NHqQS;M`b$I?9qvr^&%+cyl}5tyL|WuYg=$2- zN$LM%;PdXe`iRb5!z$vjiq+eXkB!>0lXEbZ-^4KvHmZ{a{<6r+a6aJq9Y*3#1_7nr z%+7Zw>#&$T=reh2t8n`7ryREUcPVtH8XBfC_1*!_&wZED&jiO|%Js)lpZ+oKl&N;W z(;-#<{R!}yAnK%3f=4lntf-gK{@Z^!&hV2A)?&AqA0v)J?|J?X!%p@DqG)7~wOi<2 z%+XAH9MU+N1=|OxuEy9nx$+d%ueR_+H}&sWuf3<0wxmVK65Y=Ja$*iVoIB&nnohGH z>)7r$%eQ0R3HCeUImL6~!na9YWXU{_s_hicGdC+Q|`sx z2ScDej);=nb5jdl@dLi*+9dzL>a;;7rt^>-ori#fz+dmE_TQfq zhjA_Ao4Y`hGSIf=;2^(r2({89$SsDC-g5T z&IbE=4zewv!1lO!Q_t&I;SI~A;!O36!Q|K+?9Y(S4K(#RrM)(Dd%~hf> zsiX89_Dud-YBl*5kM){CLf`#~yKb2UKGmF*d=B}$jZHTWR8BLMmbAo?X`zpOR zDtQ=T+WR}$1E(mSHBqo+&Fh=p3Y(h{f^EAf3DcyA|oa6|ZDP!1Fz%3D)6 zQFR_THzq5mAfAEM3vQ8uH4NIrSdYMQy%x?$I5UFm-9}@SglvYtoC`>gC+WUHHw>-Q9;@ygo;gBbu_C^H;2|^e6X>+hET`Ik@TRv5T;48Y`2|E2S_^r1RcpEvF?*v9AwC z3sJ8L$+6Pu5=90nWyz9$ijqI%?QKq%x9Oj@9`J`LCnAe2=*oBy66qn2( zcXy8q7^j`UQ`Wg+mGSY%ef;BO`@KsOf)uMR8?owm_!AL&PXRuKjK9QRL|ur+$`ASc zymHYp0NAW<;`Ko zmgY5EaAs~?=?wT++t;-CDLU7|?!9#@>pn+Z*N0mKyERTTgQ3p^23^e#8VOFX#hnQ= z;wL5Tb$PW%8?$B#08fTj=N^FGB;a2NJIsZ;HZg#;#vvxF-{w*KjwM!B*#gcVlOEFm zDKhMs+SR_lBp6+OZl$)9vx36&)Nh%aHb+BkI zRj?1D_W3a%Koy@Lnb2<%hNq_KY!wn+Cusxe|ujmzsCqzU!I z#uR!1$mw8pJJMI2AZ;bJIUTvy*)r9pe!h&G4h!n(0%jUnaCrSpS>dPDsfk~&rZxko zcwK%p1y(y&?oFItlA2$5{mHy~B~HO3*wIo160)8q8ql3ELE5zr??|pDk{96(_-Ca? zMOeuc_eyKjwyq)iGk8go6!CgUS1fv*W6HlPL2H6xCo90>6ZJRtbUR+QBCTPO>~Xwi zxY{~zq;J_D89R#gLTiR>Zv~ba+Z?rVcAQOfuy47(nyw<+(kjj-&f$XY-~unT2K7h3 zU2`q!;t{Wu6us>t`Cu2b*H3sm= zWv1A)Xwr_`@UgQXN0CtOWsAit_l`IioM}) zpIRl(VPXHmDb?a!F-#{9XAwm|rqRiPWIs3d8YoqhpH2}HVm=uWlid%`&?dhGdn@X- zr!h^8cz2_}xq&Rm#@c3t9c?-ygfOg^X3!8ZW;~Wz-GrzrDTqjua*TSQG-?mXetVdu z)cDD7Aw#(>TAi$GCOkUkO6s`;QXr~3qIldZp(HAQ8&+9TKLtxz4=Wp~GS6T=;qhij z+03dLe}Vv8>oP(KHfcG2hDhe;tAfx}g}EIXlw+{fH^INe?dOz`R_-+QxB-Ju;}2<* zouutm_fMj_W8KJ82(|fC^{J}hOxE*ofwjkt_&E>rGGfD8;bY|tTpg(L=XzvYin3EH zb2tMV!4bYeoM!1Ha0RQmH>;cl^)B;AY$^wP6-WC){FZYa?HyH} z^9Nv01FKx0^T9tZS_(O0rn?5d>Y`g#H#pDs{eECqzbFxk!rRbso$E&LEsS0pyz~ie zTFs~0YdcNQ)J4z}7b}*Y%@e?H#0l`qp);ajpAPx%^q9#`dOuE0f!^GVUT_5{Pf#nD zBidy7S=i3W#X($&@E0-kPk{uR5QC;Bo~nYT5c8V%krtHRH})=h>Y+G#8=VQ{Iq1)0 zXu-C{vMqRVJ#=mLS~>nFONdv39d`QD`j0@u(O2Bh@HwfUY}cf)^ek|;Z~dSbpAP~}PlBxa%>y!4#k9}QEm^*pl?5*rdO|4; zEl*;+WxFl5vWVZ|t!9s7l}(siX!xD^?M;xJH9hhoB5gKqcvLH5&p^A==s6VS%YRS} z-LliL=h?hWw@uwp$?d3*^0o}@FV6PCE*YP1X=nQo4OV?btJh}K{6-PVPr!Nx+7U_L zwcF*mVK#``?QWB!M51RuZn_|{Z<*8T$$T*w(sYfww9z4 zXZ!8}+H97>SWOD_&>QND;3I854H{enRo=gWK0HJRK|lWrOLk7~>z?hI0y-jK)pQJhNwuqdcX8RuvwgQ{ z&WVgaIDz$KdRZ2GKk?}<%w)2?;3i{E`$=jeBaR{6pYD}0&k?nujOI#z@WtJ(eG6^f?P?m!EJndO7)vzU|mme9^ZpakejvnHSW)=({12p>9sJR2jWS z?-Et9k>%3?&p|E7)0*0)P4kn6_s3}cKwBW$YSxjeGe_#sZDdNTg-}s zR|q|uvROyAmgTfYMdT-YZ+Xf$M*@qg;QelfZOM3DJ2TECrdZP@#z4y_+C*iZ&7>@| z3CaUDUU>p1#{IVI{1W&NP+0Nr14=8kf!Bhq^lsUndDvTxx;vVBgNPipDJKWJ(#wH` zIL(1ySy`GSlV>>PrxtP^vY&VwzR#5Vi@rM(L}k9{`-r?^E7LvKEa3ujS@0@wIMm;u zlz9w23xwMOyD-z_seN%#k*AtsO)gX107-3i02uaIH@`e#0BuG}aHcB%|Hs(3z(-MC z|KB_N$mT_6Lx2zh%qApkfMBAi(V}i1Y<3YyuvpP*-C)oS`m>uz?SctV_WwOIiJ-sV|B=sUGc$MY+~>LH zo^$Sb6qP;OJQ=&Uqvy*!g2_BTY@s_SrRTp&BFA$Vx zRL*!8U~OmA+k#Zb+fN}jA9UFHaVGuaG<`+iTmTLJU#A%h5kA10r$532td}_mC(twD z2eMQeK~%$}!MU+0pX`ZDpp0t0T7=LmeA1&%j+1_ZZlY}d1%8rzTai9R59}!4EQZ#V z6`C!gBSTcSMgBD}TN~jA9Wt#ErMP4RyhOXXg82Nl+#|)o<7lT_>9AAz7hU~_>OPFOSMRnup(%5q_cXqS@PzS z4mC84RyaJKr!hu@#pKB?*6&$XUn4DRbdGYC*AzCtjPb1p9U#HpgjG4l$ID003z@cM zh9*rTm3z)JhOHqY>!A9zm946ZzCVv7Uyel{3z>Z$+KQojj5ex(@a^lrRc71iII zA1Z|~dqOCu3gd*8_CEH2Wb6TkV`RVcs{uY#`o*E#nT$c!u9wg^RJP;FqfX~+2F|$} zJ$oZGxkcBRd1}yHoDDl5k`8|Y{TKbKgmQvn(%HreE?d|1ymKXLnlvzDPGE+87wzI~ zGI;?YS}<>Jme%8y+BZ|&IQi*{OMTlJQ;%q;X4uDIG}deHVj3ANQm|)~6E&B~9zk3H z+O_y(ec#f`#o0pimr4YMEV(9?dcrF|1VGB6eXT<%4E;PnO@ zp>grx1x>e~y$J0Rs=w^g9uM{B2iRGKxBr*Qf-#K=GH3?i1EL$y8;w37yg;}j8qOay zJB=DGY=@SH9!Y`v@t#&EgJ51Kzgx7ISap*ixJ_JuQ^LAYw zm%r%cHSR4=h75vcdBjlf{!@EHqwrot(&(n+ySUvQx?1|zLpgAA8R6L|)1;4eua-_@ zT^!M8rcX=R(2S9XFP6a2{u>*jw`G^wwXx}QIsD&*M-1v;n6$LmA$e4^^J=aCrIm$} zr1`)wu%qc~?_|^OxD@*yjn7xwTLDm`mYtnT(I|2mR)ys>)&`F+9fJ3fTImY`Q9b=w z9X^7&vP&Omsq{rO3{L_0HWLwT*|gId1WoYVDeJJAq2>FVMr*9GTGg?jD1X#(gVWTt zDsHxu=y1|T=ek6@KCTyFA06T3XFET);3>r{+@8_p>>E%t<%DW!xjyRS7QeRW; zLH*73+8d^9>|Zt1@|%a+n8^yzvRAd1{Xk1==-j9I!k}1L;45KO6Ad5kmz(vH%CtO$ zS03rdNLVPf?9yMgR2qlJ`}KVHYbg%wH0n!iTDMmIY%T3 z)EjsW=#OaeHvLiz@Zlc-5*&(Hg}cwOl@ z4S*br_JsHQQ`G56Ht>Yp8t3J<1#&d}yC}7JQ9nu6%A1Mej0s(v%WNx@rDx$|x|U70 zbPE>Uf_?&O-P8Hj&%X)Z5P|*-=9qUZ{(08VJO%|-ntY)L6LH{U^fYn8LU z4^f*-z6mS+zv@FwYCHdO2yQo9N-DhC?p3(Oqsb&ep$bhrlk}zZ-X`pO8u9{hc6{1` z^j%#WlO`USm9_`haYudu3w|-JIQ7TrqvThLtS9EDSxOw~#YH1zoF4(d5pBfqNBEC$ z9`Q}EEzeAaEP-Z{11`P^f6+q!*R*^S&e#W9rF7qS`cs*^@W>yqpWHRBx{I^Bj-X#s z5c0N@>Yw{jld6Czdx-%_9Sy8mJH;|Nf z7!eeO62w4(ru3A!5K2hC%PU^9-_;dO_?*U341E(m-nYejE!8R5MU34y;pu%kHzRrN zC6XtbsE-Qb`7>dmFtC>VpAt>Fc1{fDCYNpN4w%ib*A>+!mYHwOQp98kw66$5tg6S%ortKb= zck1sUk0HC4+gypD*>l+sG)zL{1RpIJr(0Yk%lYVuyw(|RiY~~dT9ibR*cn57@4qjK z0g|=X{DJry@(*#{(3?d_$#pSryQw`<42cDfop}2>>y{xwVn&mU7|rMtJ*6Z%ViDzD zlklct#ldz1<-6=`IFFjcKzWr$X<$d2~7KWmhUUoc!!BwVutwzS}XKt{D#TImBAt@2D_RGGipva z_9%E`vuA`d4*o5wT-;lDDNw;ZlMwYxHUbuJHXW;UIX&&F<%vm`0t-CMaI6AfOi}_R zvMK4MI;!gC$j!*R5KigFnl5pNgPbqVSZZ7O7`s9d$ zxy_g(c`QzvSH#E-7e(p+AEP6bEB&x(?;D|v#Ql#3fm^f~%p;U7`^7z@5TkosF|u_< zXwsD+@TPB1wmZ%n2XB|7aFTMT_s8jXdJ^F8a;|5@GGo8_;t21AqNETYeQk&M1y8=x7`K=o=RIsN zAB**pwgUKW&{(=%%ZEJI&{r1|P?GkVj;+ z=n^aUm7edsw)fB=@llWIJ*)-6tCQymIwN9}q5G0i|E(k{hC|`ez^8J(5eSrOnGB3>@A%4yWZ=hl>1!8c}&@?rQL)3ZJiE` z2K9jC@jrB}!Q1t!gcQIbzMBWR(Hdav2F+$lY%S`E0Y1}D2n%z_qRfRk(XgXZu712T zQDVv*wSDKBA_L9@xcqhaeQ0CnIA@}rKZShaa)=}fO5rVKEX(Y?WBffNX#r+0RK;E7 zh1-zZdn8|LV*#vMvqIC+gBx%sg{En3%f)?K=rI~1u1G_k|P~nJbHK}867;*IluG&j=@E>aAIKw&5jn6-RdCgu5Y1--fAgFENOz= z-d%`T>ty*Q?lGg@FQHj!!1;ja_&OZdCblNZSfTOoBnOxye2g>4xpu!J{llGJ|7ys@ zdf@|Mnol2#5#T!HY}VEb|3*@qqfKgi#4q_hzP|%Ec7+rApDQ+X{9QE)@G|V*ThxVb z4?_M)aKeBd^s^?%N zQVZPH;BdqSv^}w14J2dD0e6Y$yX7P1AZjLxI0{i4D5@@VvejopbQ%#dT}x~%C{lP) z7*n{g{ayxNbBG!Ckwdnr)n(vxWw4nB0-W%X_#!@?Q{NTJJ=44v5awf9pbdogsN zm#q*_e0tF$l&j|Ugs!5Q)07o+9Jv2r;cIDk#l_0-0KOnjUU{$3HRpPwURTa%8AS`I z+=6HV=7DN1Tqwh?YqC^;(=G||yHY}su=P{FE$H_wC-r3ht~|FEOfDvj`ULt+IMa*Qn7pb z_ACcfEcQ#waAt__W#}zsc|2Gt9-l6Kj6OKt`8<_BDH=}fKdJ6*FgrJcQ-Y-}>}A29 zf=?||65=*PbLa#lLnCBM7a#e-{n4o-Li>wM9dUS~arbu-)&NfLZF;?n6sNE`JJqNNXA+2WS|1_FBG( zXoH^+-QX)kT$Ebu%4F9&8kW6+^mVwW?;edZxW}zbuy}~JWD|`ZA80Rn`_H~|?d^Pg zPqak4YQ)cCo#)0ZA-1;I>T+?!B)fAqp1IXi>h4fkKFeTJ(-9TWn9rsPp$_C9+g#); z1Mbr_$#|j9L6PTt0@4`!I^2ZFVpQAj`ewL5A=m`pjYJcFTbqD-rlTH)D2UL#DV^>D z1%n8e#x`ielJp5_-%JO{D*90_qek8h{_J?D;;;p zo8ERrHR2i{I)ZP@o8jXOXIGlbVJXYP8WF zW@#(*389-2`MbzRl+D-SBYU&2nU`r85gJEJ8_m&B|Fx&QJ?R>)Nl{}mC>LfbwJonz zm;{I_KB?BXe}QuhMDQC$*Fr$br?~3*D7p_T#15Qc?sy-&pF}ea$WlYOEtH$~RLTvw zEY53<2fR|eRmMKTxNBoBBJ?Z9zTCQBZYDA%7%@IS`9#2=gOF&!s}K2*$zd1sMG>x=CH zT?i-@_x$G^?%h&R=si`zmO~B(oj_N!v?3h-a3J_BPe;5{8$JDQz=Mc1h>zXs!P6fG z=F6gY_?T#&E_0k8#ip4JyjgncN@7wVSv9pNT&Y(zTN)czI~Hc7T|~=Gf$&wN%K**bJ+YJQUle)G}!BaZ4)5< z!NJ$&r8ehz(GpJ{o^uBa@FXceXAY$fKjz5uY;?a2*v8tF0*^IyNAEC(>cPo*E{-XR z^StDC^!(U^d70?wF^CqAWunPbtF5+mz=!K+ufr;MUi+UsaXs!q$6az%b6mmch-1tG z90;}%p=?~!Y;mEMcogahimfRBH z!VX{VD^)&;myt(>TjVdWpRy6a1EZKDB?UiRaT4knmK{uEY@Hu6gcp!rfM5A&yk{ef zghw0!=Gca-2z=u}`Xszh$IpV_0{rHXtO0qL2luu5egMgm(b#sNW`-vl8n8Smvje!t z>uDLK`G)=&I1+tSb`M^9Xh!8)U>`w7`;^}y_Rt7rM4uq-tw~h=GEe|7$R`G*76q83 z@KQS@1xr2ua(!6&FO)^`)Re+ZP4?L}ulC#ipH#Q6I_EkB+Q@>km`Wv{!AP7bqZ1zk zPMaw5eYSj{X78i4()T`8hX0g5U8Z^|m1(I=OAY-G?Oyo3c9#!!L8nq{QR!#!Vx*RR zJZB|ZR0qp(>_oyzHRTr{xIRH0BBC4pA$n3x*mZCo&!Y1cW7}VG^1r9X7}|%H>2cZ) z5Va6E;NFj!Y@+r^O%H+Vx?Z$_#~O(!V_KQV-(PRQK0#0XLp1?E5kDh-Dfp%GchPcI zkGI#OX5=!Cq#9yF5=3cgh~n{5L%h8l7dqf|ilr8$GVt=w?2BbjXI2 z(R@gnEjSm#Dz14G!V-O;X!i**mi80U(~6%_4`F~jAK<|Zi?{^J{>n!CaUgA?Z1OHRR)ZzJZCOVZM=@btly+4d4<^HjXAmRK{8JNRgd z8>@u{9}01N3tr5Mvy<_&aXPhB^g@RMJGcQDmS@}^61Dx@NccD7=1`7Y2fX41o**2d z;R@g#4L<;<5MKHnt}fsZ7jVaR+!M}81+IaHGV+Zu&cwHWW{{2GT7rCp!}K~#;79a3 zGiYA4K4T5?wfY&|*USp}R^!;x!wQ?u0^o_vdqeyD`jf;COxK=)DEv|jY zR|=}fR_HmX$tp{%r||Bdu7iuZ0~kYZBzF<_@g{8_ zlX#P_^kY!Eg0e!ms|eCaj7U0vU&9gqhU{aEGl4;05Tp3Vxhas@UiU2jrn|8FDkqy-~dl z@hDLeVt}L`rjiy!=(}Y332=W%&s)DUHlYzwUy`PnPY5~2!yI{vkOwwb$oGg=Qy}9b z)tGsoYi;Gj?s)H(Zes#y{`TU_jgx;+^3bfYhvU5Pr2K^DFHUt;Jm~%j_5eYiA*ag| zzacrP65Zk zE(CbaQcSxZPMyDp{C0&18x&A3MuHXMS7s~>XRT{ z#>(VVQb3uq4A6YV^Exl0r&oEQ6P+G^dGo&kXR&^Z!{*Pw0Q#m4CxbqYS|)i?6#-OD zS9pG8%aXIREooSfqT50mjdi7|+Ij-L7;i-mN95EJyp=3zUqb63L%J8zJl2L3Ceo^h z42R0n)@pobN2+4c?uGbM9bb1M?%6IxAZE-@_&x^f9s2B^QHLqboWWpU7etJWA4eUC zafdW9*5B0CF_C73L%zwdlCs#T<#b08+tb^$nh?c)EF#s5c;2Yq058h|aQKbV@@6aQ zrnE^&vml2tiQZ(vXB72_N`wx?^0CccScya`a(T%hzv^20TqHE-2yvSmC)@mJ|dkb*TCPi?Z1?#!kLyl11Wx%k$Y zWa~&!RzwxVY}pV!-qHY=V=&qRmGM~n#iF}0CWiKlhGhIClEy%f4^ksGh2jv9bij~X z(B@K%mdO_y*(x{90mdKmlY$YqB$-1iu4z{s(!?af#-`BnYtnhLDho~>D0{n&0cSV=~mM6la z_862}e0iILax7tDYl5h&q$8!_gVnaElHN zwFvmWb)4Hmbd+FqCjk$qyT{>w?0EWr?Y#*4!GoRL>K3FraLJ7LE&PanVfPEng&)yB zgo`Y=UqE;TS37}vSL(aH1=7j}? zL~S31lz1&AZYaeH%<)N!b+*+#((7x^R8|^_m1po{#Unj&-VB`a6e%A3SdmH2{5F+A zmSDzCe;dXdx;1D&(QlE^*Htt_(zdO&Gk5WJ`YSJjlmwW~EZS#Z8{NYt;-# z-Rhg&mVhgO)4dru9$P8$o8-Y{7t!D_n@h(J$FN_D5+x&DP8 z*S!Y)aLUW3OwdZ8`f(!Xvd*r3;Vwi=jO{>6s%uw^YR1H|(0&2sg!hyu#$_4GW9py? z;Ur(xYQwvt1bAS??+~MuduH=Y2lULScO!ikZ@s6kuD;e+`a|49Zi0q|0>09@vq{f1 zCNx4W_j{TTBi-T&)fr_Gaq8;57Ek@Uy1;PVMQ+Lqn=aYq7h4Rn1#xGF-{tLjQS(uj zXftk4RQ}_N42%7VOoE553Cx54;}Q0m)qB0Xe!EwwKj$^ndl3(F5qv=W3RWX^kkWf_ zHyw8|9YNgX;!XgrPHf79?4SPUX%VVlY%0U)xUt*7k`ZrOg-y+1IHk|CEYT(@?T|(} zn5UXrFzx@d1-1z4$8e!;=E4757W7eV(5cBmR8_^yh0tL5L#-ZJ^(>=WJk?_Brx@cw zmjfsFbatjiZGeQCOD09_H#s*UN+`62uFURfwpmKbE-kO7s0`J0j-Kj_`Ni$f7-!>x zJ&R`;l-qDFoZ2>F=6gjm+U(GV590j!y`pJtGo90%OEozcdBA%G9>?lY<~paf{>$@Y zL`(6=dfCOYP5y*jqI3UIcC$JvfLP`8_2zu3fv;P24prtK%qWRq&@AK45#kDs&YS7r$Fwgx|jq(~9_c$tfuRj_y`p zgK6DHwUK*%wp)Fjdjh-FU-KaT2NAA80QHo@kE)MxvHqy)m*h6+Rx7FZUX|&v8S;()`2*WAC<~#g30beAi!B8ycXegOp838PTv?T`0cY#n{_j zoG0}M`jh%=BP6RZeRfn`$Sw6;`ph}9o=HOeFI{Zexm_2-w?sqe72|^aCg{zj;Cemw z>Z#nnA0t$|7cqlr%o;F8sf_g=^5~Mx% z@q9~HoPd$C26h&w37dt8!74O-h>;_Wsi~Z5WA>%M`b=@I1nyQg)*7^ZkSYF^LSufK zrEws9Ad+~JR=%|Dm3$9yF0x)v5|SVdn)Q^CUhuy#2xIpG0(E-ld9UHwQYvY z77uK=@T*t?-INm6^QL&tBPin#+v1#eLf$#g<1E+}%NVr25dU5BRwrP_QyZD` z+REe2tPSG=-aP?0W49{sZTP`b+~!CxFJ|zcRaX>y*bAFvPzhgBSps}@P#%IBXy#+q z?ZnS0jVs4C33QVG(qefd9M%}@_k@1n+K4!Y^`J6MN@nELdL7nrhR2z7R86qac$!1d zUyBGmJ29TDo3o>;B_EOsTd>QJApDY`PlzPkKr~ql==z**$6n8yY9&ch5O6TIM1#^| z7BO6;+~&{(HU%J4>49DV}LR{mCKJ)sW6)%nWq)LV#_aUK!6shvAIlh9A1 zbEqdVkmXWeTKi+_wY*YcaZID$pBT9kc=ik6fQ8s29YsludPi-Jey7dUULB%%gmvpJ z4Sz33I$yKX224YvVGo+%RfKdW34eSP0sfe}kno4UDWWP=(lGuA5dOFcG2}rz0Ds)R zZ`O>q0%y6i3HW2*tZ8jOa^CKIc#&QXVo3L#a-f9nq{b1cdRj+hxR#eA1tqh4-a*U@ z%JCJ=n^c6J9#vDTSyvGvO~9voNw8ZoS3E;&!x~}GHNKm%dWyjm*Tx#>UA9Bh=JCiv zDnVgg*q*!MVi-JF-i5MR_aeUEb+AIO_mykfVkyZ>YwEpi1<87RXRpr3eAxaF)C`a5 zj_-|F>JW}%Seg2mZv9@4?~mzpH83=$EX;f=)azLZ{K1S6sG^+1w zqw2({ChbpcRDs3r_K+5OPye;0VbrYuTn~L<%oJeDdS5Z`D&k3Ll=H9s;$}-)fi{+L z^7s0S*-y1P(`YqdRao&va2e;JF)tJ&9C-Y0AIU`HFwgpk@A*#647QVj60)aywcmkJ z_wWZW>V%h4_`x&7y(HX1b+luIc_i*K;k0$A)p8Iu=DQ~(M1<=Bt5g1O^)BnDeT@@b zY9n~H=KF?fz5_L{J+p}56}=h8W(@UhR4d_ZnK-G%xW;$T?nBs}@RjlNjp}CLm((_E z{m4ePE7~GrJ*KtMs?^pbxWa^_ls3KhH+`=aH>K$ima2`i4zZ})iXJjRO4!<{!>e@& zUPpiLd%$gs6)>yz5zKn{2=pQA470DewD|WrUcckgQ@_{8@!LLe_#0LJ^9nPvggY)h z_Ira&xPb6N#%AKOETEmnYBsj$Hy;RRM(LV^xN!z(vyN#DVAZcybNJXMO)u&t-=4ua zp5;R{UF$|jB?_9iJnDfw)Nmpk{u8(~Uu$s5x#r8^@;;NZm+bjUAfc&trVfPbBPK|r za8Wq?YwdebY>1I}dX50e`005SUU(mwG7pxS zf?~Mw*4s)TBVdy~%^ZF~uE575$&aZ9CJbq$#as?2_Z=J?tQrU}RD%^+OAV6eXTD_& zk_0XpBAm^&n^jwY3BP zDUBnowH4Bs@`3R6-{ybf01heWq!QA-FIF0ztD4AS;dv*Y%(8aPgDy*~0W?h`#T+hj zD4l`hs*yESP#%5nHB8#yZAl6!e-E5I7Z1)kKY!ZMqklc5PAb2QcnJh=(UZG<25p{t z!)Z~Y^Em9SgGKhXLu$IibXZEe5}vNoeE~-PpE&uaFZBEdedfyU?$n;k2EzwheanE& z*Kx>R4LX3#yrv; zAF;+=##jTV^7UvLefLZ4yZKK2yO##AKgR8a?5r?7E@x(2dC7L%(r694$_f2 zbyPh+jQ@^C_{Q?>r}j8tHC-SchpsoM?Gu;7FGe%uhwY2pY_?b+N}TP?YFmHy4drf>YaaM?T6}P^EYDM6|@Y5FZCT& zXIKZqv6$C!U+h-1t)Mtz_i6@i`a-m%ZBzfjB&SK%@94ec+y3h~7 zv?jmHM-Wz{{RK8Gbvm6G?9PkZ+x^F+Mx4g}(L&bRMntrAl-;lqzU$g%rG2c5fmt{=o8|2F990+aASg;-#Xz`x5Z)lF*Qi3hJ{N*=x{o-mc>|QL zrwxSf!N@JNad@K{2rn6QHEZ}jlUjFQ@j>i*#Pa~pi-|c&A&jX+V>dE&bJ4qPu5?(L zlx$P8`9^gL_qUiZe%TtWnawTQJ&k=`5j2uOe`a&yLlV1<@$^I-Nr3HEpA{WxC{=_X z72Mo*%LOC53nN<1E+|CxjIf8J2(YgHEbs#Czuo8AUX5%3ICLaZ)Wl-_ny zb-aPq6@P0e#?}`e88t%oOS?1eZ=A-jc4+*blr-LSiaN@pzm;hG5V4Y45g2Mkvg~#C zh3~=Bp^#O+wmuWphe#07TmI5v)N+*|*Eb>bB(PSUfnR)J2>W8+G&uafXjU%2#W~c~v|r(?uj;3ghz;=z zoE{@uil5mZ>Dc6oK&w@HLb6wc43i)BO!l#?#Wh(q?_#Gk_pbC^33sSw^y`MfTCIQA z4Q_%SmaAk)V_tNmuffSv1Um1Ip3C#=iVE6rEoZ&I@vYg}8j^(ufMx zzahGL$}pyp_`88L!ZXk9OqSUu!u1T=&Ez#JPtyaWT5ukT6TxJRG(8~?w`=7c(Ax0N z&hO%PE;BhEzp?n;yoOW#-(r$U{A8!P2d6Jt=A0jEJ~Lvn4P(bnF**ZkiVZRnXRE6n zsStE{WrU-u=`^6?q-AGq5(*Xtd_KHFE8o#;xEX{7rT2ZCNT{SLV5CcZ6L9 zW&o0-E!02Kfp7wg3GneKB*nA^s#x#trL$bDdy1~(caJ*IIVECI0s&rYGJ=TqZ}Mz z0H=oHnVKvgpFFuH$LaAJl>gOV;XSA>tj&I^R;{c6{oZg;y}z~@`-P;2uk$*LUj1GEI7Iq=H$SszVrV+NY|hWigf-3jqSWJf z$G0Q0wo!RX^)=s8)u7&u$mg-42BfFL1I>Hf4%|mikdqH#xCr8Cotg7olU&8@4}?;H z%@dS=^hv0X;Qwep@dB*3-v?;u9ZvmYzr6$zFPK!tDT0L91S$tU7R5q}BmoKA2AU%to@AA_B$@;d8Er7DJ1zQGz$U$h#)iAw0#3)sWcab{2{PR>aU z{R%!J4X?4Bk)e^G9HLXLp_r+O9YRig$9&kgSULjg3x$Tw?P|T1at73wtR_gs$K~{# z=!b59^Bk&iF+)64SWTd|EYwt9ueNitUZ-~(#6m<(-cZir@%2Nr1HC~2uBLU`*9P2c|Lo)2VI&4)IoCQ6?u(kksJ_lDU$n!93 zk0EPxuCxzGRigUvM4Q4nZ2$0XF%yTz!HWL8SZGxF=_httzf=i)zfMRpG8$U4Zo1 z0qUa}Pj}-<(4JxhvTSAooxc5!OBip_aX$Ri0cCe8AdK~X_5`mR`yAhJ?{l>qHb2K- zYEnz22H4wJohP1Ki6yMGL7xA&J_4Dm!?=kh-9i(LZ`jX zp^v%Yz~~&!_Y-8MR+a_SNe+kK28;JJX^f2ZC1p&B30{unwI0z?^o*&UtK1X3EVepT%)mbS@C>b#ZVkn+`25dK0>|))OCIcdf z^>(uE#U@eRG_g>DFJfP?%BVy%&l!l6yXzKb5Wc7vUy+-aIJZFl>v zZGptD85oHxDG|pmsmc!cUJ4BHL|`G}nnGUzkfpAoaU?uA0eTDJ!S{f#Y#N08g<1Mp zH*66+1kX}c9KNmuPOD=MJe%cMd5S#U$CboLG<;}~Fu^mPzjtO-y^PX)%{$eFc`vIA z#GPsr7kd9%V^ID$=*28$0e&ih1<@-`U%ZG&zZfS^l1$!a{x~?@r*ukHprO&uMqo6K z>t^dDoVw`Wya-Dw+GV)Xu@Cd)`4w>7QouvJ1`mrhc&Ld;+2#9zld&FYZU{!a5uT+q zYcK<8=C}}z(T)9ww3JP-v@oJIo5U?uvzG}wi5`)xo^!fMsAfcL&!LZrFlVli(~_b8y3E+{HUTSo5D}gbn&S{P?An8#ZALUXK`>ddVo4 zR^^d6=gKv-3(XV%6Qe0tP6w*dtOotT(dMk3+X4b23SgTrMwN?1$8G@mC zz_yU5VZGO@Tdnz+AHsuV3B!G(vC_bxrY0@oQJTbm!Xk zm+IEmBI*u}bZ);s!n<2YR!en1EFx;pF~S-=(_$m2c%c8B1_AXf5R-hA`t`L+xUT`; zjq_B~bz9VzB?qwMMrKv(lN<`p+yRI6YQ6YLj3Gq+DTBTVXHYV}XUAxj=&cpdTCV&Y z)C0?+ecYU524qy017gdmZ6`IlVx!fVa}wzr=Tq7-Ev*v%b&nyfuDs{8Z%+u2&8~rL zQ$Nr0w@?cfOUdvI!ZS@;Kl=Jac=AJRqtkEt{(hR?Z(x=duH4jT!)z(}Mx_G%3Rbn_ z?h%#VAJX=J?4an~UpVhQTTQ*6spaCm7pjfqK^XIKXnqPHW3fmW-v^Ap5~KOf_gb~D zk7sQM-Y_WVqKz8x9jK1>m;$V38i|km`pD4C`ue=hzn>77 zYX-GpQetCGCjCe7YymtIos!-`rQQR+a5+j4vOn^Vhd*&18l9WkK_yi(gEFJ9UW1TI zaUwLr$cx z-E@nDnRyyJ(x}{@5uKC!L?}78Dl{^;GL({gTZdmBo%?hsH5cB6a&PKbB@^Bn3mt+- zG`yA2r?yZlz36+bx}3+L?~gFQ%$1paKaShAGlO#Wl z-Q9xuXEAd%s&lqBXP>e`&GV;JHHZ=T6gHtcE?F$Htg+fEe6gGKWC%Rb9^xoX${J!+(`n{YPMkufAQ2L<#bHRxT80$ zx8VQpz)?I7Z2Nnwb=MN=r8p^P9G)w29TQ@itoPFz*4t5SP~guBwbiOyId`U@P4G_+ zOjtBAsJ?($enD^xfZF8cp!~eyg@73`2XlpsXZKQLGZ-+mvOR?}+P8 zGuvpi`GF{xa!!kT&h39~2=D&|5gxcLR=P`G9}@?9I03n4YcN@ly@j}gQhByUDUXyK zavb1SR6m(mSj}xQQh{v6PWS_Dui64GbF1|fMwCYIx}g!AO0=6{cnk$ZqQhzdMNg~4 zhTTfvy=aG>X{GVNN;8i<77YsnOgRk7>AU00ZKKe-$RK7IKB$g#>e4i?){{@g!5n|b z7FYoPtb;HFVG5doKFD|;)8OB4bwdj+sIC<2)n$OnzlpFTmVQigj@(9VzP`e|=)N-U z>afEG<0-(*Tzsw5OFA5d25Ak@7xX37@n>j2QtO{)@KR|@mhv^MQ7Og2dVuBTcF@<9 zZ| zTO5l2;>~Ws6rW3cs7aZaI(zKciK%y|j-AX#UjaS0|h(NOj9OmtM; z27=x+wsu(61=k7HZhvcM6eZQGFWEwnDNxQ+k=31_!AlE6>JqUKYk*+Mtj+cTaN;aP zuG1rb9Uh$S@o?{9@k{E&wFGkFKx(V{ln=$)@8E*ZjI^5Rvkz8p1VB+^rtv=W180hbkUI z-oJAP@}?m#bkq2DNEH8GaSzgaz|TGI8;5kz=8$Cfpx>9!Z+b&=m|4j4nN|*q0AzRxP+5NFmtK2G^ZlyWfprH<>6_bgwC^2Q_YYV|Dg7<(^OQ?9>8CA{tD1>i;L zT|ep>Ks}?73dsYaeJy+MaUaDOvS{VAMMojC@M7f6f*m7Ic`kNvX>lj4?rqShS!97e zZ{D7%a}%8BJkc=rMo3AfRYOk|xVRFW&#y^sq4Q@T`zLmZP_x)QkL6h$X4uMRLV@b!E88|i5@N$Z<6aZS(vSA3ikA+ zY>GUU+9WlpYw}(z5)ZTMOw^j8XUpLxb!8r{%wH54kD#CV@y!_-F(}^)zuj0zdA}%% zJz~i~$4W5t%7qma2@$g6gy2kG?K9$a(6s6W!@N01rS{_+-Z}xsI94$7oEKz=|WN zK3P5idruQ^fIEHNPCR2Y{g4UsBR@=II91+_Xv+!Rri6!P@#6vYXps}g^GBOzcY#zS}X?-(hb=3r5R(LKq%Gb+T zGM%Rdb~dZBl)3ITj4`z3WqAKde|aa#=-_h){z&n4d4uY+z1-Zaeg*7YW2M>PHbGvO zMsrkGWIADS8bCFZ6!A>CtqO7}Ni5ld^So&Is{y&L{h|Y&BctI$O_FrB91v7`C4A@J zN8N(6&i_|`YH@Oh#mTCQn%6Chg-ikKk6B<7OlJm7s!Jp(2R}Xt{*+D+HpHU_0_7^aQZ)!xb0EUm=HNf~AFiThZe;!)_>kN=iqZOp>d`d1I!I=wO*&owwg0 zs5d8AhElCl4IL}hDsd(F>K!qu#}-u`_M5aXlkp|ZnICXwX23K!SFl*G& zVo8MTFaWrrtgfe(3$0{xELcy6)(eQPCz{ypp~*h zjnP&LXvw;P@CKqOac#o2N&QT$ZU%n$f)G=_)?z=?h>b>ih#V6tp|&yN10Q zGYwK*az=5zX-mtSt zmBoDELRqX=PmB3jkzZkLoh~pg%i^>JD= zpNS)Y{k}#^&WKxpWkBk!t1C)6TmV>I(od3udesLmhRSVHYslZ;5vDY0XAfua)nYLo zJa0nI=nkB|0F!OXKb)4llT8`%c?c53T2HehqeCEH5oZ+52l^?1z4Mldv{pywxf0 zd47%wa=5`TNj-GwCC!!S7z{tVUqDOdi6SgfYSD*lW%UBwn2kmZX!-_HZ}9oqH~|$~ zA#G9$qJ!Z(B09G{+!o)SYVh-Mn#51%!xG@NkaB-GxV@R=t%9EkVb@1xB1AN>KIgRYZ&I6?1&#LpaychFtM zsM6{eIubAgi$!Rx#Ebx)aCKF2NU-uW$*4Xa?OdNxCNbp~nvYZ+cdO0f6muvAXE>v# zWQ4{|nbDB}xlX)fll#N3B6{`2BT|*crsnlSKfsP28Eqfpe#0O^Cbt=-L|K%Jw{x~? z2WKt#5e>(bF)B`QY-S04fL4Af5Kn_GFE)DAMIpW>n4Y!R!90=c@G1wQV zS5LtfntTmqVI^!3-)<(D{~IVpK|5{2Ic!d92kUM!ux@N*8LanDkjGUIa+^saYHbs9 z#PDNQ%vYjBRLn7LPkm~B`)O)d9`x8i+iF@V&^4;bYrX8|(jiT2sJraaygaAFYeaO5 zg|U$0h+H`g+Wl^E@rJ-oOU`2N9)z{xR=lTn@6n~CrA+M@Snx5J4 zs`k|%qjaTjeuQr}41Kd7loK=?#s_w`@1*yUurIP%O@?+*X(+aPAwTA7IER2Uy~59) z!}SDcmv+^bd_sK;*Q{jLTkDI!Yh51Nu3Je#FM@yK;!mD9pOV~u-k2QhT~z~}NtF9J zBJ$w$61piYBZ2T1d`xJ#tId#M1pZ2cP6i?lW)wQP6oEWGQ8r?SxHVeeN!ObYE0J_B zBjM);BjJHQ)>z&`_SrlEK4jFK6yv?408|>4wz!D zCA*}UZ|#!A+Po$3)d-n}1-Na;GRuYc1#7WQI~TmL%y40)_9WunE2^npS#nv6tT7PY z7ioc(3R74ud9l&22JMRYA1%?&sZWt+Ht3@GNw7SAMNNcO%Ou#yOq`n9CQY3ZI?$bw zG&l5foKP=dF9T{D0e?#|hN*2vdsWB+?RjI)Vpvi^GbQJTu&)-_V&v_|Nk+v`t{)BM zx@#zxBh=MNrDlZKlsiLIE+imUveiy)D|99def5K(uWlatDk~J~B)`C^ZMQhTfn_(@ zo4cLoI;P9BcMX+cYf$Hl!UfKU%Nj9M)~KPftV3nJgIKMcSs~lg%j^2Kyt5r<88g8Q zT7QjpH3Tp4^|Vti91QFfHsjoU(6*r#Yrx|CJ#?hEsV-)Ot=QRqPxH=o`Ado}1s3hB zt*I)z6!6rSl3mxoeHopxI}C5rjLf-`w@7S$MZHn9HPctW>Hlfqi*84*IvX#(wlt);Wt4w z(fZQkqY<}x1l;DAsuYm?6W~WF(P?jC*8%5Dr@j*B2|cdBhvySt`S85yNx(dltAo|D zFX)r1J=Gu03)afDd4BXd#$Fdj>~eV#UEk`L9*Tr-?|Y^19^izNeWvbYT<;q&b&tUH z%RU_=86?6bRRepUCHxZ!|73vDjcrls6?K7QY^d$&$2PnItcMso%H%6_NBD6f@Z%t2 za!Ae>ppge2hgz#)NaS$X(CdGwd48KS08OPx_>F#_H>93Jtv^649tAp6nP&)NeTfpj zgseCcei`SUO6j39FB9$MpHaa4V-eMh#)xd=_3L_)<{|!>j+sOUQ)cXA%JutJgEI7$ zu7b{@ue27s0_l~~n3~xN*E4e+UhE1+?~;0z*JG_uH+1AY8mm-A5P#Os;F*qFg0MQC z32f_umKSNgp(ShibWJ~St^Lu<;kASI<)@K5&h=_#S@OLSQEu6sZI*!fs778dr~ zmv|TP47Zc=cMS+bUmrc60+!K<(~uG{@y zNRQt3ZCz)SiWH-;wRTZeeJMc%Jmg6BYTFV+hQ)t9JaWW#Y+aXpDezNMs7MjCe1cRD z&*nr!tnEu}rjt^pJk+9HrK#W`yUWJSW0SR7O%89qAM+At_wRM;GkR_ve1G}Q)mD4+ z{80&*QS1*Nh_Xgze~tE9>?{4ywCE4NIfyxnm0KwFP_uVQp}!f?ciS(vGsxH2FwPjp zA+M=1(DOHSJO^6?ol8k;p>L{c!8x_P2R$AdtxqG{7omPdV&`iA?aTA~G?-b1^GwfyIcOo|DLac!M`Wu^RG<;szxb|-FvEDx4e&~G^25ifDb;a_+>VV4X?aMpEu6{3k zkC;Vj8(8C_AB2X>t;gQU?AHO}?hHLrt&gn)?dsUjK(O9s^Ha&)tAct zU~?yMhNS9HXOVWSV>Z%@qCEAbM}f5p>3k9JkSqo@cz6r&V6LYT4PZp8(2kfq3yqQR zTG70Y>-{xe?4j`Rw9rViF4z%e8uPn-nL{zMXzJ1oWwR1H_ z^ujuqv*;3AbfI>~x+3UJ=q(zC^RWcy^`l|UpStV(y24AW;(YDfORAeA_SITlBKzd{ zIrQ7ocF1W61*9d=Dg*>cY%^0HR-2j$_W`SbUrim<=Wga+D*H%B2p-E*+xo+uS7_E8 zn6-a)>bZ%#<%1MOjh=O%A!JFcmi3;YxV~n@#F*)3{yEqb)Ueg~5FUIdSV9Nb{{bBc&tMt?6{>gKgZBdoHuDB3@pp69zEk#b`}E^ms_f9Hg#KZuVp*ySrx3Zktq^Br z+)sXDCWN*uJJlk(W068%^H4+ci!Dibrnm3};TLg@|KG&D30PF;y+8h*Gur`1nE@9- zlrtwi#T~!P=Wa(TrwszzvOwn3%+Dw~(5~CT+r?wvxmG zX1OL!+cRi-u}SJ=X~sxzJD_k53^2dX_Y9b&y}x^(=l6e}|HE@Q>%8mt{ci7fks9}w zwl=O8Titt20eVBZ;Tf#-h+puYVvOi1tqEEm^Kl+2+vlru>~0gB4KPcJ%gXlNvu33< zA@a;nEL*V1xH>S@59zqrTkBnZrLwx#ulj?)(iMG){3`liOHI~ElD4~@JE+{wnZT0} zjsO;_b^8SC^|-FZ^UO}S8nyb%H>sW3K5j;NCUO>apB8MMGw=**u0N`*3iCK$*|eKl*i6?4toseB9b6cP-A;$^d<)`* zds%k}U#Hw&LAK5;o8r?Xo!^;uNYPY23_XLXV0us!qWqDE7G3V*eJiGQw(#D4jwurB zJ`Kz24r8ZsOYwU+I+gER-ovre2j35r#0nG6?@oIh<=nN%h;lO9cxRoWG2f=P=H#DW zD&6Jvz7Br|D%p=r~ipp!Q4}XHceMZhDrh0a2w{9*ZPIP1XYGsWQx$k?U^f zA5m@xC&lUZ`4GM1JlAd1JgR8s?r>xUU+*y`Pn6i4v^IFpwAcIGi^kJ?lL@)k6C_-* z2IZ#W2IV?+9Qg_vJcqP1niJPbMaGnpk`7;_(+#9b77~caEA1<&y?-W zJnGeT>(dhuH=`J(ZHOiG>|iGBqhKY+OqL>?7sjq}nk>5jZFbxh#daw-ak~^vF%x&8 z#Z>l7K4Ip>&O+b2E_Wt&ZMxq~uzB85VFP26^b3Ly)mLw?a!b=*<@P{F*r2w_d;F$S z=x)?Gc)g9rpS9KcsHbJq-fgM#mJjaeIfz+0wCG06Fh7xX8z;Q4Xxwk&cwaH#Y`{4Q z=OmnyaZbj02hKZi-h=ZVoFBybL7Weizlmd48cNaf-46aSK!dS+sS&>H{7zgmTz4u- zmG9wbQIajc#POJNonAHT;#8u){_x;gg#l#cy{m zdImTiv1@>dG@Pcp9Z-DB+$680eAjGtL)XbQs4e)XV(aXa_Krj01OA&9z zdxD~&>s*8KA7X>@;{)%Z2cE$101*{|f^>@Lx5L(+IVi6IwtjH{eNkh*!!J$_f(s`; zH?Cb7l>gB>DE~+6DYc#PHW7Bza9EXS)9oB1T&i-G$HB+k;3CSsAO31*>HxiaSZ*`! zh4XXMsg*A}v{Gf}do7KQ{w`B)BQPyxNhJ)R?|v)c$x)0oNh%MRkhzI|a~-rN8p#9? zE?%n6q2_!d zFj$Eto~ed)+mZ9#&RB1f$-B5j{X&19X81bn@qQU`o?1wG8z#E+YCAq1Dq4Ct(1eKU z+P-JKamkx0+?`FnGC?aX@-l_LvuxU6Fizi!kS!TmKNJ&kZU4;2ENte)^Q%=nTIWa# zn#gBA-w2w?F~4$M1yN^pqK}l=xY+2*fY|#}+XS-VRto7i*u!?iu*x}eo^SxqPOSGql zL)j{K}w%h+;P#f!z>2IRZb8Bd`jmr%Q0P6i2Day=nQCQn%ZG zMCmF&qWl@hhdBO%BZT9V@}1Z*+^K|d{db)IhBK=`ETW2?%5yk=hU1qweucw}!-wNu z9EadnwjW1B1?WhqI28Z&=jHDDkur|FaeIy^KGRM8{<%k#ZKhALm-RsTaiy;P17?h} zA;b^5{7f`5bO-#*>)M}g(cl?Ii#wwDZLjy8S^j3*9n+F_A$n2oip+O+u|9t`-}m=< zw@kzDdJ}j4?m>L7#x^>$1NotQRswf;?f-yo?HMzoW6ec8rFMEcTBrR3ri~h}9EWuJ2CTbV%B#mM$Fte9FuTN#xaCv0%p)%-|)Yf zHJUM+IrI=SRo8w8GDBHH@!9)-nYonD&mrH+*sR^Q_k+FvU(X!qh(`N>F_2fNIS;C! zNdcdQn4{pg=#JtHj%&}F&gGOZ1BWdT7gqzlIhQ=GEo<}(*od?z-gn^MgGzG4Hv97X z_FPIZI4&8o>n<6MP~mIaNV5-#}@do=oW6%4C?ykAks$N zmIs1>-`*79sm>PErA5w4;LOzaLx^qsT(^<$Y)LsgE}i72S@@Mvz5&q#NS0#-)e>YK z;KrEobwp-~oYltfw7S9%&#Lj%(f1f^1=8D%4=i?Rqx|V)%KmNqB&u7A)@Pz+T4Pk3 zt+q_7w#=AIbqr0oWK7ON+b9Y=jUaY(S?mKHyXCWE|3;X!B|3D)7@d&)zihKI@e;*- zrB-hXe7(&qWDb4V?mwS>E^O?6ldIjLX2Mh3AHN@K$?y`+lj1SkhY($tBD%wd?D$}r zd=o?52F?f?j!{hX!e6Y-=pE#4AFZktM(@20F}M*dPmURF+1 z-;4I|7G<{4xw+?7mLN6tS<7E6nuaF@c=96SL>6T5jbp~uuC=cHmpFZY$)u8BBTI)_ z(jmhp(Wa%B-o73*NWVh(iExLoHq&wG?Rk?5FPMGD>h-Vh?+}hS<5Z5QTZXfUb;pf<=^#!>elW_ySNah4F6YrOJGx3&F-}VPZmmxAZ@IYYwG;NQKp$yK1 zx^D5BP#2H7%21cF*?USjY;`9b_P7%dA9W`kzUZcBMX)$F!sd8Tc0=Y7+KNs+I{D1kYEIQQB7KK;By0gN`$JA45ivqEjDlqs(9*Z$wsX+mnz6o3?EStuH$D z+(u}UHgaOoDI+AkB;?W^hjSJ@3q_nQRzb?fIS1Czxz=fI)2%easwQf&F@Fs#n7N2P zVSMVODf6x`UR8QCE4V{i88RRjiGY~fw}gziN-C(3ZVrtrxLLX>^juFeY{$yZyFxjE z=Mc##$y##W9!kMi=7Jlg2Ibo@uT3eq_H0JMwdd!DCKb%X)x7g_=y#kZf7W^WLO3?1 zz{z1YfDSsom=_s*}Dana}&VG)G9gz%w! zEMRjrc@$ZT-Bsg9R=`kmv`;ofbv61zJx z9_I#xLuh}PN}-k0jQWeHO>TVa@?U-ah;pkf_;4z|(yDD#zp1>1qG&GFM2(kMJiPo$ z&3(r1y3GC1BOHWJSWWe98BKkU!xo74rM_CO;7oHKwlRu4ZefV9fE+!?=}ySzkn;@Z zTrQV-_u#|tKAeaB-CN5KxhOt^7C8k+Teo2u)$IDWl4VryJ%;XGlYfMImtWeIY3!@H z@8{h{<1hOjzi$m<9<6a58~fE78bPhpGIqZ@YmnlC0juP&oP)~u7`?~tylCv^If2@U z*2LQw!7LCJ$9{;I^l;q!xaOYBHbeK0)Mr|5mB!k;>|wOG-6BnLWvX@kdaSOy01tk& zxlD*AC}?kbU=iQ-GNbd7um5@9<6Dklq`vi)*8U9lIj(0~s3fXsSL)L(R=`cX zi6u!%VboymK=nLvcQ`*;i5vP@WfuZebcKx?LVBT*%)6#^!bc#ap5}tJ9$l5VZpP zBh%jxq7{e?C_tzB$MD4X(;O){G5!>@_->fmv1dq)`|=HIG^%}4K$vYrjPdwxGVQsf zz$R@PB6cHE(=21~5NvBo1IOWa%vtFhJuCn?Nf3*?Dt+HWah|lI9PA5IOnu%;<6^|P zXfZBD$A8z-aoJGV(b9g|kju?Prumr(k`|cm^&Tyvx$8s3(`kZMocZKDaPN9>?}%i9 z9R+RSR7o4+3VHaE@r9Em?vjxst4=M(t@3hmcCaOGvB2k;q|=uT7G!C$jXtqV37SI| zyXKNnlWwQqd_HRDz~y`ay99N-FfyNxJ+)})DTld4DV#}|$+bb_ZPkh>lbym*1Xw3N zLV#zR7QW@?5NAyeYQ+XGbnNY^e!{gJZ1{w)Js~VSslXI0$R=7e4j#M9BRR$_#73VR z5Y$~wSUpOUaE#&W3~w~N1AMI#=JH`3n4g5&5RpCK-v4tqB4CF|8-x{Ohb-RzCUiv< zbDi!P_EAVXY6CT8K4f4(?EPeBDzSPK@>5i*rZeC#L6?LKZ@Eb!V{SqyJJ%56a$(2d z)r7|9av_!*yRgA)JH>pIRlvJA(bKMI#J%uQGoU63*NM=18d$wQ{w_g%H%@(*puQWY zzTm9)=@?|7ddZ~S=E@#P!jVfUV(e55*8RsqTP+0awzdJ>o+ zGCkHf)#D{8&*`K0`obc-Z_L`+l2usWmX(`L-*Gl@ALbZQod2#Iezcqf^e7qaNJO7f z#l61b&ECZg$ZLQs<6Jg4OLGb05a7KbzrM|2p*JD4H-z>UqrLHWSvDbZ;3V0K(*6kT z^@)gAkDO;Y`85hRB6V&fC-44x{&$Q~Z zROgpZMD+;|UB}nIgjNi-P?;H{U$d>Ih#mTK=sBIp_Q4R9Ql%yBpmAPgsx0>LfD55u z8Q_6O{)42YOP3~3sL#r>CY~<|8L{f@A-dC?zg|5r=pv2ul4&Ca^SgGs+I=jqE&`@kx-K{D%j;r|4(>eBeCUiAu%F(99!_h^q>Lcy4q&RZ)}^($F<#Z!wM}cA zfXG3gOB|qdA(xl`ai`zMTLRtXStS2JbAdX&u(ROuD31ush0mL0fL2F<1r5Ek`^H

jB+gsIShfb^J|j-@I6}Biu!8`{#DuHQKH`wOy0Y zuFk9N`u){*ojFUrGaaWE6W1n6x_nE}>1$TfP0h-b_GV?Wt?vHp!pT8>{=~C^zEW^7 zulEgZPww0p5DE^r?QJRQba6`WUB{MVUHBv;SD2 zQ)ZE_fq0BLTRP?20<9`GM4mo{xrk8KpZ07XYwR@Ubs=E411qiF=f`?_r-j3gcgJNr zqz!_Qj>~=xpa+dj%8jNBwb_&{k=~hi=`x4VC*l9yw zj@oe8PH@Ol+2KvkzrL-t)VYd38-t7y$CAhn4xFWRO;K^yI&T56Rw$FSUWUlKuM?gm zKZ*qW@7M^B#Z7dVgge`Dyc6*TaHF$vTMuQ~`?oFnC9-}I%#81>3JCd!+mHvL^HIl7 z0W(P|%y6RZ^}{5^;f((n<7L0)rwT4JMyT|+@p{P82w98VWu96$qSJU1-F{Cgt`h2N zu@~jvEBNDhd%Rc%JeUGJCn@8BwDrb?rFVUQjU{+}=()P)PI$im9tXG8z7_FF z_$t>_g-0d}Ll-PXnXrnp{yXG!#I?iN(|_(8<;8O|L_sm)aDg@BO2z6V$w4QkY}G^- zYKSI$TVjCMB+aCoYvz-EXXi+VlVEq-N@iL%}n!T(?;jvGz24_hK`PMll2+pk#5C&3@{ zQRMsphbg6jbDAPOip<572Q4m_xhFTqF>4O1`*qn)nAd9k6e-a2hWC2 zBJTwUdl$@2J)($uiLxGp{frxZtwG#deZJp=h(+>s!zTkXLNWQ;Vbg1k9>j7OX0OpV zM_`L$OwN!RJ#mf!?FamtAmxq^ReBC8HJkujt322Q-^gO%C&^}ZCaz#pI=VZoATpQ% zn1@QU!Xj9Y7^S5cWkfyf`Ib)fZHI&aPZFQiyB+cMZjWF2c6o#HgxL@2ntEc$H^TpQYLz09!A~uTmF{7W(Yw=#uLo|s{Gc*l zT#>N)vTGt@z?B=oGsG@rO2mh=1~+|Ss@<)%&@Zk72X?>ItiWbT+iu({HHW@AvaPVl zqH)#39>@UBL9lK@?pZ4FPr*fzL|FbZ*h*8TzBs>BdAUw~_8(y?|NBELVSy>MEsAi= z1*^CT_}wDdW80o zY4W@ay~RRElnKCIJaSv5eWMS2vMxyDNf5E{%6+fUIFL0Ql~og-8JZJHRAGnuAhc0@ zv>u7x{~i6N-(;$-iT9J{f_`sovqRG-;-Kerhd^XF&V|9WL0@yl1RD%bd=2VCV^>^{ zovYm)pIbfrx5nUE_$PQa0T$w;lOz#Vw!`|JGRk27F~;P^c{lw%uM$%qG z{6bg|adY~E%Biv6e@p#6GNMV99R{PfDvOGlOM)2Ly)NulrhM87P$TOC;c>gX(N8D*Lcfk zsx|Y;Gt`JBPfEO$@K2=KF!Lu|HyRlXkOBzESjW#5k|%t2UUSlt2Thg_0c&+TeG zoLbN41Dq!x^&IuzsIE$aNTE$RMbIsP7fi%zr(Vb8sZsK-P)@mF>A6@(PksI66UFA{2BJ&^tAZim+BgZd}Vz+(+@*-Mc*{Mbo z-2==!pLDi;3SwJ&kD>_#l%2*!Rp0EoR zt}`|Pb~nYu#!XGzNY=-i*gQ+39!wOpJrfcelr3ghaI3SJAW_M?QA<*1v0C$!%EXWa z8<;bwsTnhARNJvxZ3m~egF`#$E#?yKfLDrpr!ockod|zg?g6zTzIU-+)I{!4J>Q>R zN|0_f#q!vUrq(#sD^lE}R1Y+-95fHdjpbjXd4Lk&?Tv)L_pb6QN6ZW*{!mFfrobE8 z?b%ZXPg8FEDjVVzEE^;Y{zN6#BdiUL$lIPLCX0%^bbx9;V&-uD3ci8wvRMOq%)?Vt z6C!DXi`e0L|0RXc1|hk^a!Qe39aiM}VfFWw+-w8ox)wAR(iiCf&%^T45yIeGxN_AN zHm%J*JqJ21Sx$~oiX;*>gZI`?V$?R!^`7xqGl+J3^*%+t zkHpS>!I?n$Ei3M?+f3)qeWy34B=TF-XZ4OPDT#IJ^&|DCan0YOepBzb2hZu+EX*B| zyGKjq9-unj!(D^&qM5Fx7`2zKR>dBJzJabb;yvs8)#e7}Hq7E?)&H30N)H@csq#>W zNx*TqyN4T=KSGQU*t1TjtQYj_0z|TI^pNZ^BHP;te?J30ZnzARfU*geP2LlO%LqPe z%zS_n^M*1hk*4pi+2_!81nLh{2nP&{wg^&%rxiH#P9T_n_v^LXr8-3H6MUu{Az zzu@hN-Pq3CN#}#H8jyRHDvuVH(=}WwqE&La!-&CN<;iw&eZQ(6kbkNCBTU>rByo|! zwwC6U& zqe@0BPso!LKSqT(eipe_U0sA<+@pAnhi?_4egm$sPniuLXv9Au*n`JFzV}qS@=Qe^;{Q{m?G4<)QFvv5*Evx( zood^NHIhN_iZj8GT30o}YZ)Z?cFvAH1k#mx?eP`D=F(@Z5$EHY3bGj^%q&n$o|R;kPS2FD@H zCj&IVz%6{Jv>0RWL6m>&?5a4AqI@4jJ4q^uOYH}hD%_zpR%E{j61G=l|9~RjiQ`&D zkxwW)-~~-17st*BIW3n1I)R-l+#YbJ%JYEX7jV=7_m)=>oNj@2tsNBUO|L$3RH4>x zL_T$b8IMI%paI5PVJ1mArJiMze7^#vd>4HyH+vWVNQIpj0XvYCbI6uq4W1;z1408_ z*`ch(ID0H{=udU=kbbnuMybvRXfcj{(LrA%IR)5;9<`i?w6M~`Z)F95zXIBqjL%h- z#eq1NZi^rPy+p^DcX27;n)P);E+_59A~j|S^}GfnNSKMAH4XWHRX@5~{K5dPM)z`n zzPJ`qJmUOUT*?8*COTS4_dxlNC$t$vy~xAw+U>!3Rb#wx)Kn1VVUd3)K5ub8_>{fi zRESeD%m&@AE^5={ee0|+o7z@S_QZ%J5C%o_U6qbfr1*}(c*q#bBRW;aVA$KIh&Yq5 z&kNp7-EE@%fQ(UH0h_ZjSOJe(j>j*6=igJ}oLG}b@Z~#cr^Oa1-O4B@C}0Gz1Zblb zyanrp55?s>)zUcJ15RzG1kTJX0KdGAq*Vr;`rHyjyVxv~ zWSBkv?3j!M-wsu3)k#T~VR=6IP4IKIR?<}O(S?TOjjDV=cdGVf&(BaprRBEtDZV!@ z`!iYZJ*jSF(0K##^WF>7jEyYa*-RYG(?jqP$tw@=d7KsYe30>FIXI$i)~mE$mVY-w zZK8F-B5(S~T7wvA*ncspyRESNna*a%chG6{N+h-wzJc6A?3eP$#>ipSSyZ_(K0*&c z(}37-IE3=p3@O0BSmol5vPgx>zus2;EF=tC=Zhn}Aqn$0A~y~CK?~?g87zjC#PvfB zfx7}IEz%0DginGl9Cge9#Q0&8xgkXN@IQ(EI7Dr)QX!JJt_?m5DT2YnGhV~0-~(zI zPoRwNNh206WJJ^;Dv2L0X>n)-6o^F@M_nOVc8xT8(y&HIhj1hMf3W1bpcY*2%fKkW z99XSfo8NZ=`zr^5QJA$5ayZ9WV=)Vj!k;jfXkq0Pl$LdMT+<-akCmH(v7=1q ztNJv)exKh_ zzhp;U{k|RT^=Ed}Dx!OFAU=|}AcJfp^aC9U28x)9v3+BJ?g7hlqo> zev~_z4xWX07<#IassNAe$(a(kd+@OVbreWqO_#VHfq!S}kZe|GowQyZTZ<9Zq@!9= z4w{QAo0Z4R+zwMH9~>UMvg?cMLSf)!&hfyz_##8x=Wc(nzV_zI@jF2I;RCW3+}$SN z`R|)lX`=ozAmFlmPSG?+C^u2@O~5|f47Z0(C%KDLVa_KB6ca#({0WhuPv43Kd9>|&nwH#>P!(vm*t<1$nuXM zQ39h^%JL1vVyF<`p1k_)QzHyf(@j=?#EFbxh=$X8`fXWG`C~uKfO3CYw84U}o34Jn z1EozF#+ogT$v-`rfp?E0Qe~c38=8#khwz<()#x30HlzVYoCvF}8VS-Cv?uukBt4q2 z7M_N5XjC~xlmom%(wi1vk0_K2f+F-mrydCpHF`)JgjiLGE9(Qjtfef779Gmc49I1T zz=@)f=%U8A;@+Hys4-r0q|n|E&C6p-p3QM@hTXBrD&pQeD?}Lj_o$&PvP=hccg1B7j)x^DCgRNuytWwVn)&0L4|VA^$Oq0H{VKs0NOjYI=gBm_=$^D?OUA zuZjhf{DapCJG_8I;r}z=dK~zcq-uB$hblc3C8q|dAY^&saJ-D$@HAocDb*H3xi9_8+MK9u5ML*b zemy3&Vs3$%WAb*a9`#L~vBWuTKC%qae@5iyXp$;fSg|ufes;v$Tg3+C zTO>Ir&P9<7!biS%m2}Ls=DjCm*@~VUa9kLaq3s;`3co5N6HdRZU~c35D#eDXF^}=A zYM(I9rxEo(0zIb|8oFU*ri$wctgNw>i@Y#mfpvx-wJ*Q&c=a^PafK64UpDe7$f28< z(bBhPyR{85&^n3lg{%$Rkmt=!KGH(Od(B0D_FKZ|U7%?gt={J+VSRG;vGs|$Q>9dJ z;3TEWa#GYr`}2CToP>r0?Iz6}NsrL8i!pd~_siR3GXls(00>(%pvU?vfQ0Xdo=%pJ zfIELLN;AC#MEmx+;@ShF zs<8v-DG*NkLjni>?8wNs1IU#&#u-irXE>eampH>UprRf#zE9HRPy4FYsd};$gH~Rc zlPwj2SF-`%r>SML*<~tp?B=Avko*dAuu@-l2W||F?P;W|dm3DF1NQW2=N#N+bysl9 zu?A%qBA^z8sJvqQj%fd|eCr5@Tx!rBDLPkX=u4iCI83sjOR{i?F{2|+pC6JdAkopt z6rt|BqA{z6wDftk(2qeQTaH-3-n|O*s~HIotXHL(|LwYYW`KvhgBf4GYT1rvmK)bN zZJ*)Knyy;+=|M;Bbt+vJghxk)S!CJ}Sp!}BYB^TcFld3$HV3Qu!XUxo%3-a`U|k=K z!(|nCvIa|?V|6gTC#6-N=Yk{oHZ;_vnfr3jELGhzqu-r@zOPKG@|3`ntw?O?PR()z zS$)|7+B>UvTo3)Y2uqw(1I@?4#k#@8;t<@>Z0CM`hbmL$dVfAp9+(WR_E+DTlG}nG zgyTGKO#V;k?jTnekMX?D2(Qg?J*x;JcvX}7G?FsNV^20FSB$Q;E#NI#@` zMQG578)1=Owo(t?AF6fz!sEeSSA%kJ?o*E3VB*#W#`O_l(#k%{6E{790NrNvV*b~?ne-U(8PQtK!*AVSt3_}|_wudn+e~R$C z@2YzTFM{ij@37GC#f|EIM#9*B29-C*>+w|Xg^tX!`Z7bz^9-)C7XCv1yEervO`9y6 z!&}C797<~qz=3u}pUWawP9k2E@EeTANww7kiBAnsJ5m9qbpEelp%7N2)&~H4v@08z z9qt+B@izrM#I4-}ISn&9q3yR@M@TYHIO+3Yr3Ijmj9C#$7bV%jOV zK>IYqa`lit+W-x>E|L+otFs@AJ^?* zk**kO6YN-Hj|}KwE%;!}=~@`#bAO0Y)?FRtFf`4>vOB6*NBKL$21MFn)|u)kbEBi2 zt4e5=V3mjKdvyy#&;A_MXY19`+A(-kZMi4}XYEEmy9p0}~crG#s zK8q+8+O~KCV}JT4y8r;XQMyya&m4 zO^rR4=$Hn5A>eOzDrhF-s0Gje%XZDZ+ODydJdc*V8r%-94;#dJplfHa0ot@xd`?FJXMo-`!GvT4vTIuAb@T!8k!1kFJ{v>-7=N{Vw4 znuJnSSM=3c=?gOK&5q=K5sZXs-`g`+1Id73I>8uk!CYvauD`??X9fA0$fw4^ei~Z- zm}Rl_`(w^fLg1P}YKT`yb>T>3Yla$?Ed%3u23cC;aFL~s=bESwP#+)vf)N{Fgva{0 zd1RbA3ly6tvgeyEy9}H&0v?2C*f$=Ge-jH21ILb)-7`RQbxqWY^6pf>+c?-2{%Scv z^pKzqM%uyOLGOhKwKJsBe)+=4AC}S>lI2dn+y+T?SS~^?Y>GMg2goyo?TF{*3Q{F4 z_H2ZL*aa53N7dVrCZJz_YNTIYt@4~(0_3ry9N_X^z4;_O4JkW=5Xs%GO-oBNBNJr5 zoIlKFZBsco4Fv-Crs9sgP>@XpunzsnIO%NQvk4_N7Zn<}x1bfJHCVdk-O%IE+6&hEq{pG%tabcAdLyKtu{NxO{6hO|U!h+! z8a*Z@VPPcZCG>Ilcm+n8lv)t!^q7pz_a6URDM>q49B`i zconNb1oSdks@p+hE)E(P!NP5|X>FyT)O1aI1F0Bm_Yj*Ez>wCSS(;2sgUM_d+oT%8Y% zWNBS_DUlnCcPKa}tI$MqCA1M17#CDEW0)0^X8sbR{{xU6t*{S)gDbXT>wn)O9&xgMT~ zrS&_S;ZadsTEaDi_OUz`Dz`S+gahRV2Sb3Ax=_t~CSnbcaiSI1RcW5gAb! zVx)f8L~%`7!y%uvXOG_`@UUp(aM=6jGr_r}_aE@j zg4bRTclf-LDHdl`!1h~U+Q(5d~b$ z20IYZIg>-BSKC_Z`n%fd?y&vp7qc>`waLiuF4T3Qt!b?%6=Zq{#4ga?mo3*Jo^ZbF z9HQc1mLC{_$31Iy!-m>Ru#c?dewsDE@=_1S35ajBThaM-=w%n|Oy@`%(Od0a53T)E zTx5DQ;?^IwT}omi_7;hUToK*VLcgw5PCAmi3@-JzQA1C>uF{cacl^5>qead=EejBh zl8;1U%^qrlp&69r05ASQ-SZ%*zjt4RQYdG^n@q$mfuKp5~37{C?0u$Dy+MaN4_V*zldHxXV zIc#vRKZ%Go1f%_ON{piza|}?rk+)g_P1dW>w0JH-Q*V!Zz2JOn3YBvW$}kL7l9!>Q zqU5km$Y=zFcq=KED8apZJr{Xou(9`1Q*$NySA0c&5jmQ>)VX_K&0xVt{J*6){qhU1 z-3<#xF0yLy&6afZc_sS1Q|$ruXPw%^H8B>tDfDG8Z@=2hxaI?#kcEqEc@@$oEOQxa zOkrX@^hs2LQ!T;ql`*>R>aS^xw21v4yFgJG4k6yg^8VNsaTYrpyAVYN=ZS7SV^?HX zJWe`b{}V>?_1WRRQs$%feiDlReynkwWNbCq5%uD=31sdb*`d<|H&8w2*<>g*HI-rh%AKK(Hl z<@=90`14#eWghW+pR8F{0*Z@R@A)oq{bf0ASX}KT9mSm^@~(k8*Y8U=6tSLMq1NMa zbt##EcEd1a8q_dl7+gaF!RLa8>w%AQHs1{GN@6!8psoF~d4w{0b51~jmm-7+-Me|a z>k*IHx!++pyEdaiSztQSms3-gS&yqNnf)z?mG8he@h@GhF!`gycxHDA-L>3aPm{yY zS?qad3UXndALrWO!1oP!?|#FDx`e}!b`d=pZ9;vbTHm%nbg&oCO#*f}$)}EqscGcx zBY@k_6Ad8&)CMvS;^J6sJ>g{0K6Uw(qZy}3av`2k*Vgnr?2+1y{|GOSn2dkJf2}bs`(hYv643{@-PMA8Ei0&B;`LJwdse6K zOcTHr)epx<1g(p3>6(xq{pdm~yA+Z1|94)NZ^v%$$npvBM;np59^e~Z>M2cH z>3SOd#b_s@B^Z(4Ar8#njzKeoSgu;wR_d&Fz+5AIWE!h3%h!TxU6#KUtHnLaw*%gW z?9&>eS0WuHl_f=ZHyu*x8PrH#U}c%g4up`Syx|;h7#F#Fz`#sW zk&jmX)+(Q8iA!)I)?H|P2)P9Z3@-bkH-N=E!rynbg&VO-2Niq&$!lA~-1?+$7vm1L zKO`Jm<@!KL15ewGeG7uHFfu0XR2DRH&vXHI;hpJ<+!v+RifB(HiZ+X_(ca6z5s@8^ z5=hdH&}Hn)#^eJyT1GGyrVkWtLlU6F;M(h92N$3e5$mcm%5wd#(nZ=24o3&BXrl>N zrhu!sjYdzTJVac#U!w)gJ?*h)W;)wj>KuJtE5Lj7%dZZ74O$~wCwuZ}x0V?*C|4-P z8<_=|1tVm_2sJ(pim=Lc5?nZ~v?rpR>ysa2jfswueGYx+n~J?LA!JNtB6dYZaYIE0 zFz8vqC9ZwN4J*<{4iRPfpB_>cu!U3Gf6y=Ahq|w;xVlmzmJLyx;JoOjwJyL%b^+4@ zQrjO&v~ryq6>>e*T8wV{L+!|$UJ1@;fl}AP#4VY~c#P<0c1^S6JhEr)Z8^V-J6o1{ zeiwOf98$hxs&)LM^Qfn>G6c*TFSX;LvdoTMbl3g^SnR`cUjwcsDI`GFLmrOqV$M2O zT^q0x(ZZG(IdCLvcA`@YE}p*6v+$ubWED!bluZ>72|0!?pKBbg6#o1ZBaT28_XARL$Am8@3^5d*qyAFfB?GeSW<8AZqdL z{QQyH)%O&TlR{n0#-j^ z0G_ab1^W59LWVUX-v(bliySst`VdS0a(D#3m&u@*EOJAPC?=%(*cinmtARh13UkUq zH4PE1ZSmrg<;$09U9K8^jU7AD=|SkfM%ZH*OA~aY$SePj)+D(%a19#x`X;cp(%hn5 z?zbxQYA6fdTj1h}PK=z2$=irCyWbSRSLNMd{C8grYh8AqJs{pEv<}P8k##i~LHlL- zme+q?1IsL|*iY2o($ju<_DP~zBX$;Pf-Zl={_$s2?$64~A<^&iF7W^|b6TR8dwE3T zJhO%@dnmFfVfei+yt6!cb7=|1I`X<3TytEK0V|;ZvvF^-)T%I6TGH&M6_Oui-HBWv z8ja*;{090Q!rgaX61cP`zyf4%YKMPy zqx(wu`ZD2!;9Y=U2;Nfo2^F$4UZJM6roKkZu3udXAK}~urCx9l8_hi%IE!KuX)HwR zz**9B{4s_cKrxd@UKU(-l}n3f6Jx@u?I-e7+a%Fv3K&H#;-DZlIYl)$dDgQCAA1Yg zrJi5?7;$spX*1OJo~hI!1FGALUNX+54QacJ`LaxD*E@tYkgcn~6Zo1@X3%pZ$)%U& zebJp5Pf^XRcv&8aHUgjInz(EazW8@Fzax!a6)4Sj)Vv!^d^P+gcqqb$i_APzMn{dT zzw}~{e9fRAdLGj$Ao$<0u!pw z-J7GB?GzQdEVFFdE?~HH(xi^Sit<#}33I@V{+mvHwAA8Dz*s0@mc81mMNiG~K5EJ` z{~Yfl;=ibU#2Bs_=|m6HztTe%`P;B5K)u$14(*A8!p*%b?}SzIm%YyUTCdxNiC!|X z4Os5f(x&yCo3d!?7#}3g?L%0-HLfPl-|Z)Ujkf9X35N5-$I5aSoN+gv5I0 z&mG`!HOAXd1aCj_pLlyOc=_t=@{$fvF5=~%2VH~?J!Eoqt6clVaK5Y7q3wJgyQ3ob z35*7~PVb36`F%wTUMU1g^lo6xI*%O~Vtg9DiL6K53lZ-=Q>+uE4@0YJxe++gY|XCz$3; zOApzz>0Sw&)bs3YP%HHcmWVn36}DPf#6F~TYWwEaXhPb)<{HwKFDhjl$WMLDi_UwZ zcxmqSZl5=B?h9>&)%6_WXCE38D~~#KQd5&SE-WPQzEuA4LGJL?_uI)%alyhZ#GytU%3 z)kg2;hY*(?>z&rRIgw{YE>lit7};ua{utKgq}kpJ-vG+touBnLPQm^hnrJFbE zNd5MsurO;GN-b4Oy$Pk#T%Jb!P(%?xyT)TKsb~8K^)#2W?D+ONiOt|=-GI5A++#J+ zTpBQ!i_&y`k8d^}?nBn}vH6NdcHJDc{k$jFFn5EtC&~-XR?ki88O}O~_5A8|vvXWV z^qP<5W~J35I4jekh3N5b|90ovSt*@sMYGzkR<*6aR@-_kycqNNHsf$Lc^xVcw3!D3LwwupRy}8<#-^#mgfp-z< zJ@&xDp>42N4ufKQYns93DhFWU(r}9_8($RRi`Cf8xs07B+C3?Oo!4m`Xm6gf%Owr$?@*YRvv#=2U3dBJgKr1E>=u|CN zzOM)omNyS6(3~9U$<>FdT0Fe-N5`y)=07SA&4A321DPWSku40?YgL)!syvhond3UA zfXF*q96Sy|Z0~M27`p8yioBHo8RYL_yLbiCPcNjO2V|zn&boOs`Z>F<-uiLNQ?`>4i?R!JemlC(~ zc9d6V({!qKJ(UaFlh=r6_MT_}RZXxqc^0C6?4~9qO-!9wR3t!i;I4h;)wiwlr)vZ!QTeE0HSqS zD0>bxl6hXjP`&bJDlZ8+pj_o!isP$k#uApB`ecde*%1`CH0-|1Up>UlV#@Lc8C? zPFLceEg5Cg0?{iyTvUtE8IwVv3&WEMtS{^;<c8n@%kP!g@I)HRY z1lL~G0l@Zi#107(9%Qi49g+t}uEiXNU zA~j)_r!3hpFB_UU`leUTRmWcx_o(xv7b9{lStYa6i_Gs;IN#{-S8sZB8tLd-@ zD7jAq5bs0vS6U3tb@2%B4f1H4@&oZa+PlSrj)|QO%6|0;<VJX$1jKFuC zN2W!~J$>O?11A-T`60iaor_(_5p%IGV`J7p<3q)nO}jpRsNRv^n3 z^dzyf@*(k|TD0>;*bNMcDXpJ8ge=BqvqfFVa$kPnn>=|Kowe+@ z*ioiTrn&i(Q6uFWPK6Z#>lx%(-|p%`__k9!jTJV(>-}5Mh*|hG>_(VHRCZ=@7OtARmwdh& z05`=Ej^j2F^%+_Eoafe`48l&jyQQOrWg{<&^fS*6WSHb(T~LeN+qV!;vHh|^#9ET* zNt8{%jQX*kYl61q?2%2niYFF4_|2P{G5eN^X?8jaR867vu0QAZVq?O z(YxZ^wYYPQ-gWFQez*y{MMjr%cgMp|;ws7Y#_rJPlzE(f`}TplhaU%RndcfS8RY^e zv9pP;y4?(%%+01hqBZYgoa4E>Zw*!=HqQ!-@sBXZoQ1}C0>-#Zg|Q**`SZXwU!4J+ zI)e?$eM|_X0NY^X^5}g^0b);ns6nsH@GDIZr4?i#)-L4h9IaaF7r@ig)Kb@(((}EN z_#u~H0IuR1%;3DB7)lZ;zJk~O@#o~R=CybK)ugJppQqvO0`3}> zo#kskpPHX0O~W3!C4X(OG-OiV$tuS8{}!S-eGgwD5A>b2@L1xw+G?ict*Qv6iUsJ+ zILkJyZlmSJKyJQy6yC>u4c;B_vzdnRS_kgQSfK%oN5a$c=LTbPdW?(QJkaR*`bwCH z8Xr~LwXdAPyK`Onlu$lux*v8GOc}g$5uz<2^55te1f`SB6|JLHTe#=qrE)MU!;4T0KjO7{C_|db2;DgPub6|VHC)PWr<9;bu zcr)iSAB$aZgy_w2Dhuz@@J`D~h$7nLwr>@YCtY+6$S=j{DRu%$TC|Ly*Lz|+m9^z$ zn{k-k^;b)MhstB4T(f^7@-in3CYKAcCbT!`=hsFqsy%)b%^XVWz^xV(|2=a9LhJ|I@L`}QmE zGTk7&1TMFit6EMEQ`TFL>)={~VpWHaaKt-+ zvUT1@WuF_F$jkp4Ug!NZ969khsMN0JMo&6McAZM677ucHe&A0U=^W6@Tu8_s>@8l3 zAfDI!BQm!a`e9&T%}bNA>34(j@?kdJi&CCdjN&8U_Wf&sg>m-d5ar3Kl0lGe&;5=rU}v5Y>xd0 zu<4|^ziVYZ-__jddjdJeGJN}B9pYE+FCQObeLt<{>n#eO-+(d_s~eOGR$4vI8^Rns zgOy|%U1$5tX#|>ppI*31pX2@h-GKENwP=T8JNCSXuC^)GJ@Kn*#WQ-fQ8_w#Ri#|q z10N2;OQy_x6IS@m;7n3*9%tU#niQgu;V?2KpT+4`Y8aTYoX4s(BF;^G-KT`6s_jBv zNVNXlI{rZ74#xrbU><-E=7BRi#%-qdUyt?^<=B_C%bWR`>BLsFJOQJPn$;Qmw}Dc1 zu64mC52xIhEFi!}nh{<;*w-rU$`oqo1PktirIWSR{|5 zId~kt1e^(b)R=`Q05$dHL16&^QG%QE3jP-8> zd=Rx)R53eI)Rc2#)u6mDMl|ps6RT{BZcdZ(h-e4Lc8HmkhGg;w5WI1VYfxd+I|d%n zf!BHO`i$UwjM4{HTM}x`x^h|-1RLtOVkY%~thHDx^=@kOHl+#nag0l-cl;mn-aS65 z>gpff=bX7FlVoxMCKuq$OacP|9SBqu)X5|aNhUzJRYd(cLDYlS30OO*trI{ED9S}` z2--%`HmKALnAV6f0qj%M`g8`Q1<^XT;BaZn2^Z(&I`4O#Nt8bA^M2mX=Y9Wslh2y7 z&pG?-`(Askwbx#&VWay*gbQdU9E<4G@pT{SL!*GfsvpIlcGBNwo=ddq3UeOqt%{O= z;>nd*1N$PZFsN*DA(rc3+q6ZcHca2O=@3r%stDudS#eb;s66Y!2nkY~o9gguO-HM8 z4G3{*(cyMC)g5?{vu3V3@L<{%ZO-IZ2T!987HGnwPA&_|*9-b~3&zjLiCj2)A`flJ zXT>b6!#=<9HA{|&6pV-* zl<5%0f>|--A9yem<00+eN_Ep=9N_MUFcfgp#`E({4L%PYCVci$}O<^rOavGzlll9@W z$=Yz{WFbs*-GI4HqjUiBEpVSjSjKacMVi9N} z8ebXUBk%H8M{5JuLgRmBO&0LU3N!4h$VUcB@%#3`4bfhl_ZJ-3spYDJ76?mBi_VO) zH9a^d^v2*-NN?s~F@DbuIPm+&fg+-}Kno{Vgr4{f3C;?xF>t7zi`M!_;w^B|?e*|u zR&-xRG!@@09Y{r9vjz+ZABEfod!+-QZ^cA>d;hD_g)S7(!?;E8>noQoLwg7H zrAMj7Ziqy2hMb|DL{IL7CnPOaum{!F^4^g4;Qsx=f@%AgEPrZ0{yup6g~r!f_rJ$p z7@{S6;^!gd9F3l*v#fU$w(@O`GW!dd<+)gQqu_UGem{eGovah#%pUB;GRU^*O@r_D zlN5i28vl^G=c*x%m+zi^pguE+)Eg^U#TBtb>YFsu%J?q!uheJFQU=Pi$!~}vWtOGR zlV&Ls&z|*D4;7tUa77NA21VdJ%ygB9XqK|oZ_mc)TZ{T_9`-|3?pD4Fezt~7Tc_rw z6+^KnP{W)nO146MQy{(;Bie$#NVdn)q0&){ti7Vt)#~%H;xj|J^u7Ota;NVIq(l$K z%x!VV+L_~;h`7e3&p4`%JchX+q1}0mTC*M;IfuPrqWoRN-4Tidn_0DlkDeG1Vf)jULDmx?WieYZuOuJo`i~hH+n$IApgXX+X9na| zRSD{mOY!^my=lVMZczrz0=QcW{kNH`BTJzq@nDUW@DBOIz83WzTEV(?4PQsstPSouSaegv z3pX4KTXhUy2qi>^{7ATiSqsx_T$Q}S|0sDWds=P(=*`McTv5)eM_T1L@wa9 z&2+y6skWjX6keo;%hhnH8V;-B8~bjEzKYzoLW;uG;Z#LtY29?SNBUS#d;)ZT>Fd?_ zVzbiAm|Ox%p2CX}p4{tF!@Z!57c-oW4r6~({k9k1rVf3(pf62*c3I7Dm6{Sxbt6@O zAMLtdig))=AF@X55DeY`9|eRX-p3wKk19dvH5(8n_#=Otf4ZM+@rJ$sy#V&6=eiwASuf##0K~f-uu_xw=$1lFG zKrS>0>%bx;j)Z$S&w*2P#p!-nq%y$=_z3LHw$zExVXjDw3zGi213Kf3lkltITJT%V zZ8>>9{$)F@ZfWoas zjSKI6z;A|Rdp+>b+reK%AMhJ-N1SD;w9;2E?eYaTwA7bC+I}8wtoQsg{`jE3{Q*B& z?VwmLN%Cc?Z$DJu`UgojV)Mxd{ApLD!!|fnZdK=>ffSYw-V1Hi2mFRBVo*+9(rF*1 zsq^0g`EDWC9D2Y%0&%d)cVgF~_A_N1Cn3f}uEqC`auwH7PqCOoj+Bu+7^lb|@Q+6P z^@b#(pvJupai<{8EY5{EW7Iga5a$NODZ=vt_1kK$dh`qg^&yz-2Czfry4i2Hu#!v1tp=0#o>d*a)B>5H{$jJ3#TF#bYNH+cDhL3K{Ed5u?j`-UC^ACH+k&ykczoz#$Z)9T9fJC4;+E=V&90# zjo1fAxmhrujTNF@-Msb`_TF3E>~r`anQZ)miI!6|-*=SotaKXBb^%)Uq@POejnPVF zZo?VHFzpLKhZf^ghZRPIwSTU#FUA-4#DqdurGRzSlJ4w{-CFK|>d(Jjw;hlp&7%fgA!n(WfVg^zMWhOEkWN@P0 z2Aciqu<{Ng8XlVb;A{uu_hI$*yT%~oc;Dal2k?<8-|@IT@smAfaPz(Kmz0(e@$kKI zSW8zqckqov+u;=9f`unL1x zH(T(#0&Qe&dpX%g=4_Q$q!dVA+J`-kf9JZzmE*8V@!&?ql^-IcMQ9{SyaGFP=C+NX zs+m4trK&BUiOJF>Fk-ymI|*NsW*bD_e*kX38(RLF2>%`BMm@G>ZlRSG68CziXvLW# zqT1{eEf@pOp2CWR-5ab4;zV$ycbbWxe8#o*6jSb;ufe(Z5Tt*XuqFW`_sNjgTp4?X z8oR-D?z$E3?p0)zAbzbf!jfMlLbeATW0yRxf@15v!^StOCoPVu8_r{1;^aWW`vBaJ7r+QDUo)g7Y$-T0#;@R&e*L;85rfS0k@sZ^!x24Iw`R1b9+M5HR z3-MV4oYjDx*slgJ#cWLIyI7jpus394rDn(!OBcxy3yvpGy zIO6YUeuNdd#{AcwC^YLX#&7H~w|^}?E;cM_eq_AE0V|@U3$&oW`4NZ1czF0bvcN;> zUWkV}#79(1x+0UGP%gxq6BpxSu(uUmwH*7ae}Rr!GXHxz$fgJRrlET#Klm=`4w&1P zR@3(y*fJ$eOmS6omG6=6_^*5Dx2Mndh>TXFlbmBk(xGLxq%Gq#kNAibvaR~78vAEz z?7yn9(-52Nn3q+Y^6C73j0i2$hhM*Zy5`2p>KXO$ApBb57R=4hiB-Q7;5a)0& zw1IuD3)3F9dR%z>SG?7HJ_TVp{vqBmXj;KK_oXj=!e;WQrG;q=*xDCK<6grg5C6Oz z|7k*cWF_KX#(q4tfTmTIG_z`)&uGOO(sphZ>$!nf^@2>EtjaVgvnsRFFg4TH+%0lb zCUDr9HbqMzt#|#wH2?Y2=}eE(7LKh^f{!^p@6Hi@*g+qy^--##=S%2cUXJN#1=8{^ zjxp{-(4^+JMHSugj|Yf`tf_DnbjLpgwMSeJafjXWtLObmVXfTwO2q0M_(~D$9qr_2 z*3b>3$=IQp4g3Oo8b(MceVEk?K(8%e+o$+M-&YEI#S;A-tC!jOF0(D2%KSr(z{TIrS%=OU$P-1HS52LK@ zkq;HaHp-Xsr+l2s7?k#>m{+8=g?=sD)S3n=lNF|Qn~iDRqG1&D$jkL++Y)8GSpwC0 zUyt_OQ@F42tdVdMuZOh7g9)>()blRxZ|hl6@Q(Y`iL_QqQC_zy28**N;8mXItXo_z zV^GzCfraEO@S*58%_-&rCUlwq!J;8(u^UtxsdX-AFZR9dEs)qGoWCv9N7E&pZ;ZsQ z!rf@&=oJOeyDx(la`-G5>HT4v39rHv$!l|+L%SJoVHYs*Ro%+w3TX2jn{&ar@Od}) zrC@W{RTk9MPRQTyYpV1IWYYOir3aM4mg+Q5ZJ-z7vYSSPwI|KJ*{s3aP3NX zY&#-ASKiZ~6_w-VLvL@!+lz9@2~ zsyVP6kqI2M1X$vyeUNQ{N&=onTE1Fyhk!R28*}JP8#}k2rF)vYH3laCaX=4E*kBE} zaz3=p)^oox6C#l>2PZgzdKtv zJo~H;QgmoBivNJ_?HBPAgJ$(aIR{G@Cu1cQC6x^N)!H!me51Yn?!g>zWj_ZNI2tLc zVAdymU1x+9kO0aLDrRVJ?eeqe1kqP!aVFvqK-=;F)^)8~M$O9m%0%Sw2Dp(7bP<#N z11*q&m=Vsc$W`+Z;5Q5wJqOIl<38lk9WlYG?Rp=jf1`pHs(@$X3QF6Bv>YJnb1rt0bD3{7v0H(o9xdY;_-65g_Xa;+@qajGsOA{8To^nGPK1S# znyP^Ve|?ZAi?EnM@1}9YIWbU~tYav4rVg5E^p&gN`>%#mBEO4QrgSP%F`N>8cZ5<* zewR#>ayyb(`XA#^o|HFZk5(Eb&PVC4sWhlp&bm=A;#7<#?7pC3@Wp*Mi$?CI7djM~q5X=c#4OQ1l-ZXWHA|uz+OHT&n229)MFo@CW{lhpZfxoV z>bhpLMZhuI>w3q?+L{9$T7xd&$4teHP!SWlFwfK(#?vm!ip~(hT1j zuDAm&YaFVDgFCKAEKk)!oIB*Dlrlb9yP@Z^#yIlm1XHI6Dq9Z-u42OEHh=QgVu* zWz$h!IUDJ?FBrKd#D+`}u{DTI+LNv-oGVqFX6lLSDrf$$@qU1K{JAbxs+Jf!kX6ok zQ>sT$s)7b*)Y{w{q^vo7Kw%cWnz{uidr(J)CkCXB^}$wUpI7)FzJdOL;rnms?z=YV z7zNJ-hAEZ`gD+DYQN^eX!a>ySpprAfRgmNO7OR*J`Du>uIMsSk&7DHv*(yG~Xx88f zC=H$CA4i~*TdAusOi?|neTPffW#AbZzy=fRy!nz4YMj$~asG4l6`WLG#a)Wl!o#MI zp1@8B@yg$wtK-5PtVA(b1p8X434H;-Oy}eK2fO1tlo)gcR?}MS(}2bx%9Q9m6L9~( zd_4|dk7M!yMGWZ>&pgPe#arQaJPNwgUj>r1X{aImke{}We^WkS( zIBe@>-5=@4M@sj=Qtt__J8Ip6F$nD{cu-8<<&1`f(+MLF3%y)?l>B#iz;YF=a2!1n zi~pl%Zq;0rFBW(9R#sM{Z3(acuFu!5iBd^QFL3PLn5#nLn~amSU&OVr?qn{U6m`$d zjgpoje;jjXabZ+n$Q)7tsu=Bt=;@H?$UoK+usSTq$Yur?Z3#5CpAMut%*Uoz2Eo_n zq!s8$^=UkmYXNwz`S3FOD9**MK}&k?z&d0CU8P~YT3UN>C|tzsR@b1- znAeb@;T_60MB}oy9hJP}s<8D7b2s@yz9c%r83;QNJ|^12=I$JX{w|J2$czvK>S1ft z4BJ8QMkHq8DeSa&_KVQ(}I05t=I!S`glyh z=>|xE;g#{RO0q~Lh;$AD-hD+?>eHzc;avfq1)v*`)rh`MYDbTRe(;6({sA7g>PSZ# z_J}6IQqQGBwa}90$}LX3{riAeUis~sIs@4+s3R?WM_!V0A|2)n@qOyot_#(r$*<|l z`Ip{aQ2Fi0%NOJ&zhW1@b|t?Ij-hW!0-OB$r2&5OcX?0#K5r@!(gf8)B_f?|q`7bd z(yRQozxMmGIMuRf;H!fysHI$1v&poOygprDRv6_f5Y8sX-^b z(f|ucklRT@r+DeU8rP+AmrG_Y5s<`TrV*g~0j^QZMf%hxPY~8U%W=-PQQ-1dLO%X<07Rz+Yb@ClX^(Oi{vsM{O&9hh>^$)7^VoqkY4*~+?tS$Q(BVB^X{ZlsIyu|gAneJ|VAWkl2md`&6yrg73rjucZg{(=LJ46X5VSGemrdILROkZkcs>F)>!v=5uXp7IF@p=~Jq4kKMSD+IP5GKODRuuNOqr5l*Jchnli&-nk8l544oZLF4^={7IChr$TE5g>2>grQqJ;l_>!Z(z=f&bNL~kYla;E z?Ry&$Zty`f3p))$;C!WAl^x=W)1e0=tl^4T_}=!iHK}-FjI5JZ%zPTWL6-!7lz4~z zLr}o}Im!1uk%Q{{%ZG!~X7`0-)K(|3!g970KfmVH5VNJ!xz}tBX>3(>Yo#OA3#Y;+ zyOcBSkk98kAKx_a$4U|WPy?uR!FDDl*v^4F_yi|Ez)4~^w*fgh>U?VgA&vOqJgM## zNtVvXSNFEyJjp`mX`djrLgvDWe+SO`Cr$&BpId&M9ADi7dJ8gv-&S+uuMar_t)Pra zo7)WC#O(0+I#X1V4mtEkWL4@e0f*n8;Ko5_IF5@l`Tz9L&L*S|kk!Uv(J{$+{Ee(j z2G)d{aYCLX3>-Z1U@s~0i^^!=JiI|M$Jf~N{t9{%k0`uSIoKo&a<*MIp-h?0Z11MFwiog<5=ob-)qDnX34{{@4A#{U2#I?4uM%A;sNSq}YWNPpK*XRZa0` zHN|hh9OlGVq=q>OSWW}hjcTHq-@QR=%wh7j zcPXYOT#Ga3$yO2rmQeEDv+s&)K=UB|JNk?2K80L4{XKo(C~@_7hLaG~wdvX4oRo!Ky9spa!J3K;^2Oue0EbA zUq*bAp(<0o=gtajds!x)@E(oVEM}MY7jwrleKhwE>3A2j48ogD^51oq6U=Qp^cfM& z#Iz&kLxzvC#=hiM!s2_m??I~pXSmJamJ?2MM_%ZNUVyJ^eUvCLv%<~HR5)*bzCQAO zn2T&3(;cy3S4o)Yy5NM>3BknV5kbV9`F=N_vAn#o6X8!7?q^VF=BwQrzOfVcpUj}& znVIl84UNU1;kqu_5L}>WW*V-;?jK5wB~;FNNsZdFk@ox1Z%7E9@M8Qr>C#$kIhEeEZq8cs`sL zdH*@AcXUos_?gLk9G#*XPUgYO38CyPBw}ZIH?*YQ#j3z-CUnVJLoJXW{6n|KL@j{z z5T$CNuZv$fXX2Qg_U`Rx_aiTQPB2_s>t&gRo5l-g7if(*9vQv7Wr z%0u@Rou;na6wSE}%+ZN$&Lpi-!7!l|0VMnjP6EL`TMnNsiPLDOFig zinj^n^5MLpvC2G$7m2#kBb0~G#=UDLejm4-R#UK4)P zys7H15x*v{LH*U?H`S|Ee+B%eczOJSrh1>T+qxKAGMTYI79$LZBWy+b`4bqMi+X&N ziP~8~DFs1=;9BbApi7h@@xIhG0;r@HUS#aXM#f&*&X~3dVZds@Zorp-n|3g^>1T}n z4)1@J#n}Eb#?s0W2ao{RJ&c_Kj6!+N1D>j2>;zzcCCUdlIFhj#U=-k9K<+4{4VdFY zS!)^VxRbG?cQJPR-N+A6Dlt~O5g#yM z@-PgvIrpNV~U1&SNy>FtOZ$`i2J^hVXi~hv>EC1%ck-R&Kcmjglk|j(2^uY$GCElUC z!*mB)Sueb)oo_(xHD!hp6UE+~l7xdlL>U1um%)VHTNsNEGj@vzTkJD<_VsHV<8DHF zfKI$Wf%m__`%m${67MhLJv{4iE;fVR3gJi%XF%-)cISN$EvG!L{6n+<%ijm>a?l=Q#G@Se}jQ zVeI&CIaqsv4NhF!deMjN96NK7Q?K3MqHS@XiT8BPM*M#u-qG`%dc7MxnfpG+ex-2g z^%B?1USunn7rBjLImj1wY^cL9N9ga3U;p{d5v8KpWZ*}ofsrv9IZnqLEf#^}j7CAw zqWz1;jaR$ie@m-qD6N+(um}J?1)Ktms03aG+zo()fi0SiYdOz00S5_7cy{e=9IFKU z2rvh-@%eySz^^OUzWN!S2OWR1NRH# z$WNv|o_gOUa~Ddd5np*bgM9?}1n?=~kAMi^fBwBbJA)k^dj4lzJLchjeg->%@c$cl zdG+_--~3QA{Id7^Xa6bf;j;awcf-#vum9IHuKb3=6z~7B_UybIypCC)hOMFO zikzyfJSN|+WZ*3eH)2gsUXi9%!_rt<1?i)hDwv#5z{@Ejn*jFg>0Wi$zmw4@$GD_? z=#R=W>A#_cRGz^$0Ss+O1yaooiUzdK!Fx&8O#5Y}J*;!q`xy*&rsk#1eK`L&W*zoy zxoJy4@ixx+rMo9$oM*&yz5HVTzrXW$x*kU&0gl zegB+ko@@`BbTOjDay)|PKrGKQ&J&IC=rbN|c-y-qSphA8wgLY=-{D=?3cG`wu_uk) z$Z=lC@S8zl8b4PmYM%`~B;7eC{WESF_DMCMPz{fVuzNpcpF1_oU4L)EYuy^n<%k9C zDv)Nwd?wetyIQhI+{`!OKjTNFFR+Xf-F@?SH*jGL)Fw@%B=LjPUcIEPK@iFBNv;nK?;`&cK93F;@*95g%Y zBq_)k@R*{s89p4+!8cw=D2<&s{)@ToTMD?T%Y0>u)t89>4ST1k zW4&;0Eyoq^R~mwvUViY1(oo7zEGqx&XOAPT;NwhuQ04_))z4@1kt-?i z=5DMm0W<2p1bBG{B&IE)v}#I^tUZ_Z?tE^YJ3V6aXu4-{3l&Z3Y`{j$0j^}{Q%s!E zkuLVfQeo93nMdjb(ybifaUK^oXiM0+GJz}qIPdTtZsPdkPrHkb2k$+$QkuInin0$<|`;>Z*np-9k4f7$OX|7p)thgE(#ew}bw&3nuM$ z_qk)K;NOkNc^3K(^VlZHfA7)YtUz|4>?~(*bmw%Yig?pO@6nFcR>@nS^<;(TUkWZX zq69DW!%tdB#K=AkizLD28tg#O*&6gh3ANrd^g{){rSXt4Z?i|d^!SRYQlXrodDX22 zZZd`~7#oKZl%CaNsF>!{$!q#`6~DWfs&&I=tfL$wqEsh8_&)0#PK$P}w3RyV#}a=j zx;(q=lkfJiSSK6W*YJJ?ZW)jX$Oc#dKEO&qEkMPg(g{5~%05WIFPV(*IIjg3TUcl1 zi%f(CCp)z0ON4FEGqSU730R@mwt_c>S{%)3NKnf*v>s6kirCgyyF(fZeb&uVz2`Kk zp^4XpaXKIBR+6}8v9P%7e@FINAJJNB`>X~JNKnv7WV%NIU9bVITS2o2o)6Rqg>&k7+3gp zjBwNaS9OP{dtDc})D>+V0 zQyIpHc2_fW+j5{s^5%E%*Y{&pNR8VyO}mwmPVFu`#b`~yW5;j`tNV3$OHZ}CM7$l@ zx?3S#lnsL#v$RB>ij83-Ahj4Pp{S9s@5BBP(h@yNj2FL+ z8K434+k_Tc(uw$&xW*%(v#flT0rv49{eX3D06jd`vAz>K*i7TqRyD%+MROUu9QBte zBCUb~t1;nctYc%R&a1vd%p;0xdHbkT+M(SfCwm@jx<=lm)XWnaJCUPc)F95#|o*QQB}y(EnJR1Bow)E z{+=t;^a>XbD2D0m@>_n;fi{%WoUk5LG)264P%(_qAZ&vEfmv&;fEGg0K}FOaR0{FL zf$$^%n~k?tX9w#78;o+h8fi@+{KFNpqAz?070Z&Bd{kEx@X@sK0)Cz239}>pqKO#w zcO_Esdq?6bFZN?=>}8E}?5a%p=ZSRH_COO>Z?pXfbb**VC| zpZBL#n!Qo%;@erigdNLOdtsTJo4FU31NDbfsuuakXE@NmPjAo0YQ{Q!G=`(7|Ij*9 zjWIS0c*%@CbFKn*F*?zwXrGZ@W;M6v`V#R=i5%~U>iL)0)PqV;6uP_0gv+xQp;d5S zVMoi@IomQ{6WT3U#*3f(Qaxjf^F066DL^;U3Q1&hDStV-iYsvzmnt?mz=FIQdC|O~ zKG1vZirK73f9Cntw&qLRHg1Q8=7W!KrSV05WZuuY3@DSiEeD#DInV}q2lk?u8ic+q z_gZ&DXH(vMYgO4ESn+4#hCMhRn=pY=dj~C1W8nL;%htK)%g=EQok#M#Wh77Di$xAOtCdg+0SE{vpL5g*{OYV216MMjkT zBfajksCBKvvN`Jk_}I+!5tb1u{BsCyCY(imz;>sa0GyYXsI0f54AhhJFZotsT-s@V zn$;3Tln=psQpeGvV?9>_XY$Kk%j`QMqUMA90pZfF}JZ-|$5nfJx zYE_>;i>J@wsd*^wU$vCNW;|Vwr>R46cjBbv{7YN$bWOq$(t3HMK)q*~gI%D`#VF@e z0F_sx&YctbzN4fObo+BEUcwkhJr?Dygq{A27zM)Wc7vB!=NiVWmS*H(e36`e!>xj` zkMF2WQV6{MHm;E7FL!RO*5vWzz2(+Kv>2;2WBnb@+{KC}KN0UtT!_(k|4-;T9oozQ zidRcIO~w2%O;z|-lvkuOJ2_^a2Dl4z)X=s{jadV!f08~j0l%36Gl*hZC|q`x!E#Fu zu-u5liUHR`Turz-a5dvP3D+E4ow!q)PQtYYS0}EE zah-;%57!yEuE2E`t`e>;T<^oR9IfLoO299bIW)&Rrz#I~=UMcj$J>WCvf#~Apwr4K z%b~xP53R=xUXU|{?6OqEdj#=r#0+4o@_g5*bv3GWrJjlC%R3*$SO(56yav77;4Hi3 z7Y^V`ZQObB!RL~A)?_=ZA9M6-;0x-JE3m8$Z86mjisS&ULpYdi4hzGyz7DiJ=MW;$;^^e9x&AD86XN9`?4xnA z31gmiK(pp%&jYVL?a>gp=pTNlXaEL)319}~04#ulAHw5!uU1ar^rc2V)Xzk%d{8L~ z@H6@1zZ~;J{=&JYdlo)G=@Q*=qNgELV9l)HWJiKlnm+K71-A4`=nTslu+`9U+Temu zpZ9VU*HGQpBhAeKN;|uaXfCcLPs+m1P6|=ipyYy! zp$#wZ>ahd&@{v363th1tc?}%2H813CTvYXQxnBHct&{mw%VrJVs8QP&yNy3$u3G^t$vO$DI>x) z6?!upa)S#Rwn|Mtiu;D`=3rCsw%W1CClcc)jX<1y#Cd%}N`%>(dNa7t82Tv*W?w@f(K#@{$}C*VUi(2Yh*Gdu4!vSQ*cjA zH)&6V_iAis(GJ6H%-T%e{J@6RJK9rmy|-O!-=vtF`Wes`Z$>l4)Kqjm5VYM^(%4s>7JBO5Hodz zm)4#<@KpCe^T5$Q4Rx6hi|Azk!U2ub4?^kQ^s0=C0>2e~`D+F9el}=jXx9+c!tAH| zbev9J-eZG(OkD*pzYRHFUC&=)!)2>qlELl+Ui7Ku%mGE3Q0WoSBvu+#d6F4pDm_AD zssQ695nl$o6!T@ar~n#QOosnn8Z+RD`4Sp)I=ke7Rpe=jc*P*KAFYKnmh^303zL^C zGy-3rs1G+bGX}xU6A$ut|E=*VOQ8@N?;}zPy#T+GQ)3*X~%kvzBHE=M}J` zqi(R#Dz^z9i$wdkOW_@P#h&vQwNJ3gT;!J?Hm3;ZVyxqDd{2G{RB91)U&qVu^oXuK z4ByHqYa$-)Tn#>icpBnpcqg}wmme8W+PRmC0=MlQ<=v(@MPZ^NY#OKQV;8nBJ=5N3 zdAWw3a#IiQS%+%}zDlp!Vc=$Jrj_~D`-l&@2K6WjIYJhMA5_Qve<`4CIyk4s@i}~8 z>YWW`GVc*;A{^%09D1mez;1LOZ%y;;#K@&sx%xwnl0`Ji}#bX7F;Q znpU#{%CUpK%?wd)jjB}BN^82!Ixo-vqT+N4?f#B2IK5<-)`d{AVm)X*K`zi`2@Xc1 z=B2^YpeGNiSTLY)(>0Sd-6l;e5{>PY?oh|o)zHlOdzhD3DraEB8u}HGMRemN1~2;* zEwJO4yI7oj;(^p zJp;Ua8?kSR$40KLDfL7XO4zoLQbbn)FMQu&q%+GlmFOB+QbHr0DGc;f%P^X zmT5WJ*+cqBun-`3LNicsnA=jJyD8$NbWvnwD9dYUfbQYyM)-Nn#&@qJ!b7oJI%$Qh z#60BWR})516fe0=5zZ!9^;oyGJ!fMa<``Ku;E)sSU3a*#<~DB!?GI2OE8f}gbIa(f zMtIV`7%vT4_-@XmSA;IVzqLRsKiB(e13z_Q`Kv*tgCV}$RyB80U|TDjbX)Wz zfE90+unY2`p=6)ihBp>T^sTB`RmB?2Z$4rD^i0kV!GU0w|33Vi=mO;SWN^$eJFa_! zF%Yze-8E%?LY zx#5MyFGX(h7SM?P5l;5WPXuqmSYgGFggLvxwxp8Qu{p?lO@v3Q@OHYt5%+bGi5`ST|m}?(J6})m+CK%6Jnqo3N0w;v5uV;?G4wY>l7fCpXyIQfGCQ;cLinI8K7 z{ehXVr?eX>rwpYS8tDJ#>js@SKEcr$SIhLyz=Rl$CmLf80L}5OxY8IbN0`Q6IpAji zXIoiSSp~Ca`^&0cXw3%g;_l<*(~z?fFBSa@cHCLiyI&}o zNXf}GSdXinX)iGOFNp%L6Xn#~mif)LCeW?B2Sm?^R%ZuEQ8j8FBL`kqGM$H4ESeC)I;7aXBZAJ4EUPjq$Uj{42J8IjX;Msb>vjA#ab6bYm zLh0Y(X1$7=|Ae)QlfMAJVeT+g+hFsqC#(lwlZgLbee=hDhP~nQG0KC60mh~ECOx7 zzA2b*TX5!Qis!#$cY`87htnN{@r#2iyki3VRTIO)RrAB#RgsA1O*3XYg9WR!p8r#2 zeM^E{%1`=6dGj0W z!O1bF#K{tJG^=Hk`>yr86-!T!t*WORvV*3o>|kCDdTW@oDOCz2Xt@&n%JuUx8ncan z*8mLwTGuxNo&`Jup#3v$g3?B(OvZZ1-gH(tXD@lCQ$T5K+?RoJYKt#N(m^+{;_mQu z9;-(qHqQBb%s3C6a`EYi(R&NzS~~A^Kb_Z(sxcg%);T9)pa?o!kw**Q9e|T)`nQOt zC;KxR1+)l!gQYtS-V@YvMfx3}@oU(&=fSTg;?0V~W5g_Fon83W)P%K?zE}CSl%X$; z-er@*ro+gFk`a_T+jiLb>3^ zm@FjBdsPhpwDytrMoZcAx$7sVf}*Cq9bF0bVZM_G)IiVRoW{vbgFU#x*WL0l1_5>+ zs6?S65g(lpFppVhA=;?`K<)k^fXXVjjrBZ%meUev=X}v10fX>cgcr#kV>I;6<>2j^ z$G9ZlHywN+=Heyn0}21~I@5EV=j;5_knH^l*y2=}tnkAB1i0dCZ+0asEbt@T zQV>KMZ?0VRcTe-FBc!a_Da)mh#!b9di6J4?N zq7P!`qW5ElqW5CPqIXf}E5{i14~;#4TdH@o^hA3Ku!9EeW~@%}S_63jW5qzcK4FI3 zr39xMiv0bcV@M~0zN2)gU$Aq=}Wkd_G(;l~GHC>#;hV05H;$vQ+lVwyKwDhcdn z%W_>4Q;yY3#)^p^3wGA4`bz?%%cuKANL7rm7nLj@rB7*7y5N|ggQYDtM^d~gRr%PN z-|kL{=&;t}Je9Om8h~|EL%SaLSeKzYF2Q+9bbyw3y|{S#@?+#F78Cems_T6>4mBHWril$Nk9 zXb>RNddQ|prkF((%J(UfNB7{Ob1_QKIaIdngaPTLzJ%6Tw9}n+JlRH#?%ZSP-q$We z)_-=Pa2s>yqjeVeaue~V2hy-!ARim0HI$ECK;56|hpvx!eyHv(So7Wh><0WAK-~Ls z0Q5iRWO$wjg$2tQa(@uYa&k}5i**lnJA*|33qhi@Q=9>>23(TaH1Y~A>5kdNB@s`V z)}6vRJ;Yg(wFRP@U2-HiaWub+IK!@?Cx?PBBc(U%I8T8stz`iIgkM&sIn$pnlQqI7 zgt%Y737$0FY4wy|n7T-?If1>+@K}~rz8kC9Kzs$_>zsD%3YS5*&FaZPts9mZT8Og+ zE!~{fZ88jyKOs5CsO>fghBwl7wKSwWZ+iaIGlnO@A8$^?9~&wQ&Or{9;@Y87*kudS zwWuZez8q8jLpemX9F$|SEZHav{7tLn7>H-~k3x%0avI*ycAJGOOMsI}YVKu`;k^6$ zhFgIDANfxE5BZ+#BT8T6{MT0aKIhN+czepW;k-pPZxd#U;YnKeAc1UuRC;syKAfOG zw>+t7AbN60p8ZrhEX}zuCH@~$`YiCxH zn^3L;@ufpK619`^Kk`lH`NW_e^W;C}sX?AI_Oc;KQeik7d8Y2onrpVN^b1y`Z+-)k z={yhLQjEIU`|N7n{yitL0Xa=i#B2T~r{TJhf6|6lXnusQ4XwRrVkosCv-sw)aLim> z7B-+YYKq z;cV<>P={i}Vg1pgnqA4%{)E(yMJD{jJ4Rnzs>)6^dG_%Wif@<g5z~n}Wgpv!99??SI4B*N(_~kGs`60~2tC)!gHsCQfQ+iV>K2@OQ^CrKIe#G7-9_aG%m7pXCSZ+m0Iq5CN*_yX8!T*i7b&(H@5&s-luuILmN^1SwV1wXvw&8y z*!Vu7EN{(iD>+a?!o*zYfX?X1s@lHNED_hkgsi+hpx;NsGw6)Ytp-QA0~Qg2%ON#F zP0mC(`%eEiH~}AAWLc^82KThV=c7e(fUek=_-AYd^0{>f(OcPb?+c_%8XLYUFs=OL z9^<6-ohh?U?y+FkLbLeQTCq;}Xs1uJ<8Qt<0~+XBuRSd=dx(km2Dp-YLCw)QEmYJ;lH=w#2(9d%{XK6s6K6NL+9(=M!{OnM7y8#i}Zb3(uq8yS)Nzd4qF2jyU@p#YNlwTsmXTC)J#dkPJ`k~#BWf`NOd=n z9MEU-roiYz6TD1wGbm-`kVUCO5-MDVPJ+d!^&UKfQ$}Za23-(*M|E6^EA^EQ`Z3re z38(sQF39w0syNB5*v-stfxVjHIN5D~u$anT(?ef(8+q*GJVXn)6SN;?2KLuOM>o~O zwsIcYo%jK`xuj02v1(CZ3)=a_p6%eBm_0MF-95Hb@YksIgC2dS#)%%B<3m{t6KLOn z4}%(&clW`jh%>1dvKng%*>}^!j@Kqd?_%;>eOQMWbR83$Lps0Fi#1f7?OW!5SUmgC}C;#8yaWfA_i0)SP z0tzoNlQ*pbd!|#((2@&^Tp>zb(xp@Y3?=10l56R_>wS=OAiOhya}1#EsSeD{xgL9o ziT49&m%ONQoR<~tS6mDBE9HO+KsA5?Gz&=fF)a)Ywb`R9zk>d{QCg8#C_i3)wI@${ z)tz>WTm z{KOs}Cpt)ClNCtymH`i>eAnjczIuI$=Z`TeXAotivaSIH0Db_~;m%dba|pkz`c-9i zz!>;t^>+6Yt+T>cru}MVR^U}{h6FsrW?Jm>E*|zg9__{o^y0c=)GK<{J0yta@H?v zM|(KiYT_-5uEKcV;m|S-jICEuKF;Z)TuK zetfnteMdWuvk#SWfTm;~Y3od-Gaj_-o=0alg0Si^_!O?YW>4y@D0k(G^5d=#6_*xi zP2Z7E{SeF-O6ci2cgk^kinpMc7GTGLQbRjir>lDuT3QXCTRQs(;bWc?Ns0VrAUEsSweHn`gSV>jnz`VQ1Cj?wvT^jBA&=Y7;WC42{I z{B%7t`@)g8&T%+-!Ma|;nHLT^ss&xgY7Mb$&p)x7v3Rg6=9--miLA8xYSI7YQDG}* z{|Ge2e=E$KQJD&C+&>^Rp*&`i7{KE!{2gRSGs{zb+;+PJTe_W`mD}Qt(RihCJ3NMI z?A}M?7vq}d9*twdD}#y0q1y%P6ObA)G1X=PHiq2X2cRo}@KF?6Nf>cAAKhE_7&P;X35%LKH+Wtd!le41Bql8$ z2!}u!`OV(hK4?r$?>eJt>^j5$fVh)Khw$o%p2BwHcXJ%4N2q7lX$sHB^ssAfD7=id zQ^m1p8!EG|YHQ%SkTc|7X@j;84_}nfLxp65@E^tV7C75ZFpVcm7TAtGX%YS0iN3sY zy*JN?-2{IU3W9oXZqNyP5B;%c&;|{F^?>IAn*mz^z<+a!=N30S?bbmuILcFfWWLM{ zR8y=LLC}Uuk+-PI637gEvZt`phJfp%9JSIJ+?XmEvoLtjRh5>>;CY&d8T3GyJ~{y%fsyIvSt@=P~p#=M%c`Jdy#A1S)n9< z&oYj`lvudPwPQ~#hV#f?eHE~)UxyK609D0_(82lgYVXU#nmp6JpZ9&Uu}N4|Rt*VgAc|qJ;xaXc_zJ|T z6+6e#&S?;B!_f*ZZLytm3}{=_nU0D*$4c9=#ZFynYog3Zl|pN0rt3M0O9!+I)@oX5 zr$N930_6MM33NQ?eAo5;^Ig|>uJ00k^KQ@kEcdhD%kO@{`ohUyR!p$2OOklx5;c4s zjDJGz=hs>0$3TCd4e)*YE3Ah7WlZ&t)(gIbHjJ`kHkw$*7!wa&@$gPAm(I@{zi|@i!x*f8WK)d!12slx>5jMS}DxU98tCVqs~Av^J1FI_DRluMN#Z zl#|};o7(Kn&|egE-#6@j3K6 z!kk|KQ>aZl4lCQg21ri~^68c_C1W7niL)+GQCiy6A1%8Dxli~{Pp+teV+^|m3h`h{ zyyb&sU%QJSLww~|(Tw7!xZAXREA*NX8&Eh#-nD6!r^1|9;Gs6m9CpXovQDf+%>nPf zwMr3dl7;SQ{GoU#KKecfaYH{$jnRUU1_d<6J>`&~Mgr4~sX{ARWs|H#wlLPJu{s|N zc)tZFnDiPoC=Yn3i02RvMN^w9;JqBsHp33q8rRI51*E8Gp?3?B4)@Qb&vOM~KEU^U zumq$_N$=L+9rU0|B7w_O)++49&Rr=v8jE_~j~cFO8Kv3&5xP-blT3r!9bF6HdWScYB!r%@ z)_uYE)I+Nl&^6hoJ$-^{7dtZ-&xTY&?&Ni#afSktfzT=;ePMb@#-fb-zVaPBh~q>I z>>M-}UNgHY&8)ZREPKTLqS{KF{sYFb7ycAnrvx8c<_o&;?h}5=POzf#|a%u4}4A+gJd8^`|mDj0%kN}E~7kC z-5th3bSC;{fX=~k<6MkGYL=BGSY+lz9JETOni*|hzd^eqT8*|dj8{cKb77cY)B^Tu zD~-mg+NyI{i)?KD9N|vksA`(JaOxsn%n&u85Iiv3d7a8x)xxp{U0TS=9)N^B0Dnr8 zP+q3H<;*A{-7{r%!U8U<%avnQn`Jo(R`Q5R;lhV_XzVa`yPL<}TgV#YWLfR5B=fkU zB+I$on?hW8=v71!#G{aAs96k^THqjBMGZB-63#BvTiTSWkdo==$RX z*kghZb!D(CaYc34FNuS+-)L}|inFRCtTe*4J8F$O>{+N}5te{=R^VRbTrVbp_RArw zhA!}60d!)=;r=Fi{wipt(LNMr#w=*#}7s#j~~0GY2ig5 zxCPZm?ohh#jhuhyCP^o2m7qSToweim2FLd}sBWmPNVD+WcYyU_rad@XG}>BBusq-T z8Big|U?ilmj=q^^i)INWiO{f7HpN*IfG;$1RN-6&n{Z&)CR!5ECvczyjo3j7_!{Qe|RTxOAqx!Qs2impEAn3BwXJG zSQ#QMvN?v{*0efyb7?Ss4LFlQ?L=7oCRGi3^M=6lfgazF7v#rD z%R-Bs-ybM{vd1pdEbdhqA$@}c&H~s9?}eSV1@a?RsQ_soX=vRO zh=4xD^N_Beb5nTY>rpwrW1%QnS((^vl;36E0aV)_Rivz9A69X%X ziB0Kd19W*OYiRu=*OPo&0?x@q$Ok98XrF;`G=TkrUN}iyu`5As-Oqx*e+`g6=4S!E z;j)~+L@_QK<{KJt&EtB}FzHbI%m-{@kNPNUJYB3K~7be5>v9074{lHPbFHQR2$zO0lu)xK-L{IhT0qxwP7V%@)@G( zZ~))5o9DkdfAzr_8<%$*yQ1sv)rfxz;?Bb1ZJJm-v1sCA9=dBp=Ok+?s5}*tVnbDXNl>*NwHN;VK?B0rAkDmJE@#L0mCx18?*GapEaLIsI4QoX#sS+5NY=vqZKh zs+jk*4PsSW6x_EOcu&V!mci1$bSsLfC!QblppDeM6U}~w{19yo#%T6D?$6>lfdj~a zntCINHBEio)~W4lC!Fl7*_z&3*$Z66E`{*1J&8Zpb*_}}vsFpD3eyd@>(|6h zJlR)K39V&8cK#@E4_mjYVNwT-I$8Rl$YsjpTDUD6CTna@7e9-+<*>S+Et zuw1iJRidu+n7Q)J*EW|wellgdFUods)74Gt&982r{MaLp9enKSW9rAtw|#5XLxX+( zU}qV3k1Ag|{W7HB-zmNBH1kWwT}YdM;$|Z3ecDsZz%q&Z!b&4rHZZA4Rsbr@<30az zrm}bF@gs?0yuHshv9))@TXANLvfc5pMx7ET+~)JjEz#!peS(;Fz&cqRx9l7`5Wee9t$S473hKHJt* z*9TUmCm>67eOysmQg4(x>36JiDSo3}2T3oYuVR|~Jckj>wowWkK|g$Us5?(U$}tgq ziGV(>lbig=#*eKhyOq;YT@rPE4vqL`zeFwVF5pOZ#d}PC)^M_K^EAQ5;ruVtIOpVz zo$l8+9;;xw8R!eFinOH~`!=f`&~@j12SpHW@0_Gs+y6JV#y zyCiwZR!#H4?x>)>PRPnY&oQMDV{{=7)5v&TbxK{b*VnG+#HUWGpw)M-MCn+o}vt0?DpZTWbeCAui2_|r47%*i_lD?FDP7fdQ_h0ns z=P9&POd3=4(@pg$>)5BfZzC1AVKrX!i|ZWexWgK zy8l95is_K!qOGch_3hgT9=IVvZ7lr8VP75($r{U3;7c~1bv?~swYcCbH%rISN@-F0 zML275C{F?F5i%>5Q?fH+=O@;Nq@6n(9Q8(RYaFyLjD^IB2 zm}#dhblEVsl|o8F@ktPuJZS63R7qCwcc6VVvS&u9duaw_Ob^cK$ex+TP&s&_*Ws~a z6zu?BI``ih2J;Q(v`7hX2b2f9xj3={giqiQFEt>Ha-*T)TY&JM$6AHiQ1wv$vkoyyuD;dYd);zJb;zUR68-#4hX%u#Rr;U$s;{%fNVu@ z`QoKQ-@Z+%!gp~s&!phqi|`~)ZCBK`>%`Av}b?Ku!Rw;Ivb| z4}SVOoJxPkmx_|mSIUvElo@ZJodnw`=s@c|rchxH>zT)Swz7mt`^8VgCN2~UBO!x? z)}MGa;cM`IUV$Y2V_Skf>LhIOhm$%_gCnnTjYC?t{Bu2RaW5HDoN-uZrv>7m*ZN+M zf@isC4X}AD6bUoOfVIwoVNMm24&|F@6!1D<+ep~GJ#IGjf{Rw^eBg&W^0ox|qkgmy z=NQzJ+@-+IZN-{V8iV((o6stl=k?k)z%qF(=`vE?#(18HR)QCV=b%yo&>|u;J_-Y7 zdf&bcKy~`5j)Lt4;W4+v8lj#Eu+JCzQu4T5Mbndds$_}eG2D((Dm>=4UX4*=P|-O?fa|#bw26R zUObJT{-uo>41?W9{aM(|aY?2H%bLqecX_t39QZL1$Mami# z*%y3@8CM)zou_>Y$iJR)k+fV^dK$c+EAWK4sbgMqDE5Css>R}RP&RFdyC*DL(Vd{U z>svi}J184x9JwqqP#>Yg;XcMRr(s zLRhDZr6(X3E)1Fof)?evBJXqv7ne1^jou`8LSvz{x$bh^9^({zcVm#tS4@$^p2_VB zau0rs_64e~br)gR{OHj0?ohce*BwU5FV}IJg+TrlB~Z16vL`H z%SWq_RW!1WQZC?~JXmC3WiBrP5>cA|O!2M9fTj^+Nw7SG+EoB6f2H{!@vbe++5Go+ z512V%4Y2utkL3n<0Uv@#@X?^bP9p_z1H#Y7SgyEZEN=HA@Eb#D88maGSWda;FC^(> zGB__E;>$N&WI3NK^#fyql|z!5KN|DBBe|Gmo`YO4?Q|D%k&|dqS_lp0L%+eEXU@kP z3*~&|dCtf;xxlNs20Q};=9|&@CNG>?Y*W9Fu^KYeI9>6(zU^rxi0K*R!VfzyJe@uo zwhZ=7ah8vRzZcyJBQ%`b`}4PG?3QGVhD$28sSpo(4vPbt1rGMpyMTAzU^Pnlj6dc- zjjlZUYlu$F^Yb&{*IWKJG6u5mWrp}4WCmI*#p9ZB%)qL7gEZd81=l1PS0#)Y!cBV} zBFR54xv`rQm=?>;<~nB zC;Wmj!UY)~PrL}iG=iJQ~qf8Rd*1cg&?HH(=Z7oaAPo84p z{nF_#K__#EBgW77$NTwSPB(F2NB<$mc&FVMabaU&CgvK>^U4r7D#UYpc53o*$LH=6 zG4%ZTA+?uH3tHFiuz`AQNyk7tn*#`bqU5|*j6n&~1BdID*pJq|YE*RGtjn~527XBl z=Sdm@->BtK(jiATYQwu&4iCv=cC(!=b#>y*C&!6IL7QWsZpWFL`A51KSI}C$V~1l- zYgp0_M+J`OQ0_6}Lh%iw_IzgYW62q&9gYGkYG7cjpYNj@*g0_AfwUwU&gY=xys>Z| zc6prV%fVc+7`(24_v2w-jef)i;7wy%>*L87H|uJ|Z1I8{XpRn-dnr6~(l_r9W{HZf zaIV1mrTaOfynURXM-9=tfcKHWXYMSI5HWFJmw!bte8Bt5KoaUK%lT2agxMU2kyEWm zwgp`M)TD^+z-;cwamRzErDBB0%_1CoiI4ja;vIWk2TZfA;VA8j2|MRYVQayrzV6II ztRK0Pe2_8uxW%{J1=b$7qmM0Cw%6L0vU9e*4rom3g^i^Xw$&^(GR?Uf&SI<)YKbpL zE7Ny(@H=-n_CgEfl`dW=Xf^Jz)ir>U4M`2yJ7`;p3-cbdLK_?nLDUQ4=FvCX>q1`@ zv>JBMm-J0CzUfS|Ig~90P4tZf6c`vz+bI=m9Yl?^VO6bGENI!(bZ&=qCz}KdnV(ab z1;H@1&klH_gJDPus-WplNar~6cGUP9Qm8}T8XR@VS#2GDAwQOg@hJI{iX#4vY=&HH= zZyZ3gH1=GsYIy~5QJjZxoWeogt)$Q;f-f3R#gN7t-n_gzwBM;(KxqR7uDY$q zhBC8Ox*x@MY{#{)Y22b5Xl`Vl8M|<7(G2x~_xzv=X)VKgI>iFMh&?WdtP5Lti*j+O zln(?1NUtDG8!2P&Ws(R~!Ok?`t?cJut-`5@r%UkN{hi@G=c?J}4~b`PTvH0D~vHJwV)6 z#GXze=RPMN!sW0SlDMu0_ptZRS2)QM61?b(K}_3c**gPn@^TD&MaZq?!F+cEd(`88 zrTXKr_|}}N%qmDCXQY@ub5mMC@$zitg)XBYbh%sxrjS}5(Q(mYH zkh7z_?Y^*L3F?dMDukb`i!pnA8PLn;g&Leg*Ie*g85}c0-(39Pe1l%`(>LfVcYH(p z!e>u#o@qekVIE7Z1G*F>)g>9!u=n=?;RyBaxFLE5&rHFm&j;94<|(Ot$rlBVhg`>Q zZK)+oX$2hGujlXMm-ERinXlqs!hQ=_4nr?P_f@GnQ00UcKRtPLr~w$-A3BG<1O7j| z|7{_jF40sMg3qU^+J}-+4!7eRx~?6$o;31&5}wmFJ)fk_huqNpVhwxeg{y{XQLY+bbTiMs8s__Q=2H`r>QEeJD0$^!(^-;oL*yiyWSjOANHpDxBIx=p;SKVzj0$zb%ai6&8t2k-cGSAlu&a&yfP`k-Q?RMJzKf(u6gJYpU3>i<`_t+ zY0VOD`k@`x&d}rjol$0b?Tg>KX%3GIS{pBx*4=Usd+P>xSgZM5$8NNsl?{6j z2k+-Qak)|k{DYK!~)hwao-B}b_p{uTNZTYJObq+S!}v4CHN7O4u)n%n#N zn-Tbpd5iifAqwmtwx!YaFt9nguT#6_p!3sZ7hpxd@J-}RrEcbQS}_shf7=k%)!g1M zk4ug!kQSx%DrDF|fa<3n+b*Bm=RE%PjlJmE$gyw)Ip9KR2FhtLcb?n6!`IuI%EvE%yq;L~T0(_QWLfS2avU_WcXE{1~*QPOQnc8M`lU zy3SyUENP%v)*qMd-@o9Wt`nN#74)8mkF$5muT$HiztQnKbQfA1!t(9!^HH#LZ9N98 zt|%<9^vo~pxV+=n*z-um`hIM6r)XOZ@S+-ad5pm@56R=Z$Cpj)&imajaFM) zqNqQMHOX1}#@Cd1U!*7xhCgb_7KJ~vwC`%J*1dpzK%#i0=33oT_IdVM&9KuRnb)vd z!@Nd4`F8=Uodf3YKE%$l4kP9y@pLOoqj!~%R)*%b>!_J;+>{peLz0_wMg86;@a*Xs z)|b!`9=R4JB@FqF3+DSh%v5=hMo7?bwA}NG|y_`Lm(|U zvTG_LnmJXETMaES8e@EvKgdyJR}O-!as!AI6N;JV+EAnQ>m7NfTvMavTHRjkB)+cU zoO83&+cgyp&7m(qZDEvR)S{&r)m^TrVBNomQoRdgCq)URLC6)~xM*Y^8nhwRVaUeM zLQg;7jlzC?wCvO_sE(?dShrFtK^+FXOZ(?)$9G(v!aR2G(B4BhMhm?)UB<4nUS^ zG;$f`8@{$N;1`wGs5h~C38a-e$h(294@zX9e2@Cr^CM6Co`pm<9qW;DA8E{l@}mS6 z7f{F56ziH{`YIh3q}PF#9q@jQUk>{&;`V)eIuzd9WQGN$TomA)gS5>(Eo4#Yb4^@y zvihkryQ=f5qN>BvqfA1luA1azsiw8n>AGasKI83!Mxp=Im;4RPtCo zuSpV*BvSu*WT47ECV$+(_TEE|2uK~S4}a>G>aMvmgLF+A&;nJK#-MjW*H-tj>P=On zX}H`(+j~anTL2WZ7%>*BdJC`0n(xw-{JL&z^=r^RTUf1{BTSitxlH2Wbzb8s7>2}XIHg@gLW@{u!L(|#dE zoNm5cz0+vJE;kj}DGjjfdBAn7`lJ!wWYhnlQ@CBg!AhLH3aq?HpU$jn)|sy~lNREl z;V$>uEdkwar}TC~7@G{+=zBY|cw^v-I|(C7D5umnAAyG4`>t^aV?mf!7n{=JjQ7lyz3nP7 zHHDu1tzU-S2=qVTlOQNXLmMGpU#RU+8ISyPG&9{%cIpqCnkFy&dgs!&sV8JLX9Vkb zChB-bXQLGu+qd?>zju%G;M$A67-e!2Nx_2_iKTlTVQ&L*_%_;*e;l7+wmg*stI?7n zVZuINwlel|qxIFb4M~lwIB0lG(Hn0`g~n&GR>a-Cdg4LS2y?Dk2J5+`;J9?oNBo!u zhZN&mz*~nM!fn?d(Qm*1B-C%eKT9^0ixLM<~`+U=| zW+jg&z?E!%b#0@So;2K%_XdYNn92kFD%i!1?o11y*~A#7M`;mlBtq0SU-=;lD3aUnjLZv zsQfo~+`?Ve+kI2@lJ0C_40@%cdzujHmpK?oU-W64i8FLr-ht5V?ui<;7%Ct7jZbw4 zhh@C#!{C0D@-qW`ns~9SIS%`8i=fh}U8U8-kg*1IsV?G(WDY zxeiLKwH_x|KzFppmjm0JYD6>mjawmJa}$lwR|=aJ?(^wwr@Oi6-vVD@0#*(GTtjQJ zICv)zumt|P2JiJeMjL7m6oUgJIFKr8LMS&MUqw0eyNsNZQ$=)UHBZbIpzrvK8C+lI z!61Evi%b-*n@l<+$mHYKm+AIO{V8Gij{AYL8$aNR2 zol5Phr`p2guHTk4IOzRDm{FQs8#|M-9)5~>&f4_tLKgElZL#>>YunhY7l*u8kV6Bu zUHg1<^txulExr&QUxF=`o)Bupml*HM%R_CN59VX^%@tcC^!K(qM@##F?_b=Sta;9i ztY~L))|amJ7>k(a-)&car5E4DiWFlQe6$UDiwEC#M|F?EPKt6cYf#b=}3L+uZErw`F^!M-=K6MTCLX43ssdDlbP5V-)*o+pEw_G2D8~wj|i9 zxAy%bc3TfZ%JS)V(mZ)RS-p=3CgK>L*HC(-2RP(qgOUR*>n~2EiZY&a#=gBWm`bGD zP;}fk0X82`_eW|za;Kx!OAq&ZmHs(qX}v5=RrV9oZYYhH(?yR?3)d6!)uTsx8NKTvgW7Yf6Q)3ZJ8a!|? zkG7v_8lR;xCstG8ZhS7XB)Zu0)R6bv0bxSmcH&zPxiK>FuLeU*0GXV}p9+MHbzOVP@>CXlAv8XBe~F|! znj7+-f?jBAD~*1rBU>;hRfk(~UDddDf~kD%@5^5{et!PiQ(CO`UwktQzrTC4FxcO> z_C53_>h8w1oiy@Z^cA#y<@4-j|GM(+0~mROV{^{|hgm%9zcsu85}*n14SA0ba1+J^ zM_x*eM&D5WLZdIJP?dkRG=Zj>T^fN7w}7l za&DlM=%ZVE6W@%=-r76vP0DGQGYfk7N#;^Jl`%9DOFGA6_6l87kJ0PnL7{2Ni5kO= zIJEp;CsF;e0groh^g4zSers?4aUmEwB1q3D4XtE%V&>c0+k5=Q8>8be(VhONZqiT} zk-+qab~AWJe;d4W3?$nTs<&b9=VxWb@)FnwCJA3iW`D5Uxy1kZfcHaRzqgQfJ@CIq zeoV+0*0B4(|I;^dGg7mUthRitkdr?lGrW z(~BokkMX-@yDL3xURaTQk7Q3+aVfm&06Y@Rhh(horf=r2b8l-FTpx6RZQu%RqCCY80Rg1nYg4GBLZYT zjXMfG2BEQr^!RA40W`S^;tee+!5u-bQ}RV=~X<$(_{>k#j7g1Bo(vh1Z3a_Dl$ zi(@WDRFpRx(wJwwUu)5psgS4HWQV8!u+yMfTgEhD^(u@MnfkAMF9ID+kLxUq8eF&r z^A%Ag+@1kC{Q;h!BAhElHKd!g5(c&~MxaJpSi?$FSbZMskAaVjaUU_~VjR_Q_ekmq zkEB$eRG%+O)u_wl#Tei28IUxzHFwBNttwbfm8z0}?XL@7>t7O*p79#4OP-JpR*GUAmq2!&j}q@MCQ z86%@sDT8~Guh9Pr;I$?0jL;y5Zx6YkfDf&(hC-Biy<6tzbHOVY4`WQ^5Obm!J_*|N zpqYMFSeDSibRRgSd;W}Yunp8mMC`qfvHC1A#w~>{?^(TprzPtS`untz-km2k$eiV?8pd+$HHw48KOUQL2WdV@B=g`+S9ZwUy;T z152}4Hua*UyO5s=8-un5oL=SBSg!}e3LZFlg&qI#q(-Z{BC<8(=Jm%|M!oTU$OL~N zo?}>2{(bY4Ffu4Qp-BQQu22jDd^&{s05|=d`)b096g|Avz&PKu&o^IL>nl|9d4GcL z2_)?!U)%tflnZMQwe3PG5!YSF!v5vy6YDeg!)iCOfqCAxrMH)7&UA*i6L!@(+j9Kw zu}Qj(((OK@a(d_LOwL)6dE1p?O+u+{(R{aro8pYM0-HBWxI9&})VLj`1{U4B;hMRf zoAC8(Hbr}7W}34q^NLGtHF{LM+9Gs5mYLwJ&OGm`R&V#sR{@Le-Lg*LTBasi;;cvs zt5c(t)6{oT%ws(UcodIyeCmc~Nn4UNC6ul-)xsfVp)&>V2b{5WU-^pOt;~#URcOLB zEDiZkuCcymVN+jiO|zy!B9>+eZ)Q_PptCsqJ>7yoCcEC4;v3T`^>IJU>`>?;VBL3F zuDGPBSOpE`FI)8*yqP2I4oo*BtI9t0G23j|ln@#?1LrIjW z)-)@;AnH;rQL>0jpQ1<3^Qe$=608+99+jZ6C^aYCW?50|UdNB_aIx7f72kCyS*c`Y z6=PFVEmS(#fH@OErBKNdF&1dbq+$!g5rxKDS6LZ&Fw8R@nB0bBi>2JE!RSMjKjzj{ zWc^g*Z=#ho$m1?{T7`!FXwM1a>u3=rKfQk$79`iK!U1Zpw?6Lz`U2W;Sf4uv{X#v` zH-a4mKb$APDYJA}lpcAs!ikQo>TK~a%ni`sbPn^)x+dWPd6GPJJPJH66%eT)+FmnV9rZgmnNt!5)1bK;tFfH z{Z->YN1}Ck!a?YfsH~i6c|xr*(ei~$XOX$`#j7-;5d5z*_T!v z4!rCan^lWvL))6#8Tm^nuw(|We(5Vr(YPo)JzwX$=GItOCXc@e`9z1tl48oRNIJ`b zB@)>hVJQuUS>cm(M=(vQ$|Gm*C4J&dPHJ58p<6AkwtnJ%KP4U5mIsa3oM}lEUp6q8 zzHk98B$!`)Fwb(D^Tf2~80>8c^XA1?H8>;YKnC__lw-Z`AZ%LGf^*n&umNS-Th1KJ zYVcPCd|#T`rU$-rPZ!uRH zm#(`;uBk2)P?u+0BbK)%R4piNE@@_&z&z2W&>WOQBOq`>n~!%ZA|L%u^6$(e^L^oy zbbj$2_8VBU5RXOivP7%{hKIrPv~4GRd=_;$25N7W*x!S`J~zPks0QTT=M4*P3W|M( z#W%+;(nOy24|^vLJUuwZKfbQ;rlL^pkL(88XGd3p98xBm=bG&W?0GtE{9K)BB{1anIVozR;iP6#j*^ZKiGEooDpIQNhWx=o%4mqBqL^xpM6l6kk4{cyUynEjKW9LtI@nb5wB6+SL zPCVqcU`3N4KJR`+Y+7aJRf1!IWcyHOyRH6HMtIJH{ z18iZ%x-APT*|Mqg%dM5F$8(rI`=0Easku`h$;r*lpP4gVwJ9fGufntJ9Hw!dz4=hJ zX6%R%CKMgxg#PsmS$0|0n^-Dz+3{F^>B#d9h1dbidRYWkJcDrFvhU9P|k)~rH zkfw8tlce*!G+o9xxwJ-5FlCs8V|+NGl}mZvK&M(dg-KwwqmV6;%B4c+@wVV&-pt@G z^8ZE(lwd_NvTlBK-M!&+f~PsFDpzm0ch08rjTKd!?+ss9 zSzfleqH=xq#x+&z%F5Sh)z;0Mt7c7`_QVrUWUoWTJW`omzJ6Nyy0WT`m8&0mykgB0 z*=3ums^=E3{#j05!3=fg?C?3$Mq-;YEfo2*P=d&8@gi~YL&*QK<;#M0cg2fL^OqxU zMa%AE7h%U$_`uSo^A{}(RvCh`(#nT7o7OyDQNCuDij`)pdrbBCnvI)~KNYUCM~fy@A*0093scbVsi)&V?a`dWPeQrLU{qR~eoB#W0_85-D*Wt$=2mK8liDpqp zqgg7Bmv9W>pg+x2y-vlf>lU?i+rTmY<>+`Rnh_sl4mInP*VnlIk*plnt7>NO7s zKVyn*fvr>*!9Ear#CmIiTel5(%Q!|J{f|3^+7Dx6@;*J5AN%Ny@4u9?i2rf9yqlrB z6!`y>0tJ{;1Ni$D{JN9>zyJ#ba#2*m6d|k^E*7Kxk345MpvlCn#qpTQT(IXJ_2EIb z+BS@zgc(57gR!!5^Sa8i)oV7Y{@diau42`+^&20qR%sv4&DLk@Ggb6tbH(~Ck8N6| z((1Ew@PBIV%)F_Ols#OqW_sC7{llR!k3F2L(r#SyXyxWLo2FH6tazjXGePD0hbta= ztZFqz-KjJ2$?8?B3d(0>Mup#3xq8jIS*p-%t_scOQQ^kQvW=^!7Mo_NFvm^LEy&kT zT}Jc#)W>r$PXGV#M`NiK^{Hgg{9&Dei6ez-DU4sS;Cw+6KW5aX%LZrhzkc@06Yn+0L4-#~)PMSHI_@4VTVL_;noXOt|7la@`v3arjf#O>!wsI% e@t;%NgvdfEuByOiQW-@o;NKCPFMo@-?0*5OV39lTn0$EXc6^wxM)w**5Ohc zFD=7GjVKj}S_sk?MO#3vnP6I@q!Y#Wt=9T>2E+!aHCEdZX!QgV=Hz<5pFK0t^i7}N z@A*F8|B}hGX78NKK4%@`|}dcef%}&_>XYL63oUgZ6`70=))m0i6JS2>KJ~ zGtfm)H%JAgq!3~PO$1E^%><3+kL$i*>P^G(r`UsNGKBv;)WPItB6G^lFEh#HRwBQ0 z+2-O*h&JyCy|zd220(#)mgit6Xns^ma5 zv88ZaO#$bwDJhwlXB3HC-aAbc#MUqUZX$c$l$)!rs2i)gUjLy*{K2HGjw2rC)NGM- z7{ru3m%=`@ZqmF`OKDH!xhDRispM&VXM4!Bi;=xeuD+-7E9ftgMB@>*gMV*5Uk1UX8V>#$88+ok}So^1dE5 zwnH6L__GQ8X)=UAu-+t4tP9=wnPEXP+G@mri^#P-0&v&kh~8#ALS%mrkyrN|uK6l@ z80b@^xf*v3<&=_=Azsl^{^$-=Z}V^`Qv`q6u9{esau4MjcRm*;@nbzv9;v^X7m0LY zvCeV-$xpu|axtGfZSAB&^3i$r&UMl>(FHWu^c0EKcy4CTQIg1gw~shTm=pZq)Rg|J zu0XY}LzqZpcMoxNMTo5S`6P!APiifg`1F@LvIj_i2lreFXW*C`dqE|R-pEJi84kZ; zDY-bN@aGcv(_{$$ZLGd#ag9{6)sxZgzM}Xw@pk`xw0MoAxwuV}R#Q>qEji%f&H&NY zn`*kEj8s9f1fp!1>!_~jjb`GEfYvofRbv}azp)5KB&HC@rHD@=4jH)oRZ(N728kR} zbhz5sY!J;3Hp~cmpRrYt)Yy+y0l5W|MobAZQ%MJzinmE{<`j3n6MT47qFDZ^ckZ#n z(iTFwb1IIivDU#q1?hjb@D#jzp!yZ*`w~;*saaZb#FKu80hcZ)dETQxli;5>6q}gf zuE!K`xiY5k=M(tTWC(wM&B-W{>w(Vp!7EXJ&BxLEYtBW#kqW4LJ8IdTZ-{?S4i`#- zr0EQ3-1&LosnXmBjyiI~ly4|kc*691Vf_0Be5c?)npWgr2Y$Jsqp{{}w7KRl(cjek zHEOgvz%jLh*GXGEwg`QKCj5~?j7(>MZJVj<2%>*+1@*sQs_^N1JxqiVz!Sm_Pgi7R z&>1Fm+T_Dwv>ep!(t*FB?+^kt3hfh?rb1c}sS?tJX*WX3Q;F|K zTi1xV_AY&g15$m0^14TJ>c#HBI!$-rCNjM%0$EPFpj+Z282(8*c+#uM0Y+q6f7oAU zs${KMK4V3iM4bKMOmE&qvk(1@qaXc=F`4t1rFf0ajLqWHR^~`#dViSl8I#wTlR0B6 z`GRrte`DNL~phq5o;|L!tc9WC(vE|3q;Ft)e5Tq3PcEHh=9Kglujm zHnNA=!|vhsq^6Oy8j-QHrKugIDMX&EU8)pRbG_Otb4nH<=g!~ixzwIs0dyLSC3>HJ zA|o*kStX1QeK2~1)UdX~I8!gN@v|ut^%57)Z3g~$DYvURa}k~v;xDqMQwmvmRm&-b zUpWrn`jr!d%kuR_ou^!_`l9}mxFY)Vs_oaZU7`2}f_)~ia@TbWT{yE8-_=k|4 z%*jG#GS?-fCv%FBn#}bJ`eg2ou7F>Y%oD^9T#4fuj@d+-fC2sd07hM&CAn8 zzRfd{J(D^kX3^Nn$|_fKfwOroupT07-hiHgzbcuq{IoVXJ7APK1CjFrf9T{5$2-|f zbBHL6^KeK|Sm*N>4GfXf-?-z#+Yi&19j%`c_){GV_|s$v|AKhE(7Gv)=Mr^DnoZ)< z;7l*tw+E?BF7#1ASSgu}oK)Elr=5Eg9*(%^EyWQ@MZT-ZBE6 z;74?@i!x;V=y-9)`2R2nsw&wPPMl318g0o4{N0&x{Au+L;g4Doo_{Tqybt;S^dabv zpa|%He_mRcNlqt^{|Ra968vA4NzNhv|3U{getZ8dn-cj0-fxfnyRwJg?cbdnI@Z1Y zU&|PN56#o-M)PL`{tFWL8}OsQ#eX!{z}Wt6Bk=bm@J}Cxzp+`f$X;9A!h20YzWlYz zB*571e%Rz5MIVmO>`*4rH*?;+AXmY~&+F+(ixl8IJvYuvAo)$+1LC3X!1cuXgqSIs z%5y5SEkwRU$;4R_-dmQDOi`wlC+Q@;oWS~LD2KfkR=BB(K&HXA_e3v|vlJ3aXsEnE zpF=_ESC?`9*tGD1rZ96lz84msd9l-| zy(We06m+_a+6i2zk@cMCZ}OaHZ!*q$)1yQ- z-&*hKi)dwzpB{X_DZdm?$$Jh**R7LV-y$I@6DXeodFY)aM6H*T7HLF5+9ggFGhi3Kq~>`o z(n-8c@v&8~T2C&T`sc+hyYrb@t9&Jj)u+ZjR}(UBw6eem{Gq>5{HY2&)c&bem%F%? zVG7<>>H>T(J9tW|TfkmbdLhGbLaBTEZAHKSi^wVE$*d(882*IvBAp2uD|dUwiH7iU%RFcHnfW${sFghfe8+pYg;$t5 z)#Bch#5UimE$8H#USdD|nB6zG^*i>?XokHf%GhHlE3lae_sJ}$t^D~yHbV7(rh|?I z>S_*lVji;=I)CUU{I0pp8u4&29rnZdRzc+C1-*x!+UCiK*hIc_KC?{W(-wkupbub* z4?RYNxvd#Oe>6=Pt=QAwH3EMzfqxdx4dLILtmCw4bVhcZ=sLqat|=xLOE{+V_m-1Q zOwrUcPk0L3bJ447dK(M}y9-%8Jej}}=aZ@xy%4rBgcSqk3Znf~(NIL!AE`Aa(cyN0izd3FF?SWLNRHsne< z?xpe|bIC4I=-Rw)mQ)~T@-KKa&`napX2^zdVIz{$&aLvxnh7+ozQu=+~D2 z*X1;gN4!pSltLmb(8~86C!wLbq%%aC3a$6|65G|W##HjbH*-eN)spiy-cS8yMo<>W z1Tuqspc>F>P+W(U&gsZ$@>@0bu`1&}#%r#nvb*A0BESd5{^5D1n5&mW)=uix*k4pl zBkT)(@CQPl4m)+pMPvGXt~^^`8CUd+o3 z=k(KiaQqR_OAoia(YYkk5q`7tyP1XI3Rn!Xq;g27F@=A50)Nvm{5i;WQi}S5E)=h= zJMn)(gdKPK`!n3~$}RLiPgfxO1X9L^??QSVK`y^g*TEFL7i9`Qi&EX}`!hPjbG+_L z%$gI5yO795(B^+Nh#poh?jy2OEe~ptzY6(lRU+T2YVqHczVFYNR#mu!$oeh$Ek!u; zpFOSk<*jP-Eu?mwA^}Koi}?9adxE!Rm_L%J||{DgUsW7M#`T zPA~R0NTlfLutfrgvKC*Zm#;V2h*g8DpYI1Jn)n7yz2=A;WxX{xbmr;)14@pIZzzF` z&>R_4?Y}aC|F~iJAA~ntj!TWb{7wCA@2`@Xw3wZ5cvTti(j2kVD;m{U!#7uK?APKf zJ*qh(;OzLuR~0kLczlpY&2Jw(B!UAtM{S<;R-#REXp_tHB(9rm%#*wewQ(uTg{ef| z+*R@#V{>15Vq!h7E1*4{zU%6fEp_rB-1x{{pwe5{+;q|H634+f5}k3bt7Lx`@hdf$88@%Dg`jh z&^*{UrtpVNmFoZFhv8q<)w}Ukg>|KOvJA#zhhJ5AAUS1_7u_wb$QzxyaF){$W)3s3 zw+P}-8jYft|_9R_aAoe(1L(^f=yq zvSWJ)UI&EtYAW}Js^o(uq`Sjkq6l;p$dPITz9u_%gtXrHIb3;4G0w50A8IS1JqXn` z=yk*nZE@B%UzdssB;h3-LZ))^uQN{Dd2m#%kL=qIi&j)KkR@u z;AB*-@YpDfdu)v3kvEJxp%^tOKnnltJE53wdd^3&Hb5VlJ(a_^Ybw?3;So|;1gU?QnuhPS>I`pH*L&6WlD%d2 zxZl~&)eMXhA=Ac||L@`i{^nu$!+XmPFPmac)^QqVVYt8xgcee*j}-NVan>49c)Ly3 zu^w5&zKuN9{rEylQO|kW)Fysux)KM+5pGE4v0+`D}lBh0)s~ zY*FkaPpayAaKo{_OP85>$2tR>bth9Rm-~pFo~!ri>?VxnNXSQJcn9!Ljx!cP#>|Ia zV(h@tay6D4LYoGEjQ0|&u{qbL#=6uT@3=)(U1Zh?B_ME}Z6#dy{N>;Z{9kSdXV@9r zDqjQmCQt%Ba1?(=jQ=rTN9BL+F#ON@(!|M5i}>FmPM*wKMYN^`YXUiZ-VxP6ipH;&Rnr;t_lt&ML13@l+Gv43o)cmOBJg3#AqoDVoRR6Z z)Shf%YtiZ!ymQ$NNfIbzYgvpM-d1W0Q-Iw2I_*at)~yOLG1hmKKvtHIY8hO)zl_o? zRA-|+NM21dfEX_;(RaNK??78}RhMrApM-o zkMDRYu9rc^1IOi-nnuV0NC9qRi{8t|`x?k>4egOm;*Lb`GsG2;{kV_vL@Fh(znLkZ z{TFj_tHvOTmRCG{L<3nxdn|veD|dy$=c%!fdMQfpi+etgVg?u?|Cc84&mV^W|DRn? zi#DT&#g}^3a89zg;kudI&H)<|pI0R7GgnoBK4%eZcL z$w`IJftEM!q@qV!fYgB0fz*g}I?^1ZE~I9pvytW_bt4s!mLe@cT8`9#bP>|&NUM>$ zkgh;F8>tWJT%_xe&POUCbtAnOX(_nFU#P~OhBPSimQ`ZhIEp_b@L!g|f8sFw)!0wb zhDC255Hq7@9)q2(q@vWDD&N*rt2G9$Xu z(0!2Q(Af*FMeD9}m2~;JcaYLH7P@@jQwcrOU^}Usboy%O3$#TJ(=u(~g;{o3WZpqK z)oT%PE{9C(3llnG0CEXkQ;ij>IAbG4+&ReiS;T2SoBwZ0%SI1EvWJy#&!$hbWsN9# z6vIEV|6iWKf6_4ghiWzwP4lLqJz&%wZ`V)WOx)#LI6`FN{vw08SF*(DewK~v;Z$}~ z9h~~l4cYqP$5+e1Cy$xNhgfT_KRal|$o-nPsGQgdneT7TUX;Dqv;=d_vmXj#7Ww9P z6&|Dq89+u*4#*73znPVzy&72^5Q4n?UOy2u@(HE5mYv5s|I+S<{|V!sBQE;^EtlF2 z&h^v<^Q~FsjOUZ8(v zJJ#tQPy~0YVhf}lU=DwBKIMKQKispTWiHyZYCWW|fdf8EU|(R4*W%CaV5U!q%=EsQ zTU6TMd&y=AsJ4cHp@Cj?;yic%?W-GBJH7ePKYpmP)OTS4551F{o*7{p3cOi$xq+p1 zd!z;*z4oZ>mOw+`_SKWemi~WJ0)Jr`{){aWWv7or9p#~pUYeE~A+`pe3f-O7F8cBF zoNd+W3(-XFq1JqtqMGR$u+j-VZdhh-iI43)y#_A_4tfV`3A1~KXz~QSJ1m2u-Y@-i*r3@_fG) zZTVLU`u&Bl75j;mT5X8^Z+%)uixt{7krB1!to$1M_}2IQB|3!77Vz4=&ylKA0y zGFy$64^sZ2V?ioQbj{3RtQ1$M1bV4R7v5WUu=6MvpVf+U3nTPKu`*D$_8i79$}Fd| zK6}d;d5c1Oio1Ho6#m~$;BOm-KO^V#(3)7?!^p7iiF1*^wTJIuE!BkfM$s|F(XjRt$(mHz6p)Yw+9s#&vof6bxQw1;5497goOR?Z}HGbfs*0M-Pol+=QC zOo~>@{u{Ra!YWJ;xZnTnCsqe+KL>pMylUE&t&m)S-B!!)k^CqS;ghzTKuh(7Lh``v@M7?bLwF0HzYCJdi zCG3eO;#y#>!pz~X;yVp|G|~}0B(06hm8%Dd;~!yGu2IfM=^bMV|63CH7YxIH9DFf4 z2dM<`DH>?UpY(o$KKvRST>%db8np#+8{UK;9&n-9=$qloZKE8LB{H-4qFm@xOcvK^ z;4ouXPUM~eR=&NTmN!??pkFA7=Vt+1eH`0oz!zsAhv55#r~N=>@O_WU;#*QVeBY@i zwDoPriR3T47oJ1k2mJtaA7}$;BWM%oe$bCV4}u;BZ3aCGdJ41)^ctuU6a+PannCM8 zcYzEJQ`}0NLtUXp?PtXJe^mniLj2+(|G#W}QnGc~+39J7g;fWURmy057JgbzNGoWN z(}L(KYDWHJ$Owt97db2S&f=^r;`%VMtH+EHmeI|~p^&kaa~Kg5C`S~+yrVEu6U_FS z>uAKEy`D*76YhIa4JWTY9HJw{3iQK_{DPVSi^6jrLxiz$RvpG|nw|?$27QbgJEAgp zQdiX2>cN=v;6B*?K?;0@57qtLJaNW2G5ya|r9m^>$ryAB*XH*(=4<4qdS9qxXBCyc z5KvkPu9urD7f-LPZzR**@{U0H5~GdA0~w5sTJZ71M&N&I0)N`+4dI{OFM5l8X4Hn^ z@L){a@33dod!UIkQ+FyZzxG$exhZTFZ(L-wu{eLF59yJPi5hunFL8V?e0}+KBJWdU zS3}}5@{Q`X-fKm8{Ts~EEzpZ&b}FgxPS7zdd`l*)jLj&fcWN0m_7ind zxkldDJF()OrW8ny`&FZDrl>`3y=pj`Sz*TPU=)&#kuML9Tg2O}wN%#pJ$~fEAY&D3 z)!3P_HU7UXf&bKD_|y9Ne2}p_{ia5_Rcrq(bnESCFSN~cK;ADxY6Lw8ng9xbX#2Y# z`k))_QKmYc7;OA0+Uy;Qz0T^yYTPZJ_AI0a0=jkvX((XC_fvtHctQ?xrvnz}tznb% zN@S~-d!^w4v$U^nr(zRyyUtF06N1X{l5wa{r~D)!>;94yyI09OXLAx^d77 zZ;`MHndaBWD`ZQ>pZXu^3q0t}d zI~2VMwfAD+X6NGYGUs!V?|Sp8ME~I{SaXuK9~@@CtRaV2v;yVeBbK)tDvTep3hM;kjuoYOH>c_Ad57b@b2!#JRa^@oQIm zO;&TA8vAG^{>6~5Pv;ebmJ9N#i;#^kpKUYz#nVv zzLEcPUSpl+5CggEc2#w~4PUTQ*Cem;2(7Py1rw zgko__ULTkirSgQz7zc><@q3U`8B~fql|QARpMhM>C6y)R#BTDJR6f&af&)d})wdOJMtpmhrura8g!5%&E<6YCeY&~78EA)x&=~epUIvw8idZJznT>h#L7-Me|JI;#U3^QS-en;H0yy@*8apu-m>mAc*4{U9HrMl#f4S{J;Sv%f%mNigzMaW3hhX z*b`>t)PbkaPf?y&3Y~U0Qp!J+S7^VaCuXwHmr0yBM|tbVIJO=1QxN4XV{>MlLo%S7 zjw$?6C)EGLISl`VZmx^#<{x9M#>juhe2cMFzsOcgih9C2%5EZ~Fc`Z$xXwGNmYq=)=4ModnHiA? z|FRLi9kGrv{eN`=|LMceua}cD)pg0bUNj8?`@Zk~v}ww{`NYrSxP|F1*Ny;d|1Oe4WCy zbvEtB%HKQ-Uu@sN*!lXklD6LdAb)tjUISTj8f82lX2BP8`dRSBhN$r1HXR$D1q|>T#P3oE?}uP68K*=41aGl#gP}8?6p2a#ge#G{-AGyH?PhfxGL(B7+FG%8{^o>eb;}Zy8NMEoVtHY2**~HwOE6RH z{4$c_y%l~Efs5MoU!gXA z0V4ojfi0%)RVBlv_nxCIr%<;aHvVc-Ph%^qv4e_3OhGSALT$L$(11Fm_s8e$Qj>S4 zcvngMo(4qz(bm(sJk6fOY#zM(l5+#Y@1@$O!39L)Pfg4Y8HUd|FSAG~-diMo_r7?E zn%yK>-l~5okIn~u^FGNrih7B2EG zX7*rg(%?%Txt+j)+X5>gSFXk;svP=p5-I?ntX_f! z!S3dsRbxc$2)^DOxFf5bNzD7r!8{BiM?E4tn!r#Ig zJaKZf3A4f`uc?9*O6Gq1L!;SNepS*r8rUyUqOm>ygoW_N9C!pxkR!p z%KU)(cGzmGbi7Gl${75cQw|U3ETI zMI0-`k4ocZPIGf)M!bJr5&2X(9++NLDzz)bb-nZ=v6t3+-WJ~y^=B}nU;G}98VVg^ zTv9wW7<*RvRM~Z~I!LcRs}N#?7Dwa{2Recp@nV!>j5B_VlsjCyLw?vqVxK9_Egg*6 z74mekh&7^CdcPVQ7&wEn@=MR*`+bGD=^VjeYz?Bxo`?*@zEazw8HK-%8Vip{^@VRn zQwrYz=EG$S0bDQO^-zkOBPDS zwXc#@x$dIW_AOFMd68(w%JRzo;@XL&bNm9lN>U1_4;U?%mQTy33s>CyB zd#AdIHm+X``4kPpBAL(t%WSc`!&0Z{Dph0F!F2Sph~T}PnaaR=#BBWVJa?@cvkwqQ zX9PXSa;yUV8TH=bf2PLFIQsXD;{OD`ATnYy0u%a9 ztJRdfyMp@t`{V0=Em9gJhB59flqUuB7^z|ein3s{y3n5<_w-3?FqL*jX~|!qEZR2> zl{F7#9Y$Hll4Vid(v&P~OyOUXz<>5I{JHvoo`X-rllj*X&| ze2$$1_D}XB){pRY68pm#^Bo1f3i=g@&fc#9A^t~MruZ~0OxXKF?hhbXoZJ)eV%$gM z?f|u5aRF*)PIc9KdCU?S4daK+60KcGXNl;XVtQvP;}Yr2B77QDYBhF`E&q?Z6Zq3b z&qMRSkwDQz_6VIBZA;e3dw~O}$(PqNV!kc?@IdTg#7mg%%6Pg&=DD57F~52lbFvvO ztGM9OtmT}|1?}Bf`r-NP(pNEx8;GsL^;(x5tAa}q+s!KG0QI_6`onZ)7q;Ys>754s zKx`?Z4CJI}I`y3XX!?=Eb*WDqp8oK>{!z>i?^0tAC*NgjVCXHbOTL9&Hlti~{7t@n zkD34GJ%sps&?hF|#e{dM6cg_;5XyK(Wjofeq z)Yy08wO{5~1F_{H>E$(VNnG&anna`lLCm54+>d1x^hA%shVO{$a~ko{M*lH3?p@O0afV@& zsx3J-9-a#N)X)6FdTTE$r)22t%oN}H=hw4`iFK|2Rq&wA{|o;>Yos;_rG6u{)(2uMlQmAQJ*lpLeQx5J zj|}S2PyD-Q@_6RlVAv&XR=`6QtZ zPnx5~s=s;Cn8N@23H;{{!=Iu%ge~Hxignmk%^kchxb^O$U|L<4^Oi8zZgiG}_27nT zrzgDB*%Nu<0T#X+sgH9z8a$UGPdvn9UCvi$4j@_#^{z%d7*`tV-|X_@+u~xUFr7IZ zopEIj>*_Jj;2VgY>}8HVzeA{Fp8ZhKht-&NkQ3(~`}}Si$<=*nz{DRBU<;&iX$GJ< zwuL{xn>bq$NA|7g6R*k~~*AUX#wf4V7Q|zBdIotcuA-#{r z>v+AHhZPtOQatAb$OR7wrX!pj$+88UcQIRIH0nE)>*R|wi>gI?c+); z58PhEz!Jn22tY#sS6xO2& zG?pwaS81MF@kFgbbOy;3*6~ySn8JU30{{8L@W&pGj_bopYkIA%(rjh=Gz(19<5<%f zyvW^X^5wO!tsU=U=B@SLlYg$sJe8l4;+)W@SzQ-;sWXMMmJ-44r}33^eHyyv|2)6O zvcAFBu==cTEoPBVg%9C73>*DAp#Fz&mgDzfYpvPN^)UZX|ZI=r0?(W=!F~A%XvQhT(5&{)5?2@}ds$dh1PM zD!ewSEx@DF^;kw||2o9zO%t&LoJdz^T!Y!XL`>F{%H_4Y(az2_?Zey=v1irp^GptL z{^~fsh$A23U1-5&K477rM%N9nVMtr~)xM7~*O!P3vJqnmQUKp>l7W6(=f>W{eHe!j z#ClYB1-1SZFUF9DG zlK3xwJ3Lp1|MkeQ|3)zbjOhQd&kFVbx?vdp!)oGR>g@maI5Y1=gxcNXaRCath{2m) zjy0pRjEE8!5SRj>R@|nPgY?CvKI+${^=|jU&ja~GD)w=JZJ%O@9YEa=KSzY`gXk*p z!ip(gQuwywUi!9D3MvOJ0ud0ul=^Z!W!Bv`8;_vfE#@ zj4QP~{Fj-}v@W~I@a zRhw7)ghzwu=;xYP?C3!~cCu^Jyd}^BQom_)@pbiEip4)hDNX@kM6r4RR15NhD28`J z&d`|6zo`6Wg{d~B_7{uxc^+w;A0A%z3l-V5FL*O0=ow_5*)DHJ|B>diOXI}x*m=s- z;tAS)+Kyc84x4d?MLxxn>tm+aCAR)k<+eSDFT zGuI|>_Fz?-^^?^TMaH&~&Mg$qz@}UK0hnXTF!ajVd<&3nzH@W69-yJo-^X;$Mwz>xP8UjD_ zEOCLaHA-xDDN7{IyCRi9R@Y&Z>cw3mjq3W{2(fdU8ZcgKP#B@X^A6$?*d<#F+t7eL zfXR#nVd8uUvA)T!n-(qeex&esnxz$0b1d^}3+2rVxjFk=sGNCMDFyMxOK7y3S%_wf zeL@3P3*EaSpvLYUd<^N4h0{ajrS9BO3qF3>2>kC);J;uP{(`*O{jTEHpf2a^&!g=y zkjE9%quV^GXXsI!g~egL*O3wL~Vb^dIW_9!0Z?R zKiE4uvmy=JX#W7$fcG&{kAe4)W(6~)d8KJSW}jVZK-@pZ%Ix+=sl1|cYfRz)qXhmm z=>1UpAClozcHc|u19F}Ay;P1&J8LmP+RybnZE5Y@*z5Tz+# z-KON25C^g|;CZ3@J{w}cYPKm^CY={?zY1w&AzB`N-ZyoRXVCsb=iOiH4bH;Ka!xWo zEVSIRY1L|f8TN@!&gIkl;Ga@5sp_p-4I+5#5)U2QdyJoU^_h~IhmMszjL7s(szn+? zkBiSIHA!7hLX&h3goCgQ`HkL%K17U~({`TU+jgG4hR#kr1if-h;a{7;zhoHxRIeV_ zQ_zy~O&^clQ)tWH#ut1Y)fL3xN7aq7b6m#;Z&1F_R_>|2KIjU1YHW!1!)~J9+qv+} zp!y%Z&YSOQK1X;lTjt3Aru2wzagonbs`FZWSWVzhP<}w?%?-F(b@1nS5RC_-ffC|;f(MeNP1H(9iu#oGv}J9R+AV@>{sF|9~O=&{2xf*Upfr`g7Bw`?;w1w zTvZp|OW`i2uqDb||1W~i1+%=4I>dkz^?k%O6FchM)km-LV$A(F4e<_r7UBV6{U>W=j+S0x z2<*eg{@96R6d-@|*O!ftZuqsK@@a{&Ki5+4L%g%a=yOK#XGH)1U;=;2^xw#T<1}{` zB54PzPbu4tOMQtrJ=+D|uWecLYkw=}?~TUe<)hvAYt>d`vmU!HtO{1Qpgy;3__d}I z5q^EQNh^GNeGKlvC@wT~eNoU<$CTC~1}C++(DoLK-ufnX^L6fTTIGJ{GG|)u-gbd2 z&TCr5uwCl1LEU_nB*ML)_m9oA^Gm!r(*C-%Gmo)i5q1>xi|) zyn5g2Q4Ie`{qLa!{^BtFjUt_K?MK_~jT#WepVq6~obTNy?K^gR%_Qkw3oq+x%aLn!hcAo6muK2?2HYiq%fnDMXd1D4rUfjpYePVF$({T zRs@;razv&uqnGc>xnRir#YINf6;2NV+x2oQkLT0p!d_RCjh*K3to1Y=In&1>UN<5S z0%v;O)!Y_rK@_L6Qd5w*{;aQo;ykOtx2h(AF}s5IF|$6x9eN*q`YOELx4({rXc;%Y zZm7^pyAZWDUwSy0Ryn5de>j1E*)aUaNsyS;iP^t2pUKC+Y&x$ac9Cy%9XFTJZ-3cy zsJDZlS3rM8e2Rzp+_csa=#U*`@GpYV1pR0@JvTcHjvgTGZo(I^pL@Du0}L(isV({eU9k6$!?@q{H5!vlThV>YQFI87?X zm@@MuV`GjajvHIhf4P_rM2{os-nJ$h+4^sYY?>!653+l-m8>;e;`U(X+Q=Wx2A^YB z$x-|nf&Whu_*V?WA2BjphuX~EWV@klov!Jia+l^gczvg~(3K$c2njtMKTmsTe;LhF zTi+v%#8DNVRy7Z+GIU|qi8fZK$I5_&m7rizL1p2R!o{B|2M>Z8v#`&D-N)MJ`K?}; z&*|GO?iFnk_4IG>j63yTaXU>Z=8^SpS%4j5yWanK5U2^WBzBJt2o9n5Kha|BP1Cg3c1GJ*A=+6Sccc{{jaOS~_G!JjAZn$jEpte|?u1;WyfP$bp|6$aN#_X0 zS2hlFb+>vv{;mEKu*GZ${TbK24)Ql&wdkrPtXL@8!67+e?A+@V!v0oL)E{wRo!CuS zVXnp|4NL*v#Ca)PSV?1#8EegDOwq;2Ov&ce&NNGEtOD!Asn0lzh&9C49%V82%oSyX zNl|;m;vHXZ@h!Nr8RO9?B0>ByoQPj``S`f_P7ze6Fj3C)e-_Qe5sfo7Jf`puB=Dy} zZ-?-w`)6PzE~UonH&I^`u!GXjx-Zg5gf8Is21o`eAU%%tBkiEanjdN8U*;f7sm#Tu zU-7tVdiIw`86n>G-SF)QaX-I#5jVqq>Cpgt;GS9&;)>UVGm3r^;b+_uE~>58-h4Vs zyW+H^^yOMh=|xbstg?$DznO&nDB*{6uK!~0s@jXUQxBrO9(Sa)qNp}aq8eU%(^iiY za~2fYG@lx~UcCWt?h-BFy_Hz2j99?^a}g7EJpR9co_`IZlF@lc#Fg!zQ?3D@j4AxL zB=BD}4F9xvds@>!E8gyI#*ROPBycmAq2AUDXmdS?xdWfc{vkYdApvUy$FEmo|3GY? z`B-lWdl7KH@%XgbqqSIDUwWa|RBDn{E;v7n`r6HLJ4%3z^1 zF-XgCh-ac1NtAxp?+a3lDDD&b4Z!GwsK%OF{$7+5ejiOd_nl<=pHaHflZ1HiBb77l zpf5oG08!qgyhlNJ9xU-psdhR~S8e`^B&#l!H=fF?|JJz8fA zARo+?xrnf1Y&QAKmEVvbc|Z09uVk#bJ~R3R5D+|s8B`8;W4}1Gt=OceE!{lN;!&b9b_xWCV&$OHto?b8m@dvjka3jwdG>RUyHv#Ry+WoAH?zd`jqZf8fC%(M%)#WFm^m^*oN8hs=IxOo= zgSC%rGzI)+DGU?mr^VplC7>!$H7FYdX(MN07m3Nu@J=1YpAq;!lEA-u82)a=@||j@ z_8*;#uFvM-IWrmSBd12_JPY(_74s!7?ilq7I~R}E`*HmHPb!Va`LW9GKdWO;(;8hd z$nM{dJd6C2K^jBiI|`AvDXg46kcj2Z9L5;V)gSBW*L%5o?r?uBf1p1mVDEOi^Yq-= zY&~WZU}vUl4ZC+|0zV>8`z-^`+H;)6_fyC5;@AspDX^w{fSPNux053Wab&4|8EaIU zh%l!$lbnJ)p|eavQ0FbOHEbZZvm5Y?<$T4eAMoXQKVW4?E4`MMgAzyWX9WI_Ch%X1 zUpyrLpFn-Rg1Rs^`&&%jobp_WwPCN6enu$C&#JtYlyte#o{W&d8b?lh8vKF}Q&`c-T&s{o>?jw`B#G;wzXH`df4z>UTQIE&|1xCs#}^pIpTv zb{pk0i!>2jb`@3%yO-zH8l8n$MQUVooZ}=bayi%&AP3Q-`2o7yfT;p|172bK#*44_ zbzWwkW%^7D=9UKgE_D`(WOsT6E4TH-s#_kPw{)}end7986#ONsub@5A$$l9!qVBhu zlBJ zeq0OS4-Wf3*+AfP*%#{?xU=O3+pUQ8$;!9&-(=se49+}?Z*?YJ9njp(Y`&`fo=L~L zw`?v5-Pg6HR&!C$eGs&;CoY~?&UOd<{Kb+2_m%oPO_Psx*W8Dw&7Ah+QBO{2UlV4C z))y$*#=Rbk_;ut@QN?ES^PMS-O;iO|VKR4k`XXne&E4$g>)Y?^VjjM;^gAtrm}a}K zLX90z9rn*R2(z#C&S0wKb$afirjSf!XT08?W}6m|QTe30(tfK@X}eGMGHW+|zG?0K z$MUz2t@*#Y1pdp1;h!Ejxbd@%woNZ=n)<`<{qW!qKl`EW{4#-dj50nZbtd-g{ca%Ojm z`;X+Nu)*%YN=i{H052g;iaF z4TpTG-aA)+=CiH-d^O)Gkke?t&q7YU4O$6))uV5}Nt~5R`Fk2^u*aJ3^yY}E@a{<$ zuZz%URAR63#8VnPu1G}bx84qE%Y@Qf-Pcq7?HaGG?&GO26k0wmN$Ay>SJ2P^S#)asvxmtIUfyNftfOWe}U+lv{ zTSp^Sc}#|1hU&6*FjK#`;RESdr}65E5#Ba?Ce`@8eY{Q6IhUbpw^+HfkL*9zz3FN$ z!XW+0)l7KmhK}ejH@sX!oY$f+AbuJx>QMJ4TNB~}IZpodL8epCoo$(gw=kb_)*SPU zJHy*ra%stvP*&KPgD1_LNK3yCGmklaQ@jj(1u+{5+r#G@zLbh;82feN!R~{uUqtoS zd=kZPz2kSM7`uJLi&6L;Qdg)^`xznscO>w?3BP!#|JQ{VTw2RK;UVp**nLOENbsH- z9AWD{ziEe6jo~kz;uzZwckV+co3dcN@kyyAjLWjo=S%4HFP>tAzF5)V+6RgA=ix*6 z-jCHi_6>W{W{29S+wsz?^S7@3n6_2Yo{9N=Gxq6aBYbh5WN$gxnI7M-C$Y}kwW;+Kq=pyKbvuVr0AD^q_`I7X(;Sb`x$}%6AAop#xEYi ze|o9Cv@?PlgY|x|=kM+DdWNUeR$AZoH0;lMANFsoddiP^V1CJkXd84nx)=9Ll$W5Z z6F=+LJN(VC2rbcw6C$USw$i_HQ$G4wX%og_U-yGkPbe>z(f-+NzrAEb?#5f}r5l%? zs>?5ZvFW3Lzm;@9y#YSpZnMo(@EpUjrWla2)#(oirCM31U3fuTsM+#`(UI?;Q!<#pvFAv;KM%rB&PRa=3d zJ-dr!>qFSL*NWZYy4=|mzf($1p$GcK38cTnIsxnoY<*pM@0+_*Df+|i)K@0%GA8db z7QO;G5tmWm18VOhdI4jY%L^EJGcixuD}Io+W&rdANZ97Z;QKk{TKsXLAF^|JO(}llJ z;X_RK)9XtV>o+_amlwDmV_WP-P)|7QPtSGd7c;Z;MYs6&t?7aEwmNHHOyBFaAKGf)0$V%kjkY1`*YS$?)k?HE6R|(in2)ug6Gdw;cjbyM z?esFm?h}KM8&_tRU|ntX5OPd$uJa#}&vn|xag1s2j-XBKPfItPk%6UmdtSj9c;FcvUru`$E4`vwIVq6cX0gsn|PH8y`PEZ-BA?PMJQZNyFoqCVp(@fSq-o z{t@NvocEg$8DbQFM#%qN3H)yzhQHnjzu$tBsEHKelv2kdHV-+aJc%?7=`N%Oq)#JF zN4ghj2GZwd?^H5fRaz#ZDdNLeH3t7HB2OP!=e4`N!Dr(7w_AQDuo`nSe~Hh{+*b9e zB0c}9^6+j@@C}hn(PGcIf?n=&yRNfo;^`bnWbGmSj8lsK+H*~t!*3{htp9o_LRX7x zm%jnupL2B$o{eV~v?NNu8&9neSAw&w1I#rkGxVKi{ppB^=M(2m;TwVPz1y+p`}QHO z%;^fO(_!UUpp;6rT2*whI_$Zf;$C#jz*?Yqd7D%qUo=+$06 ztCO3UkAB|rbZ~~3>f+ksv_9=Jtem-K>5jD0{Y}faF5l6j7>)ZpH=KcPh`QI$Na-}E zbVNvj8Kp2Oh{V7-fa^J3M-%taik3Igo9M!b*s#2%?rhy|&ve}P_kL!!e!33(IYlFJ z?}4WvU%)l@M9VR2{QZGvq6ys3)*S}&XX_Y5l&0(UiCo|R7~)1SsfQ4mX4wvU)GY@X zdgjsoH=^5=)LoG%m0x6iLWcGCO(tBnectFr|KH62?MdK& z`!M`jM`f6<^{+vTfz`Z7p;nkRRI?sxIcjWbe|d0?cWtFv;;gQ>DlYxdW%gzH%)UF& zy7kVK$gST0z_~VSxaHe(H+h)?l(O*KQvMEKfcN1e@cVvukZKCl8zA*~mhW6N%NLC< zfxjU<{jg^P9XaItUXLzZL{}f?!Sm#O-1$m`?i`<|={t@0TZ@&PvxiE)A^8^9d*|aV zh+|F!Z!t61XY}RzaBrVGSnQpRGd}v}$>TGV_skkw^MCaT{QqMZ{_abkZ?O2>7;g>L z=hQ`4RRnDBLRZHcT9dQlZDqT)5;gfKQ0T)xUpP8v=-SoT-^t|rApZSP)STp@8@q0P zjq2`v;m~!KihzJ}&~p&e2}KVg-<(rp3;Jt;@}qrO|Ds*8=&uueLgbs@g1^4+tE3J{ z{-Jf}{8Q_uwxS&5A=BKXmUU}#0!-W{0lktZ#GP8Yr)h_WJ+fKePli^qi{OP85@BUA%XP1>bW2=t0 zpVDpiaFyEQHR|{Vrgc3y!OvQw{m|iKsVoLv<-^xX7gGzlU5pp^Nqn^4@wG^G^o~mz z_wKh=33aUsrMYoN^&8N@drUV}sH`$KzTxp$Rf6J7BF6QTVa28=s}6X&>wkwmn$g0s zs#mQennP7norOsglE&ECPQ}FMU>CC56Whsl4DDpw8RMu>b;n-Ma9_PO`oopBOsqAS zzzbcFD4{ZE8^J->Ej9tM$|Y69X)-KVbh{$LwRa?e!>7lTpGG z)YAaowf<4mfC$MV~+Y#1)n%fV%}$PUKL}Z*`<+~abJm(o!^M@4K-?l zcC^E)iL@f#7fr|aeN13R7i~c?P78M8z7fk{1!kvpPb)`~1#{!FYByTX3Eh6Q9k*w_ zb+Evn$q-_JU|RU)s(b5SsoG;zH(#yFbfOJ(^07=n*9Ezu<9l^`J#A=>!MQ5okTiG; z*>t?BN|^lfI|SN-+@4TX_0fvFeXWEsH@d2;J<}RBx@u3!?PdSrH!}W(eekdLJPq6j z3v+~5tr=%Blh!1q+p9fhCwgFLSSNdf_P|Y{10K{hpYD4aHlA17W`N7b1TNmn5oSTw zD;#{kTdFYi_y9O)O=)~A33Ovsg^(?LC@xOg>+y^81o@eFZ)FMU)+om8yeK|xRW;qw z$)bnS-@?JA;lGMm0WNw}XmjU-k@Vrq8 z>^tCj$UaYq7MLk$eed%U^A{>R9Q5zBPjyBC?FUD0%2UAC1R491FAKT;Nz_TuF_M_M z*F>`uyAuQW=tuwmr;I<{^ynS`JvYc)ZBwOt9y#gW=7B!EiCZ~;dNwvCK@D4H>sT9sTunJo1snyZ_UMkH; zpV?3)KV@#TRMRKvGf8-+Md$WtkDD9lGdx;As5@noLa6l6){xSzugnn4$5%C+tX6Cy zqv0XuM>NgMNE*s#4hM%s(oic<=7!(nJqJ*>SFA7M4OJ*xt)~hltE|F*=nwP4P(S(k z7O(j@Ep3gp^UP;edM9`d1Ni8N{|*`dqCWU@gb8$XGCeX9SGrm%82wkGQTSSn!|n@q zV&0+@6KxAz<@&0H(C2?}MV`1xfGlOXS>6b9!HxjPiJcWG0@DTDGukSB~o zCG7`nv7emmfLus@eEw_Ki5tG+9oo4v$`6D&Xm3HA ztOw)vb5tXs41Pw#!O{)}-bxrfmFcDV-+BUiq_|$dN%8D$TiVxcE_P~^z!`@{Z2huh zk_>l1F7*Rd`bUYb((8mtETicM>d~+N@09T`#s~L~|B#7KD+PNbvFxF;MAzc$l?V-v z@JQit(Fr}7Mk+UdN)>||n-SodZ$#y+XxDia|4}q*u#$@|6UAQL+g=P{hXL}WJgjsm zw9Lz~!fDuAISrfN)TdlH_38+RzgEV7 zNgw8&kTRD&isqc+5%7UkN1xTp3vyEt%Y)JA19)y9-Z0y>hrXBg zD@8VIkT0Q$$@<2xg^d_C%W^H8qmEd9-Dy>w`9zG4#PWVfUaf1wUeGH?EXK~}4@K~U zkvb-l(vtcG*7=ekI-aO_4qmOARg2y1<|0#I59CKfu z+DAP>LKgWffi2O%M)FojOo^=gc0+Gj6)AVyN93)5_=4+w&Ctg2WtnBrM4WV6;lE49 ze`z25lkI;MX@G0ftrk^ULW>kWpVyz6c{k!J~bjDQg%y2X9jHtpd-t`iJT#6qkRkQhfyPk3f$B zdYEC}>J*F1^8$>b_)+R_l4P{|i^?6>30L$ey;kB%HPO$jL?C)aq-CMs06lZe4o#9~ z7LWGIwAvV^^=#}`DIIp{S*`+CIm|@D+6c{XTjBqljK8xF{&Jn2{TFqHS>f9{!(7>? z&M04S;~^$6u7kiIkE7B9TN+fWm+D}32Y(ml_R-lrzKg~w1UdGZFd0h%vn!vI20`LO zWhB?iE2*bwHHjrF*t^*UY!XRg%h>0@Zwdz=>v|rxU$y$3WjbbuIveq?uj3bcp9ehqfMX^0-wN!yw=3sUi&}K z%lMb{!QY{BjN2n9{TtAqnpKvzT@~c5XFs)!8|1IZr|534Ac0dM{uQdVLuoXUvC&`s z>B;LnchSRSlR$CBLeKm4Z1zR}bJ9>P9YfSvO-+2Om1SG~alXgHK{#v@$T$-Cc?HdH zc?I%ni(#}a`f+je8PgE7g~Eztdkg%GpTizA2|U=7hSGXTUB4H}xYv*})}%4+Z({a< z?;IeF!QDfMh*N`a`l#pnDZ+(4;ZB5Oe>(*J=1HIwSjTBI;M=yPo3}bvKs2M&4R1zEf^+-4|PUosZuZyXbmeyrIlibuxjpX_TY}lD^icCR0Il zeRps~=LU({BERKN9apZbazz`t#$4AS;bsDOu{f!+S;UA4^xAfXam-h4~I4f zncSn+chA#Zra8Bmo$H-grC{wB-NrzS5zy*RGyT&?;x8~HQjBO>A20n=1*%q2QTt-4gwo}s+Tcl2#KKoPju0~ zI=%hk0sa*=-bLTE2Rhs&Fr4I}qdc!3ONFx;_U@pw;G3ik0VD z?UZ7TuaVLTXaKSvS27YUcTIfIcapK*^3bd6z6T#|M$rFKhg(( z0t#A1d1=4qOa4()yJv2{oQ!@oy?yHe=>217=LDhsvHJ4xNbHjb=w0RIaFFS=mBiQ6 z+TAgenGlPyqy>9&>#c3)R$V6W#LU;yTvi-V?AS5$rF~quG-eOk#>vrR?i6S#-d^(Gbu#`d`rzM!`fSH(dOd26 z0{$P=&RI@_z?~$9cj3ErTL-~7o+0RjR~y|aiGt}E_GFIHXQYP2yJG}ZB>gLnY=L`^ zqr*0>y`d!9 z%jmC*sj!kpX)KB213en$`Q4DJx#G(aM$RIEOI>x&&#H6nIrciorK)Yr>z2WKu84~gMOOBa@%m^kfzMG zn~>@X_HJ5zidJ527C=2}!@&a35uf?^n=U@x4#^DIY68|B^fz8uP|pcj5svb5%+K;% z@d4V)`nqaq47QoJiI@76eG>Mb zP)3$OkGUhbr8^8=M%uOp>d~+N|4zpLQG9SO{#GlKUi9c^ZemcU7FDFKA~ig;HI2~s zb}ynWAszTWB9Ui$Vs31NMs6DRV~QkdF-FEi+YmK}q$pBptrmCFr_$g-^s+>e_zeFU z@ZG4i-xo*Z^udM#c#u>HoR9K)sKzJtC@J|z-E-Kr_UL9;ZrLE0CT)J3<@U_j;nC zb#S@+w5Tv%@@Gccl`fRwr9S1)tKLStY83b1Ui`n8Wc*k5!GBd*ZyozZ+PCiN>0joC zXh_|}VOQV5>a+6vhS|TW8s>Tt*4O5^^wYR8)3BD~18n>qj9 z#(TP3#bxDT<4vF9rddPogm37mm#p9T5+!EpPqErp`tQXY{S>UcmXuR$nMvP>Bl5e! zb0ZlS{awLVL+3>uC<+-VIyWzcg}8V9cOZ=eX&U`x%yHk)z;xxC{(UYB`s>LK>WBTX zFBevwV$G6&Wu zF&Q6PAM}2G&;2UQ(`w4W@li?aGR)FScz=Gs{9br}z9UP~Gz@j#tO}r){auWov)Q#l z8f)U)vbn*SmHD=DoIEd&2PL^n%J5RjpmVBbq;3*N8BzrqU(6elzK?{-aQ&$WKa%1% z3356^g+gyU_|FbbZ%p;icXdO@G;AE+5GpmGGC=~Vp0*~cxg610&ItGz zGrgmG+$uID(moBhJ{Q%(rHI@g<_g3L!IMC^f=GW`jp3tcLzn)#|p}#+j6-9%8Ws5Fr$yyRP<~B8PStQ_d$Kn4r_e!rx z=n9@k2`ykdZI`B*j9$w%)>gMs9@7v((Mf(Bim!ctShA%y9h%YJYqJITwF%tN*`_sow!rR!91r5h)G+n`2x84;8 zwG9R*i6SuN7GE1*e_R@@pW>Bse%lWmta~;d731DyrY60q+@{#4PJJ+6Q9}aW4mDQm zMMaol2+jS7dk-wLSgyV1zBe+eue})OJoQz}pA#(Qo`e zAmdLLJ-y?pRd=gmHk!E-a zp57HTV+%Idn<9Hh&%x`q8}cHK>wk!cy`Oz)`P2_L3C!u>4O>M<|93I2r`A6T1q^5r zdiduyMFGbo6WuLZbe-eq6WgU9n4XgKrnuDYn5pBCONvRcj|4J0h@oyHr8(jZC1Tyv zF|&uva;)tNei7nEhHoam_OJ-bgxwQKF%s?M$0D6S9++>n(fJ?O`IHv;nA*Q|vn++Y z6TjDb{)3uAAFxM1{13|bm*b0j@u&U#%oTYIsJ?RN+OTGr|I%8=+AL$bukPvlX7g=B zn6BXKunXGQNU1;cQFjE1vX>hXE~{HM(q6RecSX-zFPyowHUoS8yAEdI|8Ec4BJ=&a z8xJ2u-@S5a6Q#V*O6C)vNP#WnHw)j~3Cc4XIG0B7<8Kvsux@9>+v^`&#Wv?qD0mutsX3FWIFCZ_{ zHU0{|5_8nL_QZpOve&iWagdf&I)XOJ^=YL2ndtRTA`h|upQ(YFOw#sH&!Kun3-=Rd!l0k*x8C$ENHQId zvTwDLws3B5nFivuAO44A{MYuupTKLgwgI{`1srr@wpu&<+T&Hwj%1)k!8WhACJU-2 z>qz+c_R%y{Z$=W=C+yTwA8y*?LnUSeo*NMq2ft1lb{!hApWUL|QW_vLH2JEn{8r7Z z`4VqbY$eeAf{lQHTViYB*S##6N&vTVhrq!Berh%x);4h9GR5H?)4a@7s!4`?$B`^r zo_L{6tOnS({YnFgQorM>`;iFTyfwpc*xd-F|;c$-THc7y2VsUBGSbNMUnzlJdDjD%kQK zDh&Q8x}?Z!Ng;vZof(ddLcKS}FqQhDGo5O&7?u?hgQi9gN+HwqiL`4g_Zt(!S)dx2 zCz z?&51yw-^2Ak@5dUAN-$^=9_di69h#n`f}1-(06x*_}UZRW~IGR56@Zi^*WWk(HIHk zxU#b1eX5-k1fq``og$!@PBl%{7z>)qyhB@dQ*F@@2_)F~Eu)2xL~dv72zXoCO0t;q zs%?DBJP>0nhfs~dm2Hgi7rC;GxqhxzHzElheTeZ$Baq2uCn##N?@4iS;0%#Kpu=2m zF~B1+^5tte8#95gq2;_2lwpQenF={h%s*ydT0#6#u2z+6fFBTbE?1+ewE^=LqOz0C zfvmXjGH5~uIVTEHqhU=RZN@Z3lf^ZoO$^|pU;jTW!Rx5D23CTDcX$CBP%V?6@ve5WwxY?W+!>en@{p2?;62IsR%Ya{gm#YXPa zox=i3h04#jB}QGMzM=HBy8YIS3)>}|Db-1GVS&o9O*!@~-)3Vc!^gmhnT$#AGdM3t z(sBVM$HR~P0bQLlwIrr7{p#g4B)!J^E_4FFrZR^b-GsaIbpA*|2k5_k_`fdWzYgEq zOaEi`ZGj~fSn-l;kn{J>0nEgc;-?7@CY$sXl8vO=w@Z22O39{WbAJ!pE6}v>dEyGB zL>Wz!Jhs~?qD-5OXny&`p%s}s;I%iVmIU5(r!^I2PWDALkxUXe>0W^UTitw{Rk1;` zYA3cV&SZQgnK%9EP90Ep4`JJQW{fY+ndl%{+_|xadDaa;{S)cf+fjz;EvxYKi*9vO zX=aMAEc3iS)oBgr*;EJDvL-XZ=gK_eccpHS^7NlbTiz~g(K%yBBs$`qcoTLftqR6a z(?W9|7O)ISxV_|m8f5(4eejR-oEBkO<%G_eEZ4hYgo8oNb1liJpO7!E>Jusd?b6Jc zMztZzKvIB%w%GZigN)tNnBq)ev6@knykRgTF#Jj(Va!WSDc2 zlRyTC1SU%AdP|bSQRGDZU|nZ3?H3ItS>N{fgBWFNRquDKz`VqQq?nHzfRoe6{)ZIkJQtixXLJ=yvit_2+h1v7utB^$#s6ge7%H~AhedTejsC&jS~gV+*^);cjnR(zku(oVd|NazjL-*E zd@1-1+Dbm&OT(=_VcM1x(3X!iMla~CtATj!hrd_Ge?uSqPb8GhobR3OC7J3*l95c; zVB;wTNCK<92invzk9^7hnFN&5#}eQ2@t5GYV9$oq^y=q%p-O<}Mc@hdChIUEzu6P2 zyf(Z39oXwGV>~@-fo$Db=WYLbCgCXLn$5r#9Dq71rB3V{Yxu(=?AsqHwsLHG|{od-2V zQ5b5w%G=eQMB1IF>Op}$vpbJmyWma`_O_~d%hedmTjFNeW+K@xAGs4KFlJB$bT{d6 zXnk;0Qa)ICsRj2y;W-A|J+f~gabR?LT zab~l1bTd0W)Be7$;@eSxrX`WIG#yGjO^bAcQQ}NkuEQ8GbEr5YZ~vJit?b~E))WFB)M8+1LmFNx~Ob zD4oa8R?LbA=U?3zEhN~r4r$=M%)pGxGkWaXNY)nvsyK@W!`M8j*?MTBF> z?i_VAVJWv)!{f6N;1y{g1QcluVfZwbRir6tZ4BI_AO7&4M8CKSpWM6uqf%6GYNFNf z3}K@XuTrqAgBpQ+dquw3eB-2W)z618?hyPnL{?zDc zFa9gCR~DBoFDxp~NOi7WT{dOhxS##(XW7fqF_)HR7p)jqw7jrvW$EIFA1f*TS$5&7 zGS~E3i+?aa*E}gTb86JIaXqy;ZJb=WXw6g`=rzI=`TvEr4hN=jGg5zg*82St$; zrK|NzO4qDdjIh0MHBt-3i}d47`W#cv1jKy}9hW@lIjq5%2zhrum3ha}1=-g@kbfM3 z^EsSdI0yRC4}ZG%f)2C^AKr_cdP1#~l-D4-?k;RJ^nTsZ6 z4vM9j(LJR? zKm30$dEZ5Z3sz+k97v;_s9QS4fMkwzIW;RZ!3z_ zOaHfNpC4KN^HjY8af@+&5Gk&foQ_<1LIvch-(D&xMg91m!Bvm*`{TP`1O4#V5-r7l c8;ahG|G)eS3))G`_kH(Y*3JJ%kre;`1`g8?6951J literal 0 HcmV?d00001 From c8dae33e2f1b2c68b853137af6cc782b35db6983 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sun, 11 Feb 2024 16:00:05 -0600 Subject: [PATCH 178/472] [create-pull-request] automated change (#3211) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/mesh.pb.h | 8 ++++++-- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/protobufs b/protobufs index 20f2783e1..388fd79bf 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 20f2783e196da1429de4b0fcf05c7ffea98d7901 +Subproject commit 388fd79bf78df2c59dd0bdd029a382fa91b1cd88 diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index a6b36a875..d109c2f3c 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -109,8 +109,9 @@ typedef enum _meshtastic_HardwareModel { meshtastic_HardwareModel_BETAFPV_900_NANO_TX = 46, /* Raspberry Pi Pico (W) with Waveshare SX1262 LoRa Node Module */ meshtastic_HardwareModel_RPI_PICO = 47, - /* Heltec Wireless Tracker with ESP32-S3 CPU, built-in GPS, and TFT */ - meshtastic_HardwareModel_HELTEC_WIRELESS_TRACKER = 48, + /* Heltec Wireless Tracker with ESP32-S3 CPU, built-in GPS, and TFT + Newer V1.1, version is written on the PCB near the display. */ + meshtastic_HardwareModel_HELTEC_WIRELESS_TRACKER_V1_1 = 48, /* Heltec Wireless Paper with ESP32-S3 CPU and E-Ink display */ meshtastic_HardwareModel_HELTEC_WIRELESS_PAPER = 49, /* LilyGo T-Deck with ESP32-S3 CPU, Keyboard and IPS display */ @@ -135,6 +136,9 @@ typedef enum _meshtastic_HardwareModel { Tab on the screen protector is RED Flex connector marking is FPC-7528B */ meshtastic_HardwareModel_HELTEC_WIRELESS_PAPER_V1_0 = 57, + /* Heltec Wireless Tracker with ESP32-S3 CPU, built-in GPS, and TFT + Older "V1.0" Variant */ + meshtastic_HardwareModel_HELTEC_WIRELESS_TRACKER_V1_0 = 58, /* ------------------------------------------------------------------------------------------------------------------------------------------ Reserved ID For developing private Ports. These will show up in live traffic sparsely, so we can use a high number. Keep it within 8 bits. ------------------------------------------------------------------------------------------------------------------------------------------ */ From 4d18bc0658b8c5d5c7a71e5a11845f48069ca1f9 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Mon, 12 Feb 2024 07:23:52 -0600 Subject: [PATCH 179/472] V1.1 --- src/platform/esp32/architecture.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/platform/esp32/architecture.h b/src/platform/esp32/architecture.h index 9fa4a5dd7..ffff90c75 100644 --- a/src/platform/esp32/architecture.h +++ b/src/platform/esp32/architecture.h @@ -106,7 +106,7 @@ #elif defined(HELTEC_WSL_V3) #define HW_VENDOR meshtastic_HardwareModel_HELTEC_WSL_V3 #elif defined(HELTEC_WIRELESS_TRACKER) -#define HW_VENDOR meshtastic_HardwareModel_HELTEC_WIRELESS_TRACKER +#define HW_VENDOR meshtastic_HardwareModel_HELTEC_WIRELESS_TRACKER_V1_1 #elif defined(HELTEC_WIRELESS_PAPER_V1_0) #define HW_VENDOR meshtastic_HardwareModel_HELTEC_WIRELESS_PAPER_V1_0 #elif defined(HELTEC_WIRELESS_PAPER) From 124be247c7b7d01eec102662ffea09053298ffa9 Mon Sep 17 00:00:00 2001 From: Gabrielerusso Date: Sun, 11 Feb 2024 19:20:20 +0100 Subject: [PATCH 180/472] Fixed ESP32 ADC resolution bug introduced by #3184 Fixed ESP32 ADC resolution bug introduced by #3184 as esp32 analog resolution is already set some line of code before to 12 bit default. For our usage wouldn't be faster to use 10 bit? . --- src/Power.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/Power.cpp b/src/Power.cpp index 38f8ed771..24f5eee0b 100644 --- a/src/Power.cpp +++ b/src/Power.cpp @@ -390,7 +390,10 @@ bool Power::analogInit() analogReference(AR_INTERNAL); // 3.6V #endif #endif // ARCH_NRF52 + +#ifndef ARCH_ESP32 analogReadResolution(BATTERY_SENSE_RESOLUTION_BITS); +#endif batteryLevel = &analogLevel; return true; From 30507f5125bf7428d9b9c0058fd57797e8ae7ba1 Mon Sep 17 00:00:00 2001 From: Manuel <71137295+mverch67@users.noreply.github.com> Date: Mon, 12 Feb 2024 23:44:21 +0100 Subject: [PATCH 181/472] refactored ButtonThread, fix IRQ issues (#3214) * refactored ButtonThread, fix IRQ issues * fix copy&paste syntax error --- src/ButtonThread.cpp | 219 +++++++++++++++++++++++++++++++++++++ src/ButtonThread.h | 250 ++++++------------------------------------- src/main.cpp | 5 - 3 files changed, 250 insertions(+), 224 deletions(-) create mode 100644 src/ButtonThread.cpp diff --git a/src/ButtonThread.cpp b/src/ButtonThread.cpp new file mode 100644 index 000000000..84d433285 --- /dev/null +++ b/src/ButtonThread.cpp @@ -0,0 +1,219 @@ +#include "ButtonThread.h" +#include "GPS.h" +#include "MeshService.h" +#include "PowerFSM.h" +#include "RadioLibInterface.h" +#include "buzz.h" +#include "graphics/Screen.h" +#include "main.h" +#include "modules/ExternalNotificationModule.h" +#include "power.h" +#ifdef ARCH_PORTDUINO +#include "platform/portduino/PortduinoGlue.h" +#endif + +#define DEBUG_BUTTONS 0 +#if DEBUG_BUTTONS +#define LOG_BUTTON(...) LOG_DEBUG(__VA_ARGS__) +#else +#define LOG_BUTTON(...) +#endif + +using namespace concurrency; + +volatile ButtonThread::ButtonEventType ButtonThread::btnEvent = ButtonThread::BUTTON_EVENT_NONE; + +ButtonThread::ButtonThread() : OSThread("Button") +{ +#if defined(ARCH_PORTDUINO) || defined(BUTTON_PIN) +#if defined(ARCH_PORTDUINO) + if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) { + userButton = OneButton(settingsMap[user], true, true); + LOG_DEBUG("Using GPIO%02d for button\n", settingsMap[user]); + } +#elif defined(BUTTON_PIN) + int pin = config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN; + this->userButton = OneButton(pin, true, true); + LOG_DEBUG("Using GPIO%02d for button\n", pin); +#endif + +#ifdef INPUT_PULLUP_SENSE + // Some platforms (nrf52) have a SENSE variant which allows wake from sleep - override what OneButton did + pinMode(pin, INPUT_PULLUP_SENSE); +#endif + userButton.attachClick(userButtonPressed); + userButton.setClickMs(250); + userButton.setPressMs(c_longPressTime); + userButton.setDebounceMs(1); + userButton.attachDoubleClick(userButtonDoublePressed); + userButton.attachMultiClick(userButtonMultiPressed); +#ifndef T_DECK // T-Deck immediately wakes up after shutdown, so disable this function + userButton.attachLongPressStart(userButtonPressedLongStart); + userButton.attachLongPressStop(userButtonPressedLongStop); +#endif +#if defined(ARCH_PORTDUINO) + if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) + wakeOnIrq(settingsMap[user], FALLING); +#else + static OneButton *pBtn = &userButton; // only one instance of ButtonThread is created, so static is safe + attachInterrupt( + pin, + []() { + BaseType_t higherWake = 0; + mainDelay.interruptFromISR(&higherWake); + pBtn->tick(); + }, + CHANGE); +#endif +#endif +#ifdef BUTTON_PIN_ALT + userButtonAlt = OneButton(BUTTON_PIN_ALT, true, true); +#ifdef INPUT_PULLUP_SENSE + // Some platforms (nrf52) have a SENSE variant which allows wake from sleep - override what OneButton did + pinMode(BUTTON_PIN_ALT, INPUT_PULLUP_SENSE); +#endif + userButtonAlt.attachClick(userButtonPressed); + userButtonAlt.setClickMs(250); + userButtonAlt.setPressMs(c_longPressTime); + userButtonAlt.setDebounceMs(1); + userButtonAlt.attachDoubleClick(userButtonDoublePressed); + userButtonAlt.attachLongPressStart(userButtonPressedLongStart); + userButtonAlt.attachLongPressStop(userButtonPressedLongStop); + wakeOnIrq(BUTTON_PIN_ALT, FALLING); +#endif + +#ifdef BUTTON_PIN_TOUCH + userButtonTouch = OneButton(BUTTON_PIN_TOUCH, true, true); + userButtonTouch.attachClick(touchPressed); + wakeOnIrq(BUTTON_PIN_TOUCH, FALLING); +#endif +} + +int32_t ButtonThread::runOnce() +{ + // If the button is pressed we suppress CPU sleep until release + canSleep = true; // Assume we should not keep the board awake + +#if defined(BUTTON_PIN) + userButton.tick(); + canSleep &= userButton.isIdle(); +#elif defined(ARCH_PORTDUINO) + if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) { + userButton.tick(); + canSleep &= userButton.isIdle(); + } +#endif +#ifdef BUTTON_PIN_ALT + userButtonAlt.tick(); + canSleep &= userButtonAlt.isIdle(); +#endif +#ifdef BUTTON_PIN_TOUCH + userButtonTouch.tick(); + canSleep &= userButtonTouch.isIdle(); +#endif + + if (btnEvent != BUTTON_EVENT_NONE) { + switch (btnEvent) { + case BUTTON_EVENT_PRESSED: { + LOG_BUTTON("press!\n"); +#ifdef BUTTON_PIN + if (((config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN) != + moduleConfig.canned_message.inputbroker_pin_press) || + !(moduleConfig.canned_message.updown1_enabled || moduleConfig.canned_message.rotary1_enabled) || + !moduleConfig.canned_message.enabled) { + powerFSM.trigger(EVENT_PRESS); + } +#endif +#if defined(ARCH_PORTDUINO) + if ((settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) && + (settingsMap[user] != moduleConfig.canned_message.inputbroker_pin_press) || + !moduleConfig.canned_message.enabled) { + powerFSM.trigger(EVENT_PRESS); + } +#endif + break; + } + + case BUTTON_EVENT_DOUBLE_PRESSED: { + LOG_BUTTON("Double press!\n"); +#if defined(USE_EINK) && defined(PIN_EINK_EN) + digitalWrite(PIN_EINK_EN, digitalRead(PIN_EINK_EN) == LOW); +#endif + service.refreshLocalMeshNode(); + service.sendNetworkPing(NODENUM_BROADCAST, true); + if (screen) + screen->print("Sent ad-hoc ping\n"); + break; + } + + case BUTTON_EVENT_MULTI_PRESSED: { + LOG_BUTTON("Multi press!\n"); + if (!config.device.disable_triple_click && (gps != nullptr)) { + gps->toggleGpsMode(); + if (screen) + screen->forceDisplay(); + } + break; + } + + case BUTTON_EVENT_LONG_PRESSED: { + LOG_BUTTON("Long press!\n"); + powerFSM.trigger(EVENT_PRESS); + if (screen) + screen->startShutdownScreen(); + playBeep(); + break; + } + + // Do actual shutdown when button released, otherwise the button release + // may wake the board immediatedly. + case BUTTON_EVENT_LONG_RELEASED: { + LOG_INFO("Shutdown from long press\n"); + playShutdownMelody(); + delay(3000); + power->shutdown(); + break; + } + case BUTTON_EVENT_TOUCH_PRESSED: { + LOG_BUTTON("Touch press!\n"); + if (screen) + screen->forceDisplay(); + break; + } + default: + break; + } + btnEvent = BUTTON_EVENT_NONE; + } + + return 50; +} + +/** + * Watch a GPIO and if we get an IRQ, wake the main thread. + * Use to add wake on button press + */ +void ButtonThread::wakeOnIrq(int irq, int mode) +{ + attachInterrupt( + irq, + [] { + BaseType_t higherWake = 0; + mainDelay.interruptFromISR(&higherWake); + }, + FALLING); +} + +void ButtonThread::userButtonPressedLongStart() +{ + if (millis() > c_holdOffTime) { + btnEvent = BUTTON_EVENT_LONG_PRESSED; + } +} + +void ButtonThread::userButtonPressedLongStop() +{ + if (millis() > c_holdOffTime) { + btnEvent = BUTTON_EVENT_LONG_RELEASED; + } +} diff --git a/src/ButtonThread.h b/src/ButtonThread.h index 20dc14cc4..554c1f0c4 100644 --- a/src/ButtonThread.h +++ b/src/ButtonThread.h @@ -1,34 +1,29 @@ -#include "PowerFSM.h" -#include "RadioLibInterface.h" -#include "buzz.h" +#pragma once + +#include "OneButton.h" #include "concurrency/OSThread.h" #include "configuration.h" -#include "graphics/Screen.h" -#include "main.h" -#include "modules/ExternalNotificationModule.h" -#include "power.h" -#include - -namespace concurrency -{ -/** - * Watch a GPIO and if we get an IRQ, wake the main thread. - * Use to add wake on button press - */ -void wakeOnIrq(int irq, int mode) -{ - attachInterrupt( - irq, - [] { - BaseType_t higherWake = 0; - mainDelay.interruptFromISR(&higherWake); - }, - FALLING); -} class ButtonThread : public concurrency::OSThread { -// Prepare for button presses + public: + static const uint32_t c_longPressTime = 5000; // shutdown after 5s + static const uint32_t c_holdOffTime = 30000; // hold off 30s after boot + + enum ButtonEventType { + BUTTON_EVENT_NONE, + BUTTON_EVENT_PRESSED, + BUTTON_EVENT_DOUBLE_PRESSED, + BUTTON_EVENT_MULTI_PRESSED, + BUTTON_EVENT_LONG_PRESSED, + BUTTON_EVENT_LONG_RELEASED, + BUTTON_EVENT_TOUCH_PRESSED + }; + + ButtonThread(); + int32_t runOnce() override; + + private: #ifdef BUTTON_PIN OneButton userButton; #endif @@ -41,200 +36,17 @@ class ButtonThread : public concurrency::OSThread #if defined(ARCH_PORTDUINO) OneButton userButton; #endif - static bool shutdown_on_long_stop; - public: - static uint32_t longPressTime; + // set during IRQ + static volatile ButtonEventType btnEvent; - // callback returns the period for the next callback invocation (or 0 if we should no longer be called) - ButtonThread() : OSThread("Button") - { -#if defined(ARCH_PORTDUINO) || defined(BUTTON_PIN) -#if defined(ARCH_PORTDUINO) - if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) - userButton = OneButton(settingsMap[user], true, true); -#elif defined(BUTTON_PIN) - int pin = config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN; - userButton = OneButton(pin, true, true); -#endif + static void wakeOnIrq(int irq, int mode); -#ifdef INPUT_PULLUP_SENSE - // Some platforms (nrf52) have a SENSE variant which allows wake from sleep - override what OneButton did - pinMode(pin, INPUT_PULLUP_SENSE); -#endif - userButton.attachClick(userButtonPressed); - userButton.setClickMs(400); - userButton.setPressMs(1000); - userButton.setDebounceMs(10); - userButton.attachDuringLongPress(userButtonPressedLong); - userButton.attachDoubleClick(userButtonDoublePressed); - userButton.attachMultiClick(userButtonMultiPressed); - userButton.attachLongPressStart(userButtonPressedLongStart); - userButton.attachLongPressStop(userButtonPressedLongStop); -#if defined(ARCH_PORTDUINO) - if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) - wakeOnIrq(settingsMap[user], FALLING); -#else - static OneButton *pBtn = &userButton; // only one instance of ButtonThread is created, so static is safe - attachInterrupt( - pin, - []() { - BaseType_t higherWake = 0; - mainDelay.interruptFromISR(&higherWake); - pBtn->tick(); - }, - CHANGE); -#endif -#endif -#ifdef BUTTON_PIN_ALT - userButtonAlt = OneButton(BUTTON_PIN_ALT, true, true); -#ifdef INPUT_PULLUP_SENSE - // Some platforms (nrf52) have a SENSE variant which allows wake from sleep - override what OneButton did - pinMode(BUTTON_PIN_ALT, INPUT_PULLUP_SENSE); -#endif - userButtonAlt.attachClick(userButtonPressed); - userButtonAlt.attachDuringLongPress(userButtonPressedLong); - userButtonAlt.attachDoubleClick(userButtonDoublePressed); - userButtonAlt.attachLongPressStart(userButtonPressedLongStart); - userButtonAlt.attachLongPressStop(userButtonPressedLongStop); - wakeOnIrq(BUTTON_PIN_ALT, FALLING); -#endif - -#ifdef BUTTON_PIN_TOUCH - userButtonTouch = OneButton(BUTTON_PIN_TOUCH, true, true); - userButtonTouch.attachClick(touchPressed); - wakeOnIrq(BUTTON_PIN_TOUCH, FALLING); -#endif - } - - protected: - /// If the button is pressed we suppress CPU sleep until release - int32_t runOnce() override - { - canSleep = true; // Assume we should not keep the board awake - -#if defined(BUTTON_PIN) - userButton.tick(); - canSleep &= userButton.isIdle(); -#elif defined(ARCH_PORTDUINO) - if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) { - userButton.tick(); - canSleep &= userButton.isIdle(); - } -#endif -#ifdef BUTTON_PIN_ALT - userButtonAlt.tick(); - canSleep &= userButtonAlt.isIdle(); -#endif -#ifdef BUTTON_PIN_TOUCH - userButtonTouch.tick(); - canSleep &= userButtonTouch.isIdle(); -#endif - // if (!canSleep) LOG_DEBUG("Suppressing sleep!\n"); - // else LOG_DEBUG("sleep ok\n"); - - return 50; - } - - private: - static void touchPressed() - { - screen->forceDisplay(); - LOG_DEBUG("touch press!\n"); - } - - static void userButtonPressed() - { - // LOG_DEBUG("press!\n"); -#ifdef BUTTON_PIN - if (((config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN) != - moduleConfig.canned_message.inputbroker_pin_press) || - !(moduleConfig.canned_message.updown1_enabled || moduleConfig.canned_message.rotary1_enabled) || - !moduleConfig.canned_message.enabled) { - powerFSM.trigger(EVENT_PRESS); - } -#endif -#if defined(ARCH_PORTDUINO) - if ((settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) && - (settingsMap[user] != moduleConfig.canned_message.inputbroker_pin_press) || - !moduleConfig.canned_message.enabled) { - powerFSM.trigger(EVENT_PRESS); - } -#endif - } - static void userButtonPressedLong() - { - // LOG_DEBUG("Long press!\n"); - // If user button is held down for 5 seconds, shutdown the device. - if ((millis() - longPressTime > 5000) && (longPressTime > 0)) { -#if defined(ARCH_NRF52) || defined(ARCH_ESP32) - // Do actual shutdown when button released, otherwise the button release - // may wake the board immediatedly. - if ((!shutdown_on_long_stop) && (millis() > 30 * 1000)) { - screen->startShutdownScreen(); - LOG_INFO("Shutdown from long press"); - playBeep(); -#ifdef PIN_LED1 - ledOff(PIN_LED1); -#endif -#ifdef PIN_LED2 - ledOff(PIN_LED2); -#endif -#ifdef PIN_LED3 - ledOff(PIN_LED3); -#endif - shutdown_on_long_stop = true; - } -#endif - } else { - // LOG_DEBUG("Long press %u\n", (millis() - longPressTime)); - } - } - - static void userButtonDoublePressed() - { -#if defined(USE_EINK) && defined(PIN_EINK_EN) - digitalWrite(PIN_EINK_EN, digitalRead(PIN_EINK_EN) == LOW); -#endif - screen->print("Sent ad-hoc ping\n"); - service.refreshLocalMeshNode(); - service.sendNetworkPing(NODENUM_BROADCAST, true); - } - - static void userButtonMultiPressed() - { - if (!config.device.disable_triple_click && (gps != nullptr)) { - gps->toggleGpsMode(); - screen->forceDisplay(); - } - } - - static void userButtonPressedLongStart() - { -#ifdef T_DECK - // False positive long-press triggered on T-Deck with i2s audio, so short circuit - if (moduleConfig.external_notification.enabled && (externalNotificationModule->nagCycleCutoff != UINT32_MAX)) { - return; - } -#endif - if (millis() > 30 * 1000) { - LOG_DEBUG("Long press start!\n"); - longPressTime = millis(); - } - } - - static void userButtonPressedLongStop() - { - if (millis() > 30 * 1000) { - LOG_DEBUG("Long press stop!\n"); - longPressTime = 0; - if (shutdown_on_long_stop) { - playShutdownMelody(); - delay(3000); - power->shutdown(); - } - } - } + // IRQ callbacks + static void touchPressed() { btnEvent = BUTTON_EVENT_TOUCH_PRESSED; } + static void userButtonPressed() { btnEvent = BUTTON_EVENT_PRESSED; } + static void userButtonDoublePressed() { btnEvent = BUTTON_EVENT_DOUBLE_PRESSED; } + static void userButtonMultiPressed() { btnEvent = BUTTON_EVENT_MULTI_PRESSED; } + static void userButtonPressedLongStart(); + static void userButtonPressedLongStop(); }; - -} // namespace concurrency \ No newline at end of file diff --git a/src/main.cpp b/src/main.cpp index f89ece9dc..2af912d15 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -191,15 +191,10 @@ static int32_t ledBlinker() uint32_t timeLastPowered = 0; -#if HAS_BUTTON || defined(ARCH_PORTDUINO) -bool ButtonThread::shutdown_on_long_stop = false; -#endif - static Periodic *ledPeriodic; static OSThread *powerFSMthread; #if HAS_BUTTON || defined(ARCH_PORTDUINO) static OSThread *buttonThread; -uint32_t ButtonThread::longPressTime = 0; #endif static OSThread *accelerometerThread; static OSThread *ambientLightingThread; From 0b466fdca96f850f5e0db61f0224ada6c3344385 Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Wed, 14 Feb 2024 05:20:48 +1300 Subject: [PATCH 182/472] fix: Wireless Paper (v1.0 & v1.1) not showing battery percentage (#3208) * fix: Wireless Paper (v1.0 & v1.1) not showing battery percentage Addresses https://github.com/meshtastic/firmware/issues/3131 * refactor: count only valid samples Responds to https://github.com/meshtastic/firmware/pull/3208#discussion_r1485661096 --------- Co-authored-by: Ben Meadors --- src/Power.cpp | 59 +++++++++++++++++++-- variants/heltec_wireless_paper/variant.h | 10 ++-- variants/heltec_wireless_paper_v1/variant.h | 10 ++-- 3 files changed, 66 insertions(+), 13 deletions(-) diff --git a/src/Power.cpp b/src/Power.cpp index 24f5eee0b..23b790004 100644 --- a/src/Power.cpp +++ b/src/Power.cpp @@ -209,6 +209,7 @@ class AnalogBatteryLevel : public HasBatteryLevel { uint32_t raw = 0; + uint8_t raw_c = 0; #ifndef BAT_MEASURE_ADC_UNIT // ADC1 #ifdef ADC_CTRL @@ -226,7 +227,37 @@ class AnalogBatteryLevel : public HasBatteryLevel digitalWrite(ADC_CTRL, LOW); } #endif -#else // ADC2 +#else // ADC2 +#ifdef ADC_CTRL +#if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0) + pinMode(ADC_CTRL, OUTPUT); + digitalWrite(ADC_CTRL, LOW); // ACTIVE LOW + delay(10); +#endif +#endif // End ADC_CTRL + +#ifdef CONFIG_IDF_TARGET_ESP32S3 // ESP32S3 + // ADC2 wifi bug workaround not required, breaks compile + // On ESP32S3, ADC2 can take turns with Wifi (?) + + int32_t adc_buf; + esp_err_t read_result; + + // Multiple samples + for (int i = 0; i < BATTERY_SENSE_SAMPLES; i++) { + adc_buf = 0; + read_result = -1; + + read_result = adc2_get_raw(adc_channel, ADC_WIDTH_BIT_12, &adc_buf); + if (read_result == ESP_OK) { + raw += adc_buf; + raw_c++; // Count valid samples + } else { + LOG_DEBUG("An attempt to sample ADC2 failed\n"); + } + } + +#else // Other ESP32 int32_t adc_buf = 0; for (int i = 0; i < BATTERY_SENSE_SAMPLES; i++) { // ADC2 wifi bug workaround, see @@ -235,10 +266,18 @@ class AnalogBatteryLevel : public HasBatteryLevel SET_PERI_REG_MASK(SENS_SAR_READ_CTRL2_REG, SENS_SAR2_DATA_INV); adc2_get_raw(adc_channel, ADC_WIDTH_BIT_12, &adc_buf); raw += adc_buf; + raw_c++; } -#endif // BAT_MEASURE_ADC_UNIT - raw = raw / BATTERY_SENSE_SAMPLES; - return raw; +#endif + +#ifdef ADC_CTRL +#if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0) + digitalWrite(ADC_CTRL, HIGH); +#endif +#endif // End ADC_CTRL + +#endif // End BAT_MEASURE_ADC_UNIT + return (raw / (raw_c < 1 ? 1 : raw_c)); } #endif @@ -364,8 +403,11 @@ bool Power::analogInit() adc1_config_channel_atten(adc_channel, atten); #else // ADC2 adc2_config_channel_atten(adc_channel, atten); +#ifndef CONFIG_IDF_TARGET_ESP32S3 // ADC2 wifi bug workaround + // Not required with ESP32S3, breaks compile RTC_reg_b = READ_PERI_REG(SENS_SAR_READ_CTRL2_REG); +#endif #endif // calibrate ADC esp_adc_cal_value_t val_type = esp_adc_cal_characterize(unit, atten, width, DEFAULT_VREF, adc_characs); @@ -374,7 +416,14 @@ bool Power::analogInit() LOG_INFO("ADCmod: ADC characterization based on Two Point values stored in eFuse\n"); } else if (val_type == ESP_ADC_CAL_VAL_EFUSE_VREF) { LOG_INFO("ADCmod: ADC characterization based on reference voltage stored in eFuse\n"); - } else { + } +#ifdef CONFIG_IDF_TARGET_ESP32S3 + // ESP32S3 + else if (val_type == ESP_ADC_CAL_VAL_EFUSE_TP_FIT) { + LOG_INFO("ADCmod: ADC Characterization based on Two Point values and fitting curve coefficients stored in eFuse\n"); + } +#endif + else { LOG_INFO("ADCmod: ADC characterization based on default reference voltage\n"); } #if defined(HELTEC_V3) || defined(HELTEC_WSL_V3) diff --git a/variants/heltec_wireless_paper/variant.h b/variants/heltec_wireless_paper/variant.h index 4daf9a655..c2a030ed0 100644 --- a/variants/heltec_wireless_paper/variant.h +++ b/variants/heltec_wireless_paper/variant.h @@ -27,10 +27,12 @@ #define VEXT_ENABLE 45 // active low, powers the oled display and the lora antenna boost #define BUTTON_PIN 0 -#define BATTERY_PIN 1 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage -#define ADC_CHANNEL ADC1_GPIO1_CHANNEL -#define ADC_ATTENUATION ADC_ATTEN_DB_2_5 // lower dB for high resistance voltage divider -#define ADC_MULTIPLIER 4.9 +#define ADC_CTRL 19 +#define BATTERY_PIN 20 +#define ADC_CHANNEL ADC2_GPIO20_CHANNEL +#define ADC_MULTIPLIER 2 // Voltage divider is roughly 1:1 +#define BAT_MEASURE_ADC_UNIT 2 // Use ADC2 +#define ADC_ATTENUATION ADC_ATTEN_DB_11 // Voltage divider output is quite high #define USE_SX1262 diff --git a/variants/heltec_wireless_paper_v1/variant.h b/variants/heltec_wireless_paper_v1/variant.h index 7a4e54ca9..166b7f30e 100644 --- a/variants/heltec_wireless_paper_v1/variant.h +++ b/variants/heltec_wireless_paper_v1/variant.h @@ -35,10 +35,12 @@ #define VEXT_ENABLE 45 // active low, powers the oled display and the lora antenna boost #define BUTTON_PIN 0 -#define BATTERY_PIN 1 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage -#define ADC_CHANNEL ADC1_GPIO1_CHANNEL -#define ADC_ATTENUATION ADC_ATTEN_DB_2_5 // lower dB for high resistance voltage divider -#define ADC_MULTIPLIER 4.9 +#define ADC_CTRL 19 +#define BATTERY_PIN 20 +#define ADC_CHANNEL ADC2_GPIO20_CHANNEL +#define ADC_MULTIPLIER 2 // Voltage divider is roughly 1:1 +#define BAT_MEASURE_ADC_UNIT 2 // Use ADC2 +#define ADC_ATTENUATION ADC_ATTEN_DB_11 // Voltage divider output is quite high #define USE_SX1262 From d2a74a5329a7a87df876e6f942d9fc7aaac80b02 Mon Sep 17 00:00:00 2001 From: Ken McGuire Date: Wed, 14 Feb 2024 06:06:38 -0700 Subject: [PATCH 183/472] Phase 3 of the GPS rework (#3220) * Portduino multiple logging levels * Fixes based on GPSFan work * Fix derped logic * Correct size field for AID message * Reformat to add comments, beginning of GPS rework * Update PM2 message for Neo-6 * Correct ECO mode logic as ECO mode is only for Neo-6 * Cleanup ubx.h add a few more comments * GPS rework, changes for M8 and stub for M10 * Add VALSET commands for u-blox M10 receivers * Add VALSET commands for u-blox M10 receivers tweak M8 commands add comments for VALSET configuration commands * Add commands to init M10 receivers, tweak the M8 init sequence, this is a WIP as there are still some issues during init. Add M10 version of PMREQ. * Add wakeup source of uartrx to PMREQ_10 The M10 does not respond to commands when asleep, may need to do this for the M8 as well --------- Co-authored-by: Jonathan Bennett Co-authored-by: Ben Meadors --- src/gps/GPS.cpp | 161 ++++++++++++++++++++++++++++++++++++-------- src/gps/GPS.h | 16 +++++ src/gps/ubx.h | 175 +++++++++++++++++++++++++++++++++++++++++++++--- 3 files changed, 314 insertions(+), 38 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 02bca211b..addde4edd 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -358,87 +358,98 @@ bool GPS::setup() delay(1000); } } + // Disable Text Info messages + msglen = makeUBXPacket(0x06, 0x02, sizeof(_message_DISABLE_TXT_INFO), _message_DISABLE_TXT_INFO); + clearBuffer(); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x02, 500) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to disable text info messages.\n"); + } // ToDo add M10 tests for below if (strncmp(info.hwVersion, "00080000", 8) == 0) { msglen = makeUBXPacket(0x06, 0x39, sizeof(_message_JAM_8), _message_JAM_8); + clearBuffer(); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x39, 300) != GNSS_RESPONSE_OK) { + if (getACK(0x06, 0x39, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to enable interference resistance.\n"); } - clearBuffer(); + msglen = makeUBXPacket(0x06, 0x23, sizeof(_message_NAVX5_8), _message_NAVX5_8); + clearBuffer(); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x23, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to configure extra settings.\n"); + if (getACK(0x06, 0x23, 500) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to configure NAVX5_8 settings.\n"); } } else { msglen = makeUBXPacket(0x06, 0x39, sizeof(_message_JAM_6_7), _message_JAM_6_7); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x39, 300) != GNSS_RESPONSE_OK) { + if (getACK(0x06, 0x39, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to enable interference resistance.\n"); } msglen = makeUBXPacket(0x06, 0x23, sizeof(_message_NAVX5), _message_NAVX5); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x23, 300) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to configure extra settings.\n"); + if (getACK(0x06, 0x23, 500) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to configure NAVX5 settings.\n"); } } - // ublox-M10S can be compatible with UBLOX traditional protocol, so the following sentence settings are also valid + // Turn off unwanted NMEA messages, set update rate msglen = makeUBXPacket(0x06, 0x08, sizeof(_message_1HZ), _message_1HZ); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x08, 400) != GNSS_RESPONSE_OK) { + if (getACK(0x06, 0x08, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to set GPS update rate.\n"); } msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_GLL), _message_GLL); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { + if (getACK(0x06, 0x01, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to disable NMEA GLL.\n"); } msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_GSA), _message_GSA); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { + if (getACK(0x06, 0x01, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to Enable NMEA GSA.\n"); } msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_GSV), _message_GSV); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { + if (getACK(0x06, 0x01, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to disable NMEA GSV.\n"); } msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_VTG), _message_VTG); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { + if (getACK(0x06, 0x01, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to disable NMEA VTG.\n"); } msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_RMC), _message_RMC); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { + if (getACK(0x06, 0x01, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to enable NMEA RMC.\n"); } msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_GGA), _message_GGA); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { + if (getACK(0x06, 0x01, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to enable NMEA GGA.\n"); } - clearBuffer(); + if (uBloxProtocolVersion >= 18) { msglen = makeUBXPacket(0x06, 0x86, sizeof(_message_PMS), _message_PMS); + clearBuffer(); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x86, 300) != GNSS_RESPONSE_OK) { + if (getACK(0x06, 0x86, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to enable powersaving for GPS.\n"); } // For M8 we want to enable NMEA vserion 4.10 so we can see the additional sats. if (strncmp(info.hwVersion, "00080000", 8) == 0) { msglen = makeUBXPacket(0x06, 0x17, sizeof(_message_NMEA), _message_NMEA); + clearBuffer(); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x17, 400) != GNSS_RESPONSE_OK) { + if (getACK(0x06, 0x17, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to enable NMEA 4.10.\n"); } } @@ -447,23 +458,23 @@ bool GPS::setup() if (strncmp(info.hwVersion, "00040007", 8) == 0) { // This PSM mode is only for Neo-6 msglen = makeUBXPacket(0x06, 0x11, 0x2, _message_CFG_RXM_ECO); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x11, 300) != GNSS_RESPONSE_OK) { + if (getACK(0x06, 0x11, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to enable powersaving ECO mode for Neo-6.\n"); } - msglen = makeUBXPacket(0x06, 0x3B, 44, _message_CFG_PM2); + msglen = makeUBXPacket(0x06, 0x3B, sizeof(_message_CFG_PM2), _message_CFG_PM2); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x3B, 300) != GNSS_RESPONSE_OK) { + if (getACK(0x06, 0x3B, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to enable powersaving details for GPS.\n"); } msglen = makeUBXPacket(0x06, 0x01, sizeof(_message_AID), _message_AID); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) { + if (getACK(0x06, 0x01, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to disable UBX-AID.\n"); } } else { msglen = makeUBXPacket(0x06, 0x11, 0x2, _message_CFG_RXM_PSM); _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x11, 300) != GNSS_RESPONSE_OK) { + if (getACK(0x06, 0x11, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to enable powersaving mode for GPS.\n"); } } @@ -477,7 +488,96 @@ bool GPS::setup() LOG_INFO("GNSS module configuration saved!\n"); } } else { - LOG_INFO("u-blox M10 hardware found, using defaults for now\n"); + // LOG_INFO("u-blox M10 hardware found.\n"); + delay(1000); + // First disable all NMEA messages in RAM layer + msglen = makeUBXPacket(0x06, 0x8A, sizeof(_message_VALSET_DISABLE_NMEA_RAM), _message_VALSET_DISABLE_NMEA_RAM); + clearBuffer(); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x8A, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to disable NMEA messages for M10 GPS RAM.\n"); + } + delay(250); + // Next disable unwanted NMEA messages in BBR layer + msglen = makeUBXPacket(0x06, 0x8A, sizeof(_message_VALSET_DISABLE_NMEA_BBR), _message_VALSET_DISABLE_NMEA_BBR); + clearBuffer(); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x8A, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to disable NMEA messages for M10 GPS BBR.\n"); + } + delay(250); + // Disable Info txt messages in RAM layer + msglen = + makeUBXPacket(0x06, 0x8A, sizeof(_message_VALSET_DISABLE_TXT_INFO_RAM), _message_VALSET_DISABLE_TXT_INFO_RAM); + clearBuffer(); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x8A, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to disable Info messages for M10 GPS RAM.\n"); + } + delay(250); + // Next disable Info txt messages in BBR layer + msglen = + makeUBXPacket(0x06, 0x8A, sizeof(_message_VALSET_DISABLE_TXT_INFO_BBR), _message_VALSET_DISABLE_TXT_INFO_BBR); + clearBuffer(); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x8A, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to disable Info messages for M10 GPS BBR.\n"); + } + // Do M10 configuration for Power Management. + + msglen = makeUBXPacket(0x06, 0x8A, sizeof(_message_VALSET_PM_RAM), _message_VALSET_PM_RAM); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x8A, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable powersaving for M10 GPS RAM.\n"); + } + msglen = makeUBXPacket(0x06, 0x8A, sizeof(_message_VALSET_PM_BBR), _message_VALSET_PM_BBR); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x8A, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable powersaving for M10 GPS BBR.\n"); + } + + delay(250); + msglen = makeUBXPacket(0x06, 0x8A, sizeof(_message_VALSET_ITFM_RAM), _message_VALSET_ITFM_RAM); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x8A, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable Jamming detection M10 GPS RAM.\n"); + } + msglen = makeUBXPacket(0x06, 0x8A, sizeof(_message_VALSET_ITFM_BBR), _message_VALSET_ITFM_BBR); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x8A, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable Jamming detection M10 GPS BBR.\n"); + } + + // Here is where the init commands should go to do further M10 initialization. + delay(250); + msglen = makeUBXPacket(0x06, 0x8A, sizeof(_message_VALSET_DISABLE_SBAS_RAM), _message_VALSET_DISABLE_SBAS_RAM); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x8A, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to disable SBAS M10 GPS RAM.\n"); + } + delay(750); // will cause a receiver restart so wait a bit + msglen = makeUBXPacket(0x06, 0x8A, sizeof(_message_VALSET_DISABLE_SBAS_BBR), _message_VALSET_DISABLE_SBAS_BBR); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x8A, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to disable SBAS M10 GPS BBR.\n"); + } + delay(750); // will cause a receiver restart so wait a bit + // Done with initialization, Now enable wanted NMEA messages in BBR layer so they will survive a periodic sleep. + msglen = makeUBXPacket(0x06, 0x8A, sizeof(_message_VALSET_ENABLE_NMEA_BBR), _message_VALSET_ENABLE_NMEA_BBR); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x8A, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable messages for M10 GPS BBR.\n"); + } + delay(250); + // Next enable wanted NMEA messages in RAM layer + msglen = makeUBXPacket(0x06, 0x8A, sizeof(_message_VALSET_ENABLE_NMEA_RAM), _message_VALSET_ENABLE_NMEA_RAM); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x8A, 300) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable messages for M10 GPS RAM.\n"); + } + // As the M10 has no flash, the best we can do to preserve the config is to set it in RAM and BBR. + // BBR will survive a restart, and power off for a while, but modules with small backup + // batteries or super caps will not retain the config for a long power off time. } } didSerialInit = true; @@ -547,10 +647,17 @@ void GPS::setGPSPower(bool on, bool standbyOnly, uint32_t sleepTime) if (gnssModel == GNSS_MODEL_UBLOX) { uint8_t msglen; LOG_DEBUG("Sleep Time: %i\n", sleepTime); - for (int i = 0; i < 4; i++) { - gps->_message_PMREQ[0 + i] = sleepTime >> (i * 8); // Encode the sleep time in millis into the packet + if (strncmp(info.hwVersion, "000A0000", 8) != 0) { + for (int i = 0; i < 4; i++) { + gps->_message_PMREQ[0 + i] = sleepTime >> (i * 8); // Encode the sleep time in millis into the packet + } + msglen = gps->makeUBXPacket(0x02, 0x41, sizeof(_message_PMREQ), gps->_message_PMREQ); + } else { + for (int i = 0; i < 4; i++) { + gps->_message_PMREQ_10[4 + i] = sleepTime >> (i * 8); // Encode the sleep time in millis into the packet + } + msglen = gps->makeUBXPacket(0x02, 0x41, sizeof(_message_PMREQ_10), gps->_message_PMREQ_10); } - msglen = gps->makeUBXPacket(0x02, 0x41, 0x08, gps->_message_PMREQ); gps->_serial_gps->write(gps->UBXscratch, msglen); } } else { diff --git a/src/gps/GPS.h b/src/gps/GPS.h index 15c355add..77e1d8042 100644 --- a/src/gps/GPS.h +++ b/src/gps/GPS.h @@ -106,6 +106,7 @@ class GPS : private concurrency::OSThread static const uint8_t _message_NAVX5[]; static const uint8_t _message_NAVX5_8[]; static const uint8_t _message_NMEA[]; + static const uint8_t _message_DISABLE_TXT_INFO[]; static const uint8_t _message_1HZ[]; static const uint8_t _message_GLL[]; static const uint8_t _message_GSA[]; @@ -117,6 +118,21 @@ class GPS : private concurrency::OSThread static const uint8_t _message_PMS[]; static const uint8_t _message_SAVE[]; + // VALSET Commands for M10 + static const uint8_t _message_VALSET_PM[]; + static const uint8_t _message_VALSET_PM_RAM[]; + static const uint8_t _message_VALSET_PM_BBR[]; + static const uint8_t _message_VALSET_ITFM_RAM[]; + static const uint8_t _message_VALSET_ITFM_BBR[]; + static const uint8_t _message_VALSET_DISABLE_NMEA_RAM[]; + static const uint8_t _message_VALSET_DISABLE_NMEA_BBR[]; + static const uint8_t _message_VALSET_DISABLE_TXT_INFO_RAM[]; + static const uint8_t _message_VALSET_DISABLE_TXT_INFO_BBR[]; + static const uint8_t _message_VALSET_ENABLE_NMEA_RAM[]; + static const uint8_t _message_VALSET_ENABLE_NMEA_BBR[]; + static const uint8_t _message_VALSET_DISABLE_SBAS_RAM[]; + static const uint8_t _message_VALSET_DISABLE_SBAS_BBR[]; + meshtastic_Position p = meshtastic_Position_init_default; GPS() : concurrency::OSThread("GPS") {} diff --git a/src/gps/ubx.h b/src/gps/ubx.h index 4fff51d52..28f9573bf 100644 --- a/src/gps/ubx.h +++ b/src/gps/ubx.h @@ -1,16 +1,16 @@ +// Power Management + uint8_t GPS::_message_PMREQ[] PROGMEM = { - 0x00, 0x00, // 4 bytes duration of request task - 0x00, 0x00, // (milliseconds) - 0x02, 0x00, // Task flag bitfield - 0x00, 0x00, // byte index 1 = sleep mode + 0x00, 0x00, 0x00, 0x00, // 4 bytes duration of request task (milliseconds) + 0x02, 0x00, 0x00, 0x00 // Bitfield, set backup = 1 }; uint8_t GPS::_message_PMREQ_10[] PROGMEM = { - 0x00, 0x00, // 4 bytes duration of request task - 0x00, 0x00, // (milliseconds) - 0x02, 0x00, // Task flag bitfield - 0x00, 0x00, // byte index 1 = sleep mode - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 // wakeupSources + 0x00, // version (0 for this version) + 0x00, 0x00, 0x00, // Reserved 1 + 0x00, 0x00, 0x00, 0x00, // 4 bytes duration of request task (milliseconds) + 0x06, 0x00, 0x00, 0x00, // Bitfield, set backup =1 and force =1 + 0x08, 0x00, 0x00, 0x00 // wakeupSources Wake on uartrx }; const uint8_t GPS::_message_CFG_RXM_PSM[] PROGMEM = { @@ -46,6 +46,9 @@ const uint8_t GPS::_message_CFG_PM2[] PROGMEM = { 0x00, 0x00, 0x00, 0x00 // 0x64, 0x40, 0x01, 0x00 // reserved 11 }; +// Constallation setup, none required for Neo-6 + +// For Neo-7 GPS & SBAS const uint8_t GPS::_message_GNSS_7[] = { 0x00, // msgVer (0 for this version) 0x00, // numTrkChHw (max number of hardware channels, read only, so it's always 0) @@ -272,6 +275,20 @@ const uint8_t GPS::_message_AID[] = { 0x00 // Reserved }; +// Turn off TEXT INFO Messages for all but M10 series + +// B5 62 06 02 0A 00 01 00 00 00 03 03 00 03 03 00 1F 20 +const uint8_t GPS::_message_DISABLE_TXT_INFO[] = { + 0x01, // Protocol ID for NMEA + 0x00, 0x00, 0x00, // Reserved + 0x03, // I2C + 0x03, // I/O Port 1 + 0x00, // I/O Port 2 + 0x03, // USB + 0x03, // SPI + 0x00 // Reserved +}; + // The Power Management configuration allows the GPS module to operate in different power modes for optimized // power consumption. The modes supported are: 0x00 = Full power: The module operates at full power with no power // saving. 0x01 = Balanced: The module dynamically adjusts the tracking behavior to balance power consumption. @@ -283,7 +300,7 @@ const uint8_t GPS::_message_AID[] = { // is set to Interval; otherwise, it must be set to '0'. The 'onTime' field specifies the duration of the ON phase // and must be smaller than the period. It is only valid when the powerSetupValue is set to Interval; otherwise, // it must be set to '0'. -// This command applies to M8 and higher products +// This command applies to M8 products const uint8_t GPS::_message_PMS[] = { 0x00, // Version (0) 0x03, // Power setup value 3 = Agresssive 1Hz @@ -297,4 +314,140 @@ const uint8_t GPS::_message_SAVE[] = { 0xFF, 0xFF, 0x00, 0x00, // saveMask: save all sections 0x00, 0x00, 0x00, 0x00, // loadMask: no sections loaded 0x17 // deviceMask: BBR, Flash, EEPROM, and SPI Flash -}; \ No newline at end of file +}; + +// As the M10 has no flash, the best we can do to preserve the config is to set it in RAM and BBR. +// BBR will survive a restart, and power off for a while, but modules with small backup +// batteries or super caps will not retain the config for a long power off time. + +// VALSET Commands for M10 +// Please refer to the M10 Protocol Specification: +// https://content.u-blox.com/sites/default/files/u-blox-M10-SPG-5.10_InterfaceDescription_UBX-21035062.pdf +// Where the VALSET/VALGET/VALDEL commands are described in detail. +// and: +// https://content.u-blox.com/sites/default/files/u-blox-M10-ROM-5.10_ReleaseNotes_UBX-22001426.pdf +// for interesting insights. +/* +CFG-PM2 has been replaced by many CFG-PM commands +OPERATEMODE E1 2 (0 | 1 | 2) +POSUPDATEPERIOD U4 1000ms for M10 must be >= 5s try 5 +ACQPERIOD U4 10 seems ok for M10 def ok +GRIDOFFSET U4 0 seems ok for M10 def ok +ONTIME U2 1 will try 1 +MINACQTIME U1 0 will try 0 def ok +MAXACQTIME U1 stick with default of 0 def ok +DONOTENTEROFF L 1 stay at 1 +WAITTIMEFIX L 1 stay with 1 +UPDATEEPH L 1 changed to 1 for gps rework default is 1 +EXTINTWAKE L 0 no ext ints +EXTINTBACKUP L 0 no ext ints +EXTINTINACTIVE L 0 no ext ints +EXTINTACTIVITY U4 0 no ext ints +LIMITPEAKCURRENT L 1 stay with 1 +*/ +// CFG-PMS has been removed + +// Ram layer config message: +// b5 62 06 8a 26 00 00 01 00 00 01 00 d0 20 02 02 00 d0 40 05 00 00 00 05 00 d0 30 01 00 08 00 d0 10 01 09 00 d0 10 01 10 00 d0 +// 10 01 8b de + +// BBR layer config message: +// b5 62 06 8a 26 00 00 02 00 00 01 00 d0 20 02 02 00 d0 40 05 00 00 00 05 00 d0 30 01 00 08 00 d0 10 01 09 00 d0 10 01 10 00 d0 +// 10 01 8c 03 + +const uint8_t GPS::_message_VALSET_PM_RAM[] = {0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0xd0, 0x20, 0x02, 0x02, 0x00, 0xd0, 0x40, + 0x05, 0x00, 0x00, 0x00, 0x05, 0x00, 0xd0, 0x30, 0x01, 0x00, 0x08, 0x00, 0xd0, + 0x10, 0x01, 0x09, 0x00, 0xd0, 0x10, 0x01, 0x10, 0x00, 0xd0, 0x10, 0x01}; +const uint8_t GPS::_message_VALSET_PM_BBR[] = {0x00, 0x02, 0x00, 0x00, 0x01, 0x00, 0xd0, 0x20, 0x02, 0x02, 0x00, 0xd0, 0x40, + 0x05, 0x00, 0x00, 0x00, 0x05, 0x00, 0xd0, 0x30, 0x01, 0x00, 0x08, 0x00, 0xd0, + 0x10, 0x01, 0x09, 0x00, 0xd0, 0x10, 0x01, 0x10, 0x00, 0xd0, 0x10, 0x01}; + +/* +CFG-ITFM replaced by 5 valset messages which can be combined into one for RAM and one for BBR + +20410001 bbthreshold U1 3 +20410002 cwthreshold U1 15 +1041000d enable L 0 -> 1 +20410010 ant E1 0 +10410013 enable aux L 0 -> 1 + + +b5 62 06 8a 0e 00 00 01 00 00 0d 00 41 10 01 13 00 41 10 01 63 c6 +*/ +const uint8_t GPS::_message_VALSET_ITFM_RAM[] = {0x00, 0x01, 0x00, 0x00, 0x0d, 0x00, 0x41, + 0x10, 0x01, 0x13, 0x00, 0x41, 0x10, 0x01}; +const uint8_t GPS::_message_VALSET_ITFM_BBR[] = {0x00, 0x02, 0x00, 0x00, 0x0d, 0x00, 0x41, + 0x10, 0x01, 0x13, 0x00, 0x41, 0x10, 0x01}; + +// Turn off all NMEA messages: +// Ram layer config message: +// b5 62 06 8a 22 00 00 01 00 00 c0 00 91 20 00 ca 00 91 20 00 c5 00 91 20 00 ac 00 91 20 00 b1 00 91 20 00 bb 00 91 20 00 40 8f + +// Disable GLL, GSV, VTG messages in BBR layer +// BBR layer config message: +// b5 62 06 8a 13 00 00 02 00 00 ca 00 91 20 00 c5 00 91 20 00 b1 00 91 20 00 f8 4e + +const uint8_t GPS::_message_VALSET_DISABLE_NMEA_RAM[] = { + /*0x00, 0x01, 0x00, 0x00, 0xca, 0x00, 0x91, 0x20, 0x00, 0xc5, 0x00, 0x91, 0x20, 0x00, 0xb1, 0x00, 0x91, 0x20, 0x00 */ + 0x00, 0x01, 0x00, 0x00, 0xc0, 0x00, 0x91, 0x20, 0x00, 0xca, 0x00, 0x91, 0x20, 0x00, 0xc5, 0x00, 0x91, + 0x20, 0x00, 0xac, 0x00, 0x91, 0x20, 0x00, 0xb1, 0x00, 0x91, 0x20, 0x00, 0xbb, 0x00, 0x91, 0x20, 0x00}; + +const uint8_t GPS::_message_VALSET_DISABLE_NMEA_BBR[] = {0x00, 0x02, 0x00, 0x00, 0xca, 0x00, 0x91, 0x20, 0x00, 0xc5, + 0x00, 0x91, 0x20, 0x00, 0xb1, 0x00, 0x91, 0x20, 0x00}; + +// Turn off text info messages: +// Ram layer config message: +// b5 62 06 8a 09 00 00 01 00 00 07 00 92 20 06 59 50 + +// BBR layer config message: +// b5 62 06 8a 09 00 00 02 00 00 07 00 92 20 06 5a 58 + +// Turn NMEA GSA, GGA, RMC messages on: +// Ram layer config message: +// b5 62 06 8a 13 00 00 01 00 00 c0 00 91 20 01 bb 00 91 20 01 ac 00 91 20 01 e1 3b + +// BBR layer config message: +// b5 62 06 8a 13 00 00 02 00 00 c0 00 91 20 01 bb 00 91 20 01 ac 00 91 20 01 e2 4d + +const uint8_t GPS::_message_VALSET_DISABLE_TXT_INFO_RAM[] = {0x00, 0x01, 0x00, 0x00, 0x07, 0x00, 0x92, 0x20, 0x03}; +const uint8_t GPS::_message_VALSET_DISABLE_TXT_INFO_BBR[] = {0x00, 0x02, 0x00, 0x00, 0x07, 0x00, 0x92, 0x20, 0x03}; +const uint8_t GPS::_message_VALSET_ENABLE_NMEA_RAM[] = {0x00, 0x01, 0x00, 0x00, 0xc0, 0x00, 0x91, 0x20, 0x01, 0xbb, + 0x00, 0x91, 0x20, 0x01, 0xac, 0x00, 0x91, 0x20, 0x01}; +const uint8_t GPS::_message_VALSET_ENABLE_NMEA_BBR[] = {0x00, 0x02, 0x00, 0x00, 0xc0, 0x00, 0x91, 0x20, 0x01, 0xbb, + 0x00, 0x91, 0x20, 0x01, 0xac, 0x00, 0x91, 0x20, 0x01}; +const uint8_t GPS::_message_VALSET_DISABLE_SBAS_RAM[] = {0x00, 0x01, 0x00, 0x00, 0x20, 0x00, 0x31, + 0x10, 0x00, 0x05, 0x00, 0x31, 0x10, 0x00}; +const uint8_t GPS::_message_VALSET_DISABLE_SBAS_BBR[] = {0x00, 0x02, 0x00, 0x00, 0x20, 0x00, 0x31, + 0x10, 0x00, 0x05, 0x00, 0x31, 0x10, 0x00}; +/* +Operational issues with the M10: + +PowerSave doesn't work with SBAS, seems like you can have SBAS enabled, but it will never lock +onto the SBAS sats. +PowerSave doesn't work with BDS B1C, u-blox says use B1l instead. +BDS B1l cannot be enabled with BDS B1C or GLONASS L1OF, so GLONASS will work with B1C, but not B1l +So no powersave with GLONASS and BDS B1l enabled. +So disable GLONASS and use BDS B1l, which is part of the default M10 config. + +GNSS configuration: + +Default GNSS configuration is: GPS, Galileo, BDS B1l, with QZSS and SBAS enabled. +The PMREQ puts the receiver to sleep and wakeup re-acquires really fast and seems to not need +the PM config. Lets try without it. +PMREQ sort of works with SBAS, but the awake time is too short to re-acquire any SBAS sats. +The defination of "Got Fix" doesn't seem to include SBAS. Much more too this... +Even if it was, it can take minutes (up to 12.5), +even under good sat visability conditions to re-acquire the SBAS data. + +Another effect fo the quick transition to sleep is that no other sats will be acquired so the +sat count will tend to remain at what the initial fix was. +*/ + +// GNSS disable SBAS as recommended by u-blox if using GNSS defaults and power save mode +/* +Ram layer config message: +b5 62 06 8a 0e 00 00 01 00 00 20 00 31 10 00 05 00 31 10 00 46 87 + +BBR layer config message: +b5 62 06 8a 0e 00 00 02 00 00 20 00 31 10 00 05 00 31 10 00 47 94 +*/ \ No newline at end of file From d9bd9bdfb0eb4989e680f4a2d97b1c2ca83dbb7a Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Wed, 14 Feb 2024 14:07:20 +0100 Subject: [PATCH 184/472] StoreForward updates (#3194) * StoreForward updates - Send history in "text" variant - Don't send history the client already got - Check if PSRAM is full - More sensible defaults * Set `TEXT_BROADCAST` or `TEXT_DIRECT` RequestResponse tag * feat: E-Ink "Dynamic Partial" (#3193) Use a mixture of full refresh, partial refresh, and skipped updates, balancing urgency and display health. Co-authored-by: Ben Meadors * [create-pull-request] automated change (#3209) Co-authored-by: thebentern * Reset `last_index` if history was cleared, e.g. by reboot --------- Co-authored-by: Ben Meadors Co-authored-by: todd-herbert Co-authored-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: thebentern Co-authored-by: Garth Vander Houwen --- src/modules/esp32/StoreForwardModule.cpp | 93 +++++++++++++----------- src/modules/esp32/StoreForwardModule.h | 21 +++--- 2 files changed, 61 insertions(+), 53 deletions(-) diff --git a/src/modules/esp32/StoreForwardModule.cpp b/src/modules/esp32/StoreForwardModule.cpp index 6b2c079cc..93472b8b1 100644 --- a/src/modules/esp32/StoreForwardModule.cpp +++ b/src/modules/esp32/StoreForwardModule.cpp @@ -38,16 +38,11 @@ int32_t StoreForwardModule::runOnce() // Only send packets if the channel is less than 25% utilized. if (airTime->isTxAllowedChannelUtil(true)) { storeForwardModule->sendPayload(this->busyTo, this->packetHistoryTXQueue_index); - if (this->packetHistoryTXQueue_index == packetHistoryTXQueue_size) { - // Tell the client we're done sending - meshtastic_StoreAndForward sf = meshtastic_StoreAndForward_init_zero; - sf.rr = meshtastic_StoreAndForward_RequestResponse_ROUTER_PING; - storeForwardModule->sendMessage(this->busyTo, sf); - LOG_INFO("*** S&F - Done. (ROUTER_PING)\n"); + if (this->packetHistoryTXQueue_index < packetHistoryTXQueue_size - 1) { + this->packetHistoryTXQueue_index++; + } else { this->packetHistoryTXQueue_index = 0; this->busy = false; - } else { - this->packetHistoryTXQueue_index++; } } } else if ((millis() - lastHeartbeat > (heartbeatInterval * 1000)) && airTime->isTxAllowedChannelUtil(true)) { @@ -56,7 +51,7 @@ int32_t StoreForwardModule::runOnce() meshtastic_StoreAndForward sf = meshtastic_StoreAndForward_init_zero; sf.rr = meshtastic_StoreAndForward_RequestResponse_ROUTER_HEARTBEAT; sf.which_variant = meshtastic_StoreAndForward_heartbeat_tag; - sf.variant.heartbeat.period = 300; + sf.variant.heartbeat.period = heartbeatInterval; sf.variant.heartbeat.secondary = 0; // TODO we always have one primary router for now storeForwardModule->sendMessage(NODENUM_BROADCAST, sf); } @@ -101,10 +96,11 @@ void StoreForwardModule::populatePSRAM() * * @param msAgo The number of milliseconds ago from which to start sending messages. * @param to The recipient ID to send the messages to. + * @param last_request_index The index in the packet history of the last request from this node. */ -void StoreForwardModule::historySend(uint32_t msAgo, uint32_t to) +void StoreForwardModule::historySend(uint32_t msAgo, uint32_t to, uint32_t last_request_index) { - uint32_t queueSize = storeForwardModule->historyQueueCreate(msAgo, to); + uint32_t queueSize = storeForwardModule->historyQueueCreate(msAgo, to, &last_request_index); if (queueSize) { LOG_INFO("*** S&F - Sending %u message(s)\n", queueSize); @@ -118,6 +114,7 @@ void StoreForwardModule::historySend(uint32_t msAgo, uint32_t to) sf.which_variant = meshtastic_StoreAndForward_history_tag; sf.variant.history.history_messages = queueSize; sf.variant.history.window = msAgo; + sf.variant.history.last_request = last_request_index; storeForwardModule->sendMessage(to, sf); } @@ -125,15 +122,18 @@ void StoreForwardModule::historySend(uint32_t msAgo, uint32_t to) * Creates a new history queue with messages that were received within the specified time frame. * * @param msAgo The number of milliseconds ago to start the history queue. - * @param to The maximum number of messages to include in the history queue. + * @param to The NodeNum of the recipient. + * @param last_request_index The index in the packet history of the last request from this node. * @return The ID of the newly created history queue. */ -uint32_t StoreForwardModule::historyQueueCreate(uint32_t msAgo, uint32_t to) +uint32_t StoreForwardModule::historyQueueCreate(uint32_t msAgo, uint32_t to, uint32_t *last_request_index) { this->packetHistoryTXQueue_size = 0; + // If our history was cleared, ignore what the client is telling us + uint32_t last_index = *last_request_index >= this->packetHistoryCurrent ? 0 : *last_request_index; - for (int i = 0; i < this->packetHistoryCurrent; i++) { + for (int i = last_index; i < this->packetHistoryCurrent; i++) { /* LOG_DEBUG("SF historyQueueCreate\n"); LOG_DEBUG("SF historyQueueCreate - time %d\n", this->packetHistory[i].time); @@ -141,16 +141,11 @@ uint32_t StoreForwardModule::historyQueueCreate(uint32_t msAgo, uint32_t to) LOG_DEBUG("SF historyQueueCreate - math %d\n", (millis() - msAgo)); */ if (this->packetHistory[i].time && (this->packetHistory[i].time < (millis() - msAgo))) { - LOG_DEBUG("*** SF historyQueueCreate - Time matches - ok\n"); - /* - Copy the messages that were received by the router in the last msAgo + /* Copy the messages that were received by the router in the last msAgo to the packetHistoryTXQueue structure. - - TODO: The condition (this->packetHistory[i].to & NODENUM_BROADCAST) == to) is not tested since - I don't have an easy way to target a specific user. Will need to do this soon. - */ - if ((this->packetHistory[i].to & NODENUM_BROADCAST) == NODENUM_BROADCAST || - ((this->packetHistory[i].to & NODENUM_BROADCAST) == to)) { + Client not interested in packets from itself and only in broadcast packets or packets towards it. */ + if (this->packetHistory[i].from != to && + (this->packetHistory[i].to == NODENUM_BROADCAST || this->packetHistory[i].to == to)) { this->packetHistoryTXQueue[this->packetHistoryTXQueue_size].time = this->packetHistory[i].time; this->packetHistoryTXQueue[this->packetHistoryTXQueue_size].to = this->packetHistory[i].to; this->packetHistoryTXQueue[this->packetHistoryTXQueue_size].from = this->packetHistory[i].from; @@ -159,9 +154,10 @@ uint32_t StoreForwardModule::historyQueueCreate(uint32_t msAgo, uint32_t to) memcpy(this->packetHistoryTXQueue[this->packetHistoryTXQueue_size].payload, this->packetHistory[i].payload, meshtastic_Constants_DATA_PAYLOAD_LEN); this->packetHistoryTXQueue_size++; + *last_request_index = i + 1; // Set to one higher such that we don't send the same message again - LOG_DEBUG("*** PacketHistoryStruct time=%d\n", this->packetHistory[i].time); - LOG_DEBUG("*** PacketHistoryStruct msg=%s\n", this->packetHistory[i].payload); + LOG_DEBUG("*** PacketHistoryStruct time=%d, msg=%s\n", this->packetHistory[i].time, + this->packetHistory[i].payload); } } } @@ -177,15 +173,20 @@ void StoreForwardModule::historyAdd(const meshtastic_MeshPacket &mp) { const auto &p = mp.decoded; - this->packetHistory[this->packetHistoryCurrent].time = millis(); - this->packetHistory[this->packetHistoryCurrent].to = mp.to; - this->packetHistory[this->packetHistoryCurrent].channel = mp.channel; - this->packetHistory[this->packetHistoryCurrent].from = mp.from; - this->packetHistory[this->packetHistoryCurrent].payload_size = p.payload.size; - memcpy(this->packetHistory[this->packetHistoryCurrent].payload, p.payload.bytes, meshtastic_Constants_DATA_PAYLOAD_LEN); + if (this->packetHistoryCurrent < this->records) { + this->packetHistory[this->packetHistoryCurrent].time = millis(); + this->packetHistory[this->packetHistoryCurrent].to = mp.to; + this->packetHistory[this->packetHistoryCurrent].channel = mp.channel; + this->packetHistory[this->packetHistoryCurrent].from = mp.from; + this->packetHistory[this->packetHistoryCurrent].payload_size = p.payload.size; + memcpy(this->packetHistory[this->packetHistoryCurrent].payload, p.payload.bytes, meshtastic_Constants_DATA_PAYLOAD_LEN); - this->packetHistoryCurrent++; - this->packetHistoryMax++; + this->packetHistoryCurrent++; + this->packetHistoryMax++; + } else { + // TODO: Overwrite the oldest message in the history buffer when it is full. + LOG_WARN("*** S&F - PSRAM Full. Packet is not added to the history.\n"); + } } meshtastic_MeshPacket *StoreForwardModule::allocReply() @@ -213,10 +214,19 @@ void StoreForwardModule::sendPayload(NodeNum dest, uint32_t packetHistory_index) // TODO: Make this configurable. p->want_ack = false; - p->decoded.payload.size = - this->packetHistoryTXQueue[packetHistory_index].payload_size; // You must specify how many bytes are in the reply - memcpy(p->decoded.payload.bytes, this->packetHistoryTXQueue[packetHistory_index].payload, + meshtastic_StoreAndForward sf = meshtastic_StoreAndForward_init_zero; + sf.which_variant = meshtastic_StoreAndForward_text_tag; + sf.variant.text.size = this->packetHistoryTXQueue[packetHistory_index].payload_size; + memcpy(sf.variant.text.bytes, this->packetHistoryTXQueue[packetHistory_index].payload, this->packetHistoryTXQueue[packetHistory_index].payload_size); + if (this->packetHistoryTXQueue[packetHistory_index].to == NODENUM_BROADCAST) { + sf.rr = meshtastic_StoreAndForward_RequestResponse_ROUTER_TEXT_BROADCAST; + } else { + sf.rr = meshtastic_StoreAndForward_RequestResponse_ROUTER_TEXT_DIRECT; + } + + p->decoded.payload.size = + pb_encode_to_bytes(p->decoded.payload.bytes, sizeof(p->decoded.payload.bytes), &meshtastic_StoreAndForward_msg, &sf); service.sendToMesh(p); } @@ -387,7 +397,9 @@ bool StoreForwardModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, LOG_INFO("*** S&F - Busy. Try again shortly.\n"); } else { if ((p->which_variant == meshtastic_StoreAndForward_history_tag) && (p->variant.history.window > 0)) { - storeForwardModule->historySend(p->variant.history.window * 60000, getFrom(&mp)); // window is in minutes + // window is in minutes + storeForwardModule->historySend(p->variant.history.window * 60000, getFrom(&mp), + p->variant.history.last_request); } else { storeForwardModule->historySend(historyReturnWindow * 60000, getFrom(&mp)); // defaults to 4 hours } @@ -406,8 +418,7 @@ bool StoreForwardModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, case meshtastic_StoreAndForward_RequestResponse_CLIENT_PONG: if (is_server) { LOG_INFO("*** StoreAndForward_RequestResponse_CLIENT_PONG\n"); - // The Client is alive, update NodeDB - nodeDB.updateFrom(mp); + // NodeDB is already updated } break; @@ -546,9 +557,7 @@ StoreForwardModule::StoreForwardModule() } // Client - } - if ((config.device.role == meshtastic_Config_DeviceConfig_Role_CLIENT) || - (config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER_CLIENT)) { + } else { is_client = true; LOG_INFO("*** Initializing Store & Forward Module in Client mode\n"); } diff --git a/src/modules/esp32/StoreForwardModule.h b/src/modules/esp32/StoreForwardModule.h index 806f0a836..b04d9ef84 100644 --- a/src/modules/esp32/StoreForwardModule.h +++ b/src/modules/esp32/StoreForwardModule.h @@ -13,7 +13,6 @@ struct PacketHistoryStruct { uint32_t to; uint32_t from; uint8_t channel; - bool ack; uint8_t payload[meshtastic_Constants_DATA_PAYLOAD_LEN]; pb_size_t payload_size; }; @@ -32,7 +31,7 @@ class StoreForwardModule : private concurrency::OSThread, public ProtobufModule< uint32_t packetHistoryTXQueue_size = 0; uint32_t packetHistoryTXQueue_index = 0; - uint32_t packetTimeMax = 5000; + uint32_t packetTimeMax = 5000; // Interval between sending history packets as a server. bool is_client = false; bool is_server = false; @@ -41,7 +40,7 @@ class StoreForwardModule : private concurrency::OSThread, public ProtobufModule< StoreForwardModule(); unsigned long lastHeartbeat = 0; - uint32_t heartbeatInterval = 300; + uint32_t heartbeatInterval = default_broadcast_interval_secs; /** Update our local reference of when we last saw that node. @@ -49,9 +48,9 @@ class StoreForwardModule : private concurrency::OSThread, public ProtobufModule< */ void historyAdd(const meshtastic_MeshPacket &mp); void statsSend(uint32_t to); - void historySend(uint32_t msAgo, uint32_t to); + void historySend(uint32_t msAgo, uint32_t to, uint32_t last_request_index = 0); - uint32_t historyQueueCreate(uint32_t msAgo, uint32_t to); + uint32_t historyQueueCreate(uint32_t msAgo, uint32_t to, uint32_t *last_request_index); /** * Send our payload into the mesh @@ -79,16 +78,16 @@ class StoreForwardModule : private concurrency::OSThread, public ProtobufModule< void populatePSRAM(); // S&F Defaults - uint32_t historyReturnMax = 250; // 250 records - uint32_t historyReturnWindow = 240; // 4 hours + uint32_t historyReturnMax = 25; // Return maximum of 25 records by default. + uint32_t historyReturnWindow = 240; // Return history of last 4 hours by default. uint32_t records = 0; // Calculated bool heartbeat = false; // No heartbeat. // stats - uint32_t requests = 0; - uint32_t requests_history = 0; + uint32_t requests = 0; // Number of times any client sent a request to the S&F. + uint32_t requests_history = 0; // Number of times the history was requested. - uint32_t retry_delay = 0; + uint32_t retry_delay = 0; // If server is busy, retry after this delay (in ms). protected: virtual int32_t runOnce() override; @@ -102,4 +101,4 @@ class StoreForwardModule : private concurrency::OSThread, public ProtobufModule< virtual bool handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_StoreAndForward *p); }; -extern StoreForwardModule *storeForwardModule; +extern StoreForwardModule *storeForwardModule; \ No newline at end of file From 007ecd06041bae35e456b8a8f316178702886c8a Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 14 Feb 2024 07:23:55 -0600 Subject: [PATCH 185/472] Update protos --- protobufs | 2 +- src/mesh/generated/meshtastic/config.pb.h | 52 ++++++++++--------- src/mesh/generated/meshtastic/deviceonly.pb.h | 2 +- src/mesh/generated/meshtastic/localonly.pb.h | 2 +- src/mesh/generated/meshtastic/mesh.pb.h | 2 +- 5 files changed, 32 insertions(+), 28 deletions(-) diff --git a/protobufs b/protobufs index 388fd79bf..4432d3bfc 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 388fd79bf78df2c59dd0bdd029a382fa91b1cd88 +Subproject commit 4432d3bfc155107e27079d96ddba16b52f2d9ea3 diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index 4047f7367..445ef7e1b 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -12,46 +12,45 @@ /* Enum definitions */ /* Defines the device's role on the Mesh network */ typedef enum _meshtastic_Config_DeviceConfig_Role { - /* Client device role */ + /* Description: App connected or stand alone messaging device. + Technical Details: Default Role */ meshtastic_Config_DeviceConfig_Role_CLIENT = 0, - /* Client Mute device role - Same as a client except packets will not hop over this node, does not contribute to routing packets for mesh. */ + /* Description: Device that does not forward packets from other devices. */ meshtastic_Config_DeviceConfig_Role_CLIENT_MUTE = 1, - /* Router device role. - Mesh packets will prefer to be routed over this node. This node will not be used by client apps. - The wifi/ble radios and the oled screen will be put to sleep. + /* Description: Infrastructure node for extending network coverage by relaying messages. Visible in Nodes list. + Technical Details: Mesh packets will prefer to be routed over this node. This node will not be used by client apps. + The wifi radio and the oled screen will be put to sleep. This mode may still potentially have higher power usage due to it's preference in message rebroadcasting on the mesh. */ meshtastic_Config_DeviceConfig_Role_ROUTER = 2, - /* Router Client device role - Mesh packets will prefer to be routed over this node. The Router Client can be used as both a Router and an app connected Client. */ + /* Description: Combination of both ROUTER and CLIENT. Not for mobile devices. */ meshtastic_Config_DeviceConfig_Role_ROUTER_CLIENT = 3, - /* Repeater device role - Mesh packets will simply be rebroadcasted over this node. Nodes configured with this role will not originate NodeInfo, Position, Telemetry + /* Description: Infrastructure node for extending network coverage by relaying messages with minimal overhead. Not visible in Nodes list. + Technical Details: Mesh packets will simply be rebroadcasted over this node. Nodes configured with this role will not originate NodeInfo, Position, Telemetry or any other packet type. They will simply rebroadcast any mesh packets on the same frequency, channel num, spread factor, and coding rate. */ meshtastic_Config_DeviceConfig_Role_REPEATER = 4, - /* Tracker device role - Position Mesh packets will be prioritized higher and sent more frequently by default. + /* Description: Broadcasts GPS position packets as priority. + Technical Details: Position Mesh packets will be prioritized higher and sent more frequently by default. When used in conjunction with power.is_power_saving = true, nodes will wake up, send position, and then sleep for position.position_broadcast_secs seconds. */ meshtastic_Config_DeviceConfig_Role_TRACKER = 5, - /* Sensor device role - Telemetry Mesh packets will be prioritized higher and sent more frequently by default. + /* Description: Broadcasts telemetry packets as priority. + Technical Details: Telemetry Mesh packets will be prioritized higher and sent more frequently by default. When used in conjunction with power.is_power_saving = true, nodes will wake up, send environment telemetry, and then sleep for telemetry.environment_update_interval seconds. */ meshtastic_Config_DeviceConfig_Role_SENSOR = 6, - /* TAK device role - Used for nodes dedicated for connection to an ATAK EUD. + /* Description: Optimized for ATAK system communication, reduces routine broadcasts. + Technical Details: Used for nodes dedicated for connection to an ATAK EUD. Turns off many of the routine broadcasts to favor CoT packet stream from the Meshtastic ATAK plugin -> IMeshService -> Node */ meshtastic_Config_DeviceConfig_Role_TAK = 7, - /* Client Hidden device role - Used for nodes that "only speak when spoken to" + /* Description: Device that only broadcasts as needed for stealth or power savings. + Technical Details: Used for nodes that "only speak when spoken to" Turns all of the routine broadcasts but allows for ad-hoc communication Still rebroadcasts, but with local only rebroadcast mode (known meshes only) Can be used for clandestine operation or to dramatically reduce airtime / power consumption */ meshtastic_Config_DeviceConfig_Role_CLIENT_HIDDEN = 8, - /* Lost and Found device role - Used to automatically send a text message to the mesh + /* Description: Broadcasts location as message to default channel regularly for to assist with device recovery. + Technical Details: Used to automatically send a text message to the mesh with the current position of the device on a frequent interval: "I'm lost! Position: lat / long" */ meshtastic_Config_DeviceConfig_Role_LOST_AND_FOUND = 9 @@ -313,6 +312,9 @@ typedef struct _meshtastic_Config_PositionConfig { uint32_t gps_en_gpio; /* Set where GPS is enabled, disabled, or not present */ meshtastic_Config_PositionConfig_GpsMode gps_mode; + /* Set GPS precision in bits per channel, or 0 for disabled */ + pb_size_t channel_precision_count; + uint32_t channel_precision[8]; } meshtastic_Config_PositionConfig; /* Power Config\ @@ -580,7 +582,7 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_Config_init_default {0, {meshtastic_Config_DeviceConfig_init_default}} #define meshtastic_Config_DeviceConfig_init_default {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0, 0} -#define meshtastic_Config_PositionConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, _meshtastic_Config_PositionConfig_GpsMode_MIN} +#define meshtastic_Config_PositionConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, _meshtastic_Config_PositionConfig_GpsMode_MIN, 0, {0, 0, 0, 0, 0, 0, 0, 0}} #define meshtastic_Config_PowerConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_Config_NetworkConfig_init_default {0, "", "", "", 0, _meshtastic_Config_NetworkConfig_AddressMode_MIN, false, meshtastic_Config_NetworkConfig_IpV4Config_init_default, ""} #define meshtastic_Config_NetworkConfig_IpV4Config_init_default {0, 0, 0, 0} @@ -589,7 +591,7 @@ extern "C" { #define meshtastic_Config_BluetoothConfig_init_default {0, _meshtastic_Config_BluetoothConfig_PairingMode_MIN, 0} #define meshtastic_Config_init_zero {0, {meshtastic_Config_DeviceConfig_init_zero}} #define meshtastic_Config_DeviceConfig_init_zero {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0, 0} -#define meshtastic_Config_PositionConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, _meshtastic_Config_PositionConfig_GpsMode_MIN} +#define meshtastic_Config_PositionConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, _meshtastic_Config_PositionConfig_GpsMode_MIN, 0, {0, 0, 0, 0, 0, 0, 0, 0}} #define meshtastic_Config_PowerConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_Config_NetworkConfig_init_zero {0, "", "", "", 0, _meshtastic_Config_NetworkConfig_AddressMode_MIN, false, meshtastic_Config_NetworkConfig_IpV4Config_init_zero, ""} #define meshtastic_Config_NetworkConfig_IpV4Config_init_zero {0, 0, 0, 0} @@ -621,6 +623,7 @@ extern "C" { #define meshtastic_Config_PositionConfig_broadcast_smart_minimum_interval_secs_tag 11 #define meshtastic_Config_PositionConfig_gps_en_gpio_tag 12 #define meshtastic_Config_PositionConfig_gps_mode_tag 13 +#define meshtastic_Config_PositionConfig_channel_precision_tag 14 #define meshtastic_Config_PowerConfig_is_power_saving_tag 1 #define meshtastic_Config_PowerConfig_on_battery_shutdown_after_secs_tag 2 #define meshtastic_Config_PowerConfig_adc_multiplier_override_tag 3 @@ -724,7 +727,8 @@ X(a, STATIC, SINGULAR, UINT32, tx_gpio, 9) \ X(a, STATIC, SINGULAR, UINT32, broadcast_smart_minimum_distance, 10) \ X(a, STATIC, SINGULAR, UINT32, broadcast_smart_minimum_interval_secs, 11) \ X(a, STATIC, SINGULAR, UINT32, gps_en_gpio, 12) \ -X(a, STATIC, SINGULAR, UENUM, gps_mode, 13) +X(a, STATIC, SINGULAR, UENUM, gps_mode, 13) \ +X(a, STATIC, REPEATED, UINT32, channel_precision, 14) #define meshtastic_Config_PositionConfig_CALLBACK NULL #define meshtastic_Config_PositionConfig_DEFAULT NULL @@ -830,7 +834,7 @@ extern const pb_msgdesc_t meshtastic_Config_BluetoothConfig_msg; #define meshtastic_Config_LoRaConfig_size 80 #define meshtastic_Config_NetworkConfig_IpV4Config_size 20 #define meshtastic_Config_NetworkConfig_size 196 -#define meshtastic_Config_PositionConfig_size 62 +#define meshtastic_Config_PositionConfig_size 110 #define meshtastic_Config_PowerConfig_size 40 #define meshtastic_Config_size 199 diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index e017be9a2..bca305c14 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -316,7 +316,7 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg; #define meshtastic_DeviceState_size 17062 #define meshtastic_NodeInfoLite_size 153 #define meshtastic_NodeRemoteHardwarePin_size 29 -#define meshtastic_OEMStore_size 3246 +#define meshtastic_OEMStore_size 3294 #define meshtastic_PositionLite_size 28 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/localonly.pb.h b/src/mesh/generated/meshtastic/localonly.pb.h index 7d39da01f..644d965ab 100644 --- a/src/mesh/generated/meshtastic/localonly.pb.h +++ b/src/mesh/generated/meshtastic/localonly.pb.h @@ -180,7 +180,7 @@ extern const pb_msgdesc_t meshtastic_LocalModuleConfig_msg; #define meshtastic_LocalModuleConfig_fields &meshtastic_LocalModuleConfig_msg /* Maximum encoded size of messages (where known) */ -#define meshtastic_LocalConfig_size 469 +#define meshtastic_LocalConfig_size 517 #define meshtastic_LocalModuleConfig_size 631 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index d109c2f3c..6c3a9729f 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -111,7 +111,7 @@ typedef enum _meshtastic_HardwareModel { meshtastic_HardwareModel_RPI_PICO = 47, /* Heltec Wireless Tracker with ESP32-S3 CPU, built-in GPS, and TFT Newer V1.1, version is written on the PCB near the display. */ - meshtastic_HardwareModel_HELTEC_WIRELESS_TRACKER_V1_1 = 48, + meshtastic_HardwareModel_HELTEC_WIRELESS_TRACKER = 48, /* Heltec Wireless Paper with ESP32-S3 CPU and E-Ink display */ meshtastic_HardwareModel_HELTEC_WIRELESS_PAPER = 49, /* LilyGo T-Deck with ESP32-S3 CPU, Keyboard and IPS display */ From cb4e1840e3ed35abe28fd59dcc17d45025fd8b25 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 14 Feb 2024 07:30:01 -0600 Subject: [PATCH 186/472] Revert HW_MODEL name --- src/platform/esp32/architecture.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/platform/esp32/architecture.h b/src/platform/esp32/architecture.h index ffff90c75..9fa4a5dd7 100644 --- a/src/platform/esp32/architecture.h +++ b/src/platform/esp32/architecture.h @@ -106,7 +106,7 @@ #elif defined(HELTEC_WSL_V3) #define HW_VENDOR meshtastic_HardwareModel_HELTEC_WSL_V3 #elif defined(HELTEC_WIRELESS_TRACKER) -#define HW_VENDOR meshtastic_HardwareModel_HELTEC_WIRELESS_TRACKER_V1_1 +#define HW_VENDOR meshtastic_HardwareModel_HELTEC_WIRELESS_TRACKER #elif defined(HELTEC_WIRELESS_PAPER_V1_0) #define HW_VENDOR meshtastic_HardwareModel_HELTEC_WIRELESS_PAPER_V1_0 #elif defined(HELTEC_WIRELESS_PAPER) From fdc27fe08b9348878cde8e82eb522430d192a2f8 Mon Sep 17 00:00:00 2001 From: Ken McGuire Date: Thu, 15 Feb 2024 10:19:35 -0700 Subject: [PATCH 187/472] Enable NMEA Messages on USB port for u-blox receivers (#3227) * Portduino multiple logging levels * Fixes based on GPSFan work * Fix derped logic * Correct size field for AID message * Reformat to add comments, beginning of GPS rework * Update PM2 message for Neo-6 * Correct ECO mode logic as ECO mode is only for Neo-6 * Cleanup ubx.h add a few more comments * GPS rework, changes for M8 and stub for M10 * Add VALSET commands for u-blox M10 receivers * Add VALSET commands for u-blox M10 receivers tweak M8 commands add comments for VALSET configuration commands * Add commands to init M10 receivers, tweak the M8 init sequence, this is a WIP as there are still some issues during init. Add M10 version of PMREQ. * Add wakeup source of uartrx to PMREQ_10 The M10 does not respond to commands when asleep, may need to do this for the M8 as well * Enable NMEA messages on USB port. Normally, it is a good idea to disable messages on unused ports. Native Linux needs to be able to use GNSS modules connected via via either serial or USB. In the future I2C connections may be required, but are not enabled for now. --------- Co-authored-by: Jonathan Bennett Co-authored-by: Ben Meadors --- src/gps/ubx.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/gps/ubx.h b/src/gps/ubx.h index 28f9573bf..5b2cb24ce 100644 --- a/src/gps/ubx.h +++ b/src/gps/ubx.h @@ -213,7 +213,7 @@ const uint8_t GPS::_message_GSA[] = { 0x00, // Rate for DDC 0x01, // Rate for UART1 0x00, // Rate for UART2 - 0x00, // Rate for USB + 0x01, // Rate for USB usefull for native linux 0x00, // Rate for SPI 0x00 // Reserved }; @@ -247,7 +247,7 @@ const uint8_t GPS::_message_RMC[] = { 0x00, // Rate for DDC 0x01, // Rate for UART1 0x00, // Rate for UART2 - 0x00, // Rate for USB + 0x01, // Rate for USB usefull for native linux 0x00, // Rate for SPI 0x00 // Reserved }; @@ -258,7 +258,7 @@ const uint8_t GPS::_message_GGA[] = { 0x00, // Rate for DDC 0x01, // Rate for UART1 0x00, // Rate for UART2 - 0x00, // Rate for USB + 0x01, // Rate for USB, usefull for native linux 0x00, // Rate for SPI 0x00 // Reserved }; From e3c4bc5473a5ca9775617103aeb559e2bcc0d0ee Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 15 Feb 2024 11:46:30 -0600 Subject: [PATCH 188/472] Re-enable GPS on native --- variants/portduino/variant.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/variants/portduino/variant.h b/variants/portduino/variant.h index 959fe6275..f47b58afc 100644 --- a/variants/portduino/variant.h +++ b/variants/portduino/variant.h @@ -1,2 +1,3 @@ #define HAS_SCREEN 1 -#define CANNED_MESSAGE_MODULE_ENABLE 1 \ No newline at end of file +#define CANNED_MESSAGE_MODULE_ENABLE 1 +#define HAS_GPS 1 From 7c9d1b0abf3163f9545acff20fc49c61ec017e82 Mon Sep 17 00:00:00 2001 From: Gabriele Russo Date: Fri, 16 Feb 2024 13:09:57 +0100 Subject: [PATCH 189/472] Battery level with proportional filter and lookup table (#3216) * Add battery level with lookup table now uses a lookup table to better calculate battery level of different cells * LifePo4 and PB battery table - added voltage filter removed delay from adc reading, added a software filter to smooth out voltage readings. In those applications battery would last hours to days, no sudden change should be expected so a less frequent voltage reading or a more aggressive filtering could be done. Note: to speed up convergence i initiliazied the last value to the minimum voltage, there are other and better ways to init the filter. Added LiFePO4 and PB open circuit volta battery tables, * Fixed ADC_CTRL , Checks for valid ADC readings line 230/386 For heltec v3 and heltec tracker a different approach was used with the ADC_CTRL pin, now is more uniform using the same code for the 3 boards. line 236 Check if the raw reading we are getting is Valid or not, count only the valid readings. This could lead to a division by 0 (improbable) so that's why at line 258 there is a check for that. * updated OCV values updated value to not OCV but to very low current, almost the same anyway * Added Alkaline/Nimh voltage curve Added Alkaline/Nimh voltage curve for AA/AAA and similar cells * updates variants for new capacity measurement * trunk reformatting * trunk fmt * Add LTO chemistry --------- Co-authored-by: Ben Meadors Co-authored-by: code8buster <20384924+code8buster@users.noreply.github.com> --- src/Power.cpp | 112 +++++++++++---------- src/power.h | 45 +++++++-- variants/chatter2/variant.h | 15 ++- variants/heltec_v2.1/variant.h | 3 +- variants/heltec_v3/variant.h | 2 + variants/heltec_wireless_tracker/variant.h | 1 + variants/heltec_wsl_v3/variant.h | 2 + variants/station-g1/variant.h | 6 +- 8 files changed, 109 insertions(+), 77 deletions(-) diff --git a/src/Power.cpp b/src/Power.cpp index 23b790004..8e44ddb98 100644 --- a/src/Power.cpp +++ b/src/Power.cpp @@ -127,8 +127,6 @@ class AnalogBatteryLevel : public HasBatteryLevel { /** * Battery state of charge, from 0 to 100 or -1 for unknown - * - * FIXME - use a lipo lookup table, the current % full is super wrong */ virtual int getBatteryPercent() override { @@ -137,13 +135,32 @@ class AnalogBatteryLevel : public HasBatteryLevel if (v < noBatVolt) return -1; // If voltage is super low assume no battery installed -#ifdef ARCH_ESP32 +#ifdef NO_BATTERY_LEVEL_ON_CHARGE // This does not work on a RAK4631 with battery connected if (v > chargingVolt) return 0; // While charging we can't report % full on the battery #endif - - return clamp((int)(100 * (v - emptyVolt) / (fullVolt - emptyVolt)), 0, 100); + /** + * @brief Battery voltage lookup table interpolation to obtain a more + * precise percentage rather than the old proportional one. + * @author Gabriele Russo + * @date 06/02/2024 + */ + float battery_SOC = 0.0; + uint16_t voltage = v / NUM_CELLS; // single cell voltage (average) + for (int i = 0; i < NUM_OCV_POINTS; i++) { + if (OCV[i] <= voltage) { + if (i == 0) { + battery_SOC = 100.0; // 100% full + } else { + // interpolate between OCV[i] and OCV[i-1] + battery_SOC = (float)100.0 / (NUM_OCV_POINTS - 1.0) * + (NUM_OCV_POINTS - 1.0 - i + ((float)voltage - OCV[i]) / (OCV[i - 1] - OCV[i])); + } + break; + } + } + return clamp((int)(battery_SOC), 0, 100); } /** @@ -165,7 +182,7 @@ class AnalogBatteryLevel : public HasBatteryLevel #ifndef BATTERY_SENSE_SAMPLES #define BATTERY_SENSE_SAMPLES \ - 30 // Set the number of samples, it has an effect of increasing sensitivity in complex electromagnetic environment. + 15 // Set the number of samples, it has an effect of increasing sensitivity in complex electromagnetic environment. #endif #ifdef BATTERY_PIN @@ -191,12 +208,11 @@ class AnalogBatteryLevel : public HasBatteryLevel raw = raw / BATTERY_SENSE_SAMPLES; scaled = operativeAdcMultiplier * ((1000 * AREF_VOLTAGE) / pow(2, BATTERY_SENSE_RESOLUTION_BITS)) * raw; #endif - // LOG_DEBUG("battery gpio %d raw val=%u scaled=%u\n", BATTERY_PIN, raw, (uint32_t)(scaled)); - last_read_value = scaled; - return scaled; - } else { - return last_read_value; + last_read_value += (scaled - last_read_value) * 0.5; // Virtual LPF + // LOG_DEBUG("battery gpio %d raw val=%u scaled=%u filtered=%u\n", BATTERY_PIN, raw, (uint32_t)(scaled), (uint32_t) + // (last_read_value)); } + return last_read_value; #endif // BATTERY_PIN return 0; } @@ -209,23 +225,24 @@ class AnalogBatteryLevel : public HasBatteryLevel { uint32_t raw = 0; - uint8_t raw_c = 0; + uint8_t raw_c = 0; // raw reading counter #ifndef BAT_MEASURE_ADC_UNIT // ADC1 -#ifdef ADC_CTRL - if (heltec_version == 5) { - pinMode(ADC_CTRL, OUTPUT); - digitalWrite(ADC_CTRL, HIGH); - delay(10); - } +#ifdef ADC_CTRL // enable adc voltage divider when we need to read + pinMode(ADC_CTRL, OUTPUT); + digitalWrite(ADC_CTRL, ADC_CTRL_ENABLED); + delay(10); #endif for (int i = 0; i < BATTERY_SENSE_SAMPLES; i++) { - raw += adc1_get_raw(adc_channel); - } -#ifdef ADC_CTRL - if (heltec_version == 5) { - digitalWrite(ADC_CTRL, LOW); + int val_ = adc1_get_raw(adc_channel); + if (val_ >= 0) { // save only valid readings + raw += val_; + raw_c++; + } + // delayMicroseconds(100); } +#ifdef ADC_CTRL // disable adc voltage divider when we need to read + digitalWrite(ADC_CTRL, !ADC_CTRL_ENABLED); #endif #else // ADC2 #ifdef ADC_CTRL @@ -257,7 +274,7 @@ class AnalogBatteryLevel : public HasBatteryLevel } } -#else // Other ESP32 +#else // Other ESP32 int32_t adc_buf = 0; for (int i = 0; i < BATTERY_SENSE_SAMPLES; i++) { // ADC2 wifi bug workaround, see @@ -268,7 +285,7 @@ class AnalogBatteryLevel : public HasBatteryLevel raw += adc_buf; raw_c++; } -#endif +#endif // BAT_MEASURE_ADC_UNIT #ifdef ADC_CTRL #if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0) @@ -311,22 +328,14 @@ class AnalogBatteryLevel : public HasBatteryLevel /// If we see a battery voltage higher than physics allows - assume charger is pumping /// in power -#ifndef BAT_FULLVOLT -#define BAT_FULLVOLT 4200 -#endif -#ifndef BAT_EMPTYVOLT -#define BAT_EMPTYVOLT 3270 -#endif -#ifndef BAT_CHARGINGVOLT -#define BAT_CHARGINGVOLT 4210 -#endif -#ifndef BAT_NOBATVOLT -#define BAT_NOBATVOLT 2230 -#endif - - /// For heltecs with no battery connected, the measured voltage is 2204, so raising to 2230 from 2100 - const float fullVolt = BAT_FULLVOLT, emptyVolt = BAT_EMPTYVOLT, chargingVolt = BAT_CHARGINGVOLT, noBatVolt = BAT_NOBATVOLT; - float last_read_value = 0.0; + /// For heltecs with no battery connected, the measured voltage is 2204, so + // need to be higher than that, in this case is 2500mV (3000-500) + const uint16_t OCV[NUM_OCV_POINTS] = {OCV_ARRAY}; + const float chargingVolt = (OCV[0] + 10) * NUM_CELLS; + const float noBatVolt = (OCV[NUM_OCV_POINTS - 1] - 500) * NUM_CELLS; + // Start value from minimum voltage for the filter to not start from 0 + // that could trigger some events. + float last_read_value = (OCV[NUM_OCV_POINTS - 1] * NUM_CELLS); uint32_t last_read_time_ms = 0; #if defined(HAS_TELEMETRY) && !defined(ARCH_PORTDUINO) @@ -426,10 +435,6 @@ bool Power::analogInit() else { LOG_INFO("ADCmod: ADC characterization based on default reference voltage\n"); } -#if defined(HELTEC_V3) || defined(HELTEC_WSL_V3) - pinMode(37, OUTPUT); // needed for P channel mosfet to work - digitalWrite(37, LOW); -#endif #endif // ARCH_ESP32 #ifdef ARCH_NRF52 @@ -510,11 +515,11 @@ void Power::readPowerStatus() batteryChargePercent = batteryLevel->getBatteryPercent(); } else { // If the AXP192 returns a percentage less than 0, the feature is either not supported or there is an error - // In that case, we compute an estimate of the charge percent based on maximum and minimum voltages defined in - // power.h - batteryChargePercent = - clamp((int)(((batteryVoltageMv - BAT_MILLIVOLTS_EMPTY) * 1e2) / (BAT_MILLIVOLTS_FULL - BAT_MILLIVOLTS_EMPTY)), - 0, 100); + // In that case, we compute an estimate of the charge percent based on open circuite voltage table defined + // in power.h + batteryChargePercent = clamp((int)(((batteryVoltageMv - (OCV[NUM_OCV_POINTS - 1] * NUM_CELLS)) * 1e2) / + ((OCV[0] * NUM_CELLS) - (OCV[NUM_OCV_POINTS - 1] * NUM_CELLS))), + 0, 100); } } @@ -579,10 +584,11 @@ void Power::readPowerStatus() #endif - // If we have a battery at all and it is less than 10% full, force deep sleep if we have more than 10 low readings in - // a row + // If we have a battery at all and it is less than 0%, force deep sleep if we have more than 10 low readings in + // a row. NOTE: min LiIon/LiPo voltage is 2.0 to 2.5V, current OCV min is set to 3100 that is large enough. + // if (powerStatus2.getHasBattery() && !powerStatus2.getHasUSB()) { - if (batteryLevel->getBattVoltage() < MIN_BAT_MILLIVOLTS) { + if (batteryLevel->getBattVoltage() < OCV[NUM_OCV_POINTS - 1]) { low_voltage_counter++; LOG_DEBUG("Low voltage counter: %d/10\n", low_voltage_counter); if (low_voltage_counter > 10) { diff --git a/src/power.h b/src/power.h index 54d98e715..4dd35e710 100644 --- a/src/power.h +++ b/src/power.h @@ -5,18 +5,39 @@ #include #include #endif -/** - * Per @spattinson - * MIN_BAT_MILLIVOLTS seems high. Typical 18650 are different chemistry to LiPo, even for LiPos that chart seems a bit off, other - * charts put 3690mV at about 30% for a lipo, for 18650 i think 10% remaining iis in the region of 3.2-3.3V. Reference 1st graph - * in [this test report](https://lygte-info.dk/review/batteries2012/Samsung%20INR18650-30Q%203000mAh%20%28Pink%29%20UK.html) - * looking at the red line - discharge at 0.2A - he gets a capacity of 2900mah, 90% of 2900 = 2610, that point in the graph looks - * to be a shade above 3.2V - */ -#define MIN_BAT_MILLIVOLTS 3250 // millivolts. 10% per https://blog.ampow.com/lipo-voltage-chart/ -#define BAT_MILLIVOLTS_FULL 4100 -#define BAT_MILLIVOLTS_EMPTY 3500 +#ifndef NUM_OCV_POINTS +#define NUM_OCV_POINTS 11 +#endif + +// 3400,3350,3320,3290,3270,3260,3250,3230,3200,3120,3000 //3.4 to 3.0 LiFePO4 +// 2120,2090,2070,2050,2030,2010,1990,1980,1970,1960,1950 //2.12 to 1.95 Lead Acid +// 4200,4050,3990,3890,3790,3700,3650,3550,3450,3300,3200 //4.2 to 3.2 LiIon/LiPo +// 4200,4050,3990,3890,3790,3700,3650,3550,3400,3300,3000 //4.2 to 3.0 LiIon/LiPo +// 4150,4050,3990,3890,3790,3690,3620,3520,3420,3300,3100 //4.15 to 3.1 LiIon/LiPo +// 2770,2650,2540,2420,2300,2180,2060,1940,1800,1680,1550 //2.8 to 1.5 Lithium Titanate + +#ifndef OCV_ARRAY +#ifdef CELL_TYPE_LIFEPO4 +#define OCV_ARRAY 3400, 3350, 3320, 3290, 3270, 3260, 3250, 3230, 3200, 3120, 3000 +#elif defined(CELL_TYPE_LEADACID) +#define OCV_ARRAY 2120, 2090, 2070, 2050, 2030, 2010, 1990, 1980, 1970, 1960, 1950 +#elif defined(CELL_TYPE_ALKALINE) +#define OCV_ARRAY 1580, 1400, 1350, 1300, 1280, 1250, 1230, 1190, 1150, 1100, 1000 +#elif defined(CELL_TYPE_NIMH) +#define OCV_ARRAY 1400, 1300, 1280, 1270, 1260, 1250, 1240, 1230, 1210, 1150, 1000 +#elif defined(CELL_TYPE_LTO) +#define OCV_ARRAY 2770, 2650, 2540, 2420, 2300, 2180, 2060, 1940, 1800, 1680, 1550 +#else // LiIon +#define OCV_ARRAY 4190, 4050, 3990, 3890, 3800, 3720, 3630, 3530, 3420, 3300, 3100 +#endif +#endif + +/*Note: 12V lead acid is 6 cells, most board accept only 1 cell LiIon/LiPo*/ +#ifndef NUM_CELLS +#define NUM_CELLS 1 +#endif + #ifdef BAT_MEASURE_ADC_UNIT extern RTC_NOINIT_ATTR uint64_t RTC_reg_b; #include "soc/sens_reg.h" // needed for adc pin reset @@ -44,6 +65,7 @@ class Power : private concurrency::OSThread virtual bool setup(); virtual int32_t runOnce() override; void setStatusHandler(meshtastic::PowerStatus *handler) { statusHandler = handler; } + const uint16_t OCV[11] = {OCV_ARRAY}; protected: meshtastic::PowerStatus *statusHandler; @@ -54,6 +76,7 @@ class Power : private concurrency::OSThread bool analogInit(); private: + // open circuit voltage lookup table uint8_t low_voltage_counter; #ifdef DEBUG_HEAP uint32_t lastheap; diff --git a/variants/chatter2/variant.h b/variants/chatter2/variant.h index b7ffcf732..90faa1d7b 100644 --- a/variants/chatter2/variant.h +++ b/variants/chatter2/variant.h @@ -72,14 +72,13 @@ #define BATTERY_PIN 34 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage #define ADC_CHANNEL ADC1_GPIO34_CHANNEL #define ADC_ATTENUATION \ - ADC_ATTEN_DB_2_5 // 2_5-> 100mv-1250mv, 11-> 150mv-3100mv for ESP32 - // ESP32-S2/C3/S3 are different - // lower dB for lower voltage rnage -#define ADC_MULTIPLIER \ - 5.0 // VBATT---10k--pin34---2.5K---GND - // Chatter2 uses 3 AAA cells -#define BAT_FULLVOLT 4800 // with the 5.0 divider, input to BATTERY_PIN is 900mv -#define BAT_EMPTYVOLT 3300 + ADC_ATTEN_DB_2_5 // 2_5-> 100mv-1250mv, 11-> 150mv-3100mv for ESP32 + // ESP32-S2/C3/S3 are different + // lower dB for lower voltage rnage +#define ADC_MULTIPLIER 5.0 // VBATT---10k--pin34---2.5K---GND +// Chatter2 uses 3 AAA cells +#define CELL_TYPE_ALKALINE +#define NUM_CELLS 3 #undef EXT_PWR_DETECT // GPS diff --git a/variants/heltec_v2.1/variant.h b/variants/heltec_v2.1/variant.h index ed123efec..8ebccc54f 100644 --- a/variants/heltec_v2.1/variant.h +++ b/variants/heltec_v2.1/variant.h @@ -29,7 +29,8 @@ #define LORA_DIO1 35 // https://www.thethingsnetwork.org/forum/t/big-esp32-sx127x-topic-part-3/18436 #define LORA_DIO2 34 // Not really used -#define ADC_MULTIPLIER 3.8 +#define ADC_MULTIPLIER 3.2 // 220k + 100k (320k/100k=3.2) +// #define ADC_WIDTH ADC_WIDTH_BIT_10 #define BATTERY_PIN 37 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage #define ADC_CHANNEL ADC1_GPIO37_CHANNEL diff --git a/variants/heltec_v3/variant.h b/variants/heltec_v3/variant.h index 2532ea682..70b122f58 100644 --- a/variants/heltec_v3/variant.h +++ b/variants/heltec_v3/variant.h @@ -11,6 +11,8 @@ #define VEXT_ENABLE Vext // active low, powers the oled display and the lora antenna boost #define BUTTON_PIN 0 +#define ADC_CTRL 37 +#define ADC_CTRL_ENABLED LOW #define BATTERY_PIN 1 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage #define ADC_CHANNEL ADC1_GPIO1_CHANNEL #define ADC_ATTENUATION ADC_ATTEN_DB_2_5 // lower dB for high resistance voltage divider diff --git a/variants/heltec_wireless_tracker/variant.h b/variants/heltec_wireless_tracker/variant.h index 88b4804a1..ba2a0676a 100644 --- a/variants/heltec_wireless_tracker/variant.h +++ b/variants/heltec_wireless_tracker/variant.h @@ -35,6 +35,7 @@ #define ADC_ATTENUATION ADC_ATTEN_DB_2_5 // lower dB for high resistance voltage divider #define ADC_MULTIPLIER 4.9 #define ADC_CTRL 2 // active HIGH, powers the voltage divider. Only on 1.1 +#define ADC_CTRL_ENABLED HIGH #undef GPS_RX_PIN #undef GPS_TX_PIN diff --git a/variants/heltec_wsl_v3/variant.h b/variants/heltec_wsl_v3/variant.h index 0ad1b8487..d3a009ade 100644 --- a/variants/heltec_wsl_v3/variant.h +++ b/variants/heltec_wsl_v3/variant.h @@ -8,6 +8,8 @@ #define VEXT_ENABLE Vext // active low, powers the oled display and the lora antenna boost #define BUTTON_PIN 0 +#define ADC_CTRL 37 +#define ADC_CTRL_ENABLED LOW #define BATTERY_PIN 1 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage #define ADC_CHANNEL ADC1_GPIO1_CHANNEL #define ADC_ATTENUATION ADC_ATTEN_DB_2_5 // lower dB for high resistance voltage divider diff --git a/variants/station-g1/variant.h b/variants/station-g1/variant.h index e58853fb7..9a3c37b73 100644 --- a/variants/station-g1/variant.h +++ b/variants/station-g1/variant.h @@ -37,10 +37,8 @@ #define ADC_CHANNEL ADC1_GPIO35_CHANNEL #define BATTERY_SENSE_SAMPLES 30 // Set the number of samples, It has an effect of increasing sensitivity. #define ADC_MULTIPLIER 6.45 -#define BAT_FULLVOLT 12600 -#define BAT_EMPTYVOLT 8200 -#define BAT_CHARGINGVOLT 12600 -#define BAT_NOBATVOLT 6690 +#define CELL_TYPE_LION // same curve for liion/lipo +#define NUM_CELLS 3 // different screen #define USE_SH1106 From 1bacd8641d6c0ea81987b0c21fc8a764a5660b63 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Fri, 16 Feb 2024 06:39:53 -0600 Subject: [PATCH 190/472] [create-pull-request] automated change (#3232) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/config.pb.h | 13 +++++++++---- 2 files changed, 10 insertions(+), 5 deletions(-) diff --git a/protobufs b/protobufs index 4432d3bfc..5f28be497 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 4432d3bfc155107e27079d96ddba16b52f2d9ea3 +Subproject commit 5f28be497a5518334c86378335e8ffcd177ed661 diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index 445ef7e1b..b8e79fe6b 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -38,7 +38,7 @@ typedef enum _meshtastic_Config_DeviceConfig_Role { When used in conjunction with power.is_power_saving = true, nodes will wake up, send environment telemetry, and then sleep for telemetry.environment_update_interval seconds. */ meshtastic_Config_DeviceConfig_Role_SENSOR = 6, - /* Description: Optimized for ATAK system communication, reduces routine broadcasts. + /* Description: Optimized for ATAK system communication and reduces routine broadcasts. Technical Details: Used for nodes dedicated for connection to an ATAK EUD. Turns off many of the routine broadcasts to favor CoT packet stream from the Meshtastic ATAK plugin -> IMeshService -> Node */ @@ -53,7 +53,12 @@ typedef enum _meshtastic_Config_DeviceConfig_Role { Technical Details: Used to automatically send a text message to the mesh with the current position of the device on a frequent interval: "I'm lost! Position: lat / long" */ - meshtastic_Config_DeviceConfig_Role_LOST_AND_FOUND = 9 + meshtastic_Config_DeviceConfig_Role_LOST_AND_FOUND = 9, + /* Description: Enables automatic TAK PLI broadcasts and reduces routine broadcasts. + Technical Details: Turns off many of the routine broadcasts to favor ATAK CoT packet stream + and automatic TAK PLI (position location information) broadcasts. + Uses position module configuration to determine TAK PLI broadcast interval. */ + meshtastic_Config_DeviceConfig_Role_TAK_TRACKER = 10 } meshtastic_Config_DeviceConfig_Role; /* Defines the device's behavior for how messages are rebroadcast */ @@ -511,8 +516,8 @@ extern "C" { /* Helper constants for enums */ #define _meshtastic_Config_DeviceConfig_Role_MIN meshtastic_Config_DeviceConfig_Role_CLIENT -#define _meshtastic_Config_DeviceConfig_Role_MAX meshtastic_Config_DeviceConfig_Role_LOST_AND_FOUND -#define _meshtastic_Config_DeviceConfig_Role_ARRAYSIZE ((meshtastic_Config_DeviceConfig_Role)(meshtastic_Config_DeviceConfig_Role_LOST_AND_FOUND+1)) +#define _meshtastic_Config_DeviceConfig_Role_MAX meshtastic_Config_DeviceConfig_Role_TAK_TRACKER +#define _meshtastic_Config_DeviceConfig_Role_ARRAYSIZE ((meshtastic_Config_DeviceConfig_Role)(meshtastic_Config_DeviceConfig_Role_TAK_TRACKER+1)) #define _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN meshtastic_Config_DeviceConfig_RebroadcastMode_ALL #define _meshtastic_Config_DeviceConfig_RebroadcastMode_MAX meshtastic_Config_DeviceConfig_RebroadcastMode_KNOWN_ONLY From 998013aff3a9d97dfe3d9bea22e4f31dfb01363a Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 16 Feb 2024 20:04:21 -0600 Subject: [PATCH 191/472] Add TAK Tracker role behavior (#3233) * Proto * Standalone TAK Tracker * Add log * Make TAK_Tracker behave like Tracker --- src/PowerFSM.cpp | 1 + src/mesh/NodeDB.cpp | 11 ++++++ src/modules/PositionModule.cpp | 61 ++++++++++++++++++++++++++++--- src/modules/PositionModule.h | 1 + src/platform/nrf52/main-nrf52.cpp | 1 + 5 files changed, 70 insertions(+), 5 deletions(-) diff --git a/src/PowerFSM.cpp b/src/PowerFSM.cpp index c64599ce6..bac3899bb 100644 --- a/src/PowerFSM.cpp +++ b/src/PowerFSM.cpp @@ -246,6 +246,7 @@ void PowerFSM_setup() { bool isRouter = (config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER ? 1 : 0); bool isTrackerOrSensor = config.device.role == meshtastic_Config_DeviceConfig_Role_TRACKER || + config.device.role == meshtastic_Config_DeviceConfig_Role_TAK_TRACKER || config.device.role == meshtastic_Config_DeviceConfig_Role_SENSOR; bool hasPower = isPowered(); diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 891b7a61f..add1b1296 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -325,6 +325,17 @@ void NodeDB::installRoleDefaults(meshtastic_Config_DeviceConfig_Role role) (meshtastic_Config_PositionConfig_PositionFlags_ALTITUDE | meshtastic_Config_PositionConfig_PositionFlags_SPEED | meshtastic_Config_PositionConfig_PositionFlags_HEADING | meshtastic_Config_PositionConfig_PositionFlags_DOP); moduleConfig.telemetry.device_update_interval = ONE_DAY; + } else if (role == meshtastic_Config_DeviceConfig_Role_TAK_TRACKER) { + config.device.node_info_broadcast_secs = ONE_DAY; + config.position.position_broadcast_smart_enabled = true; + config.position.position_broadcast_secs = 3 * 60; // Every 3 minutes + config.position.broadcast_smart_minimum_distance = 20; + config.position.broadcast_smart_minimum_interval_secs = 15; + // Remove Altitude MSL from flags since CoTs use HAE (height above ellipsoid) + config.position.position_flags = + (meshtastic_Config_PositionConfig_PositionFlags_ALTITUDE | meshtastic_Config_PositionConfig_PositionFlags_SPEED | + meshtastic_Config_PositionConfig_PositionFlags_HEADING | meshtastic_Config_PositionConfig_PositionFlags_DOP); + moduleConfig.telemetry.device_update_interval = ONE_DAY; } else if (role == meshtastic_Config_DeviceConfig_Role_CLIENT_HIDDEN) { config.device.rebroadcast_mode = meshtastic_Config_DeviceConfig_RebroadcastMode_LOCAL_ONLY; config.device.node_info_broadcast_secs = UINT32_MAX; diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index 5e808b6b6..e82362bc6 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -8,9 +8,15 @@ #include "airtime.h" #include "configuration.h" #include "gps/GeoCoord.h" +#include "main.h" +#include "meshtastic/atak.pb.h" #include "sleep.h" #include "target_specific.h" +extern "C" { +#include "mesh/compression/unishox2.h" +} + PositionModule *positionModule; PositionModule::PositionModule() @@ -18,11 +24,14 @@ PositionModule::PositionModule() concurrency::OSThread("PositionModule") { isPromiscuous = true; // We always want to update our nodedb, even if we are sniffing on others - if (config.device.role != meshtastic_Config_DeviceConfig_Role_TRACKER) + if (config.device.role != meshtastic_Config_DeviceConfig_Role_TRACKER && + config.device.role != meshtastic_Config_DeviceConfig_Role_TAK_TRACKER) setIntervalFromNow(60 * 1000); // Power saving trackers should clear their position on startup to avoid waking up and sending a stale position - if (config.device.role == meshtastic_Config_DeviceConfig_Role_TRACKER && config.power.is_power_saving) { + if ((config.device.role == meshtastic_Config_DeviceConfig_Role_TRACKER || + config.device.role == meshtastic_Config_DeviceConfig_Role_TAK_TRACKER) && + config.power.is_power_saving) { clearPosition(); } } @@ -157,9 +166,47 @@ meshtastic_MeshPacket *PositionModule::allocReply() LOG_INFO("Position reply: time=%i, latI=%i, lonI=-%i\n", p.time, p.latitude_i, p.longitude_i); + // TAK Tracker devices should send their position in a TAK packet over the ATAK port + if (config.device.role == meshtastic_Config_DeviceConfig_Role_TAK_TRACKER) + return allocAtakPli(); + return allocDataProtobuf(p); } +meshtastic_MeshPacket *PositionModule::allocAtakPli() +{ + LOG_INFO("Sending TAK PLI packet\n"); + meshtastic_MeshPacket *mp = allocDataPacket(); + mp->decoded.portnum = meshtastic_PortNum_ATAK_PLUGIN; + + meshtastic_TAKPacket takPacket = {.is_compressed = true, + .has_contact = true, + .contact = {0}, + .has_group = true, + .group = {meshtastic_MemberRole_TeamMember, meshtastic_Team_Cyan}, + .has_status = true, + .status = + { + .battery = powerStatus->getBatteryChargePercent(), + }, + .which_payload_variant = meshtastic_TAKPacket_pli_tag, + {.pli = { + .latitude_i = localPosition.latitude_i, + .longitude_i = localPosition.longitude_i, + .altitude = localPosition.altitude_hae > 0 ? localPosition.altitude_hae : 0, + .speed = localPosition.ground_speed, + .course = static_cast(localPosition.ground_track), + }}}; + + auto length = unishox2_compress_simple(owner.long_name, strlen(owner.long_name), takPacket.contact.device_callsign); + LOG_DEBUG("Uncompressed device_callsign '%s' - %d bytes\n", owner.long_name, strlen(owner.long_name)); + LOG_DEBUG("Compressed device_callsign '%s' - %d bytes\n", takPacket.contact.device_callsign, length); + length = unishox2_compress_simple(owner.long_name, strlen(owner.long_name), takPacket.contact.callsign); + mp->decoded.payload.size = + pb_encode_to_bytes(mp->decoded.payload.bytes, sizeof(mp->decoded.payload.bytes), &meshtastic_TAKPacket_msg, &takPacket); + return mp; +} + void PositionModule::sendOurPosition(NodeNum dest, bool wantReplies, uint8_t channel) { // cancel any not yet sent (now stale) position packets @@ -174,7 +221,8 @@ void PositionModule::sendOurPosition(NodeNum dest, bool wantReplies, uint8_t cha p->to = dest; p->decoded.want_response = config.device.role == meshtastic_Config_DeviceConfig_Role_TRACKER ? false : wantReplies; - if (config.device.role == meshtastic_Config_DeviceConfig_Role_TRACKER) + if (config.device.role == meshtastic_Config_DeviceConfig_Role_TRACKER || + config.device.role == meshtastic_Config_DeviceConfig_Role_TAK_TRACKER) p->priority = meshtastic_MeshPacket_Priority_RELIABLE; else p->priority = meshtastic_MeshPacket_Priority_BACKGROUND; @@ -185,7 +233,9 @@ void PositionModule::sendOurPosition(NodeNum dest, bool wantReplies, uint8_t cha service.sendToMesh(p, RX_SRC_LOCAL, true); - if (config.device.role == meshtastic_Config_DeviceConfig_Role_TRACKER && config.power.is_power_saving) { + if ((config.device.role == meshtastic_Config_DeviceConfig_Role_TRACKER || + config.device.role == meshtastic_Config_DeviceConfig_Role_TAK_TRACKER) && + config.power.is_power_saving) { LOG_DEBUG("Starting next execution in 5 seconds and then going to sleep.\n"); sleepOnNextExecution = true; setIntervalFromNow(5000); @@ -212,7 +262,8 @@ int32_t PositionModule::runOnce() uint32_t intervalMs = getConfiguredOrDefaultMs(config.position.position_broadcast_secs, default_broadcast_interval_secs); uint32_t msSinceLastSend = now - lastGpsSend; // Only send packets if the channel util. is less than 25% utilized or we're a tracker with less than 40% utilized. - if (!airTime->isTxAllowedChannelUtil(config.device.role != meshtastic_Config_DeviceConfig_Role_TRACKER)) { + if (!airTime->isTxAllowedChannelUtil(config.device.role != meshtastic_Config_DeviceConfig_Role_TRACKER && + config.device.role != meshtastic_Config_DeviceConfig_Role_TAK_TRACKER)) { return RUNONCE_INTERVAL; } diff --git a/src/modules/PositionModule.h b/src/modules/PositionModule.h index 983fcdf8f..bd7a9def4 100644 --- a/src/modules/PositionModule.h +++ b/src/modules/PositionModule.h @@ -49,6 +49,7 @@ class PositionModule : public ProtobufModule, private concu private: struct SmartPosition getDistanceTraveledSinceLastSend(meshtastic_PositionLite currentPosition); + meshtastic_MeshPacket *allocAtakPli(); /** Only used in power saving trackers for now */ void clearPosition(); diff --git a/src/platform/nrf52/main-nrf52.cpp b/src/platform/nrf52/main-nrf52.cpp index c1d3e93fb..63b014c46 100644 --- a/src/platform/nrf52/main-nrf52.cpp +++ b/src/platform/nrf52/main-nrf52.cpp @@ -185,6 +185,7 @@ void cpuDeepSleep(uint32_t msecToWake) // Don't enter this if we're sleeping portMAX_DELAY, since that's a shutdown event if (msecToWake != portMAX_DELAY && (config.device.role == meshtastic_Config_DeviceConfig_Role_TRACKER || + config.device.role == meshtastic_Config_DeviceConfig_Role_TAK_TRACKER || config.device.role == meshtastic_Config_DeviceConfig_Role_SENSOR) && config.power.is_power_saving == true) { sd_power_mode_set(NRF_POWER_MODE_LOWPWR); From 143ee9cdf61773f0d719a9162affd96427f8b3ad Mon Sep 17 00:00:00 2001 From: Manuel <71137295+mverch67@users.noreply.github.com> Date: Sat, 17 Feb 2024 20:25:57 +0100 Subject: [PATCH 192/472] remove logging from int handler (#3242) --- src/input/RotaryEncoderInterruptBase.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/input/RotaryEncoderInterruptBase.cpp b/src/input/RotaryEncoderInterruptBase.cpp index 19b507f6c..0b8e8325d 100644 --- a/src/input/RotaryEncoderInterruptBase.cpp +++ b/src/input/RotaryEncoderInterruptBase.cpp @@ -104,7 +104,6 @@ RotaryEncoderInterruptBaseStateType RotaryEncoderInterruptBase::intHandler(bool newState = ROTARY_EVENT_OCCURRED; if ((this->action != ROTARY_ACTION_PRESSED) && (this->action != action)) { this->action = action; - LOG_DEBUG("Rotary action\n"); } } } else if (!actualPinRaising && (otherPinLevel == HIGH)) { From 5672e6825dd33b697c359e8996a197c1f320c7c8 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Sun, 18 Feb 2024 21:27:44 +0100 Subject: [PATCH 193/472] feat: implement StoreAndForward `lastRequest` map handling (2) (#3246) * feat: implement StoreAndForward `lastRequest` map handling * Correct type, check if NodeNum is in map --------- Co-authored-by: andrekir Co-authored-by: Ben Meadors --- src/modules/esp32/StoreForwardModule.cpp | 18 +++++++++--------- src/modules/esp32/StoreForwardModule.h | 6 +++++- 2 files changed, 14 insertions(+), 10 deletions(-) diff --git a/src/modules/esp32/StoreForwardModule.cpp b/src/modules/esp32/StoreForwardModule.cpp index 93472b8b1..cb1552521 100644 --- a/src/modules/esp32/StoreForwardModule.cpp +++ b/src/modules/esp32/StoreForwardModule.cpp @@ -96,11 +96,11 @@ void StoreForwardModule::populatePSRAM() * * @param msAgo The number of milliseconds ago from which to start sending messages. * @param to The recipient ID to send the messages to. - * @param last_request_index The index in the packet history of the last request from this node. */ -void StoreForwardModule::historySend(uint32_t msAgo, uint32_t to, uint32_t last_request_index) +void StoreForwardModule::historySend(uint32_t msAgo, uint32_t to) { - uint32_t queueSize = storeForwardModule->historyQueueCreate(msAgo, to, &last_request_index); + uint32_t lastIndex = lastRequest.find(to) != lastRequest.end() ? lastRequest[to] : 0; + uint32_t queueSize = storeForwardModule->historyQueueCreate(msAgo, to, &lastIndex); if (queueSize) { LOG_INFO("*** S&F - Sending %u message(s)\n", queueSize); @@ -114,7 +114,8 @@ void StoreForwardModule::historySend(uint32_t msAgo, uint32_t to, uint32_t last_ sf.which_variant = meshtastic_StoreAndForward_history_tag; sf.variant.history.history_messages = queueSize; sf.variant.history.window = msAgo; - sf.variant.history.last_request = last_request_index; + sf.variant.history.last_request = lastIndex; + lastRequest[to] = lastIndex; storeForwardModule->sendMessage(to, sf); } @@ -130,10 +131,10 @@ uint32_t StoreForwardModule::historyQueueCreate(uint32_t msAgo, uint32_t to, uin { this->packetHistoryTXQueue_size = 0; - // If our history was cleared, ignore what the client is telling us - uint32_t last_index = *last_request_index >= this->packetHistoryCurrent ? 0 : *last_request_index; + // If our history was cleared, ignore the last request index + uint32_t last_index = *last_request_index > this->packetHistoryCurrent ? 0 : *last_request_index; - for (int i = last_index; i < this->packetHistoryCurrent; i++) { + for (uint32_t i = last_index; i < this->packetHistoryCurrent; i++) { /* LOG_DEBUG("SF historyQueueCreate\n"); LOG_DEBUG("SF historyQueueCreate - time %d\n", this->packetHistory[i].time); @@ -398,8 +399,7 @@ bool StoreForwardModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, } else { if ((p->which_variant == meshtastic_StoreAndForward_history_tag) && (p->variant.history.window > 0)) { // window is in minutes - storeForwardModule->historySend(p->variant.history.window * 60000, getFrom(&mp), - p->variant.history.last_request); + storeForwardModule->historySend(p->variant.history.window * 60000, getFrom(&mp)); } else { storeForwardModule->historySend(historyReturnWindow * 60000, getFrom(&mp)); // defaults to 4 hours } diff --git a/src/modules/esp32/StoreForwardModule.h b/src/modules/esp32/StoreForwardModule.h index b04d9ef84..cfa9945d5 100644 --- a/src/modules/esp32/StoreForwardModule.h +++ b/src/modules/esp32/StoreForwardModule.h @@ -7,6 +7,7 @@ #include "configuration.h" #include #include +#include struct PacketHistoryStruct { uint32_t time; @@ -36,6 +37,9 @@ class StoreForwardModule : private concurrency::OSThread, public ProtobufModule< bool is_client = false; bool is_server = false; + // Unordered_map stores the last request for each nodeNum (`to` field) + std::unordered_map lastRequest; + public: StoreForwardModule(); @@ -48,7 +52,7 @@ class StoreForwardModule : private concurrency::OSThread, public ProtobufModule< */ void historyAdd(const meshtastic_MeshPacket &mp); void statsSend(uint32_t to); - void historySend(uint32_t msAgo, uint32_t to, uint32_t last_request_index = 0); + void historySend(uint32_t msAgo, uint32_t to); uint32_t historyQueueCreate(uint32_t msAgo, uint32_t to, uint32_t *last_request_index); From 5a3180a52550278dfb934739579d0ed7bf3357a3 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Mon, 19 Feb 2024 07:02:36 -0600 Subject: [PATCH 194/472] [create-pull-request] automated change (#3247) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 4d1f50ad6..ed7e93154 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 2 -build = 23 +build = 24 From 0bfac7b5f93188f7ddb80fda35c1dbba8e102109 Mon Sep 17 00:00:00 2001 From: Gabriele Russo Date: Tue, 20 Feb 2024 14:27:48 +0100 Subject: [PATCH 195/472] Fixes [3074] Heltec Tracker Screen issues + minor fixes (#3213) * Fix Heltec Tracker Screen issues Fix Heltec Tracker Screen issues like wrong offsets, display size and screen not shutting down. Divides board into two different envs for 1.0 and 1.1 version PCB * Helteck wireless tracker default version V1_1 * rename heltec tracker 1.1 - trunk fmt rename varian of heltec tracker 1.1 to "heltec tracker" to be retro-compatible. Trunk formatting. * Heltec Tracker increase Screen update to 3Hz Heltec Tracker increase Screen update to 3Hz from 1Hz --- .github/workflows/main_matrix.yml | 1 + protobufs | 2 +- src/graphics/TFTDisplay.cpp | 59 ++++++-------- src/main.cpp | 79 ++++-------------- src/main.h | 2 - src/platform/esp32/architecture.h | 4 + src/sleep.cpp | 9 +-- .../heltec_wireless_tracker/pins_arduino.h | 8 +- .../heltec_wireless_tracker/platformio.ini | 4 +- variants/heltec_wireless_tracker/variant.h | 27 +++---- .../pins_arduino.h | 80 +++++++++++++++++++ .../platformio.ini | 14 ++++ .../heltec_wireless_tracker_V1_0/variant.h | 71 ++++++++++++++++ 13 files changed, 231 insertions(+), 129 deletions(-) create mode 100644 variants/heltec_wireless_tracker_V1_0/pins_arduino.h create mode 100644 variants/heltec_wireless_tracker_V1_0/platformio.ini create mode 100644 variants/heltec_wireless_tracker_V1_0/variant.h diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 22ff92feb..17e2fbf5a 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -93,6 +93,7 @@ jobs: - board: heltec-v3 - board: heltec-wsl-v3 - board: heltec-wireless-tracker + - board: heltec-wireless-tracker-V1-0 - board: heltec-wireless-paper - board: tbeam-s3-core - board: tlora-t3s3-v1 diff --git a/protobufs b/protobufs index 5f28be497..4432d3bfc 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 5f28be497a5518334c86378335e8ffcd177ed661 +Subproject commit 4432d3bfc155107e27079d96ddba16b52f2d9ea3 diff --git a/src/graphics/TFTDisplay.cpp b/src/graphics/TFTDisplay.cpp index ef3f6182c..9475e0296 100644 --- a/src/graphics/TFTDisplay.cpp +++ b/src/graphics/TFTDisplay.cpp @@ -90,11 +90,9 @@ class LGFX : public lgfx::LGFX_Device auto cfg = _light_instance.config(); // Gets a structure for backlight settings. #ifdef ST7735_BL_V03 - if (heltec_version == 3) { - cfg.pin_bl = ST7735_BL_V03; - } else { - cfg.pin_bl = ST7735_BL_V05; - } + cfg.pin_bl = ST7735_BL_V03; +#elif defined(ST7735_BL_V05) + cfg.pin_bl = ST7735_BL_V05; #else cfg.pin_bl = ST7735_BL; // Pin number to which the backlight is connected #endif @@ -471,30 +469,27 @@ void TFTDisplay::sendCommand(uint8_t com) display(true); if (settingsMap[displayBacklight] > 0) digitalWrite(settingsMap[displayBacklight], TFT_BACKLIGHT_ON); -#elif defined(ST7735_BACKLIGHT_EN_V03) && defined(TFT_BACKLIGHT_ON) - if (heltec_version == 3) { - digitalWrite(ST7735_BACKLIGHT_EN_V03, TFT_BACKLIGHT_ON); - } else { - digitalWrite(ST7735_BACKLIGHT_EN_V05, TFT_BACKLIGHT_ON); - } +#elif defined(ST7735_BL_V03) + digitalWrite(ST7735_BL_V03, TFT_BACKLIGHT_ON); +#elif defined(ST7735_BL_V05) + pinMode(ST7735_BL_V05, OUTPUT); + digitalWrite(ST7735_BL_V05, TFT_BACKLIGHT_ON); #endif #if defined(TFT_BL) && defined(TFT_BACKLIGHT_ON) digitalWrite(TFT_BL, TFT_BACKLIGHT_ON); #endif + #ifdef VTFT_CTRL_V03 - if (heltec_version == 3) { - digitalWrite(VTFT_CTRL_V03, LOW); - } else { - digitalWrite(VTFT_CTRL_V05, LOW); - } + digitalWrite(VTFT_CTRL_V03, LOW); #endif + #ifdef VTFT_CTRL digitalWrite(VTFT_CTRL, LOW); #endif #ifdef RAK14014 #elif !defined(M5STACK) - tft->setBrightness(128); + tft->setBrightness(172); #endif break; } @@ -503,22 +498,17 @@ void TFTDisplay::sendCommand(uint8_t com) tft->clear(); if (settingsMap[displayBacklight] > 0) digitalWrite(settingsMap[displayBacklight], !TFT_BACKLIGHT_ON); -#elif defined(ST7735_BACKLIGHT_EN_V03) && defined(TFT_BACKLIGHT_ON) - if (heltec_version == 3) { - digitalWrite(ST7735_BACKLIGHT_EN_V03, !TFT_BACKLIGHT_ON); - } else { - digitalWrite(ST7735_BACKLIGHT_EN_V05, !TFT_BACKLIGHT_ON); - } +#elif defined(ST7735_BL_V03) + digitalWrite(ST7735_BL_V03, !TFT_BACKLIGHT_ON); +#elif defined(ST7735_BL_V05) + pinMode(ST7735_BL_V05, OUTPUT); + digitalWrite(ST7735_BL_V05, !TFT_BACKLIGHT_ON); #endif #if defined(TFT_BL) && defined(TFT_BACKLIGHT_ON) digitalWrite(TFT_BL, !TFT_BACKLIGHT_ON); #endif #ifdef VTFT_CTRL_V03 - if (heltec_version == 3) { - digitalWrite(VTFT_CTRL_V03, HIGH); - } else { - digitalWrite(VTFT_CTRL_V05, HIGH); - } + digitalWrite(VTFT_CTRL_V03, HIGH); #endif #ifdef VTFT_CTRL digitalWrite(VTFT_CTRL, HIGH); @@ -588,14 +578,11 @@ bool TFTDisplay::connect() LOG_INFO("Power to TFT Backlight\n"); #endif -#ifdef ST7735_BACKLIGHT_EN_V03 - if (heltec_version == 3) { - pinMode(ST7735_BACKLIGHT_EN_V03, OUTPUT); - digitalWrite(ST7735_BACKLIGHT_EN_V03, TFT_BACKLIGHT_ON); - } else { - pinMode(ST7735_BACKLIGHT_EN_V05, OUTPUT); - digitalWrite(ST7735_BACKLIGHT_EN_V05, TFT_BACKLIGHT_ON); - } +#ifdef ST7735_BL_V03 + digitalWrite(ST7735_BL_V03, TFT_BACKLIGHT_ON); +#elif defined(ST7735_BL_V05) + pinMode(ST7735_BL_V05, OUTPUT); + digitalWrite(ST7735_BL_V05, TFT_BACKLIGHT_ON); #endif tft->init(); diff --git a/src/main.cpp b/src/main.cpp index 2af912d15..fbfb983d2 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -159,25 +159,6 @@ const char *getDeviceName() return name; } -#ifdef VEXT_ENABLE_V03 - -#include - -static uint32_t calibrate_one(rtc_cal_sel_t cal_clk, const char *name) -{ - const uint32_t cal_count = 1000; - uint32_t cali_val; - for (int i = 0; i < 5; ++i) { - cali_val = rtc_clk_cal(cal_clk, cal_count); - } - return cali_val; -} - -int heltec_version = 3; - -#define CALIBRATE_ONE(cali_clk) calibrate_one(cali_clk, #cali_clk) -#endif - static int32_t ledBlinker() { static bool ledOn; @@ -243,61 +224,31 @@ void setup() digitalWrite(PIN_EINK_PWR_ON, HIGH); #endif -#if defined(LORA_TCXO_GPIO) - pinMode(LORA_TCXO_GPIO, OUTPUT); - digitalWrite(LORA_TCXO_GPIO, HIGH); -#endif - -#ifdef ST7735_BL_V03 // Heltec Wireless Tracker PCB Change Detect/Hack - - rtc_clk_32k_enable(true); - CALIBRATE_ONE(RTC_CAL_RTC_MUX); - if (CALIBRATE_ONE(RTC_CAL_32K_XTAL) != 0) { - rtc_clk_slow_freq_set(RTC_SLOW_FREQ_32K_XTAL); - CALIBRATE_ONE(RTC_CAL_RTC_MUX); - CALIBRATE_ONE(RTC_CAL_32K_XTAL); - } - - if (rtc_clk_slow_freq_get() != RTC_SLOW_FREQ_32K_XTAL) { - heltec_version = 3; - } else { - heltec_version = 5; - } -#endif - #if defined(VEXT_ENABLE_V03) - if (heltec_version == 3) { - pinMode(VEXT_ENABLE_V03, OUTPUT); - digitalWrite(VEXT_ENABLE_V03, 0); // turn on the display power - LOG_DEBUG("HELTEC Detect Tracker V1.0\n"); - } else { - pinMode(VEXT_ENABLE_V05, OUTPUT); - digitalWrite(VEXT_ENABLE_V05, 1); // turn on the display power - LOG_DEBUG("HELTEC Detect Tracker V1.1\n"); - } + pinMode(VEXT_ENABLE_V03, OUTPUT); + pinMode(ST7735_BL_V03, OUTPUT); + digitalWrite(VEXT_ENABLE_V03, 0); // turn on the display power and antenna boost + digitalWrite(ST7735_BL_V03, 1); // display backligth on + LOG_DEBUG("HELTEC Detect Tracker V1.0\n"); +#elif defined(VEXT_ENABLE_V05) + pinMode(VEXT_ENABLE_V05, OUTPUT); + pinMode(ST7735_BL_V05, OUTPUT); + digitalWrite(VEXT_ENABLE_V05, 1); // turn on the lora antenna boost + digitalWrite(ST7735_BL_V05, 1); // turn on display backligth + LOG_DEBUG("HELTEC Detect Tracker V1.1\n"); #elif defined(VEXT_ENABLE) pinMode(VEXT_ENABLE, OUTPUT); digitalWrite(VEXT_ENABLE, 0); // turn on the display power #endif #if defined(VGNSS_CTRL_V03) - if (heltec_version == 3) { - pinMode(VGNSS_CTRL_V03, OUTPUT); - digitalWrite(VGNSS_CTRL_V03, LOW); - } else { - pinMode(VGNSS_CTRL_V05, OUTPUT); - digitalWrite(VGNSS_CTRL_V05, LOW); - } + pinMode(VGNSS_CTRL_V03, OUTPUT); + digitalWrite(VGNSS_CTRL_V03, LOW); #endif #if defined(VTFT_CTRL_V03) - if (heltec_version == 3) { - pinMode(VTFT_CTRL_V03, OUTPUT); - digitalWrite(VTFT_CTRL_V03, LOW); - } else { - pinMode(VTFT_CTRL_V05, OUTPUT); - digitalWrite(VTFT_CTRL_V05, LOW); - } + pinMode(VTFT_CTRL_V03, OUTPUT); + digitalWrite(VTFT_CTRL_V03, LOW); #endif #if defined(VGNSS_CTRL) diff --git a/src/main.h b/src/main.h index 1a93298aa..5af0b4082 100644 --- a/src/main.h +++ b/src/main.h @@ -70,8 +70,6 @@ extern uint32_t shutdownAtMsec; extern uint32_t serialSinceMsec; -extern int heltec_version; - // If a thread does something that might need for it to be rescheduled ASAP it can set this flag // This will suppress the current delay and instead try to run ASAP. extern bool runASAP; diff --git a/src/platform/esp32/architecture.h b/src/platform/esp32/architecture.h index 9fa4a5dd7..22d34aa33 100644 --- a/src/platform/esp32/architecture.h +++ b/src/platform/esp32/architecture.h @@ -106,7 +106,11 @@ #elif defined(HELTEC_WSL_V3) #define HW_VENDOR meshtastic_HardwareModel_HELTEC_WSL_V3 #elif defined(HELTEC_WIRELESS_TRACKER) +#ifdef HELTEC_TRACKER_V1_0 +#define HW_VENDOR meshtastic_HardwareModel_HELTEC_WIRELESS_TRACKER_V1_0 +#else #define HW_VENDOR meshtastic_HardwareModel_HELTEC_WIRELESS_TRACKER +#endif #elif defined(HELTEC_WIRELESS_PAPER_V1_0) #define HW_VENDOR meshtastic_HardwareModel_HELTEC_WIRELESS_PAPER_V1_0 #elif defined(HELTEC_WIRELESS_PAPER) diff --git a/src/sleep.cpp b/src/sleep.cpp index 464486d00..0f71ab25b 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -203,11 +203,10 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) #endif #if defined(VEXT_ENABLE_V03) - if (heltec_version == 3) { - digitalWrite(VEXT_ENABLE_V03, 1); // turn off the display power - } else { - digitalWrite(VEXT_ENABLE_V05, 0); // turn off the display power - } + digitalWrite(VEXT_ENABLE_V03, 1); // turn off the display power +#elif defined(VEXT_ENABLE_V05) + digitalWrite(VEXT_ENABLE_V05, 0); // turn off the lora amplifier power + digitalWrite(ST7735_BL_V05, 0); // turn off the display power #elif defined(VEXT_ENABLE) digitalWrite(VEXT_ENABLE, 1); // turn off the display power #endif diff --git a/variants/heltec_wireless_tracker/pins_arduino.h b/variants/heltec_wireless_tracker/pins_arduino.h index e4d2631e7..5c0b529b0 100644 --- a/variants/heltec_wireless_tracker/pins_arduino.h +++ b/variants/heltec_wireless_tracker/pins_arduino.h @@ -5,8 +5,8 @@ #include #define WIFI_LoRa_32_V3 true -#define DISPLAY_HEIGHT 64 -#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 80 +#define DISPLAY_WIDTH 160 #define USB_VID 0x303a #define USB_PID 0x1001 @@ -26,8 +26,8 @@ static const uint8_t LED_BUILTIN = 18; static const uint8_t TX = 43; static const uint8_t RX = 44; -static const uint8_t SDA = 41; -static const uint8_t SCL = 42; +static const uint8_t SDA = 45; +static const uint8_t SCL = 46; static const uint8_t SS = 8; static const uint8_t MOSI = 10; diff --git a/variants/heltec_wireless_tracker/platformio.ini b/variants/heltec_wireless_tracker/platformio.ini index fa79eeb6a..3259d563c 100644 --- a/variants/heltec_wireless_tracker/platformio.ini +++ b/variants/heltec_wireless_tracker/platformio.ini @@ -5,7 +5,9 @@ upload_protocol = esp-builtin build_flags = ${esp32s3_base.build_flags} -I variants/heltec_wireless_tracker - -DGPS_POWER_TOGGLE + -D HELTEC_TRACKER_V1_1 + -D GPS_POWER_TOGGLE ; comment this line to disable triple press function on the user button to turn off gps entirely. + ;-D DEBUG_DISABLED ; uncomment this line to disable DEBUG output lib_deps = ${esp32s3_base.lib_deps} diff --git a/variants/heltec_wireless_tracker/variant.h b/variants/heltec_wireless_tracker/variant.h index ba2a0676a..167345e1a 100644 --- a/variants/heltec_wireless_tracker/variant.h +++ b/variants/heltec_wireless_tracker/variant.h @@ -1,5 +1,11 @@ #define LED_PIN 18 +#define HELTEC_TRACKER_V1_X + +// I2C +#define I2C_SDA SDA +#define I2C_SCL SCL + // ST7735S TFT LCD #define ST7735S 1 // there are different (sub-)versions of ST7735 #define ST7735_CS 38 @@ -9,25 +15,19 @@ #define ST7735_RESET 39 #define ST7735_MISO -1 #define ST7735_BUSY -1 -#define ST7735_BL_V03 45 #define ST7735_BL_V05 21 /* V1.1 PCB marking */ #define ST7735_SPI_HOST SPI3_HOST -#define ST7735_BACKLIGHT_EN_V03 45 -#define ST7735_BACKLIGHT_EN_V05 21 #define SPI_FREQUENCY 40000000 #define SPI_READ_FREQUENCY 16000000 #define SCREEN_ROTATE -#define TFT_HEIGHT 160 -#define TFT_WIDTH 80 +#define TFT_HEIGHT DISPLAY_WIDTH +#define TFT_WIDTH DISPLAY_HEIGHT #define TFT_OFFSET_X 26 -#define TFT_OFFSET_Y 0 -#define VTFT_CTRL_V03 46 // Heltec Tracker needs this pulled low for TFT -#define VTFT_CTRL_V05 -1 -#define SCREEN_TRANSITION_FRAMERATE 1 // fps +#define TFT_OFFSET_Y -1 +#define SCREEN_TRANSITION_FRAMERATE 3 // fps #define DISPLAY_FORCE_SMALL_FONTS -#define VEXT_ENABLE_V03 Vext // active low, powers the oled display and the lora antenna boost -#define VEXT_ENABLE_V05 3 // active HIGH, powers the oled display +#define VEXT_ENABLE_V05 3 // active HIGH, powers the lora antenna boost #define BUTTON_PIN 0 #define BATTERY_PIN 1 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage @@ -44,11 +44,6 @@ #define PIN_GPS_RESET 35 #define PIN_GPS_PPS 36 -#define VGNSS_CTRL_V03 37 // Heltec Tracker needs this pulled low for GPS -#define VGNSS_CTRL_V05 -1 // Heltec Tracker needs this pulled low for GPS -#define PIN_GPS_EN VGNSS_CTRL_V03 -#define GPS_EN_ACTIVE LOW - #define GPS_RESET_MODE LOW #define GPS_UC6580 diff --git a/variants/heltec_wireless_tracker_V1_0/pins_arduino.h b/variants/heltec_wireless_tracker_V1_0/pins_arduino.h new file mode 100644 index 000000000..5c0b529b0 --- /dev/null +++ b/variants/heltec_wireless_tracker_V1_0/pins_arduino.h @@ -0,0 +1,80 @@ +#ifndef Pins_Arduino_h +#define Pins_Arduino_h + +#include "soc/soc_caps.h" +#include + +#define WIFI_LoRa_32_V3 true +#define DISPLAY_HEIGHT 80 +#define DISPLAY_WIDTH 160 + +#define USB_VID 0x303a +#define USB_PID 0x1001 + +#define EXTERNAL_NUM_INTERRUPTS 46 +#define NUM_DIGITAL_PINS 48 +#define NUM_ANALOG_INPUTS 20 + +static const uint8_t LED_BUILTIN = 18; +#define BUILTIN_LED LED_BUILTIN // backward compatibility +#define LED_BUILTIN LED_BUILTIN + +#define analogInputToDigitalPin(p) (((p) < 20) ? (analogChannelToDigitalPin(p)) : -1) +#define digitalPinToInterrupt(p) (((p) < 48) ? (p) : -1) +#define digitalPinHasPWM(p) (p < 46) + +static const uint8_t TX = 43; +static const uint8_t RX = 44; + +static const uint8_t SDA = 45; +static const uint8_t SCL = 46; + +static const uint8_t SS = 8; +static const uint8_t MOSI = 10; +static const uint8_t MISO = 11; +static const uint8_t SCK = 9; + +static const uint8_t A0 = 1; +static const uint8_t A1 = 2; +static const uint8_t A2 = 3; +static const uint8_t A3 = 4; +static const uint8_t A4 = 5; +static const uint8_t A5 = 6; +static const uint8_t A6 = 7; +static const uint8_t A7 = 8; +static const uint8_t A8 = 9; +static const uint8_t A9 = 10; +static const uint8_t A10 = 11; +static const uint8_t A11 = 12; +static const uint8_t A12 = 13; +static const uint8_t A13 = 14; +static const uint8_t A14 = 15; +static const uint8_t A15 = 16; +static const uint8_t A16 = 17; +static const uint8_t A17 = 18; +static const uint8_t A18 = 19; +static const uint8_t A19 = 20; + +static const uint8_t T1 = 1; +static const uint8_t T2 = 2; +static const uint8_t T3 = 3; +static const uint8_t T4 = 4; +static const uint8_t T5 = 5; +static const uint8_t T6 = 6; +static const uint8_t T7 = 7; +static const uint8_t T8 = 8; +static const uint8_t T9 = 9; +static const uint8_t T10 = 10; +static const uint8_t T11 = 11; +static const uint8_t T12 = 12; +static const uint8_t T13 = 13; +static const uint8_t T14 = 14; + +static const uint8_t Vext = 36; +static const uint8_t LED = 18; + +static const uint8_t RST_LoRa = 12; +static const uint8_t BUSY_LoRa = 13; +static const uint8_t DIO0 = 14; + +#endif /* Pins_Arduino_h */ diff --git a/variants/heltec_wireless_tracker_V1_0/platformio.ini b/variants/heltec_wireless_tracker_V1_0/platformio.ini new file mode 100644 index 000000000..034360c3d --- /dev/null +++ b/variants/heltec_wireless_tracker_V1_0/platformio.ini @@ -0,0 +1,14 @@ +[env:heltec-wireless-tracker-V1-0] +extends = esp32s3_base +board = heltec_wireless_tracker +upload_protocol = esp-builtin + +build_flags = + ${esp32s3_base.build_flags} -I variants/heltec_wireless_tracker_V1_0 + -D HELTEC_TRACKER_V1_0 + -D GPS_POWER_TOGGLE ; comment this line to disable triple press function on the user button to turn off gps entirely. + ;-D DEBUG_DISABLED ; uncomment this line to disable DEBUG output + +lib_deps = + ${esp32s3_base.lib_deps} + lovyan03/LovyanGFX@^1.1.8 \ No newline at end of file diff --git a/variants/heltec_wireless_tracker_V1_0/variant.h b/variants/heltec_wireless_tracker_V1_0/variant.h new file mode 100644 index 000000000..84e77a6b9 --- /dev/null +++ b/variants/heltec_wireless_tracker_V1_0/variant.h @@ -0,0 +1,71 @@ +#define LED_PIN 18 + +#define HELTEC_TRACKER_V1_X + +// I2C +#define I2C_SDA SDA +#define I2C_SCL SCL + +// ST7735S TFT LCD +#define ST7735S 1 // there are different (sub-)versions of ST7735 +#define ST7735_CS 38 +#define ST7735_RS 40 // DC +#define ST7735_SDA 42 // MOSI +#define ST7735_SCK 41 +#define ST7735_RESET 39 +#define ST7735_MISO -1 +#define ST7735_BUSY -1 +#define ST7735_BL_V03 45 +#define ST7735_SPI_HOST SPI3_HOST +#define SPI_FREQUENCY 40000000 +#define SPI_READ_FREQUENCY 16000000 +#define SCREEN_ROTATE +#define TFT_HEIGHT DISPLAY_WIDTH +#define TFT_WIDTH DISPLAY_HEIGHT +#define TFT_OFFSET_X 26 +#define TFT_OFFSET_Y -1 +#define VTFT_CTRL_V03 46 // Heltec Tracker needs this pulled low for TFT +#define SCREEN_TRANSITION_FRAMERATE 3 // fps +#define DISPLAY_FORCE_SMALL_FONTS + +#define VEXT_ENABLE_V03 Vext // active low, powers the oled display and the lora antenna boost +#define BUTTON_PIN 0 + +#define BATTERY_PIN 1 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage +#define ADC_CHANNEL ADC1_GPIO1_CHANNEL +#define ADC_ATTENUATION ADC_ATTEN_DB_2_5 // lower dB for high resistance voltage divider +#define ADC_MULTIPLIER 4.9 + +#undef GPS_RX_PIN +#undef GPS_TX_PIN +#define GPS_RX_PIN 33 +#define GPS_TX_PIN 34 +#define PIN_GPS_RESET 35 +#define PIN_GPS_PPS 36 + +#define VGNSS_CTRL_V03 37 // Heltec Tracker needs this pulled low for GPS +#define PIN_GPS_EN VGNSS_CTRL_V03 +#define GPS_EN_ACTIVE LOW + +#define GPS_RESET_MODE LOW +#define GPS_UC6580 + +#define USE_SX1262 +#define LORA_DIO0 -1 // a No connect on the SX1262 module +#define LORA_RESET 12 +#define LORA_DIO1 14 // SX1262 IRQ +#define LORA_DIO2 13 // SX1262 BUSY +#define LORA_DIO3 // Not connected on PCB, but internally on the TTGO SX1262, if DIO3 is high the TXCO is enabled + +#define LORA_SCK 9 +#define LORA_MISO 11 +#define LORA_MOSI 10 +#define LORA_CS 8 + +#define SX126X_CS LORA_CS +#define SX126X_DIO1 LORA_DIO1 +#define SX126X_BUSY LORA_DIO2 +#define SX126X_RESET LORA_RESET + +#define SX126X_DIO2_AS_RF_SWITCH +#define SX126X_DIO3_TCXO_VOLTAGE 1.8 From 7a1c56570185ed1105420dae5ec120fa629afb58 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Tue, 20 Feb 2024 19:31:48 -0600 Subject: [PATCH 196/472] [create-pull-request] automated change (#3255) Co-authored-by: thebentern --- protobufs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/protobufs b/protobufs index 4432d3bfc..5f28be497 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 4432d3bfc155107e27079d96ddba16b52f2d9ea3 +Subproject commit 5f28be497a5518334c86378335e8ffcd177ed661 From 23df6ddf014bb9996a16ef6a767a3a796d7945f0 Mon Sep 17 00:00:00 2001 From: Mark Trevor Birss Date: Wed, 21 Feb 2024 15:18:36 +0200 Subject: [PATCH 197/472] [BOARD] Adds Waveshare ESP32-S3-PICO (#3081) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Update architecture.h * Add files via upload * Add files via upload * Update EInkDisplay2.cpp * Update platformio.ini * Update architecture.h * Update EInkDisplay2.cpp * Update platformio.ini * Update EInkDisplay2.cpp * Update platformio.ini * Update EInkDisplay2.cpp --------- Co-authored-by: Ben Meadors Co-authored-by: Thomas Göttgens --- boards/esp32-s3-pico.json | 40 ++++++++++++++ src/graphics/EInkDisplay2.cpp | 29 +++++----- src/platform/esp32/architecture.h | 6 +-- variants/esp32-s3-pico/pins_arduino.h | 36 +++++++++++++ variants/esp32-s3-pico/platformio.ini | 25 +++++++++ variants/esp32-s3-pico/variant.h | 77 +++++++++++++++++++++++++++ 6 files changed, 197 insertions(+), 16 deletions(-) create mode 100644 boards/esp32-s3-pico.json create mode 100644 variants/esp32-s3-pico/pins_arduino.h create mode 100644 variants/esp32-s3-pico/platformio.ini create mode 100644 variants/esp32-s3-pico/variant.h diff --git a/boards/esp32-s3-pico.json b/boards/esp32-s3-pico.json new file mode 100644 index 000000000..8f8c6fdb7 --- /dev/null +++ b/boards/esp32-s3-pico.json @@ -0,0 +1,40 @@ +{ + "build": { + "arduino": { + "ldscript": "esp32s3_out.ld", + "partitions": "default_16MB.csv" + }, + "core": "esp32", + "extra_flags": [ + "-DARDUINO_ESP32S3_DEV", + "-DARDUINO_USB_MODE=1", + "-DARDUINO_RUNNING_CORE=1", + "-DARDUINO_EVENT_RUNNING_CORE=1" + ], + "f_cpu": "240000000L", + "f_flash": "80000000L", + "flash_mode": "qio", + "hwids": [["0x303A", "0x1001"]], + "mcu": "esp32s3", + "variant": "esp32s3" + }, + "connectivity": ["wifi", "bluetooth", "lora"], + "debug": { + "default_tool": "esp-builtin", + "onboard_tools": ["esp-builtin"], + "openocd_target": "esp32s3.cfg" + }, + "frameworks": ["arduino", "espidf"], + "name": "Waveshare ESP32-S3-Pico (16 MB FLASH, 2 MB PSRAM)", + "upload": { + "flash_size": "16MB", + "maximum_ram_size": 327680, + "maximum_size": 16777216, + "use_1200bps_touch": true, + "wait_for_upload_port": true, + "require_upload_port": true, + "speed": 921600 + }, + "url": "https://www.waveshare.com/esp32-s3-pico.htm", + "vendor": "Waveshare" +} diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index 51d7ac5f8..4df44bdc2 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -109,6 +109,12 @@ EInkDisplay::EInkDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY setGeometry(GEOMETRY_RAWMODE, 296, 128); LOG_DEBUG("GEOMETRY_RAWMODE, 296, 128\n"); +#elif defined(ESP32_S3_PICO) + + // GxEPD2_290_T94_V2 + setGeometry(GEOMETRY_RAWMODE, EPD_WIDTH, EPD_HEIGHT); + LOG_DEBUG("GEOMETRY_RAWMODE, 296, 128\n"); + #endif // setGeometry(GEOMETRY_RAWMODE, 128, 64); // old resolution // setGeometry(GEOMETRY_128_64); // We originally used this because I wasn't sure if rawmode worked - it does @@ -176,10 +182,11 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit) #elif defined(HELTEC_WIRELESS_PAPER_V1_0) adafruitDisplay->nextPage(); #elif defined(HELTEC_WIRELESS_PAPER) - adafruitDisplay->nextPage(); + adafruitDisplay->nextPage(); +#elif defined(ESP32_S3_PICO) + adafruitDisplay->nextPage(); #elif defined(PRIVATE_HW) || defined(my) adafruitDisplay->nextPage(); - #endif // Put screen to sleep to save power (possibly not necessary because we already did poweroff inside of display) @@ -248,11 +255,8 @@ bool EInkDisplay::connect() { if (eink_found) { auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); - adafruitDisplay = new GxEPD2_BW(*lowLevel); - adafruitDisplay->init(115200, true, 10, false, SPI1, SPISettings(4000000, MSBFIRST, SPI_MODE0)); - // RAK14000 2.13 inch b/w 250x122 does actually now support partial updates adafruitDisplay->setRotation(3); // Partial update support for 1.54, 2.13 RAK14000 b/w , 2.9 and 4.2 @@ -321,12 +325,12 @@ bool EInkDisplay::connect() adafruitDisplay->setPartialWindow(0, 0, displayWidth, displayHeight); } #elif defined(M5_COREINK) - auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); - adafruitDisplay = new GxEPD2_BW(*lowLevel); - adafruitDisplay->init(115200, true, 40, false, SPI, SPISettings(4000000, MSBFIRST, SPI_MODE0)); - adafruitDisplay->setRotation(0); - adafruitDisplay->setPartialWindow(0, 0, EPD_WIDTH, EPD_HEIGHT); -#elif defined(my) + auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); + adafruitDisplay = new GxEPD2_BW(*lowLevel); + adafruitDisplay->init(115200, true, 40, false, SPI, SPISettings(4000000, MSBFIRST, SPI_MODE0)); + adafruitDisplay->setRotation(0); + adafruitDisplay->setPartialWindow(0, 0, EPD_WIDTH, EPD_HEIGHT); +#elif defined(my) || defined(ESP32_S3_PICO) { auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); adafruitDisplay = new GxEPD2_BW(*lowLevel); @@ -340,7 +344,6 @@ bool EInkDisplay::connect() // adafruitDisplay->fillScreen(UNCOLORED); // adafruitDisplay->drawCircle(100, 100, 20, COLORED); // adafruitDisplay->display(false); - return true; } @@ -470,4 +473,4 @@ bool EInkDisplay::determineRefreshMode() #endif // End USE_EINK_DYNAMIC_PARTIAL -#endif \ No newline at end of file +#endif diff --git a/src/platform/esp32/architecture.h b/src/platform/esp32/architecture.h index 22d34aa33..7fab475f3 100644 --- a/src/platform/esp32/architecture.h +++ b/src/platform/esp32/architecture.h @@ -125,8 +125,8 @@ #define HW_VENDOR meshtastic_HardwareModel_BETAFPV_900_NANO_TX #elif defined(PICOMPUTER_S3) #define HW_VENDOR meshtastic_HardwareModel_PICOMPUTER_S3 -#elif defined(HELTEC_HT62) -#define HW_VENDOR meshtastic_HardwareModel_HELTEC_HT62 +#elif defined(ESP32_S3_PICO) +#define HW_VENDOR meshtastic_HardwareModel_ESP32_S3_PICO #elif defined(SENSELORA_S3) #define HW_VENDOR meshtastic_HardwareModel_SENSELORA_S3 #elif defined(HELTEC_HT62) @@ -155,4 +155,4 @@ #define LORA_CS 18 #endif -#define SERIAL0_RX_GPIO 3 // Always GPIO3 on ESP32 // FIXME: may be different on ESP32-S3, etc. \ No newline at end of file +#define SERIAL0_RX_GPIO 3 // Always GPIO3 on ESP32 // FIXME: may be different on ESP32-S3, etc. diff --git a/variants/esp32-s3-pico/pins_arduino.h b/variants/esp32-s3-pico/pins_arduino.h new file mode 100644 index 000000000..d24d98a2e --- /dev/null +++ b/variants/esp32-s3-pico/pins_arduino.h @@ -0,0 +1,36 @@ +#ifndef Pins_Arduino_h +#define Pins_Arduino_h + +#include + +#define USB_VID 0x303a +#define USB_PID 0x1001 + +#define EXTERNAL_NUM_INTERRUPTS 46 +#define NUM_DIGITAL_PINS 48 +#define NUM_ANALOG_INPUTS 20 + +#define analogInputToDigitalPin(p) (((p) < 20) ? (analogChannelToDigitalPin(p)) : -1) +#define digitalPinToInterrupt(p) (((p) < 48) ? (p) : -1) +#define digitalPinHasPWM(p) (p < 46) + +// The default Wire will be mapped to PMU and RTC +static const uint8_t SDA = 15; +static const uint8_t SCL = 16; + +// Default SPI will be mapped to Radio +static const uint8_t MISO = 37; +static const uint8_t SCK = 35; +static const uint8_t MOSI = 36; +static const uint8_t SS = 14; + +static const uint8_t BAT_ADC_PIN = 26; + +// #define SPI_MOSI (11) +// #define SPI_SCK (14) +// #define SPI_MISO (2) +// #define SPI_CS (13) + +// #define SDCARD_CS SPI_CS + +#endif /* Pins_Arduino_h */ \ No newline at end of file diff --git a/variants/esp32-s3-pico/platformio.ini b/variants/esp32-s3-pico/platformio.ini new file mode 100644 index 000000000..f39004c36 --- /dev/null +++ b/variants/esp32-s3-pico/platformio.ini @@ -0,0 +1,25 @@ +[env:ESP32-S3-Pico] + +board_level = extra +extends = esp32s3_base +upload_protocol = esptool +board = esp32-s3-pico + +board_upload.use_1200bps_touch = yes +board_upload.wait_for_upload_port = yes +board_upload.require_upload_port = yes + +;upload_port = /dev/ttyACM0 + +build_flags = ${esp32_base.build_flags} + -DESP32_S3_PICO + ;-DPRIVATE_HW + -Ivariants/esp32-s3-pico + -DBOARD_HAS_PSRAM + -DTECHO_DISPLAY_MODEL=GxEPD2_290_T94_V2 + -DEPD_HEIGHT=128 + -DEPD_WIDTH=296 + +lib_deps = ${esp32s3_base.lib_deps} + zinggjm/GxEPD2@^1.5.3 + ;adafruit/Adafruit NeoPixel@^1.10.7 diff --git a/variants/esp32-s3-pico/variant.h b/variants/esp32-s3-pico/variant.h new file mode 100644 index 000000000..03c23d1ef --- /dev/null +++ b/variants/esp32-s3-pico/variant.h @@ -0,0 +1,77 @@ +/* + +*/ +#define HAS_GPS 0 +#undef GPS_RX_PIN +#undef GPS_TX_PIN + +#define EXT_NOTIFY_OUT 22 +#define BUTTON_PIN 0 // 17 + +// #define LED_PIN PIN_LED +// Board has RGB LED 21 + +//The usbPower state is revered ? +//DEBUG | ??:??:?? 365 [Power] Battery: usbPower=0, isCharging=0, batMv=4116, batPct=90 +//DEBUG | ??:??:?? 385 [Power] Battery: usbPower=1, isCharging=1, batMv=4243, batPct=0 + +// https://www.waveshare.com/img/devkit/ESP32-S3-Pico/ESP32-S3-Pico-details-inter-1.jpg +// digram is incorrect labeled as battery pin is getting readings on GPIO7_CH1? +#define BATTERY_PIN 7 +#define ADC_CHANNEL ADC1_GPIO7_CHANNEL +// #define ADC_CHANNEL ADC1_GPIO6_CHANNEL +// ratio of voltage divider = 3.0 (R17=200k, R18=100k) +#define ADC_MULTIPLIER 3.1 // 3.0 + a bit for being optimistic + +#define I2C_SDA 15 +#define I2C_SCL 16 + +// Enable secondary bus for external periherals +// https://www.waveshare.com/wiki/Pico-OLED-1.3 +// #define USE_SH1107_128_64 +// Not working +#define I2C_SDA1 17 +#define I2C_SCL1 18 + +#define BUTTON_PIN 0 // This is the BOOT button +#define BUTTON_NEED_PULLUP + +// #define USE_RF95 // RFM95/SX127x +#define USE_SX1262 +// #define USE_SX1280 + +#define LORA_MISO 37 +#define LORA_SCK 35 +#define LORA_MOSI 36 +#define LORA_CS 14 + +#define LORA_RESET 40 +#define LORA_DIO1 4 +#define LORA_DIO2 13 + +#ifdef USE_SX1262 +#define SX126X_CS LORA_CS +#define SX126X_DIO1 LORA_DIO1 +#define SX126X_BUSY LORA_DIO2 +#define SX126X_RESET LORA_RESET +#define SX126X_DIO2_AS_RF_SWITCH +#define SX126X_DIO3_TCXO_VOLTAGE 1.8 +#endif + +#ifdef USE_SX1280 +#define SX128X_CS LORA_CS +#define SX128X_DIO1 LORA_DIO1 +#define SX128X_BUSY 9 +#define SX128X_RESET LORA_RESET +#endif + +#define USE_EINK +/* + * eink display pins + */ +#define PIN_EINK_CS 34 +#define PIN_EINK_BUSY 38 +#define PIN_EINK_DC 33 +#define PIN_EINK_RES 42 // 37 //(-1) // cant be MISO Waveshare ??) +#define PIN_EINK_SCLK 35 +#define PIN_EINK_MOSI 36 From e0c7f7207bddab78fb66de064345a185cb51e842 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 21 Feb 2024 07:45:23 -0600 Subject: [PATCH 198/472] Manual trunk --- src/graphics/EInkDisplay2.cpp | 14 +++++++------- variants/esp32-s3-pico/variant.h | 6 +++--- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index 4df44bdc2..10653e25a 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -182,9 +182,9 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit) #elif defined(HELTEC_WIRELESS_PAPER_V1_0) adafruitDisplay->nextPage(); #elif defined(HELTEC_WIRELESS_PAPER) - adafruitDisplay->nextPage(); + adafruitDisplay->nextPage(); #elif defined(ESP32_S3_PICO) - adafruitDisplay->nextPage(); + adafruitDisplay->nextPage(); #elif defined(PRIVATE_HW) || defined(my) adafruitDisplay->nextPage(); #endif @@ -325,11 +325,11 @@ bool EInkDisplay::connect() adafruitDisplay->setPartialWindow(0, 0, displayWidth, displayHeight); } #elif defined(M5_COREINK) - auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); - adafruitDisplay = new GxEPD2_BW(*lowLevel); - adafruitDisplay->init(115200, true, 40, false, SPI, SPISettings(4000000, MSBFIRST, SPI_MODE0)); - adafruitDisplay->setRotation(0); - adafruitDisplay->setPartialWindow(0, 0, EPD_WIDTH, EPD_HEIGHT); + auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); + adafruitDisplay = new GxEPD2_BW(*lowLevel); + adafruitDisplay->init(115200, true, 40, false, SPI, SPISettings(4000000, MSBFIRST, SPI_MODE0)); + adafruitDisplay->setRotation(0); + adafruitDisplay->setPartialWindow(0, 0, EPD_WIDTH, EPD_HEIGHT); #elif defined(my) || defined(ESP32_S3_PICO) { auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); diff --git a/variants/esp32-s3-pico/variant.h b/variants/esp32-s3-pico/variant.h index 03c23d1ef..9e10183fb 100644 --- a/variants/esp32-s3-pico/variant.h +++ b/variants/esp32-s3-pico/variant.h @@ -11,9 +11,9 @@ // #define LED_PIN PIN_LED // Board has RGB LED 21 -//The usbPower state is revered ? -//DEBUG | ??:??:?? 365 [Power] Battery: usbPower=0, isCharging=0, batMv=4116, batPct=90 -//DEBUG | ??:??:?? 385 [Power] Battery: usbPower=1, isCharging=1, batMv=4243, batPct=0 +// The usbPower state is revered ? +// DEBUG | ??:??:?? 365 [Power] Battery: usbPower=0, isCharging=0, batMv=4116, batPct=90 +// DEBUG | ??:??:?? 385 [Power] Battery: usbPower=1, isCharging=1, batMv=4243, batPct=0 // https://www.waveshare.com/img/devkit/ESP32-S3-Pico/ESP32-S3-Pico-details-inter-1.jpg // digram is incorrect labeled as battery pin is getting readings on GPIO7_CH1? From 9784758c7b88b95627a0685d797c9cef427f6e40 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 21 Feb 2024 10:03:45 -0600 Subject: [PATCH 199/472] Remove heltec-v1 --- .github/workflows/main_matrix.yml | 1 - bin/check-all.sh | 2 +- bin/check-dependencies.sh | 2 +- 3 files changed, 2 insertions(+), 3 deletions(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 17e2fbf5a..5c1cf4c21 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -68,7 +68,6 @@ jobs: - board: tlora-v2-1-1_8 - board: tbeam - board: heltec-ht62-esp32c3-sx1262 - - board: heltec-v1 - board: heltec-v2_0 - board: heltec-v2_1 - board: tbeam0_7 diff --git a/bin/check-all.sh b/bin/check-all.sh index cdd1ceb9d..d1b50a8aa 100755 --- a/bin/check-all.sh +++ b/bin/check-all.sh @@ -13,7 +13,7 @@ if [[ $# -gt 0 ]]; then # can override which environment by passing arg BOARDS="$@" else - BOARDS="tlora-v2 tlora-v1 tlora_v1_3 tlora-v2-1-1.6 tbeam heltec-v1 heltec-v2.0 heltec-v2.1 tbeam0.7 meshtastic-diy-v1 rak4631 rak4631_eink rak11200 t-echo canaryone pca10059_diy_eink" + BOARDS="tlora-v2 tlora-v1 tlora_v1_3 tlora-v2-1-1.6 tbeam heltec-v2.0 heltec-v2.1 tbeam0.7 meshtastic-diy-v1 rak4631 rak4631_eink rak11200 t-echo canaryone pca10059_diy_eink" fi echo "BOARDS:${BOARDS}" diff --git a/bin/check-dependencies.sh b/bin/check-dependencies.sh index 52bc76089..4aa0fccc0 100644 --- a/bin/check-dependencies.sh +++ b/bin/check-dependencies.sh @@ -8,7 +8,7 @@ if [[ $# -gt 0 ]]; then # can override which environment by passing arg BOARDS="$@" else - BOARDS="rak4631 rak4631_eink t-echo canaryone pca10059_diy_eink pico rak11200 tlora-v2 tlora-v1 tlora_v1_3 tlora-v2-1-1.6 tbeam heltec-v1 heltec-v2.0 heltec-v2.1 tbeam0.7 meshtastic-diy-v1 nano-g1 station-g1 m5stack-core m5stack-coreink tbeam-s3-core" + BOARDS="rak4631 rak4631_eink t-echo canaryone pca10059_diy_eink pico rak11200 tlora-v2 tlora-v1 tlora_v1_3 tlora-v2-1-1.6 tbeam heltec-v2.0 heltec-v2.1 tbeam0.7 meshtastic-diy-v1 nano-g1 station-g1 m5stack-core m5stack-coreink tbeam-s3-core" fi echo "BOARDS:${BOARDS}" From eb8a12e5a2fc65441a5d0ac2b0993aa0d76aeb5d Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Wed, 21 Feb 2024 20:00:14 +0100 Subject: [PATCH 200/472] Refactor MQTT: only publish on LoRa Tx if packet is from us and on Rx if not (#3245) Such that direct message to MQTT node gets published and we get rid of always rebroadcasting when MQTT is enabled Co-authored-by: Ben Meadors --- src/mesh/FloodingRouter.cpp | 2 +- src/mesh/Router.cpp | 17 ++++++++++++----- src/mqtt/MQTT.cpp | 5 +++-- src/mqtt/MQTT.h | 3 ++- 4 files changed, 18 insertions(+), 9 deletions(-) diff --git a/src/mesh/FloodingRouter.cpp b/src/mesh/FloodingRouter.cpp index d27d47e87..db3f3f35e 100644 --- a/src/mesh/FloodingRouter.cpp +++ b/src/mesh/FloodingRouter.cpp @@ -21,7 +21,7 @@ bool FloodingRouter::shouldFilterReceived(const meshtastic_MeshPacket *p) { if (wasSeenRecently(p)) { // Note: this will also add a recent packet record printPacket("Ignoring incoming msg, because we've already seen it", p); - if (!moduleConfig.mqtt.enabled && config.device.role != meshtastic_Config_DeviceConfig_Role_ROUTER && + if (config.device.role != meshtastic_Config_DeviceConfig_Role_ROUTER && config.device.role != meshtastic_Config_DeviceConfig_Role_ROUTER_CLIENT && config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER) { // cancel rebroadcast of this message *if* there was already one, unless we're a router/repeater! diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp index 492ed962b..4a6dc9007 100644 --- a/src/mesh/Router.cpp +++ b/src/mesh/Router.cpp @@ -257,10 +257,9 @@ ErrorCode Router::send(meshtastic_MeshPacket *p) return encodeResult; // FIXME - this isn't a valid ErrorCode } - if (moduleConfig.mqtt.enabled) { - LOG_INFO("Should encrypt MQTT?: %d\n", moduleConfig.mqtt.encryption_enabled); - if (mqtt) - mqtt->onSend(*p, *p_decoded, chIndex); + // Only publish to MQTT if we're the original transmitter of the packet + if (moduleConfig.mqtt.enabled && p->from == nodeDB.getNodeNum() && mqtt) { + mqtt->onSend(*p, *p_decoded, chIndex); } packetPool.release(p_decoded); } @@ -438,6 +437,8 @@ void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src) { // Also, we should set the time from the ISR and it should have msec level resolution p->rx_time = getValidTime(RTCQualityFromNet); // store the arrival timestamp for the phone + // Store a copy of encrypted packet for MQTT + meshtastic_MeshPacket *p_encrypted = packetPool.allocCopy(*p); // Take those raw bytes and convert them back into a well structured protobuf we can understand bool decoded = perhapsDecode(p); @@ -449,10 +450,16 @@ void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src) printPacket("handleReceived(USER)", p); else printPacket("handleReceived(REMOTE)", p); + + // Publish received message to MQTT if we're not the original transmitter of the packet + if (moduleConfig.mqtt.enabled && getFrom(p) != nodeDB.getNodeNum() && mqtt) + mqtt->onSend(*p_encrypted, *p, p->channel); } else { printPacket("packet decoding failed or skipped (no PSK?)", p); } + packetPool.release(p_encrypted); // Release the encrypted packet + // call modules here MeshModule::callPlugins(*p, src); } @@ -474,4 +481,4 @@ void Router::perhapsHandleReceived(meshtastic_MeshPacket *p) handleReceived(p); packetPool.release(p); -} +} \ No newline at end of file diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 8d7c329a2..8c241a302 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -485,14 +485,15 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket & env->channel_id = (char *)channelId; env->gateway_id = owner.id; + LOG_DEBUG("MQTT onSend - Publishing "); if (moduleConfig.mqtt.encryption_enabled) { env->packet = (meshtastic_MeshPacket *)∓ + LOG_DEBUG("encrypted message\n"); } else { env->packet = (meshtastic_MeshPacket *)&mp_decoded; + LOG_DEBUG("portnum %i message\n", env->packet->decoded.portnum); } - LOG_DEBUG("MQTT onSend - Publishing portnum %i message\n", env->packet->decoded.portnum); - if (moduleConfig.mqtt.proxy_to_client_enabled || this->isConnectedDirectly()) { // FIXME - this size calculation is super sloppy, but it will go away once we dynamically alloc meshpackets static uint8_t bytes[meshtastic_MeshPacket_size + 64]; diff --git a/src/mqtt/MQTT.h b/src/mqtt/MQTT.h index dfcb75b7d..2b803e3fc 100644 --- a/src/mqtt/MQTT.h +++ b/src/mqtt/MQTT.h @@ -50,7 +50,8 @@ class MQTT : private concurrency::OSThread /** * Publish a packet on the global MQTT server. - * This hook must be called **after** the packet is encrypted (including the channel being changed to a hash). + * @param mp the encrypted packet to publish + * @param mp_decoded the decrypted packet to publish * @param chIndex the index of the channel for this message * * Note: for messages we are forwarding on the mesh that we can't find the channel for (because we don't have the keys), we From 78b4a656354dbabf2270866b201a0a2d57f54218 Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Thu, 22 Feb 2024 08:00:56 +1300 Subject: [PATCH 201/472] E-Ink: additional conditions for "Dynamic Partial" mode (#3256) Co-authored-by: Ben Meadors --- src/graphics/EInkDisplay2.cpp | 74 ++++++++++++++++++++++++++++++++--- src/graphics/EInkDisplay2.h | 17 +++++++- 2 files changed, 83 insertions(+), 8 deletions(-) diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index 10653e25a..66e7ffd40 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -362,6 +362,12 @@ void EInkDisplay::lowPriority() isHighPriority = false; } +// Full-refresh is explicitly requested for next one update - no skipping please +void EInkDisplay::demandFullRefresh() +{ + demandingFull = true; +} + // configure display for partial-refresh void EInkDisplay::configForPartialRefresh() { @@ -384,6 +390,49 @@ void EInkDisplay::configForFullRefresh() #endif } +#ifdef EINK_PARTIAL_ERASURE_LIMIT +// Count black pixels in an image. Used for "erasure tracking" +int32_t EInkDisplay::countBlackPixels() +{ + int32_t blackCount = 0; // Signed, to avoid underflow when comparing + for (uint16_t b = 0; b < (displayWidth / 8) * displayHeight; b++) { + for (uint8_t i = 0; i < 7; i++) { + // Check if each bit is black or white + blackCount += (buffer[b] >> i) & 1; + } + } + return blackCount; +} + +// Evaluate the (rough) amount of black->white pixel change since last full refresh +bool EInkDisplay::tooManyErasures() +{ + // Ideally, we would compare the new and old buffers, to count *actual* white-to-black pixel changes + // but that would require substantially more "code tampering" + + // Get the black pixel stats for this image + int32_t blackCount = countBlackPixels(); + int32_t blackDifference = blackCount - prevBlackCount; + + // Update the running total of "erasures" - black pixels which have become white, since last full-refresh + if (blackDifference < 0) + erasedSinceFull -= blackDifference; + + // Store black pixel count for next time + prevBlackCount = blackCount; + + // Log the running total - help devs setup new boards + LOG_DEBUG("Dynamic Partial: erasedSinceFull=%hu, EINK_PARTIAL_ERASURE_LIMIT=%hu\n", erasedSinceFull, + EINK_PARTIAL_ERASURE_LIMIT); + + // Check if too many pixels have been erased + if (erasedSinceFull > EINK_PARTIAL_ERASURE_LIMIT) + return true; // Too many + else + return false; // Still okay +} +#endif // ifdef EINK_PARTIAL_BRIGHTEN_LIMIT_PX + bool EInkDisplay::newImageMatchesOld() { uint32_t newImageHash = 0; @@ -416,16 +465,20 @@ bool EInkDisplay::determineRefreshMode() missedHighPriorityUpdate = false; } - // Abort: if too soon for a new frame - if (isHighPriority && partialRefreshCount > 0 && sinceLast < highPriorityLimitMsec) { - LOG_DEBUG("Update skipped: exceeded EINK_HIGHPRIORITY_LIMIT_SECONDS\n"); + // Abort: if too soon for a new frame (unless demanding full) + if (!demandingFull && isHighPriority && partialRefreshCount > 0 && sinceLast < highPriorityLimitMsec) { + LOG_DEBUG("Dynamic Partial: update skipped. Exceeded EINK_HIGHPRIORITY_LIMIT_SECONDS\n"); missedHighPriorityUpdate = true; return false; } - if (!isHighPriority && sinceLast < lowPriorityLimitMsec) { + if (!demandingFull && !isHighPriority && !demandingFull && sinceLast < lowPriorityLimitMsec) { return false; } + // If demanded full refresh: give it to them + if (demandingFull) + needsFull = true; + // Check if old image (partial) should be redrawn (as full), for image quality if (partialRefreshCount > 0 && !isHighPriority) needsFull = true; @@ -434,7 +487,14 @@ bool EInkDisplay::determineRefreshMode() if (partialRefreshCount >= partialRefreshLimit) needsFull = true; +#ifdef EINK_PARTIAL_ERASURE_LIMIT + // Some displays struggle with erasing black pixels to white, during partial refresh + if (tooManyErasures()) + needsFull = true; +#endif + // If image matches + // (Block must run, even if full already selected, to store hash for next time) if (newImageMatchesOld()) { // If low priority: limit rate // otherwise, every loop() will run the hash method @@ -453,9 +513,11 @@ bool EInkDisplay::determineRefreshMode() if (partialRefreshCount > 0) configForFullRefresh(); - LOG_DEBUG("Conditions met for full-refresh\n"); + LOG_DEBUG("Dynamic Partial: conditions met for full-refresh\n"); partialRefreshCount = 0; needsFull = false; + demandingFull = false; + erasedSinceFull = 0; // Reset the count for EINK_PARTIAL_ERASURE_LIMIT - tracks ghosting buildup } // If options allow a partial refresh @@ -463,7 +525,7 @@ bool EInkDisplay::determineRefreshMode() if (partialRefreshCount == 0) configForPartialRefresh(); - LOG_DEBUG("Conditions met for partial-refresh\n"); + LOG_DEBUG("Dynamic Partial: conditions met for partial-refresh\n"); partialRefreshCount++; } diff --git a/src/graphics/EInkDisplay2.h b/src/graphics/EInkDisplay2.h index 91261c865..aeaddee2d 100644 --- a/src/graphics/EInkDisplay2.h +++ b/src/graphics/EInkDisplay2.h @@ -64,8 +64,10 @@ class EInkDisplay : public OLEDDisplay // Use full refresh if EITHER: // * lowPriority() was set + // * demandFullRefresh() was called - (single shot) // * too many partial updates in a row: protect display - (EINK_PARTIAL_REPEAT_LIMIT) // * no recent updates, and last update was partial: redraw for image quality (EINK_LOWPRIORITY_LIMIT_SECONDS) + // * (optional) too many "erasures" since full-refresh (black pixels cleared to white) // Rate limit if: // * lowPriority() - (EINK_LOWPRIORITY_LIMIT_SECONDS) @@ -74,6 +76,7 @@ class EInkDisplay : public OLEDDisplay // Skip update entirely if ALL criteria met: // * new image matches old image // * lowPriority() + // * no call to demandFullRefresh() // * not redrawing for image quality // * not refreshing for display health @@ -89,24 +92,33 @@ class EInkDisplay : public OLEDDisplay #define EINK_LOWPRIORITY_LIMIT_SECONDS 30 #define EINK_HIGHPRIORITY_LIMIT_SECONDS 1 #define EINK_PARTIAL_REPEAT_LIMIT 5 + #define EINK_PARTIAL_ERASURE_LIMIT 300 // optional */ public: - void highPriority(); // Suggest partial refresh - void lowPriority(); // Suggest full refresh + void highPriority(); // Suggest partial refresh + void lowPriority(); // Suggest full refresh + void demandFullRefresh(); // For next update: explicitly request full refresh protected: void configForPartialRefresh(); // Display specific code to select partial refresh mode void configForFullRefresh(); // Display specific code to return to full refresh mode bool newImageMatchesOld(); // Is the new update actually different to the last image? bool determineRefreshMode(); // Called immediately before data written to display - choose refresh mode, or abort update +#ifdef EINK_PARTIAL_ERASURE_LIMIT + int32_t countBlackPixels(); // Calculate the number of black pixels in the new image + bool tooManyErasures(); // Has too much "ghosting" (black pixels erased to white) accumulated since last full-refresh? +#endif bool isHighPriority = true; // Does the method calling update believe that this is urgent? bool needsFull = false; // Is a full refresh forced? (display health) + bool demandingFull = false; // Was full refresh specifically requested? (splash screens, etc) bool missedHighPriorityUpdate = false; // Was a high priority update skipped for rate-limiting? uint16_t partialRefreshCount = 0; // How many partials have occurred since last full refresh? uint32_t lastUpdateMsec = 0; // When did the last update occur? uint32_t prevImageHash = 0; // Used to check if update will change screen image (skippable or not) + int32_t prevBlackCount = 0; // How many black pixels were in the previous image + uint32_t erasedSinceFull = 0; // How many black pixels have been set back to white since last full-refresh? (roughly) // Set in variant.h const uint32_t lowPriorityLimitMsec = (uint32_t)1000 * EINK_LOWPRIORITY_LIMIT_SECONDS; // Max rate for partial refreshes @@ -117,5 +129,6 @@ class EInkDisplay : public OLEDDisplay // Tolerate calls to these methods anywhere, just to be safe void highPriority() {} void lowPriority() {} + void demandFullRefresh() {} #endif }; From 880afb9477b945da94228e8e24b273789c903de0 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 22 Feb 2024 07:18:53 -0600 Subject: [PATCH 202/472] Protos --- protobufs | 2 +- src/mesh/generated/meshtastic/atak.pb.h | 6 +++--- src/modules/PositionModule.cpp | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/protobufs b/protobufs index 5f28be497..b88889941 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 5f28be497a5518334c86378335e8ffcd177ed661 +Subproject commit b88889941c1ac6bec7b3043913ccbc9007077d3d diff --git a/src/mesh/generated/meshtastic/atak.pb.h b/src/mesh/generated/meshtastic/atak.pb.h index 71c3c387f..17d3cd3b9 100644 --- a/src/mesh/generated/meshtastic/atak.pb.h +++ b/src/mesh/generated/meshtastic/atak.pb.h @@ -110,7 +110,7 @@ typedef struct _meshtastic_PLI { in floating point */ int32_t longitude_i; /* Altitude (ATAK prefers HAE) */ - uint32_t altitude; + int32_t altitude; /* Speed */ uint32_t speed; /* Course in degrees */ @@ -238,7 +238,7 @@ X(a, STATIC, SINGULAR, STRING, device_callsign, 2) #define meshtastic_PLI_FIELDLIST(X, a) \ X(a, STATIC, SINGULAR, SFIXED32, latitude_i, 1) \ X(a, STATIC, SINGULAR, SFIXED32, longitude_i, 2) \ -X(a, STATIC, SINGULAR, UINT32, altitude, 3) \ +X(a, STATIC, SINGULAR, INT32, altitude, 3) \ X(a, STATIC, SINGULAR, UINT32, speed, 4) \ X(a, STATIC, SINGULAR, UINT32, course, 5) #define meshtastic_PLI_CALLBACK NULL @@ -263,7 +263,7 @@ extern const pb_msgdesc_t meshtastic_PLI_msg; #define meshtastic_Contact_size 242 #define meshtastic_GeoChat_size 323 #define meshtastic_Group_size 4 -#define meshtastic_PLI_size 26 +#define meshtastic_PLI_size 31 #define meshtastic_Status_size 3 #define meshtastic_TAKPacket_size 584 diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index e82362bc6..eaa224d3b 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -193,7 +193,7 @@ meshtastic_MeshPacket *PositionModule::allocAtakPli() {.pli = { .latitude_i = localPosition.latitude_i, .longitude_i = localPosition.longitude_i, - .altitude = localPosition.altitude_hae > 0 ? localPosition.altitude_hae : 0, + .altitude = localPosition.altitude_hae, .speed = localPosition.ground_speed, .course = static_cast(localPosition.ground_track), }}}; From 0153daa8ba25705d08a0e766ca15fe05263a6b5a Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 22 Feb 2024 00:18:51 -0600 Subject: [PATCH 203/472] Minor typo fix --- src/modules/PositionModule.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index eaa224d3b..32c5a0c41 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -164,7 +164,7 @@ meshtastic_MeshPacket *PositionModule::allocReply() LOG_INFO("Providing time to mesh %u\n", p.time); } - LOG_INFO("Position reply: time=%i, latI=%i, lonI=-%i\n", p.time, p.latitude_i, p.longitude_i); + LOG_INFO("Position reply: time=%i, latI=%i, lonI=%i\n", p.time, p.latitude_i, p.longitude_i); // TAK Tracker devices should send their position in a TAK packet over the ATAK port if (config.device.role == meshtastic_Config_DeviceConfig_Role_TAK_TRACKER) From 790f100620860acb01323025d5f49d899621cd92 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 22 Feb 2024 11:36:16 -0600 Subject: [PATCH 204/472] Protobuf bump --- protobufs | 2 +- src/mesh/generated/meshtastic/apponly.pb.h | 2 +- src/mesh/generated/meshtastic/channel.pb.c | 3 ++ src/mesh/generated/meshtastic/channel.pb.h | 34 ++++++++++++++++--- src/mesh/generated/meshtastic/config.pb.h | 13 +++---- src/mesh/generated/meshtastic/deviceonly.pb.h | 4 +-- src/mesh/generated/meshtastic/localonly.pb.h | 2 +- src/mesh/generated/meshtastic/mesh.pb.h | 14 +++++--- 8 files changed, 50 insertions(+), 24 deletions(-) diff --git a/protobufs b/protobufs index b88889941..24edea644 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit b88889941c1ac6bec7b3043913ccbc9007077d3d +Subproject commit 24edea64429de4474c00d09990ef4c496614dc5d diff --git a/src/mesh/generated/meshtastic/apponly.pb.h b/src/mesh/generated/meshtastic/apponly.pb.h index c9c120efa..253fdd8ef 100644 --- a/src/mesh/generated/meshtastic/apponly.pb.h +++ b/src/mesh/generated/meshtastic/apponly.pb.h @@ -54,7 +54,7 @@ extern const pb_msgdesc_t meshtastic_ChannelSet_msg; #define meshtastic_ChannelSet_fields &meshtastic_ChannelSet_msg /* Maximum encoded size of messages (where known) */ -#define meshtastic_ChannelSet_size 594 +#define meshtastic_ChannelSet_size 658 #ifdef __cplusplus } /* extern "C" */ diff --git a/src/mesh/generated/meshtastic/channel.pb.c b/src/mesh/generated/meshtastic/channel.pb.c index 62585fd17..f604f64e9 100644 --- a/src/mesh/generated/meshtastic/channel.pb.c +++ b/src/mesh/generated/meshtastic/channel.pb.c @@ -9,6 +9,9 @@ PB_BIND(meshtastic_ChannelSettings, meshtastic_ChannelSettings, AUTO) +PB_BIND(meshtastic_ModuleSettings, meshtastic_ModuleSettings, AUTO) + + PB_BIND(meshtastic_Channel, meshtastic_Channel, AUTO) diff --git a/src/mesh/generated/meshtastic/channel.pb.h b/src/mesh/generated/meshtastic/channel.pb.h index 535962ae6..1587483c0 100644 --- a/src/mesh/generated/meshtastic/channel.pb.h +++ b/src/mesh/generated/meshtastic/channel.pb.h @@ -30,6 +30,12 @@ typedef enum _meshtastic_Channel_Role { } meshtastic_Channel_Role; /* Struct definitions */ +/* This message is specifically for modules to store per-channel configuration data. */ +typedef struct _meshtastic_ModuleSettings { + /* Bits of precision for the location sent in position packets. */ + uint32_t position_precision; +} meshtastic_ModuleSettings; + typedef PB_BYTES_ARRAY_T(32) meshtastic_ChannelSettings_psk_t; /* This information can be encoded as a QRcode/url so that other users can configure their radio to join the same channel. @@ -85,6 +91,9 @@ typedef struct _meshtastic_ChannelSettings { bool uplink_enabled; /* If true, messages seen on the internet will be forwarded to the local mesh. */ bool downlink_enabled; + /* Per-channel module settings. */ + bool has_module_settings; + meshtastic_ModuleSettings module_settings; } meshtastic_ChannelSettings; /* A pair of a channel number, mode and the (sharable) settings for that channel */ @@ -111,22 +120,27 @@ extern "C" { #define _meshtastic_Channel_Role_ARRAYSIZE ((meshtastic_Channel_Role)(meshtastic_Channel_Role_SECONDARY+1)) + #define meshtastic_Channel_role_ENUMTYPE meshtastic_Channel_Role /* Initializer values for message structs */ -#define meshtastic_ChannelSettings_init_default {0, {0, {0}}, "", 0, 0, 0} +#define meshtastic_ChannelSettings_init_default {0, {0, {0}}, "", 0, 0, 0, false, meshtastic_ModuleSettings_init_default} +#define meshtastic_ModuleSettings_init_default {0} #define meshtastic_Channel_init_default {0, false, meshtastic_ChannelSettings_init_default, _meshtastic_Channel_Role_MIN} -#define meshtastic_ChannelSettings_init_zero {0, {0, {0}}, "", 0, 0, 0} +#define meshtastic_ChannelSettings_init_zero {0, {0, {0}}, "", 0, 0, 0, false, meshtastic_ModuleSettings_init_zero} +#define meshtastic_ModuleSettings_init_zero {0} #define meshtastic_Channel_init_zero {0, false, meshtastic_ChannelSettings_init_zero, _meshtastic_Channel_Role_MIN} /* Field tags (for use in manual encoding/decoding) */ +#define meshtastic_ModuleSettings_position_precision_tag 1 #define meshtastic_ChannelSettings_channel_num_tag 1 #define meshtastic_ChannelSettings_psk_tag 2 #define meshtastic_ChannelSettings_name_tag 3 #define meshtastic_ChannelSettings_id_tag 4 #define meshtastic_ChannelSettings_uplink_enabled_tag 5 #define meshtastic_ChannelSettings_downlink_enabled_tag 6 +#define meshtastic_ChannelSettings_module_settings_tag 7 #define meshtastic_Channel_index_tag 1 #define meshtastic_Channel_settings_tag 2 #define meshtastic_Channel_role_tag 3 @@ -138,9 +152,16 @@ X(a, STATIC, SINGULAR, BYTES, psk, 2) \ X(a, STATIC, SINGULAR, STRING, name, 3) \ X(a, STATIC, SINGULAR, FIXED32, id, 4) \ X(a, STATIC, SINGULAR, BOOL, uplink_enabled, 5) \ -X(a, STATIC, SINGULAR, BOOL, downlink_enabled, 6) +X(a, STATIC, SINGULAR, BOOL, downlink_enabled, 6) \ +X(a, STATIC, OPTIONAL, MESSAGE, module_settings, 7) #define meshtastic_ChannelSettings_CALLBACK NULL #define meshtastic_ChannelSettings_DEFAULT NULL +#define meshtastic_ChannelSettings_module_settings_MSGTYPE meshtastic_ModuleSettings + +#define meshtastic_ModuleSettings_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, UINT32, position_precision, 1) +#define meshtastic_ModuleSettings_CALLBACK NULL +#define meshtastic_ModuleSettings_DEFAULT NULL #define meshtastic_Channel_FIELDLIST(X, a) \ X(a, STATIC, SINGULAR, INT32, index, 1) \ @@ -151,15 +172,18 @@ X(a, STATIC, SINGULAR, UENUM, role, 3) #define meshtastic_Channel_settings_MSGTYPE meshtastic_ChannelSettings extern const pb_msgdesc_t meshtastic_ChannelSettings_msg; +extern const pb_msgdesc_t meshtastic_ModuleSettings_msg; extern const pb_msgdesc_t meshtastic_Channel_msg; /* Defines for backwards compatibility with code written before nanopb-0.4.0 */ #define meshtastic_ChannelSettings_fields &meshtastic_ChannelSettings_msg +#define meshtastic_ModuleSettings_fields &meshtastic_ModuleSettings_msg #define meshtastic_Channel_fields &meshtastic_Channel_msg /* Maximum encoded size of messages (where known) */ -#define meshtastic_ChannelSettings_size 62 -#define meshtastic_Channel_size 77 +#define meshtastic_ChannelSettings_size 70 +#define meshtastic_Channel_size 85 +#define meshtastic_ModuleSettings_size 6 #ifdef __cplusplus } /* extern "C" */ diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index b8e79fe6b..c56cf65a0 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -317,9 +317,6 @@ typedef struct _meshtastic_Config_PositionConfig { uint32_t gps_en_gpio; /* Set where GPS is enabled, disabled, or not present */ meshtastic_Config_PositionConfig_GpsMode gps_mode; - /* Set GPS precision in bits per channel, or 0 for disabled */ - pb_size_t channel_precision_count; - uint32_t channel_precision[8]; } meshtastic_Config_PositionConfig; /* Power Config\ @@ -587,7 +584,7 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_Config_init_default {0, {meshtastic_Config_DeviceConfig_init_default}} #define meshtastic_Config_DeviceConfig_init_default {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0, 0} -#define meshtastic_Config_PositionConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, _meshtastic_Config_PositionConfig_GpsMode_MIN, 0, {0, 0, 0, 0, 0, 0, 0, 0}} +#define meshtastic_Config_PositionConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, _meshtastic_Config_PositionConfig_GpsMode_MIN} #define meshtastic_Config_PowerConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_Config_NetworkConfig_init_default {0, "", "", "", 0, _meshtastic_Config_NetworkConfig_AddressMode_MIN, false, meshtastic_Config_NetworkConfig_IpV4Config_init_default, ""} #define meshtastic_Config_NetworkConfig_IpV4Config_init_default {0, 0, 0, 0} @@ -596,7 +593,7 @@ extern "C" { #define meshtastic_Config_BluetoothConfig_init_default {0, _meshtastic_Config_BluetoothConfig_PairingMode_MIN, 0} #define meshtastic_Config_init_zero {0, {meshtastic_Config_DeviceConfig_init_zero}} #define meshtastic_Config_DeviceConfig_init_zero {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0, 0} -#define meshtastic_Config_PositionConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, _meshtastic_Config_PositionConfig_GpsMode_MIN, 0, {0, 0, 0, 0, 0, 0, 0, 0}} +#define meshtastic_Config_PositionConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, _meshtastic_Config_PositionConfig_GpsMode_MIN} #define meshtastic_Config_PowerConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_Config_NetworkConfig_init_zero {0, "", "", "", 0, _meshtastic_Config_NetworkConfig_AddressMode_MIN, false, meshtastic_Config_NetworkConfig_IpV4Config_init_zero, ""} #define meshtastic_Config_NetworkConfig_IpV4Config_init_zero {0, 0, 0, 0} @@ -628,7 +625,6 @@ extern "C" { #define meshtastic_Config_PositionConfig_broadcast_smart_minimum_interval_secs_tag 11 #define meshtastic_Config_PositionConfig_gps_en_gpio_tag 12 #define meshtastic_Config_PositionConfig_gps_mode_tag 13 -#define meshtastic_Config_PositionConfig_channel_precision_tag 14 #define meshtastic_Config_PowerConfig_is_power_saving_tag 1 #define meshtastic_Config_PowerConfig_on_battery_shutdown_after_secs_tag 2 #define meshtastic_Config_PowerConfig_adc_multiplier_override_tag 3 @@ -732,8 +728,7 @@ X(a, STATIC, SINGULAR, UINT32, tx_gpio, 9) \ X(a, STATIC, SINGULAR, UINT32, broadcast_smart_minimum_distance, 10) \ X(a, STATIC, SINGULAR, UINT32, broadcast_smart_minimum_interval_secs, 11) \ X(a, STATIC, SINGULAR, UINT32, gps_en_gpio, 12) \ -X(a, STATIC, SINGULAR, UENUM, gps_mode, 13) \ -X(a, STATIC, REPEATED, UINT32, channel_precision, 14) +X(a, STATIC, SINGULAR, UENUM, gps_mode, 13) #define meshtastic_Config_PositionConfig_CALLBACK NULL #define meshtastic_Config_PositionConfig_DEFAULT NULL @@ -839,7 +834,7 @@ extern const pb_msgdesc_t meshtastic_Config_BluetoothConfig_msg; #define meshtastic_Config_LoRaConfig_size 80 #define meshtastic_Config_NetworkConfig_IpV4Config_size 20 #define meshtastic_Config_NetworkConfig_size 196 -#define meshtastic_Config_PositionConfig_size 110 +#define meshtastic_Config_PositionConfig_size 62 #define meshtastic_Config_PowerConfig_size 40 #define meshtastic_Config_size 199 diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index bca305c14..735644c47 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -312,11 +312,11 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg; #define meshtastic_NodeRemoteHardwarePin_fields &meshtastic_NodeRemoteHardwarePin_msg /* Maximum encoded size of messages (where known) */ -#define meshtastic_ChannelFile_size 638 +#define meshtastic_ChannelFile_size 702 #define meshtastic_DeviceState_size 17062 #define meshtastic_NodeInfoLite_size 153 #define meshtastic_NodeRemoteHardwarePin_size 29 -#define meshtastic_OEMStore_size 3294 +#define meshtastic_OEMStore_size 3246 #define meshtastic_PositionLite_size 28 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/localonly.pb.h b/src/mesh/generated/meshtastic/localonly.pb.h index 644d965ab..7d39da01f 100644 --- a/src/mesh/generated/meshtastic/localonly.pb.h +++ b/src/mesh/generated/meshtastic/localonly.pb.h @@ -180,7 +180,7 @@ extern const pb_msgdesc_t meshtastic_LocalModuleConfig_msg; #define meshtastic_LocalModuleConfig_fields &meshtastic_LocalModuleConfig_msg /* Maximum encoded size of messages (where known) */ -#define meshtastic_LocalConfig_size 517 +#define meshtastic_LocalConfig_size 469 #define meshtastic_LocalModuleConfig_size 631 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index 6c3a9729f..e8a27d43f 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -380,6 +380,8 @@ typedef struct _meshtastic_Position { /* A sequence number, incremented with each Position message to help detect lost updates if needed */ uint32_t seq_number; + /* Indicates the bits of precision set by the sending node */ + uint32_t precision_bits; } meshtastic_Position; /* Broadcast when a newly powered mesh node wants to find a node num it can use @@ -882,7 +884,7 @@ extern "C" { /* Initializer values for message structs */ -#define meshtastic_Position_init_default {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN, _meshtastic_Position_AltSource_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define meshtastic_Position_init_default {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN, _meshtastic_Position_AltSource_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_User_init_default {"", "", "", {0}, _meshtastic_HardwareModel_MIN, 0, _meshtastic_Config_DeviceConfig_Role_MIN} #define meshtastic_RouteDiscovery_init_default {0, {0, 0, 0, 0, 0, 0, 0, 0}} #define meshtastic_Routing_init_default {0, {meshtastic_RouteDiscovery_init_default}} @@ -900,7 +902,7 @@ extern "C" { #define meshtastic_NeighborInfo_init_default {0, 0, 0, 0, {meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default}} #define meshtastic_Neighbor_init_default {0, 0, 0, 0} #define meshtastic_DeviceMetadata_init_default {"", 0, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_Role_MIN, 0, _meshtastic_HardwareModel_MIN, 0} -#define meshtastic_Position_init_zero {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN, _meshtastic_Position_AltSource_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define meshtastic_Position_init_zero {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN, _meshtastic_Position_AltSource_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_User_init_zero {"", "", "", {0}, _meshtastic_HardwareModel_MIN, 0, _meshtastic_Config_DeviceConfig_Role_MIN} #define meshtastic_RouteDiscovery_init_zero {0, {0, 0, 0, 0, 0, 0, 0, 0}} #define meshtastic_Routing_init_zero {0, {meshtastic_RouteDiscovery_init_zero}} @@ -942,6 +944,7 @@ extern "C" { #define meshtastic_Position_sensor_id_tag 20 #define meshtastic_Position_next_update_tag 21 #define meshtastic_Position_seq_number_tag 22 +#define meshtastic_Position_precision_bits_tag 23 #define meshtastic_User_id_tag 1 #define meshtastic_User_long_name_tag 2 #define meshtastic_User_short_name_tag 3 @@ -1068,7 +1071,8 @@ X(a, STATIC, SINGULAR, UINT32, fix_type, 18) \ X(a, STATIC, SINGULAR, UINT32, sats_in_view, 19) \ X(a, STATIC, SINGULAR, UINT32, sensor_id, 20) \ X(a, STATIC, SINGULAR, UINT32, next_update, 21) \ -X(a, STATIC, SINGULAR, UINT32, seq_number, 22) +X(a, STATIC, SINGULAR, UINT32, seq_number, 22) \ +X(a, STATIC, SINGULAR, UINT32, precision_bits, 23) #define meshtastic_Position_CALLBACK NULL #define meshtastic_Position_DEFAULT NULL @@ -1313,8 +1317,8 @@ extern const pb_msgdesc_t meshtastic_DeviceMetadata_msg; #define meshtastic_MyNodeInfo_size 18 #define meshtastic_NeighborInfo_size 258 #define meshtastic_Neighbor_size 22 -#define meshtastic_NodeInfo_size 263 -#define meshtastic_Position_size 137 +#define meshtastic_NodeInfo_size 270 +#define meshtastic_Position_size 144 #define meshtastic_QueueStatus_size 23 #define meshtastic_RouteDiscovery_size 40 #define meshtastic_Routing_size 42 From eb2fa727a7c634109e6d7c27f1d71892f562869e Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 22 Feb 2024 12:32:01 -0600 Subject: [PATCH 205/472] Adds support for position_precision --- src/mesh/Channels.cpp | 1 + src/modules/PositionModule.cpp | 23 +++++++++++------------ src/modules/PositionModule.h | 1 + 3 files changed, 13 insertions(+), 12 deletions(-) diff --git a/src/mesh/Channels.cpp b/src/mesh/Channels.cpp index 80bcc10c6..fe1041d3d 100644 --- a/src/mesh/Channels.cpp +++ b/src/mesh/Channels.cpp @@ -87,6 +87,7 @@ void Channels::initDefaultChannel(ChannelIndex chIndex) channelSettings.psk.bytes[0] = defaultpskIndex; channelSettings.psk.size = 1; strncpy(channelSettings.name, "", sizeof(channelSettings.name)); + channelSettings.module_settings.position_precision = 32; // default to sending location on the primary channel ch.has_settings = true; ch.role = meshtastic_Channel_Role_PRIMARY; diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index 32c5a0c41..7ef539b1e 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -23,6 +23,7 @@ PositionModule::PositionModule() : ProtobufModule("position", meshtastic_PortNum_POSITION_APP, &meshtastic_Position_msg), concurrency::OSThread("PositionModule") { + precision = 0; // safe starting value isPromiscuous = true; // We always want to update our nodedb, even if we are sniffing on others if (config.device.role != meshtastic_Config_DeviceConfig_Role_TRACKER && config.device.role != meshtastic_Config_DeviceConfig_Role_TAK_TRACKER) @@ -83,20 +84,13 @@ bool PositionModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes nodeDB.updatePosition(getFrom(&mp), p); - // Only respond to location requests on the channel where we broadcast location. - if (channels.getByIndex(mp.channel).role == meshtastic_Channel_Role_PRIMARY) { - ignoreRequest = false; - } else { - ignoreRequest = true; - } - return false; // Let others look at this message also if they want } meshtastic_MeshPacket *PositionModule::allocReply() { - if (ignoreRequest) { - ignoreRequest = false; // Reset for next request + if (precision == 0) { + LOG_DEBUG("Skipping location send because precision is set to 0!\n"); return nullptr; } @@ -116,8 +110,10 @@ meshtastic_MeshPacket *PositionModule::allocReply() localPosition.seq_number++; // lat/lon are unconditionally included - IF AVAILABLE! - p.latitude_i = localPosition.latitude_i; - p.longitude_i = localPosition.longitude_i; + LOG_DEBUG("Sending location with precision %i\n", precision); + p.latitude_i = localPosition.latitude_i & (INT32_MAX << (32 - precision)); + p.longitude_i = localPosition.longitude_i & (INT32_MAX << (32 - precision)); + p.precision_bits = precision; p.time = localPosition.time; if (pos_flags & meshtastic_Config_PositionConfig_PositionFlags_ALTITUDE) { @@ -213,9 +209,12 @@ void PositionModule::sendOurPosition(NodeNum dest, bool wantReplies, uint8_t cha if (prevPacketId) // if we wrap around to zero, we'll simply fail to cancel in that rare case (no big deal) service.cancelSending(prevPacketId); + // Set's the class precision value for this particular packet + precision = channels.getByIndex(channel).settings.module_settings.position_precision; + meshtastic_MeshPacket *p = allocReply(); if (p == nullptr) { - LOG_WARN("allocReply returned a nullptr\n"); + LOG_DEBUG("allocReply returned a nullptr\n"); return; } diff --git a/src/modules/PositionModule.h b/src/modules/PositionModule.h index bd7a9def4..fddafef6f 100644 --- a/src/modules/PositionModule.h +++ b/src/modules/PositionModule.h @@ -50,6 +50,7 @@ class PositionModule : public ProtobufModule, private concu private: struct SmartPosition getDistanceTraveledSinceLastSend(meshtastic_PositionLite currentPosition); meshtastic_MeshPacket *allocAtakPli(); + uint32_t precision; /** Only used in power saving trackers for now */ void clearPosition(); From 77067865411448d35811d38630338eb195fee677 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 22 Feb 2024 12:59:35 -0600 Subject: [PATCH 206/472] Correct powersave settings for ublox --- src/gps/GPS.cpp | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index addde4edd..08ef116b2 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -444,6 +444,11 @@ bool GPS::setup() if (getACK(0x06, 0x86, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to enable powersaving for GPS.\n"); } + msglen = makeUBXPacket(0x06, 0x3B, sizeof(_message_CFG_PM2), _message_CFG_PM2); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x3B, 500) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable powersaving details for GPS.\n"); + } // For M8 we want to enable NMEA vserion 4.10 so we can see the additional sats. if (strncmp(info.hwVersion, "00080000", 8) == 0) { msglen = makeUBXPacket(0x06, 0x17, sizeof(_message_NMEA), _message_NMEA); @@ -477,6 +482,12 @@ bool GPS::setup() if (getACK(0x06, 0x11, 500) != GNSS_RESPONSE_OK) { LOG_WARN("Unable to enable powersaving mode for GPS.\n"); } + + msglen = makeUBXPacket(0x06, 0x3B, sizeof(_message_CFG_PM2), _message_CFG_PM2); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x3B, 500) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to enable powersaving details for GPS.\n"); + } } } From f95b90364a2a5fd8096b626b67816f92d9e84c27 Mon Sep 17 00:00:00 2001 From: Mark Trevor Birss Date: Fri, 23 Feb 2024 00:18:05 +0200 Subject: [PATCH 207/472] Update EInkDisplay2.cpp (#3264) Fix for line at bottom of e-ink display. From @todd-herbert new e-ink enhancements --- src/graphics/EInkDisplay2.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index 66e7ffd40..d5e3f5263 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -65,7 +65,7 @@ EInkDisplay::EInkDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY // GxEPD2_213_BN - RAK14000 2.13 inch b/w 250x122 setGeometry(GEOMETRY_RAWMODE, 250, 122); - + this->displayBufferSize = 250 * (128 / 8); // GxEPD2_420_M01 // setGeometry(GEOMETRY_RAWMODE, 300, 400); From 3ad34f875986ba0ec6750081e0e6eeb3d290058f Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Sat, 24 Feb 2024 02:45:23 +1300 Subject: [PATCH 208/472] E-Ink: change inaccurate terminology (#3269) Follows a discussion with @markbirss on discord --- src/graphics/EInkDisplay2.cpp | 76 ++++++++++----------- src/graphics/EInkDisplay2.h | 40 +++++------ variants/heltec_wireless_paper_v1/variant.h | 8 +-- 3 files changed, 62 insertions(+), 62 deletions(-) diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index d5e3f5263..de53daaee 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -18,7 +18,7 @@ SPIClass *hspi = NULL; #define TECHO_DISPLAY_MODEL GxEPD2_154_D67 #elif defined(RAK4630) -// GxEPD2_213_BN - RAK14000 2.13 inch b/w 250x122 - changed from GxEPD2_213_B74 - which was not going to give partial update +// GxEPD2_213_BN - RAK14000 2.13 inch b/w 250x122 - changed from GxEPD2_213_B74 - which was not going to give fast refresh // support #define TECHO_DISPLAY_MODEL GxEPD2_213_BN @@ -131,8 +131,8 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit) // No need to grab this lock because we are on our own SPI bus // concurrency::LockGuard g(spiLock); -#if defined(USE_EINK_DYNAMIC_PARTIAL) - // Decide if update is partial or full +#if defined(USE_EINK_DYNAMIC_REFRESH) + // Decide between full refresh, fast refresh, or skipping the update bool continueUpdate = determineRefreshMode(); if (!continueUpdate) return false; @@ -165,12 +165,12 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit) adafruitDisplay->nextPage(); #elif defined(RAK4630) || defined(MAKERPYTHON) - // RAK14000 2.13 inch b/w 250x122 actually now does support partial updates + // RAK14000 2.13 inch b/w 250x122 actually now does support fast refresh // Full update mode (slow) - // adafruitDisplay->display(false); // FIXME, use partial update mode + // adafruitDisplay->display(false); // FIXME, use fast refresh mode - // Only enable for e-Paper with support for partial updates and comment out above adafruitDisplay->display(false); + // Only enable for e-Paper with support for fast updates and comment out above adafruitDisplay->display(false); // 1.54 inch 200x200 - GxEPD2_154_M09 // 2.13 inch 250x122 - GxEPD2_213_BN // 2.9 inch 296x128 - GxEPD2_290_T5D @@ -203,7 +203,7 @@ void EInkDisplay::display(void) // at least one forceDisplay() keyframe. This prevents flashing when we should the critical // bootscreen (that we want to look nice) -#ifdef USE_EINK_DYNAMIC_PARTIAL +#ifdef USE_EINK_DYNAMIC_REFRESH lowPriority(); forceDisplay(); highPriority(); @@ -257,9 +257,9 @@ bool EInkDisplay::connect() auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); adafruitDisplay = new GxEPD2_BW(*lowLevel); adafruitDisplay->init(115200, true, 10, false, SPI1, SPISettings(4000000, MSBFIRST, SPI_MODE0)); - // RAK14000 2.13 inch b/w 250x122 does actually now support partial updates + // RAK14000 2.13 inch b/w 250x122 does actually now support fast refresh adafruitDisplay->setRotation(3); - // Partial update support for 1.54, 2.13 RAK14000 b/w , 2.9 and 4.2 + // Fast refresh support for 1.54, 2.13 RAK14000 b/w , 2.9 and 4.2 // adafruitDisplay->setRotation(1); adafruitDisplay->setPartialWindow(0, 0, displayWidth, displayHeight); } else { @@ -347,10 +347,10 @@ bool EInkDisplay::connect() return true; } -// Use a mix of full and partial refreshes, to preserve display health -#if defined(USE_EINK_DYNAMIC_PARTIAL) +// Use a mix of full refresh, fast refresh, and update skipping, to balance urgency and display health +#if defined(USE_EINK_DYNAMIC_REFRESH) -// Suggest that subsequent updates should use partial-refresh +// Suggest that subsequent updates should use fast-refresh void EInkDisplay::highPriority() { isHighPriority = true; @@ -368,8 +368,8 @@ void EInkDisplay::demandFullRefresh() demandingFull = true; } -// configure display for partial-refresh -void EInkDisplay::configForPartialRefresh() +// configure display for fast-refresh +void EInkDisplay::configForFastRefresh() { // Display-specific code can go here #if defined(PRIVATE_HW) @@ -390,7 +390,7 @@ void EInkDisplay::configForFullRefresh() #endif } -#ifdef EINK_PARTIAL_ERASURE_LIMIT +#ifdef EINK_FASTREFRESH_ERASURE_LIMIT // Count black pixels in an image. Used for "erasure tracking" int32_t EInkDisplay::countBlackPixels() { @@ -422,16 +422,16 @@ bool EInkDisplay::tooManyErasures() prevBlackCount = blackCount; // Log the running total - help devs setup new boards - LOG_DEBUG("Dynamic Partial: erasedSinceFull=%hu, EINK_PARTIAL_ERASURE_LIMIT=%hu\n", erasedSinceFull, - EINK_PARTIAL_ERASURE_LIMIT); + LOG_DEBUG("Dynamic Refresh: erasedSinceFull=%hu, EINK_FASTREFRESH_ERASURE_LIMIT=%hu\n", erasedSinceFull, + EINK_FASTREFRESH_ERASURE_LIMIT); // Check if too many pixels have been erased - if (erasedSinceFull > EINK_PARTIAL_ERASURE_LIMIT) + if (erasedSinceFull > EINK_FASTREFRESH_ERASURE_LIMIT) return true; // Too many else return false; // Still okay } -#endif // ifdef EINK_PARTIAL_BRIGHTEN_LIMIT_PX +#endif // ifdef EINK_FASTREFRESH_ERASURE_LIMIT bool EInkDisplay::newImageMatchesOld() { @@ -452,7 +452,7 @@ bool EInkDisplay::newImageMatchesOld() return hashMatches; } -// Change between partial and full refresh config, or skip update, balancing urgency and display health. +// Choose between, full-refresh, fast refresh, and update skipping, to balance urgency and display health. bool EInkDisplay::determineRefreshMode() { uint32_t now = millis(); @@ -466,8 +466,8 @@ bool EInkDisplay::determineRefreshMode() } // Abort: if too soon for a new frame (unless demanding full) - if (!demandingFull && isHighPriority && partialRefreshCount > 0 && sinceLast < highPriorityLimitMsec) { - LOG_DEBUG("Dynamic Partial: update skipped. Exceeded EINK_HIGHPRIORITY_LIMIT_SECONDS\n"); + if (!demandingFull && isHighPriority && fastRefreshCount > 0 && sinceLast < highPriorityLimitMsec) { + LOG_DEBUG("Dynamic Refresh: update skipped. Exceeded EINK_HIGHPRIORITY_LIMIT_SECONDS\n"); missedHighPriorityUpdate = true; return false; } @@ -479,16 +479,16 @@ bool EInkDisplay::determineRefreshMode() if (demandingFull) needsFull = true; - // Check if old image (partial) should be redrawn (as full), for image quality - if (partialRefreshCount > 0 && !isHighPriority) + // Check if old image (fast-refresh) should be redrawn (as full), for image quality + if (fastRefreshCount > 0 && !isHighPriority) needsFull = true; - // If too many partials, require a full-refresh (display health) - if (partialRefreshCount >= partialRefreshLimit) + // If too many fast updates, require a full-refresh (display health) + if (fastRefreshCount >= fastRefreshLimit) needsFull = true; -#ifdef EINK_PARTIAL_ERASURE_LIMIT - // Some displays struggle with erasing black pixels to white, during partial refresh +#ifdef EINK_FASTREFRESH_ERASURE_LIMIT + // Some displays struggle with erasing black pixels to white, during fast-refresh if (tooManyErasures()) needsFull = true; #endif @@ -510,29 +510,29 @@ bool EInkDisplay::determineRefreshMode() // If options require a full refresh if (!isHighPriority || needsFull) { - if (partialRefreshCount > 0) + if (fastRefreshCount > 0) configForFullRefresh(); - LOG_DEBUG("Dynamic Partial: conditions met for full-refresh\n"); - partialRefreshCount = 0; + LOG_DEBUG("Dynamic Refresh: conditions met for full-refresh\n"); + fastRefreshCount = 0; needsFull = false; demandingFull = false; - erasedSinceFull = 0; // Reset the count for EINK_PARTIAL_ERASURE_LIMIT - tracks ghosting buildup + erasedSinceFull = 0; // Reset the count for EINK_FASTREFRESH_ERASURE_LIMIT - tracks ghosting buildup } - // If options allow a partial refresh + // If options allow a fast-refresh else { - if (partialRefreshCount == 0) - configForPartialRefresh(); + if (fastRefreshCount == 0) + configForFastRefresh(); - LOG_DEBUG("Dynamic Partial: conditions met for partial-refresh\n"); - partialRefreshCount++; + LOG_DEBUG("Dynamic Refresh: conditions met for fast-refresh\n"); + fastRefreshCount++; } lastUpdateMsec = now; // Mark time for rate limiting return true; // Instruct calling method to continue with update } -#endif // End USE_EINK_DYNAMIC_PARTIAL +#endif // End USE_EINK_DYNAMIC_REFRESH #endif diff --git a/src/graphics/EInkDisplay2.h b/src/graphics/EInkDisplay2.h index aeaddee2d..260a79755 100644 --- a/src/graphics/EInkDisplay2.h +++ b/src/graphics/EInkDisplay2.h @@ -55,23 +55,23 @@ class EInkDisplay : public OLEDDisplay // Connect to the display virtual bool connect() override; -#if defined(USE_EINK_DYNAMIC_PARTIAL) - // Full, partial, or skip: balance urgency with display health +#if defined(USE_EINK_DYNAMIC_REFRESH) + // Full, fast, or skip: balance urgency with display health - // Use partial refresh if EITHER: + // Use fast refresh if EITHER: // * highPriority() was set // * a highPriority() update was previously skipped, for rate-limiting - (EINK_HIGHPRIORITY_LIMIT_SECONDS) // Use full refresh if EITHER: // * lowPriority() was set // * demandFullRefresh() was called - (single shot) - // * too many partial updates in a row: protect display - (EINK_PARTIAL_REPEAT_LIMIT) - // * no recent updates, and last update was partial: redraw for image quality (EINK_LOWPRIORITY_LIMIT_SECONDS) + // * too many fast updates in a row: protect display - (EINK_FASTREFRESH_REPEAT_LIMIT) + // * no recent updates, and last update was fast: redraw for image quality (EINK_LOWPRIORITY_LIMIT_SECONDS) // * (optional) too many "erasures" since full-refresh (black pixels cleared to white) // Rate limit if: // * lowPriority() - (EINK_LOWPRIORITY_LIMIT_SECONDS) - // * highPriority(), if multiple partials have run back-to-back - (EINK_HIGHPRIORITY_LIMIT_SECONDS) + // * highPriority(), if multiple fast updates have run back-to-back - (EINK_HIGHPRIORITY_LIMIT_SECONDS) // Skip update entirely if ALL criteria met: // * new image matches old image @@ -83,29 +83,29 @@ class EInkDisplay : public OLEDDisplay // ------------------------------------ // To implement for your E-Ink display: - // * edit configForPartialRefresh() + // * edit configForFastRefresh() // * edit configForFullRefresh() // * add macros to variant.h, and adjust to taste: /* - #define USE_EINK_DYNAMIC_PARTIAL + #define USE_EINK_DYNAMIC_REFRESH #define EINK_LOWPRIORITY_LIMIT_SECONDS 30 #define EINK_HIGHPRIORITY_LIMIT_SECONDS 1 - #define EINK_PARTIAL_REPEAT_LIMIT 5 - #define EINK_PARTIAL_ERASURE_LIMIT 300 // optional + #define EINK_FASTREFRESH_REPEAT_LIMIT 5 + #define EINK_FASTREFRESH_ERASURE_LIMIT 300 // optional */ public: - void highPriority(); // Suggest partial refresh + void highPriority(); // Suggest fast refresh void lowPriority(); // Suggest full refresh void demandFullRefresh(); // For next update: explicitly request full refresh protected: - void configForPartialRefresh(); // Display specific code to select partial refresh mode - void configForFullRefresh(); // Display specific code to return to full refresh mode - bool newImageMatchesOld(); // Is the new update actually different to the last image? - bool determineRefreshMode(); // Called immediately before data written to display - choose refresh mode, or abort update -#ifdef EINK_PARTIAL_ERASURE_LIMIT + void configForFastRefresh(); // Display specific code to select fast refresh mode + void configForFullRefresh(); // Display specific code to return to full refresh mode + bool newImageMatchesOld(); // Is the new update actually different to the last image? + bool determineRefreshMode(); // Called immediately before data written to display - choose refresh mode, or abort update +#ifdef EINK_FASTREFRESH_ERASURE_LIMIT int32_t countBlackPixels(); // Calculate the number of black pixels in the new image bool tooManyErasures(); // Has too much "ghosting" (black pixels erased to white) accumulated since last full-refresh? #endif @@ -114,18 +114,18 @@ class EInkDisplay : public OLEDDisplay bool needsFull = false; // Is a full refresh forced? (display health) bool demandingFull = false; // Was full refresh specifically requested? (splash screens, etc) bool missedHighPriorityUpdate = false; // Was a high priority update skipped for rate-limiting? - uint16_t partialRefreshCount = 0; // How many partials have occurred since last full refresh? + uint16_t fastRefreshCount = 0; // How many fast updates have occurred since last full refresh? uint32_t lastUpdateMsec = 0; // When did the last update occur? uint32_t prevImageHash = 0; // Used to check if update will change screen image (skippable or not) int32_t prevBlackCount = 0; // How many black pixels were in the previous image uint32_t erasedSinceFull = 0; // How many black pixels have been set back to white since last full-refresh? (roughly) // Set in variant.h - const uint32_t lowPriorityLimitMsec = (uint32_t)1000 * EINK_LOWPRIORITY_LIMIT_SECONDS; // Max rate for partial refreshes + const uint32_t lowPriorityLimitMsec = (uint32_t)1000 * EINK_LOWPRIORITY_LIMIT_SECONDS; // Max rate for fast refreshes const uint32_t highPriorityLimitMsec = (uint32_t)1000 * EINK_HIGHPRIORITY_LIMIT_SECONDS; // Max rate for full refreshes - const uint32_t partialRefreshLimit = EINK_PARTIAL_REPEAT_LIMIT; // Max consecutive partials, before full is triggered + const uint32_t fastRefreshLimit = EINK_FASTREFRESH_REPEAT_LIMIT; // Max consecutive fast updates, before full is triggered -#else // !USE_EINK_DYNAMIC_PARTIAL +#else // !USE_EINK_DYNAMIC_REFRESH // Tolerate calls to these methods anywhere, just to be safe void highPriority() {} void lowPriority() {} diff --git a/variants/heltec_wireless_paper_v1/variant.h b/variants/heltec_wireless_paper_v1/variant.h index 166b7f30e..25e061938 100644 --- a/variants/heltec_wireless_paper_v1/variant.h +++ b/variants/heltec_wireless_paper_v1/variant.h @@ -6,12 +6,12 @@ #define USE_EINK -// Settings for Dynamic Partial mode -// Change between partial and full refresh config, or skip update, balancing urgency and display health. -#define USE_EINK_DYNAMIC_PARTIAL +// Settings for Dynamic Refresh mode +// Change between full-refresh, fast-refresh, or update-skipping, to balance urgency and display health. +#define USE_EINK_DYNAMIC_REFRESH #define EINK_LOWPRIORITY_LIMIT_SECONDS 30 #define EINK_HIGHPRIORITY_LIMIT_SECONDS 1 -#define EINK_PARTIAL_REPEAT_LIMIT 5 +#define EINK_FASTREFRESH_REPEAT_LIMIT 5 /* * eink display pins From b2ea1e23be49ddc63b7032531572c656d559bcb0 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Fri, 23 Feb 2024 15:39:32 -0600 Subject: [PATCH 209/472] Move imprecise locations to grid middle --- src/modules/PositionModule.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index 7ef539b1e..d90df89e9 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -83,6 +83,7 @@ bool PositionModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes } nodeDB.updatePosition(getFrom(&mp), p); + precision = channels.getByIndex(mp.channel).settings.module_settings.position_precision; return false; // Let others look at this message also if they want } @@ -113,6 +114,12 @@ meshtastic_MeshPacket *PositionModule::allocReply() LOG_DEBUG("Sending location with precision %i\n", precision); p.latitude_i = localPosition.latitude_i & (INT32_MAX << (32 - precision)); p.longitude_i = localPosition.longitude_i & (INT32_MAX << (32 - precision)); + + // We want the imprecise position to be the middle of the possible location, not + if (precision < 31 && precision > 1) { + p.latitude_i += (1 << 31 - precision); + p.longitude_i += (1 << 31 - precision); + } p.precision_bits = precision; p.time = localPosition.time; From f1b314251c3e04b49d5bc18af5f428aea39723ac Mon Sep 17 00:00:00 2001 From: rcarteraz Date: Sat, 24 Feb 2024 06:49:15 -0700 Subject: [PATCH 210/472] remove flasher and replace with web on unset screen (#3272) --- src/graphics/Screen.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index c0e55ea83..5197e4dbc 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -274,7 +274,7 @@ static void drawWelcomeScreen(OLEDDisplay *display, OLEDDisplayUiState *state, i if ((millis() / 10000) % 2) { display->drawString(x, y + FONT_HEIGHT_SMALL * 2 - 3, "Set the region using the"); display->drawString(x, y + FONT_HEIGHT_SMALL * 3 - 3, "Meshtastic Android, iOS,"); - display->drawString(x, y + FONT_HEIGHT_SMALL * 4 - 3, "Flasher or CLI client."); + display->drawString(x, y + FONT_HEIGHT_SMALL * 4 - 3, "Web or CLI clients."); } else { display->drawString(x, y + FONT_HEIGHT_SMALL * 2 - 3, "Visit meshtastic.org"); display->drawString(x, y + FONT_HEIGHT_SMALL * 3 - 3, "for more information."); From 730429fc9b95adc2e33a48a4ee0c5e95b24bac09 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sat, 24 Feb 2024 07:55:00 -0600 Subject: [PATCH 211/472] Routers / Repeaters deep sleep default w/ LoRA interrupts (#3251) * Experimenting with deep sleep routers / repeaters * Make decision to SDS or LS based on Router/Repeater role * Don't sleep LoRA on router / repeater deep sleep * Guards * Platform guards * Rename method --- src/PowerFSM.cpp | 5 +++-- src/sleep.cpp | 46 ++++++++++++++++++++++++++++++++++++++++------ src/sleep.h | 6 +++++- 3 files changed, 48 insertions(+), 9 deletions(-) diff --git a/src/PowerFSM.cpp b/src/PowerFSM.cpp index bac3899bb..c359e4c12 100644 --- a/src/PowerFSM.cpp +++ b/src/PowerFSM.cpp @@ -245,6 +245,7 @@ Fsm powerFSM(&stateBOOT); void PowerFSM_setup() { bool isRouter = (config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER ? 1 : 0); + bool isInfrastructureRole = isRouter || config.device.role == meshtastic_Config_DeviceConfig_Role_REPEATER; bool isTrackerOrSensor = config.device.role == meshtastic_Config_DeviceConfig_Role_TRACKER || config.device.role == meshtastic_Config_DeviceConfig_Role_TAK_TRACKER || config.device.role == meshtastic_Config_DeviceConfig_Role_SENSOR; @@ -357,10 +358,10 @@ void PowerFSM_setup() // Don't add power saving transitions if we are a power saving tracker or sensor. Sleep will be initiatiated through the // modules if ((isRouter || config.power.is_power_saving) && !isTrackerOrSensor) { - powerFSM.add_timed_transition(&stateNB, &stateLS, + powerFSM.add_timed_transition(&stateNB, isInfrastructureRole ? &stateSDS : &stateLS, getConfiguredOrDefaultMs(config.power.min_wake_secs, default_min_wake_secs), NULL, "Min wake timeout"); - powerFSM.add_timed_transition(&stateDARK, &stateLS, + powerFSM.add_timed_transition(&stateDARK, isInfrastructureRole ? &stateSDS : &stateLS, getConfiguredOrDefaultMs(config.power.wait_bluetooth_secs, default_wait_bluetooth_secs), NULL, "Bluetooth timeout"); } diff --git a/src/sleep.cpp b/src/sleep.cpp index 0f71ab25b..1afba1173 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -186,7 +186,15 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) // not using wifi yet, but once we are this is needed to shutoff the radio hw // esp_wifi_stop(); waitEnterSleep(skipPreflight); +#ifdef ARCH_ESP32 + if (shouldLoraWake(msecToWake)) { + notifySleep.notifyObservers(NULL); + } else { + notifyDeepSleep.notifyObservers(NULL); + } +#else notifyDeepSleep.notifyObservers(NULL); +#endif screen->doDeepSleep(); // datasheet says this will draw only 10ua @@ -240,6 +248,11 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) } #endif +#ifdef ARCH_ESP32 + if (shouldLoraWake(msecToWake)) { + enableLoraInterrupt(); + } +#endif cpuDeepSleep(msecToWake); } @@ -294,12 +307,7 @@ esp_sleep_wakeup_cause_t doLightSleep(uint64_t sleepMsec) // FIXME, use a more r gpio_wakeup_enable((gpio_num_t)BUTTON_PIN, GPIO_INTR_LOW_LEVEL); #endif #endif -#if defined(LORA_DIO1) && (LORA_DIO1 != RADIOLIB_NC) - gpio_wakeup_enable((gpio_num_t)LORA_DIO1, GPIO_INTR_HIGH_LEVEL); // SX126x/SX128x interrupt, active high -#endif -#ifdef RF95_IRQ - gpio_wakeup_enable((gpio_num_t)RF95_IRQ, GPIO_INTR_HIGH_LEVEL); // RF95 interrupt, active high -#endif + enableLoraInterrupt(); #ifdef PMU_IRQ // wake due to PMU can happen repeatedly if there is no battery installed or the battery fills if (pmu_found) @@ -359,4 +367,30 @@ void enableModemSleep() int rv = esp_pm_configure(&esp32_config); LOG_DEBUG("Sleep request result %x\n", rv); } + +bool shouldLoraWake(uint32_t msecToWake) +{ + return msecToWake < portMAX_DELAY && (config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER || + config.device.role == meshtastic_Config_DeviceConfig_Role_REPEATER); +} + +void enableLoraInterrupt() +{ +#if SOC_PM_SUPPORT_EXT_WAKEUP && defined(LORA_DIO1) && (LORA_DIO1 != RADIOLIB_NC) + rtc_gpio_pulldown_en((gpio_num_t)LORA_DIO1); +#if defined(LORA_RESET) && (LORA_RESET != RADIOLIB_NC) + rtc_gpio_pullup_en((gpio_num_t)LORA_RESET); +#endif +#if defined(LORA_CS) && (LORA_CS != RADIOLIB_NC) + rtc_gpio_pullup_en((gpio_num_t)LORA_CS); +#endif + // Setup deep sleep with wakeup by external source + esp_sleep_enable_ext0_wakeup((gpio_num_t)LORA_DIO1, RISING); +#elif defined(LORA_DIO1) && (LORA_DIO1 != RADIOLIB_NC) + gpio_wakeup_enable((gpio_num_t)LORA_DIO1, GPIO_INTR_HIGH_LEVEL); // SX126x/SX128x interrupt, active high +#endif +#ifdef RF95_IRQ + gpio_wakeup_enable((gpio_num_t)RF95_IRQ, GPIO_INTR_HIGH_LEVEL); // RF95 interrupt, active high +#endif +} #endif \ No newline at end of file diff --git a/src/sleep.h b/src/sleep.h index a592ad2c1..8d5b9a94f 100644 --- a/src/sleep.h +++ b/src/sleep.h @@ -43,4 +43,8 @@ extern Observable notifyDeepSleep; /// Called to tell GPS thread to enter deep sleep independently of LoRa/MCU sleep, prior to full poweroff. Must return 0 extern Observable notifyGPSSleep; -void enableModemSleep(); \ No newline at end of file +void enableModemSleep(); +#ifdef ARCH_ESP32 +void enableLoraInterrupt(); +bool shouldLoraWake(uint32_t msecToWake); +#endif \ No newline at end of file From c2085c2c888b361b9f7bc15f0107a9ce3425e9f7 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sat, 24 Feb 2024 12:53:46 -0600 Subject: [PATCH 212/472] Fix default stance in position_precision --- src/mesh/Channels.cpp | 1 + src/modules/PositionModule.cpp | 20 ++++++++++++++++---- 2 files changed, 17 insertions(+), 4 deletions(-) diff --git a/src/mesh/Channels.cpp b/src/mesh/Channels.cpp index fe1041d3d..2d27c737d 100644 --- a/src/mesh/Channels.cpp +++ b/src/mesh/Channels.cpp @@ -88,6 +88,7 @@ void Channels::initDefaultChannel(ChannelIndex chIndex) channelSettings.psk.size = 1; strncpy(channelSettings.name, "", sizeof(channelSettings.name)); channelSettings.module_settings.position_precision = 32; // default to sending location on the primary channel + channelSettings.has_module_settings = true; ch.has_settings = true; ch.role = meshtastic_Channel_Role_PRIMARY; diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index d90df89e9..5f20dbafb 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -83,7 +83,13 @@ bool PositionModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes } nodeDB.updatePosition(getFrom(&mp), p); - precision = channels.getByIndex(mp.channel).settings.module_settings.position_precision; + if (channels.getByIndex(mp.channel).settings.has_module_settings) { + precision = channels.getByIndex(mp.channel).settings.module_settings.position_precision; + } else if (channels.getByIndex(mp.channel).role == meshtastic_Channel_Role_PRIMARY) { + precision = 32; + } else { + precision = 0; + } return false; // Let others look at this message also if they want } @@ -117,8 +123,8 @@ meshtastic_MeshPacket *PositionModule::allocReply() // We want the imprecise position to be the middle of the possible location, not if (precision < 31 && precision > 1) { - p.latitude_i += (1 << 31 - precision); - p.longitude_i += (1 << 31 - precision); + p.latitude_i += (1 << (31 - precision)); + p.longitude_i += (1 << (31 - precision)); } p.precision_bits = precision; p.time = localPosition.time; @@ -217,7 +223,13 @@ void PositionModule::sendOurPosition(NodeNum dest, bool wantReplies, uint8_t cha service.cancelSending(prevPacketId); // Set's the class precision value for this particular packet - precision = channels.getByIndex(channel).settings.module_settings.position_precision; + if (channels.getByIndex(channel).settings.has_module_settings) { + precision = channels.getByIndex(channel).settings.module_settings.position_precision; + } else if (channels.getByIndex(channel).role == meshtastic_Channel_Role_PRIMARY) { + precision = 32; + } else { + precision = 0; + } meshtastic_MeshPacket *p = allocReply(); if (p == nullptr) { From 9c4d1b5ac864f694323c37235194728891e5e55c Mon Sep 17 00:00:00 2001 From: caveman99 Date: Sat, 24 Feb 2024 20:08:49 +0000 Subject: [PATCH 213/472] [create-pull-request] automated change --- protobufs | 2 +- src/mesh/generated/meshtastic/mesh.pb.h | 9 ++++----- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/protobufs b/protobufs index 24edea644..524158356 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 24edea64429de4474c00d09990ef4c496614dc5d +Subproject commit 5241583565ccbbb4986180bf4c6eb7f8a0dec285 diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index e8a27d43f..6ffd93294 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -75,6 +75,8 @@ typedef enum _meshtastic_HardwareModel { meshtastic_HardwareModel_CANARYONE = 29, /* Waveshare RP2040 LoRa - https://www.waveshare.com/rp2040-lora.htm */ meshtastic_HardwareModel_RP2040_LORA = 30, + /* B&Q Consulting Station G2: https://wiki.uniteng.com/en/meshtastic/station-g2 */ + meshtastic_HardwareModel_STATION_G2 = 31, /* --------------------------------------------------------------------------- Less common/prototype boards listed here (needs one more byte over the air) --------------------------------------------------------------------------- */ @@ -530,8 +532,7 @@ typedef PB_BYTES_ARRAY_T(256) meshtastic_MeshPacket_encrypted_t; typedef struct _meshtastic_MeshPacket { /* The sending node number. Note: Our crypto implementation uses this field as well. - See [crypto](/docs/overview/encryption) for details. - FIXME - really should be fixed32 instead, this encoding only hurts the ble link though. */ + See [crypto](/docs/overview/encryption) for details. */ uint32_t from; /* The (immediatSee Priority description for more details.y should be fixed32 instead, this encoding only hurts the ble link though. */ @@ -558,9 +559,7 @@ typedef struct _meshtastic_MeshPacket { needs to be unique for a few minutes (long enough to last for the length of any ACK or the completion of a mesh broadcast flood). Note: Our crypto implementation uses this id as well. - See [crypto](/docs/overview/encryption) for details. - FIXME - really should be fixed32 instead, this encoding only - hurts the ble link though. */ + See [crypto](/docs/overview/encryption) for details. */ uint32_t id; /* The time this message was received by the esp32 (secs since 1970). Note: this field is _never_ sent on the radio link itself (to save space) Times From 74714bf0c58d8dc898281835b52be9844d7301a2 Mon Sep 17 00:00:00 2001 From: neil Date: Sat, 24 Feb 2024 14:28:58 -0800 Subject: [PATCH 214/472] station-g2 --- .vscode/extensions.json | 9 +++--- boards/station-g2.json | 41 +++++++++++++++++++++++ src/platform/esp32/architecture.h | 4 ++- variants/station-g2/pins_arduino.h | 29 +++++++++++++++++ variants/station-g2/platformio.ini | 15 +++++++++ variants/station-g2/variant.h | 52 ++++++++++++++++++++++++++++++ 6 files changed, 145 insertions(+), 5 deletions(-) create mode 100755 boards/station-g2.json create mode 100755 variants/station-g2/pins_arduino.h create mode 100755 variants/station-g2/platformio.ini create mode 100755 variants/station-g2/variant.h diff --git a/.vscode/extensions.json b/.vscode/extensions.json index 783791f0b..080e70d08 100644 --- a/.vscode/extensions.json +++ b/.vscode/extensions.json @@ -2,8 +2,9 @@ // See http://go.microsoft.com/fwlink/?LinkId=827846 // for the documentation about the extensions.json format "recommendations": [ - "ms-vscode.cpptools", - "platformio.platformio-ide", - "trunk.io" + "platformio.platformio-ide" ], -} \ No newline at end of file + "unwantedRecommendations": [ + "ms-vscode.cpptools-extension-pack" + ] +} diff --git a/boards/station-g2.json b/boards/station-g2.json new file mode 100755 index 000000000..871f067aa --- /dev/null +++ b/boards/station-g2.json @@ -0,0 +1,41 @@ +{ + "build": { + "arduino": { + "ldscript": "esp32s3_out.ld", + "memory_type": "qio_opi" + }, + "core": "esp32", + "extra_flags": [ + "-DBOARD_HAS_PSRAM", + "-DARDUINO_USB_CDC_ON_BOOT=1", + "-DARDUINO_USB_MODE=0", + "-DARDUINO_RUNNING_CORE=1", + "-DARDUINO_EVENT_RUNNING_CORE=0" + ], + "f_cpu": "240000000L", + "f_flash": "80000000L", + "flash_mode": "qio", + "hwids": [["0x303A", "0x1001"]], + "mcu": "esp32s3", + "variant": "station-g2" + }, + "connectivity": ["wifi", "bluetooth", "lora"], + "debug": { + "default_tool": "esp-builtin", + "onboard_tools": ["esp-builtin"], + "openocd_target": "esp32s3.cfg" + }, + "frameworks": ["arduino", "espidf"], + "name": "BQ Station G2", + "upload": { + "flash_size": "16MB", + "maximum_ram_size": 327680, + "maximum_size": 16777216, + "use_1200bps_touch": true, + "wait_for_upload_port": true, + "require_upload_port": true, + "speed": 921600 + }, + "url": "https://wiki.uniteng.com/en/meshtastic/station-g2", + "vendor": "BQ Consulting" +} diff --git a/src/platform/esp32/architecture.h b/src/platform/esp32/architecture.h index 7fab475f3..703bcefc9 100644 --- a/src/platform/esp32/architecture.h +++ b/src/platform/esp32/architecture.h @@ -133,6 +133,8 @@ #define HW_VENDOR meshtastic_HardwareModel_HELTEC_HT62 #elif defined(CHATTER_2) #define HW_VENDOR meshtastic_HardwareModel_CHATTER_2 +#elif defined(STATION_G2) +#define HW_VENDOR meshtastic_HardwareModel_STATION_G2 #endif // ----------------------------------------------------------------------------- @@ -155,4 +157,4 @@ #define LORA_CS 18 #endif -#define SERIAL0_RX_GPIO 3 // Always GPIO3 on ESP32 // FIXME: may be different on ESP32-S3, etc. +#define SERIAL0_RX_GPIO 3 // Always GPIO3 on ESP32 // FIXME: may be different on ESP32-S3, etc. \ No newline at end of file diff --git a/variants/station-g2/pins_arduino.h b/variants/station-g2/pins_arduino.h new file mode 100755 index 000000000..98cbd46d3 --- /dev/null +++ b/variants/station-g2/pins_arduino.h @@ -0,0 +1,29 @@ +#ifndef Pins_Arduino_h +#define Pins_Arduino_h + +#include + +#define USB_VID 0x303a +#define USB_PID 0x1001 + +#define EXTERNAL_NUM_INTERRUPTS 46 +#define NUM_DIGITAL_PINS 48 +#define NUM_ANALOG_INPUTS 20 + +#define analogInputToDigitalPin(p) (((p) < 20) ? (analogChannelToDigitalPin(p)) : -1) +#define digitalPinToInterrupt(p) (((p) <= 48) ? (p) : -1) +#define digitalPinHasPWM(p) (p < 46) + +// GPIO48 Reference: https://github.com/espressif/arduino-esp32/pull/8600 + +// The default Wire will be mapped to Screen and Sensors +static const uint8_t SDA = 5; +static const uint8_t SCL = 6; + +// Default SPI will be mapped to Radio +static const uint8_t MISO = 14; +static const uint8_t SCK = 12; +static const uint8_t MOSI = 13; +static const uint8_t SS = 11; + +#endif /* Pins_Arduino_h */ \ No newline at end of file diff --git a/variants/station-g2/platformio.ini b/variants/station-g2/platformio.ini new file mode 100755 index 000000000..b39136684 --- /dev/null +++ b/variants/station-g2/platformio.ini @@ -0,0 +1,15 @@ +[env:station-g2] +extends = esp32s3_base +board = station-g2 +board_build.mcu = esp32s3 +upload_protocol = esptool +;upload_port = /dev/ttyACM0 +upload_speed = 921600 +lib_deps = + ${esp32s3_base.lib_deps} +build_unflags = -DARDUINO_USB_MODE=1 +build_flags = + ${esp32s3_base.build_flags} -D STATION_G2 -I variants/station-g2 + -DBOARD_HAS_PSRAM + -DSTATION_G2 + -DARDUINO_USB_MODE=0 \ No newline at end of file diff --git a/variants/station-g2/variant.h b/variants/station-g2/variant.h new file mode 100755 index 000000000..6a24cd016 --- /dev/null +++ b/variants/station-g2/variant.h @@ -0,0 +1,52 @@ +/* +Board Information: https://wiki.uniteng.com/en/meshtastic/station-g2 +*/ + +// Station G2 may not have GPS installed, but it has a GROVE GPS Socket for Optional GPS Module +#define GPS_RX_PIN 7 +#define GPS_TX_PIN 15 + +// Station G2 has 1.3 inch OLED Screen +#define USE_SH1107_128_64 + +#define I2C_SDA 5 // I2C pins for this board +#define I2C_SCL 6 + +#define BUTTON_PIN 38 // This is the Program Button +#define BUTTON_NEED_PULLUP + +#define USE_SX1262 + +#define LORA_MISO 14 +#define LORA_SCK 12 +#define LORA_MOSI 13 +#define LORA_CS 11 + +#define LORA_RESET 21 +#define LORA_DIO1 48 + +#ifdef USE_SX1262 +#define SX126X_CS LORA_CS // FIXME - we really should define LORA_CS instead +#define SX126X_DIO1 LORA_DIO1 +#define SX126X_BUSY 47 +#define SX126X_RESET LORA_RESET + +// DIO2 controlls an antenna switch and the TCXO voltage is controlled by DIO3 +#define SX126X_DIO2_AS_RF_SWITCH +#define SX126X_DIO3_TCXO_VOLTAGE 1.8 + +#define SX126X_MAX_POWER \ + 19 // Ensure the PA does not exceed the saturation output power. More + // Info:https://wiki.uniteng.com/en/meshtastic/station-g2#summary-for-lora-power-amplifier-conduction-test +#endif + +#define BATTERY_PIN 4 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage +#define ADC_CHANNEL ADC1_GPIO4_CHANNEL +#define ADC_MULTIPLIER 4 +#define BATTERY_SENSE_SAMPLES 15 // Set the number of samples, It has an effect of increasing sensitivity. +#define BAT_FULLVOLT 8400 +#define BAT_EMPTYVOLT 5000 +#define BAT_CHARGINGVOLT 8400 +#define BAT_NOBATVOLT 4460 +#define CELL_TYPE_LION // same curve for liion/lipo +#define NUM_CELLS 2 \ No newline at end of file From 1fe230a0653556c849e21ec6630e6ee24df51db4 Mon Sep 17 00:00:00 2001 From: Neil Hao Date: Sun, 25 Feb 2024 08:18:30 +0800 Subject: [PATCH 215/472] Undo VS automatic modifications to this file --- .vscode/extensions.json | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/.vscode/extensions.json b/.vscode/extensions.json index 080e70d08..4fc84fa78 100644 --- a/.vscode/extensions.json +++ b/.vscode/extensions.json @@ -2,9 +2,8 @@ // See http://go.microsoft.com/fwlink/?LinkId=827846 // for the documentation about the extensions.json format "recommendations": [ - "platformio.platformio-ide" + "ms-vscode.cpptools", + "platformio.platformio-ide", + "trunk.io" ], - "unwantedRecommendations": [ - "ms-vscode.cpptools-extension-pack" - ] } From 8c7ee1a7bb6f375b817638c884851713aa3e8ff9 Mon Sep 17 00:00:00 2001 From: Neil Hao Date: Sun, 25 Feb 2024 18:32:46 +0800 Subject: [PATCH 216/472] Corrected the Trunk Problem --- variants/station-g2/variant.h | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/variants/station-g2/variant.h b/variants/station-g2/variant.h index 6a24cd016..b1d6914bb 100755 --- a/variants/station-g2/variant.h +++ b/variants/station-g2/variant.h @@ -35,9 +35,8 @@ Board Information: https://wiki.uniteng.com/en/meshtastic/station-g2 #define SX126X_DIO2_AS_RF_SWITCH #define SX126X_DIO3_TCXO_VOLTAGE 1.8 -#define SX126X_MAX_POWER \ - 19 // Ensure the PA does not exceed the saturation output power. More - // Info:https://wiki.uniteng.com/en/meshtastic/station-g2#summary-for-lora-power-amplifier-conduction-test +// Ensure the PA does not exceed the saturation output power. More Info:https://wiki.uniteng.com/en/meshtastic/station-g2#summary-for-lora-power-amplifier-conduction-test +#define SX126X_MAX_POWER 19 #endif #define BATTERY_PIN 4 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage @@ -49,4 +48,4 @@ Board Information: https://wiki.uniteng.com/en/meshtastic/station-g2 #define BAT_CHARGINGVOLT 8400 #define BAT_NOBATVOLT 4460 #define CELL_TYPE_LION // same curve for liion/lipo -#define NUM_CELLS 2 \ No newline at end of file +#define NUM_CELLS 2 From 8726cb830ed6e5c3286d5979545f6bd5a3ac4b05 Mon Sep 17 00:00:00 2001 From: Neil Hao Date: Sun, 25 Feb 2024 18:44:43 +0800 Subject: [PATCH 217/472] Trunk don't like long line:) --- variants/station-g2/variant.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/variants/station-g2/variant.h b/variants/station-g2/variant.h index b1d6914bb..f781ceb24 100755 --- a/variants/station-g2/variant.h +++ b/variants/station-g2/variant.h @@ -35,7 +35,8 @@ Board Information: https://wiki.uniteng.com/en/meshtastic/station-g2 #define SX126X_DIO2_AS_RF_SWITCH #define SX126X_DIO3_TCXO_VOLTAGE 1.8 -// Ensure the PA does not exceed the saturation output power. More Info:https://wiki.uniteng.com/en/meshtastic/station-g2#summary-for-lora-power-amplifier-conduction-test +// Ensure the PA does not exceed the saturation output power. More +// Info:https://wiki.uniteng.com/en/meshtastic/station-g2#summary-for-lora-power-amplifier-conduction-test #define SX126X_MAX_POWER 19 #endif From 6932f073100092211f8a1d8a4d29efab1a2777ed Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sun, 25 Feb 2024 12:11:11 +0100 Subject: [PATCH 218/472] Add Station G2 to the build matrix --- .github/workflows/main_matrix.yml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 5c1cf4c21..1e3e07106 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -32,7 +32,7 @@ jobs: - board: meshtastic-diy-v1 - board: rak4631 - board: t-echo - - board: station-g1 + - board: station-g2 - board: m5stack-coreink - board: tbeam-s3-core - board: tlora-t3s3-v1 @@ -99,6 +99,7 @@ jobs: - board: t-watch-s3 - board: t-deck - board: picomputer-s3 + - board: station-g2 uses: ./.github/workflows/build_esp32_s3.yml with: board: ${{ matrix.board }} From b98ddbddf413084ce3258cafb482d90767398853 Mon Sep 17 00:00:00 2001 From: rcarteraz Date: Sat, 24 Feb 2024 08:19:31 -0700 Subject: [PATCH 219/472] update node db lite log message --- src/mesh/NodeDB.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index add1b1296..506adda5c 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -903,8 +903,8 @@ meshtastic_NodeInfoLite *NodeDB::getOrCreateMeshNode(NodeNum n) if (!lite) { if ((*numMeshNodes >= MAX_NUM_NODES) || (memGet.getFreeHeap() < meshtastic_NodeInfoLite_size * 3)) { if (screen) - screen->print("warning: node_db_lite full! erasing oldest entry\n"); - LOG_INFO("warning: node_db_lite full! erasing oldest entry\n"); + screen->print("Warn: node database full!\nErasing oldest entry\n"); + LOG_INFO("Warn: node database full!\nErasing oldest entry\n"); // look for oldest node and erase it uint32_t oldest = UINT32_MAX; int oldestIndex = -1; From 02192e1163d1145974b4004db72dd86b4f9f30df Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Sun, 25 Feb 2024 14:29:34 +0100 Subject: [PATCH 220/472] More StoreForward updates (#3274) * More StoreForward updates * Disable heartbeat again if not in config --------- Co-authored-by: Ben Meadors --- src/modules/esp32/StoreForwardModule.cpp | 78 ++++++++++++++---------- src/modules/esp32/StoreForwardModule.h | 2 +- 2 files changed, 47 insertions(+), 33 deletions(-) diff --git a/src/modules/esp32/StoreForwardModule.cpp b/src/modules/esp32/StoreForwardModule.cpp index cb1552521..70d13afca 100644 --- a/src/modules/esp32/StoreForwardModule.cpp +++ b/src/modules/esp32/StoreForwardModule.cpp @@ -45,7 +45,8 @@ int32_t StoreForwardModule::runOnce() this->busy = false; } } - } else if ((millis() - lastHeartbeat > (heartbeatInterval * 1000)) && airTime->isTxAllowedChannelUtil(true)) { + } else if (this->heartbeat && (millis() - lastHeartbeat > (heartbeatInterval * 1000)) && + airTime->isTxAllowedChannelUtil(true)) { lastHeartbeat = millis(); LOG_INFO("*** Sending heartbeat\n"); meshtastic_StoreAndForward sf = meshtastic_StoreAndForward_init_zero; @@ -141,25 +142,31 @@ uint32_t StoreForwardModule::historyQueueCreate(uint32_t msAgo, uint32_t to, uin LOG_DEBUG("SF historyQueueCreate - millis %d\n", millis()); LOG_DEBUG("SF historyQueueCreate - math %d\n", (millis() - msAgo)); */ - if (this->packetHistory[i].time && (this->packetHistory[i].time < (millis() - msAgo))) { - /* Copy the messages that were received by the router in the last msAgo - to the packetHistoryTXQueue structure. - Client not interested in packets from itself and only in broadcast packets or packets towards it. */ - if (this->packetHistory[i].from != to && - (this->packetHistory[i].to == NODENUM_BROADCAST || this->packetHistory[i].to == to)) { - this->packetHistoryTXQueue[this->packetHistoryTXQueue_size].time = this->packetHistory[i].time; - this->packetHistoryTXQueue[this->packetHistoryTXQueue_size].to = this->packetHistory[i].to; - this->packetHistoryTXQueue[this->packetHistoryTXQueue_size].from = this->packetHistory[i].from; - this->packetHistoryTXQueue[this->packetHistoryTXQueue_size].channel = this->packetHistory[i].channel; - this->packetHistoryTXQueue[this->packetHistoryTXQueue_size].payload_size = this->packetHistory[i].payload_size; - memcpy(this->packetHistoryTXQueue[this->packetHistoryTXQueue_size].payload, this->packetHistory[i].payload, - meshtastic_Constants_DATA_PAYLOAD_LEN); - this->packetHistoryTXQueue_size++; - *last_request_index = i + 1; // Set to one higher such that we don't send the same message again + if (this->packetHistoryTXQueue_size < this->historyReturnMax) { + if (this->packetHistory[i].time && (this->packetHistory[i].time < (millis() - msAgo))) { + /* Copy the messages that were received by the router in the last msAgo + to the packetHistoryTXQueue structure. + Client not interested in packets from itself and only in broadcast packets or packets towards it. */ + if (this->packetHistory[i].from != to && + (this->packetHistory[i].to == NODENUM_BROADCAST || this->packetHistory[i].to == to)) { + this->packetHistoryTXQueue[this->packetHistoryTXQueue_size].time = this->packetHistory[i].time; + this->packetHistoryTXQueue[this->packetHistoryTXQueue_size].to = this->packetHistory[i].to; + this->packetHistoryTXQueue[this->packetHistoryTXQueue_size].from = this->packetHistory[i].from; + this->packetHistoryTXQueue[this->packetHistoryTXQueue_size].channel = this->packetHistory[i].channel; + this->packetHistoryTXQueue[this->packetHistoryTXQueue_size].payload_size = + this->packetHistory[i].payload_size; + memcpy(this->packetHistoryTXQueue[this->packetHistoryTXQueue_size].payload, this->packetHistory[i].payload, + meshtastic_Constants_DATA_PAYLOAD_LEN); + this->packetHistoryTXQueue_size++; + *last_request_index = i + 1; // Set to one higher such that we don't send the same message again - LOG_DEBUG("*** PacketHistoryStruct time=%d, msg=%s\n", this->packetHistory[i].time, - this->packetHistory[i].payload); + LOG_DEBUG("*** PacketHistoryStruct time=%d, msg=%s\n", this->packetHistory[i].time, + this->packetHistory[i].payload); + } } + } else { + LOG_WARN("*** S&F - Maximum history return reached.\n"); + return this->packetHistoryTXQueue_size; } } return this->packetHistoryTXQueue_size; @@ -174,20 +181,24 @@ void StoreForwardModule::historyAdd(const meshtastic_MeshPacket &mp) { const auto &p = mp.decoded; - if (this->packetHistoryCurrent < this->records) { - this->packetHistory[this->packetHistoryCurrent].time = millis(); - this->packetHistory[this->packetHistoryCurrent].to = mp.to; - this->packetHistory[this->packetHistoryCurrent].channel = mp.channel; - this->packetHistory[this->packetHistoryCurrent].from = mp.from; - this->packetHistory[this->packetHistoryCurrent].payload_size = p.payload.size; - memcpy(this->packetHistory[this->packetHistoryCurrent].payload, p.payload.bytes, meshtastic_Constants_DATA_PAYLOAD_LEN); - - this->packetHistoryCurrent++; - this->packetHistoryMax++; - } else { - // TODO: Overwrite the oldest message in the history buffer when it is full. - LOG_WARN("*** S&F - PSRAM Full. Packet is not added to the history.\n"); + if (this->packetHistoryCurrent == this->records) { + LOG_WARN("*** S&F - PSRAM Full. Starting overwrite now.\n"); + this->packetHistoryCurrent = 0; + this->packetHistoryMax = 0; + for (auto &i : lastRequest) { + i.second = 0; // Clear the last request index for each client device + } } + + this->packetHistory[this->packetHistoryCurrent].time = millis(); + this->packetHistory[this->packetHistoryCurrent].to = mp.to; + this->packetHistory[this->packetHistoryCurrent].channel = mp.channel; + this->packetHistory[this->packetHistoryCurrent].from = mp.from; + this->packetHistory[this->packetHistoryCurrent].payload_size = p.payload.size; + memcpy(this->packetHistory[this->packetHistoryCurrent].payload, p.payload.bytes, meshtastic_Constants_DATA_PAYLOAD_LEN); + + this->packetHistoryCurrent++; + this->packetHistoryMax++; } meshtastic_MeshPacket *StoreForwardModule::allocReply() @@ -313,7 +324,8 @@ ProcessMessage StoreForwardModule::handleReceived(const meshtastic_MeshPacket &m if ((mp.decoded.portnum == meshtastic_PortNum_TEXT_MESSAGE_APP) && is_server) { auto &p = mp.decoded; - if ((p.payload.bytes[0] == 'S') && (p.payload.bytes[1] == 'F') && (p.payload.bytes[2] == 0x00)) { + if (mp.to == nodeDB.getNodeNum() && (p.payload.bytes[0] == 'S') && (p.payload.bytes[1] == 'F') && + (p.payload.bytes[2] == 0x00)) { LOG_DEBUG("*** Legacy Request to send\n"); // Send the last 60 minutes of messages. @@ -543,6 +555,8 @@ StoreForwardModule::StoreForwardModule() // send heartbeat advertising? if (moduleConfig.store_forward.heartbeat) this->heartbeat = moduleConfig.store_forward.heartbeat; + else + this->heartbeat = false; // Popupate PSRAM with our data structures. this->populatePSRAM(); diff --git a/src/modules/esp32/StoreForwardModule.h b/src/modules/esp32/StoreForwardModule.h index cfa9945d5..0d2fb9fce 100644 --- a/src/modules/esp32/StoreForwardModule.h +++ b/src/modules/esp32/StoreForwardModule.h @@ -44,7 +44,7 @@ class StoreForwardModule : private concurrency::OSThread, public ProtobufModule< StoreForwardModule(); unsigned long lastHeartbeat = 0; - uint32_t heartbeatInterval = default_broadcast_interval_secs; + uint32_t heartbeatInterval = 900; /** Update our local reference of when we last saw that node. From 824991c17804d2418405af85b6c734618b213b8c Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Sun, 25 Feb 2024 14:43:44 +0100 Subject: [PATCH 221/472] Ignore MQTT by default if region has a duty cycle limit (#3277) Co-authored-by: Ben Meadors --- src/modules/AdminModule.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index 94df601d8..abd7c2e54 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -332,6 +332,9 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c) if (isRegionUnset && config.lora.region > meshtastic_Config_LoRaConfig_RegionCode_UNSET) { config.lora.tx_enabled = true; initRegion(); + if (myRegion->dutyCycle < 100) { + config.lora.ignore_mqtt = true; // Ignore MQTT by default if region has a duty cycle limit + } if (strcmp(moduleConfig.mqtt.root, default_mqtt_root) == 0) { sprintf(moduleConfig.mqtt.root, "%s/%s", default_mqtt_root, myRegion->name); changes = SEGMENT_CONFIG | SEGMENT_MODULECONFIG; From 0f27992c5a95c73e7a71876d2bd049d46ff2a1d7 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Sun, 25 Feb 2024 14:44:08 +0100 Subject: [PATCH 222/472] Ignore JSON enabled setting on nRF52 platforms (#3286) Not supported, see #2804 Co-authored-by: Ben Meadors --- src/mqtt/MQTT.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 8c241a302..898607eca 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -351,11 +351,13 @@ void MQTT::sendSubscriptions() std::string topic = cryptTopic + channels.getGlobalId(i) + "/#"; LOG_INFO("Subscribing to %s\n", topic.c_str()); pubSub.subscribe(topic.c_str(), 1); // FIXME, is QOS 1 right? +#ifndef ARCH_NRF52 // JSON is not supported on nRF52, see issue #2804 if (moduleConfig.mqtt.json_enabled == true) { std::string topicDecoded = jsonTopic + channels.getGlobalId(i) + "/#"; LOG_INFO("Subscribing to %s\n", topicDecoded.c_str()); pubSub.subscribe(topicDecoded.c_str(), 1); // FIXME, is QOS 1 right? } +#endif // ARCH_NRF52 } } #endif @@ -450,6 +452,7 @@ void MQTT::publishQueuedMessages() publish(topic.c_str(), bytes, numBytes, false); +#ifndef ARCH_NRF52 // JSON is not supported on nRF52, see issue #2804 if (moduleConfig.mqtt.json_enabled) { // handle json topic auto jsonString = this->meshPacketToJson(env->packet); @@ -460,6 +463,7 @@ void MQTT::publishQueuedMessages() publish(topicJson.c_str(), jsonString.c_str(), false); } } +#endif // ARCH_NRF52 mqttPool.release(env); } } @@ -504,6 +508,7 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket & publish(topic.c_str(), bytes, numBytes, false); +#ifndef ARCH_NRF52 // JSON is not supported on nRF52, see issue #2804 if (moduleConfig.mqtt.json_enabled) { // handle json topic auto jsonString = this->meshPacketToJson((meshtastic_MeshPacket *)&mp_decoded); @@ -514,7 +519,7 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket & publish(topicJson.c_str(), jsonString.c_str(), false); } } - +#endif // ARCH_NRF52 } else { LOG_INFO("MQTT not connected, queueing packet\n"); if (mqttQueue.numFree() == 0) { From d434117ffdded1e1dbb118264c546fafab097375 Mon Sep 17 00:00:00 2001 From: Thomas Herrmann Date: Sun, 25 Feb 2024 20:03:54 +0100 Subject: [PATCH 223/472] add UI frame for PaxCounter module (#3285) * add UI frame to display PaxCounter module data * only acquire screen when paxcounter is active, i.e. enabled and wifi and ble are both off * sync font #define with other occurrences in code * protect screen specific code with #if HAS_SCREEN * limit upload_speed to 115200 for TLORA_V2_1_16 * fix failing trunk checks; sorry * Revert "limit upload_speed to 115200 for TLORA_V2_1_16" This reverts commit 4eb549c5e886508a4d39a7bfe689bc1976cbaa4b. --------- Co-authored-by: Ben Meadors --- src/modules/esp32/PaxcounterModule.cpp | 45 +++++++++++++++++++++++++- src/modules/esp32/PaxcounterModule.h | 5 +++ 2 files changed, 49 insertions(+), 1 deletion(-) diff --git a/src/modules/esp32/PaxcounterModule.cpp b/src/modules/esp32/PaxcounterModule.cpp index f3df7ffdf..b3506891d 100644 --- a/src/modules/esp32/PaxcounterModule.cpp +++ b/src/modules/esp32/PaxcounterModule.cpp @@ -57,7 +57,7 @@ meshtastic_MeshPacket *PaxcounterModule::allocReply() int32_t PaxcounterModule::runOnce() { - if (moduleConfig.paxcounter.enabled && !config.bluetooth.enabled && !config.network.wifi_enabled) { + if (isActive()) { if (firstTime) { firstTime = false; LOG_DEBUG( @@ -87,4 +87,47 @@ int32_t PaxcounterModule::runOnce() } } +#if HAS_SCREEN + +// TODO / FIXME: This code is copied from src/graphics/Screen.cpp +// It appears (in slightly variants) also in other modules like +// src/modules/Telemetry/PowerTelemetry.cpp, src/modules/Telemetry/EnvironmentTelemetry.cpp +// and src/modules/CannedMessageModule.cpp +// It probably should go to a common header file for consistency +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \ + !defined(DISPLAY_FORCE_SMALL_FONTS) +// The screen is bigger so use bigger fonts +#define FONT_SMALL ArialMT_Plain_16 // Height: 19 +#define FONT_MEDIUM ArialMT_Plain_24 // Height: 28 +#define FONT_LARGE ArialMT_Plain_24 // Height: 28 +#else +#ifdef OLED_RU +#define FONT_SMALL ArialMT_Plain_10_RU +#else +#ifdef OLED_UA +#define FONT_SMALL ArialMT_Plain_10_UA +#else +#define FONT_SMALL ArialMT_Plain_10 // Height: 13 +#endif +#endif +#define FONT_MEDIUM ArialMT_Plain_16 // Height: 19 +#define FONT_LARGE ArialMT_Plain_24 // Height: 28 +#endif + +void PaxcounterModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) +{ + char buffer[50]; + display->setTextAlignment(TEXT_ALIGN_LEFT); + display->setFont(FONT_SMALL); + display->drawString(x + 0, y + 0, "PAX"); + + libpax_counter_count(&count_from_libpax); + + display->setTextAlignment(TEXT_ALIGN_CENTER); + display->setFont(FONT_SMALL); + display->drawStringf(display->getWidth() / 2 + x, 0 + y + 12, buffer, "WiFi: %d\nBLE: %d\nuptime: %ds", + count_from_libpax.wifi_count, count_from_libpax.ble_count, millis() / 1000); +} +#endif // HAS_SCREEN + #endif \ No newline at end of file diff --git a/src/modules/esp32/PaxcounterModule.h b/src/modules/esp32/PaxcounterModule.h index 0aa9be68d..e72f87450 100644 --- a/src/modules/esp32/PaxcounterModule.h +++ b/src/modules/esp32/PaxcounterModule.h @@ -23,6 +23,11 @@ class PaxcounterModule : private concurrency::OSThread, public ProtobufModule Date: Sun, 25 Feb 2024 21:27:32 -0600 Subject: [PATCH 224/472] Fix wrong-side-of-globe when precision set to 32 --- src/modules/PositionModule.cpp | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index 5f20dbafb..d8d52667c 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -118,13 +118,16 @@ meshtastic_MeshPacket *PositionModule::allocReply() // lat/lon are unconditionally included - IF AVAILABLE! LOG_DEBUG("Sending location with precision %i\n", precision); - p.latitude_i = localPosition.latitude_i & (INT32_MAX << (32 - precision)); - p.longitude_i = localPosition.longitude_i & (INT32_MAX << (32 - precision)); + if (precision < 32 && precision > 0) { + p.latitude_i = localPosition.latitude_i & (INT32_MAX << (32 - precision)); + p.longitude_i = localPosition.longitude_i & (INT32_MAX << (32 - precision)); - // We want the imprecise position to be the middle of the possible location, not - if (precision < 31 && precision > 1) { + // We want the imprecise position to be the middle of the possible location, not p.latitude_i += (1 << (31 - precision)); p.longitude_i += (1 << (31 - precision)); + } else { + p.latitude_i = localPosition.latitude_i; + p.longitude_i = localPosition.longitude_i; } p.precision_bits = precision; p.time = localPosition.time; From 146b5b557adc5653287d7cf02792aa4e59aab56f Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Mon, 26 Feb 2024 00:22:05 -0600 Subject: [PATCH 225/472] UINT32_MAX is not the same as INT32_MAX --- src/modules/PositionModule.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index d8d52667c..92e8f8a4d 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -119,8 +119,8 @@ meshtastic_MeshPacket *PositionModule::allocReply() // lat/lon are unconditionally included - IF AVAILABLE! LOG_DEBUG("Sending location with precision %i\n", precision); if (precision < 32 && precision > 0) { - p.latitude_i = localPosition.latitude_i & (INT32_MAX << (32 - precision)); - p.longitude_i = localPosition.longitude_i & (INT32_MAX << (32 - precision)); + p.latitude_i = localPosition.latitude_i & (UINT32_MAX << (32 - precision)); + p.longitude_i = localPosition.longitude_i & (UINT32_MAX << (32 - precision)); // We want the imprecise position to be the middle of the possible location, not p.latitude_i += (1 << (31 - precision)); From d556d59308faa5404f987eac0c6e1544cf55a3dd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Mon, 26 Feb 2024 09:42:12 +0100 Subject: [PATCH 226/472] fix compilation for Cyrillic fonts --- src/modules/esp32/PaxcounterModule.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/modules/esp32/PaxcounterModule.cpp b/src/modules/esp32/PaxcounterModule.cpp index b3506891d..89bf8f072 100644 --- a/src/modules/esp32/PaxcounterModule.cpp +++ b/src/modules/esp32/PaxcounterModule.cpp @@ -89,6 +89,14 @@ int32_t PaxcounterModule::runOnce() #if HAS_SCREEN +#ifdef OLED_RU +#include "graphics/fonts/OLEDDisplayFontsRU.h" +#endif + +#ifdef OLED_UA +#include "graphics/fonts/OLEDDisplayFontsUA.h" +#endif + // TODO / FIXME: This code is copied from src/graphics/Screen.cpp // It appears (in slightly variants) also in other modules like // src/modules/Telemetry/PowerTelemetry.cpp, src/modules/Telemetry/EnvironmentTelemetry.cpp From 4796c8edc488b71571ad5c1eeb9905abde09cbc6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Mon, 26 Feb 2024 17:38:16 +0100 Subject: [PATCH 227/472] Update trunk to latest version (#3295) --- .trunk/.gitignore | 1 + .trunk/trunk.yaml | 32 +++++++++++++++++--------------- 2 files changed, 18 insertions(+), 15 deletions(-) diff --git a/.trunk/.gitignore b/.trunk/.gitignore index 1e2465290..15966d087 100644 --- a/.trunk/.gitignore +++ b/.trunk/.gitignore @@ -6,3 +6,4 @@ plugins user_trunk.yaml user.yaml +tmp diff --git a/.trunk/trunk.yaml b/.trunk/trunk.yaml index 81a35f8f1..af7d3d21d 100644 --- a/.trunk/trunk.yaml +++ b/.trunk/trunk.yaml @@ -1,34 +1,36 @@ version: 0.1 cli: - version: 1.17.2 + version: 1.20.1 plugins: sources: - id: trunk - ref: v1.3.0 + ref: v1.4.3 uri: https://github.com/trunk-io/plugins lint: enabled: - - bandit@1.7.5 - - checkov@3.1.9 - - terrascan@1.18.5 - - trivy@0.47.0 + - trufflehog@3.68.2 + - yamllint@1.35.1 + - bandit@1.7.7 + - checkov@3.2.26 + - terrascan@1.18.11 + - trivy@0.49.1 #- trufflehog@3.63.2-rc0 - taplo@0.8.1 - - ruff@0.1.6 - - isort@5.12.0 - - markdownlint@0.37.0 + - ruff@0.2.2 + - isort@5.13.2 + - markdownlint@0.39.0 - oxipng@9.0.0 - - svgo@3.0.5 - - actionlint@1.6.26 - - flake8@6.1.0 + - svgo@3.2.0 + - actionlint@1.6.27 + - flake8@7.0.0 - hadolint@2.12.0 - shfmt@3.6.0 - shellcheck@0.9.0 - - black@23.9.1 + - black@24.2.0 - git-diff-check - - gitleaks@8.18.1 + - gitleaks@8.18.2 - clang-format@16.0.3 - - prettier@3.1.0 + - prettier@3.2.5 runtimes: enabled: - python@3.10.8 From 59bbd1ad00fafc18553cd01f4673fd9deac4af2e Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Mon, 26 Feb 2024 19:32:58 -0600 Subject: [PATCH 228/472] Revert I2C changes --- variants/heltec_wireless_tracker_V1_0/pins_arduino.h | 4 ++-- variants/heltec_wireless_tracker_V1_0/platformio.ini | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/variants/heltec_wireless_tracker_V1_0/pins_arduino.h b/variants/heltec_wireless_tracker_V1_0/pins_arduino.h index 5c0b529b0..42c5770a9 100644 --- a/variants/heltec_wireless_tracker_V1_0/pins_arduino.h +++ b/variants/heltec_wireless_tracker_V1_0/pins_arduino.h @@ -26,8 +26,8 @@ static const uint8_t LED_BUILTIN = 18; static const uint8_t TX = 43; static const uint8_t RX = 44; -static const uint8_t SDA = 45; -static const uint8_t SCL = 46; +static const uint8_t SDA = 41; +static const uint8_t SCL = 42; static const uint8_t SS = 8; static const uint8_t MOSI = 10; diff --git a/variants/heltec_wireless_tracker_V1_0/platformio.ini b/variants/heltec_wireless_tracker_V1_0/platformio.ini index 034360c3d..303e27dbf 100644 --- a/variants/heltec_wireless_tracker_V1_0/platformio.ini +++ b/variants/heltec_wireless_tracker_V1_0/platformio.ini @@ -1,7 +1,7 @@ [env:heltec-wireless-tracker-V1-0] extends = esp32s3_base board = heltec_wireless_tracker -upload_protocol = esp-builtin +upload_protocol = esptool build_flags = ${esp32s3_base.build_flags} -I variants/heltec_wireless_tracker_V1_0 From ce0e5c0ce72db7746c923a0ede1d8e84b92032dd Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Mon, 26 Feb 2024 19:49:43 -0600 Subject: [PATCH 229/472] SDA and SCL remap --- variants/heltec_wireless_tracker_V1_0/pins_arduino.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/variants/heltec_wireless_tracker_V1_0/pins_arduino.h b/variants/heltec_wireless_tracker_V1_0/pins_arduino.h index 42c5770a9..f72c7661a 100644 --- a/variants/heltec_wireless_tracker_V1_0/pins_arduino.h +++ b/variants/heltec_wireless_tracker_V1_0/pins_arduino.h @@ -26,8 +26,8 @@ static const uint8_t LED_BUILTIN = 18; static const uint8_t TX = 43; static const uint8_t RX = 44; -static const uint8_t SDA = 41; -static const uint8_t SCL = 42; +static const uint8_t SDA = 5; +static const uint8_t SCL = 6; static const uint8_t SS = 8; static const uint8_t MOSI = 10; From e6a2c06346e37a2a9b03469ba6a60d3632ddb51d Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Mon, 26 Feb 2024 20:24:36 -0600 Subject: [PATCH 230/472] Various position fixes (#3297) * Guard against no movement * Add newlines * Fix printfs --- src/gps/GPS.cpp | 6 ++---- src/gps/GeoCoord.cpp | 15 +++++++++------ src/gps/GeoCoord.h | 1 + src/modules/PositionModule.cpp | 2 +- 4 files changed, 13 insertions(+), 11 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 08ef116b2..3a3660308 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -319,7 +319,6 @@ bool GPS::setup() delay(250); _serial_gps->write("$CFGMSG,6,1,0\r\n"); delay(250); - } else if (gnssModel == GNSS_MODEL_UBLOX) { // Configure GNSS system to GPS+SBAS+GLONASS (Module may restart after this command) // We need set it because by default it is GPS only, and we want to use GLONASS too @@ -458,7 +457,6 @@ bool GPS::setup() LOG_WARN("Unable to enable NMEA 4.10.\n"); } } - } else { if (strncmp(info.hwVersion, "00040007", 8) == 0) { // This PSM mode is only for Neo-6 msglen = makeUBXPacket(0x06, 0x11, 0x2, _message_CFG_RXM_ECO); @@ -642,12 +640,12 @@ void GPS::setGPSPower(bool on, bool standbyOnly, uint32_t sleepTime) #endif #ifdef PIN_GPS_STANDBY // Specifically the standby pin for L76K and clones if (on) { - LOG_INFO("Waking GPS"); + LOG_INFO("Waking GPS\n"); pinMode(PIN_GPS_STANDBY, OUTPUT); digitalWrite(PIN_GPS_STANDBY, 1); return; } else { - LOG_INFO("GPS entering sleep"); + LOG_INFO("GPS entering sleep\n"); // notifyGPSSleep.notifyObservers(NULL); pinMode(PIN_GPS_STANDBY, OUTPUT); digitalWrite(PIN_GPS_STANDBY, 0); diff --git a/src/gps/GeoCoord.cpp b/src/gps/GeoCoord.cpp index 19a753c02..cb4e69ff2 100644 --- a/src/gps/GeoCoord.cpp +++ b/src/gps/GeoCoord.cpp @@ -376,14 +376,17 @@ void GeoCoord::convertWGS84ToOSGB36(const double lat, const double lon, double & } /// Ported from my old java code, returns distance in meters along the globe -/// surface (by magic?) +/// surface (by Haversine formula) float GeoCoord::latLongToMeter(double lat_a, double lng_a, double lat_b, double lng_b) { - double pk = (180 / 3.14169); - double a1 = lat_a / pk; - double a2 = lng_a / pk; - double b1 = lat_b / pk; - double b2 = lng_b / pk; + // Don't do math if the points are the same + if (lat_a == lat_b && lng_a == lng_b) + return 0.0; + + double a1 = lat_a / DEG_CONVERT; + double a2 = lng_a / DEG_CONVERT; + double b1 = lat_b / DEG_CONVERT; + double b2 = lng_b / DEG_CONVERT; double cos_b1 = cos(b1); double cos_a1 = cos(a1); double t1 = cos_a1 * cos(a2) * cos_b1 * cos(b2); diff --git a/src/gps/GeoCoord.h b/src/gps/GeoCoord.h index 06b11c3de..9f911ed93 100644 --- a/src/gps/GeoCoord.h +++ b/src/gps/GeoCoord.h @@ -11,6 +11,7 @@ #define PI 3.1415926535897932384626433832795 #define OLC_CODE_LEN 11 +#define DEG_CONVERT 180 / PI // Helper functions // Raises a number to an exponent, handling negative exponents. diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index 92e8f8a4d..1e4ea5de1 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -372,7 +372,7 @@ struct SmartPosition PositionModule::getDistanceTraveledSinceLastSend(meshtastic LOG_DEBUG("currentPosition.latitude_i=%i, currentPosition.longitude_i=%i\n", lastGpsLatitude, lastGpsLongitude); LOG_DEBUG("--------SMART POSITION-----------------------------------\n"); - LOG_DEBUG("hasTraveledOverThreshold=%i, distanceTraveled=%d, distanceThreshold=% u\n", + LOG_DEBUG("hasTraveledOverThreshold=%i, distanceTraveled=%f, distanceThreshold=%f\n", abs(distanceTraveledSinceLastSend) >= distanceTravelThreshold, abs(distanceTraveledSinceLastSend), distanceTravelThreshold); From f7758b4e4401640c55d320d60fffc30ecc0868da Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Mon, 26 Feb 2024 21:32:49 -0600 Subject: [PATCH 231/472] [create-pull-request] automated change (#3298) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index ed7e93154..14d1884fb 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 2 -build = 24 +build = 25 From 4ffb906fe8f45cb40e628ad0edbe146670d725ed Mon Sep 17 00:00:00 2001 From: Thomas Herrmann Date: Tue, 27 Feb 2024 19:49:46 +0100 Subject: [PATCH 232/472] move duplicate #define for screen to unified header file (#3302) --- src/graphics/Screen.cpp | 34 +----------------- src/graphics/ScreenFonts.h | 35 +++++++++++++++++++ src/modules/CannedMessageModule.cpp | 35 +------------------ .../Telemetry/EnvironmentTelemetry.cpp | 18 +--------- src/modules/Telemetry/PowerTelemetry.cpp | 18 +--------- src/modules/esp32/AudioModule.cpp | 35 +------------------ src/modules/esp32/PaxcounterModule.cpp | 35 ++----------------- 7 files changed, 42 insertions(+), 168 deletions(-) create mode 100644 src/graphics/ScreenFonts.h diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 5197e4dbc..129af226b 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -56,14 +56,6 @@ along with this program. If not, see . #include "platform/portduino/PortduinoGlue.h" #endif -#ifdef OLED_RU -#include "fonts/OLEDDisplayFontsRU.h" -#endif - -#ifdef OLED_UA -#include "fonts/OLEDDisplayFontsUA.h" -#endif - using namespace meshtastic; /** @todo remove */ namespace graphics @@ -111,31 +103,7 @@ static uint16_t displayWidth, displayHeight; #define SCREEN_WIDTH displayWidth #define SCREEN_HEIGHT displayHeight -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \ - !defined(DISPLAY_FORCE_SMALL_FONTS) -// The screen is bigger so use bigger fonts -#define FONT_SMALL ArialMT_Plain_16 // Height: 19 -#define FONT_MEDIUM ArialMT_Plain_24 // Height: 28 -#define FONT_LARGE ArialMT_Plain_24 // Height: 28 -#else -#ifdef OLED_RU -#define FONT_SMALL ArialMT_Plain_10_RU -#else -#ifdef OLED_UA -#define FONT_SMALL ArialMT_Plain_10_UA -#else -#define FONT_SMALL ArialMT_Plain_10 // Height: 13 -#endif -#endif -#define FONT_MEDIUM ArialMT_Plain_16 // Height: 19 -#define FONT_LARGE ArialMT_Plain_24 // Height: 28 -#endif - -#define fontHeight(font) ((font)[1] + 1) // height is position 1 - -#define FONT_HEIGHT_SMALL fontHeight(FONT_SMALL) -#define FONT_HEIGHT_MEDIUM fontHeight(FONT_MEDIUM) -#define FONT_HEIGHT_LARGE fontHeight(FONT_LARGE) +#include "graphics/ScreenFonts.h" #define getStringCenteredX(s) ((SCREEN_WIDTH - display->getStringWidth(s)) / 2) diff --git a/src/graphics/ScreenFonts.h b/src/graphics/ScreenFonts.h new file mode 100644 index 000000000..d858add2c --- /dev/null +++ b/src/graphics/ScreenFonts.h @@ -0,0 +1,35 @@ +#pragma once + +#ifdef OLED_RU +#include "graphics/fonts/OLEDDisplayFontsRU.h" +#endif + +#ifdef OLED_UA +#include "graphics/fonts/OLEDDisplayFontsUA.h" +#endif + +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \ + !defined(DISPLAY_FORCE_SMALL_FONTS) +// The screen is bigger so use bigger fonts +#define FONT_SMALL ArialMT_Plain_16 // Height: 19 +#define FONT_MEDIUM ArialMT_Plain_24 // Height: 28 +#define FONT_LARGE ArialMT_Plain_24 // Height: 28 +#else +#ifdef OLED_RU +#define FONT_SMALL ArialMT_Plain_10_RU +#else +#ifdef OLED_UA +#define FONT_SMALL ArialMT_Plain_10_UA +#else +#define FONT_SMALL ArialMT_Plain_10 // Height: 13 +#endif +#endif +#define FONT_MEDIUM ArialMT_Plain_16 // Height: 19 +#define FONT_LARGE ArialMT_Plain_24 // Height: 28 +#endif + +#define fontHeight(font) ((font)[1] + 1) // height is position 1 + +#define FONT_HEIGHT_SMALL fontHeight(FONT_SMALL) +#define FONT_HEIGHT_MEDIUM fontHeight(FONT_MEDIUM) +#define FONT_HEIGHT_LARGE fontHeight(FONT_LARGE) diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index 3127b0986..b2b52d1ab 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -18,40 +18,7 @@ #define INPUTBROKER_MATRIX_TYPE 0 #endif -#ifdef OLED_RU -#include "graphics/fonts/OLEDDisplayFontsRU.h" -#endif - -#ifdef OLED_UA -#include "graphics/fonts/OLEDDisplayFontsUA.h" -#endif - -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \ - !defined(DISPLAY_FORCE_SMALL_FONTS) - -// The screen is bigger so use bigger fonts -#define FONT_SMALL ArialMT_Plain_16 -#define FONT_MEDIUM ArialMT_Plain_24 -#define FONT_LARGE ArialMT_Plain_24 -#else -#ifdef OLED_RU -#define FONT_SMALL ArialMT_Plain_10_RU -#else -#ifdef OLED_UA -#define FONT_SMALL ArialMT_Plain_10_UA -#else -#define FONT_SMALL ArialMT_Plain_10 -#endif -#endif -#define FONT_MEDIUM ArialMT_Plain_16 -#define FONT_LARGE ArialMT_Plain_24 -#endif - -#define fontHeight(font) ((font)[1] + 1) // height is position 1 - -#define FONT_HEIGHT_SMALL fontHeight(FONT_SMALL) -#define FONT_HEIGHT_MEDIUM fontHeight(FONT_MEDIUM) -#define FONT_HEIGHT_LARGE fontHeight(FONT_LARGE) +#include "graphics/ScreenFonts.h" // Remove Canned message screen if no action is taken for some milliseconds #define INACTIVATE_AFTER_MS 20000 diff --git a/src/modules/Telemetry/EnvironmentTelemetry.cpp b/src/modules/Telemetry/EnvironmentTelemetry.cpp index 9c7b406e9..e501f17c2 100644 --- a/src/modules/Telemetry/EnvironmentTelemetry.cpp +++ b/src/modules/Telemetry/EnvironmentTelemetry.cpp @@ -33,23 +33,7 @@ SHT31Sensor sht31Sensor; #define FAILED_STATE_SENSOR_READ_MULTIPLIER 10 #define DISPLAY_RECEIVEID_MEASUREMENTS_ON_SCREEN true -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \ - !defined(DISPLAY_FORCE_SMALL_FONTS) - -// The screen is bigger so use bigger fonts -#define FONT_SMALL ArialMT_Plain_16 -#define FONT_MEDIUM ArialMT_Plain_24 -#define FONT_LARGE ArialMT_Plain_24 -#else -#define FONT_SMALL ArialMT_Plain_10 -#define FONT_MEDIUM ArialMT_Plain_16 -#define FONT_LARGE ArialMT_Plain_24 -#endif - -#define fontHeight(font) ((font)[1] + 1) // height is position 1 - -#define FONT_HEIGHT_SMALL fontHeight(FONT_SMALL) -#define FONT_HEIGHT_MEDIUM fontHeight(FONT_MEDIUM) +#include "graphics/ScreenFonts.h" int32_t EnvironmentTelemetryModule::runOnce() { diff --git a/src/modules/Telemetry/PowerTelemetry.cpp b/src/modules/Telemetry/PowerTelemetry.cpp index 032d7fc27..30628bfd7 100644 --- a/src/modules/Telemetry/PowerTelemetry.cpp +++ b/src/modules/Telemetry/PowerTelemetry.cpp @@ -14,23 +14,7 @@ #define FAILED_STATE_SENSOR_READ_MULTIPLIER 10 #define DISPLAY_RECEIVEID_MEASUREMENTS_ON_SCREEN true -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \ - !defined(DISPLAY_FORCE_SMALL_FONTS) - -// The screen is bigger so use bigger fonts -#define FONT_SMALL ArialMT_Plain_16 -#define FONT_MEDIUM ArialMT_Plain_24 -#define FONT_LARGE ArialMT_Plain_24 -#else -#define FONT_SMALL ArialMT_Plain_10 -#define FONT_MEDIUM ArialMT_Plain_16 -#define FONT_LARGE ArialMT_Plain_24 -#endif - -#define fontHeight(font) ((font)[1] + 1) // height is position 1 - -#define FONT_HEIGHT_SMALL fontHeight(FONT_SMALL) -#define FONT_HEIGHT_MEDIUM fontHeight(FONT_MEDIUM) +#include "graphics/ScreenFonts.h" int32_t PowerTelemetryModule::runOnce() { diff --git a/src/modules/esp32/AudioModule.cpp b/src/modules/esp32/AudioModule.cpp index bc104df11..a10cae954 100644 --- a/src/modules/esp32/AudioModule.cpp +++ b/src/modules/esp32/AudioModule.cpp @@ -8,14 +8,6 @@ #include "RTC.h" #include "Router.h" -#ifdef OLED_RU -#include "graphics/fonts/OLEDDisplayFontsRU.h" -#endif - -#ifdef OLED_UA -#include "graphics/fonts/OLEDDisplayFontsUA.h" -#endif - /* AudioModule A interface to send raw codec2 audio data over the mesh network. Based on the example code from the ESP32_codec2 project. @@ -48,32 +40,7 @@ AudioModule *audioModule; #define YIELD_FROM_ISR(x) portYIELD_FROM_ISR(x) #endif -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \ - !defined(DISPLAY_FORCE_SMALL_FONTS) - -// The screen is bigger so use bigger fonts -#define FONT_SMALL ArialMT_Plain_16 -#define FONT_MEDIUM ArialMT_Plain_24 -#define FONT_LARGE ArialMT_Plain_24 -#else -#ifdef OLED_RU -#define FONT_SMALL ArialMT_Plain_10_RU -#else -#ifdef OLED_UA -#define FONT_SMALL ArialMT_Plain_10_UA -#else -#define FONT_SMALL ArialMT_Plain_10 -#endif -#endif -#define FONT_MEDIUM ArialMT_Plain_16 -#define FONT_LARGE ArialMT_Plain_24 -#endif - -#define fontHeight(font) ((font)[1] + 1) // height is position 1 - -#define FONT_HEIGHT_SMALL fontHeight(FONT_SMALL) -#define FONT_HEIGHT_MEDIUM fontHeight(FONT_MEDIUM) -#define FONT_HEIGHT_LARGE fontHeight(FONT_LARGE) +#include "graphics/ScreenFonts.h" void run_codec2(void *parameter) { diff --git a/src/modules/esp32/PaxcounterModule.cpp b/src/modules/esp32/PaxcounterModule.cpp index 89bf8f072..2182ed124 100644 --- a/src/modules/esp32/PaxcounterModule.cpp +++ b/src/modules/esp32/PaxcounterModule.cpp @@ -89,38 +89,7 @@ int32_t PaxcounterModule::runOnce() #if HAS_SCREEN -#ifdef OLED_RU -#include "graphics/fonts/OLEDDisplayFontsRU.h" -#endif - -#ifdef OLED_UA -#include "graphics/fonts/OLEDDisplayFontsUA.h" -#endif - -// TODO / FIXME: This code is copied from src/graphics/Screen.cpp -// It appears (in slightly variants) also in other modules like -// src/modules/Telemetry/PowerTelemetry.cpp, src/modules/Telemetry/EnvironmentTelemetry.cpp -// and src/modules/CannedMessageModule.cpp -// It probably should go to a common header file for consistency -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \ - !defined(DISPLAY_FORCE_SMALL_FONTS) -// The screen is bigger so use bigger fonts -#define FONT_SMALL ArialMT_Plain_16 // Height: 19 -#define FONT_MEDIUM ArialMT_Plain_24 // Height: 28 -#define FONT_LARGE ArialMT_Plain_24 // Height: 28 -#else -#ifdef OLED_RU -#define FONT_SMALL ArialMT_Plain_10_RU -#else -#ifdef OLED_UA -#define FONT_SMALL ArialMT_Plain_10_UA -#else -#define FONT_SMALL ArialMT_Plain_10 // Height: 13 -#endif -#endif -#define FONT_MEDIUM ArialMT_Plain_16 // Height: 19 -#define FONT_LARGE ArialMT_Plain_24 // Height: 28 -#endif +#include "graphics/ScreenFonts.h" void PaxcounterModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) { @@ -138,4 +107,4 @@ void PaxcounterModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state } #endif // HAS_SCREEN -#endif \ No newline at end of file +#endif From 2786db499df7b824845578082256a14deab9acf3 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 28 Feb 2024 08:01:59 -0600 Subject: [PATCH 233/472] Missing include --- src/graphics/Screen.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 129af226b..c92877d41 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -31,6 +31,7 @@ along with this program. If not, see . #include "error.h" #include "gps/GeoCoord.h" #include "gps/RTC.h" +#include "graphics/ScreenFonts.h" #include "graphics/images.h" #include "input/TouchScreenImpl1.h" #include "main.h" From 7aee014f5e545550c27be135bba2f5370f9b2e5e Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Thu, 29 Feb 2024 04:20:20 +1300 Subject: [PATCH 234/472] Add Heltec Wireless Paper V1.0 to the build matrix (#3306) --- .github/workflows/main_matrix.yml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 1e3e07106..e77b4a261 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -93,7 +93,8 @@ jobs: - board: heltec-wsl-v3 - board: heltec-wireless-tracker - board: heltec-wireless-tracker-V1-0 - - board: heltec-wireless-paper + - board: heltec-wireless-paper-v1_0 + - board: heltec-wireless-paper #v1.1 - board: tbeam-s3-core - board: tlora-t3s3-v1 - board: t-watch-s3 From 6acc63729b702501dba4a83e7285f068d6a21d13 Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Thu, 29 Feb 2024 04:45:15 +1300 Subject: [PATCH 235/472] Refactor EInkDisplay (#3299) * Refactor EInkDisplay A lot of variant specific code is merged, with the macros pushed to the respective variant.h files. "Dynamic Partial" code has been purged, pending a rewrite. * fix: declare class only if USE_EINK, init all members * refactor: move macros to platformio.ini Responds to https://github.com/meshtastic/firmware/pull/3299#issuecomment-1966425926 * fix: EInkDisplay::connect() references old macros Usage was in a block of variant-specific code, which had been intentionally left untouched. * fix: remove duplicate macros from variant.h --------- Co-authored-by: Ben Meadors --- src/graphics/EInkDisplay2.cpp | 409 +++--------------- src/graphics/EInkDisplay2.h | 87 +--- .../platformio.ini | 3 + .../Dongle_nRF52840-pca10059-v1/variant.h | 2 +- .../MakePython_nRF52840_eink/platformio.ini | 3 + variants/esp32-s3-pico/platformio.ini | 6 +- variants/esp32-s3-pico/variant.h | 2 +- variants/heltec_wireless_paper/platformio.ini | 7 +- .../heltec_wireless_paper_v1/platformio.ini | 3 + variants/heltec_wireless_paper_v1/variant.h | 7 - variants/m5stack_coreink/platformio.ini | 5 +- variants/my_esp32s3_diy_eink/platformio.ini | 6 +- variants/my_esp32s3_diy_eink/variant.h | 2 +- variants/rak10701/platformio.ini | 3 + variants/rak10701/variant.h | 14 +- variants/rak4631/platformio.ini | 3 + variants/rak4631/variant.h | 14 +- variants/rak4631_epaper/platformio.ini | 3 + variants/rak4631_epaper_onrxtx/platformio.ini | 3 + variants/t-echo/platformio.ini | 3 + 20 files changed, 124 insertions(+), 461 deletions(-) diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index de53daaee..d715d398b 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -2,127 +2,49 @@ #ifdef USE_EINK #include "EInkDisplay2.h" -#include "GxEPD2_BW.h" #include "SPILock.h" #include "main.h" #include -#if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0) -SPIClass *hspi = NULL; -#endif +/* + The macros EINK_DISPLAY_MODEL, EINK_WIDTH, and EINK_HEIGHT are defined as build_flags in a variant's platformio.ini + Previously, these macros were defined at the top of this file. -#define COLORED GxEPD_BLACK -#define UNCOLORED GxEPD_WHITE + For archival reasons, note that the following configurations had also been tested during this period: + * ifdef RAK4631 + - 4.2 inch + EINK_DISPLAY_MODEL: GxEPD2_420_M01 + EINK_WIDTH: 300 + EINK_WIDTH: 400 -#if defined(TTGO_T_ECHO) -#define TECHO_DISPLAY_MODEL GxEPD2_154_D67 -#elif defined(RAK4630) + - 2.9 inch + EINK_DISPLAY_MODEL: GxEPD2_290_T5D + EINK_WIDTH: 296 + EINK_HEIGHT: 128 -// GxEPD2_213_BN - RAK14000 2.13 inch b/w 250x122 - changed from GxEPD2_213_B74 - which was not going to give fast refresh -// support -#define TECHO_DISPLAY_MODEL GxEPD2_213_BN - -// 4.2 inch 300x400 - GxEPD2_420_M01 -// #define TECHO_DISPLAY_MODEL GxEPD2_420_M01 - -// 2.9 inch 296x128 - GxEPD2_290_T5D -// #define TECHO_DISPLAY_MODEL GxEPD2_290_T5D - -// 1.54 inch 200x200 - GxEPD2_154_M09 -// #define TECHO_DISPLAY_MODEL GxEPD2_154_M09 - -#elif defined(MAKERPYTHON) -// 2.9 inch 296x128 - GxEPD2_290_T5D -#define TECHO_DISPLAY_MODEL GxEPD2_290_T5D - -#elif defined(PCA10059) - -// 4.2 inch 300x400 - GxEPD2_420_M01 -#define TECHO_DISPLAY_MODEL GxEPD2_420_M01 - -#elif defined(M5_COREINK) -// M5Stack CoreInk -// 1.54 inch 200x200 - GxEPD2_154_M09 -#define TECHO_DISPLAY_MODEL GxEPD2_154_M09 - -#elif defined(HELTEC_WIRELESS_PAPER) -// #define TECHO_DISPLAY_MODEL GxEPD2_213_T5D -#define TECHO_DISPLAY_MODEL GxEPD2_213_FC1 - -#elif defined(HELTEC_WIRELESS_PAPER_V1_0) -// 2.13" 122x250 - DEPG0213BNS800 -#define TECHO_DISPLAY_MODEL GxEPD2_213_BN - -#endif - -GxEPD2_BW *adafruitDisplay; + - 1.54 inch + EINK_DISPLAY_MODEL: GxEPD2_154_M09 + EINK_WIDTH: 200 + EINK_HEIGHT: 200 +*/ +// Constructor EInkDisplay::EInkDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY geometry, HW_I2C i2cBus) { -#if defined(TTGO_T_ECHO) - setGeometry(GEOMETRY_RAWMODE, 200, 200); -#elif defined(RAK4630) - - // GxEPD2_213_BN - RAK14000 2.13 inch b/w 250x122 - setGeometry(GEOMETRY_RAWMODE, 250, 122); - this->displayBufferSize = 250 * (128 / 8); - // GxEPD2_420_M01 - // setGeometry(GEOMETRY_RAWMODE, 300, 400); - - // GxEPD2_290_T5D - // setGeometry(GEOMETRY_RAWMODE, 296, 128); - - // GxEPD2_154_M09 - // setGeometry(GEOMETRY_RAWMODE, 200, 200); - -#elif defined(HELTEC_WIRELESS_PAPER_V1_0) - - // The display's memory is actually 128px x 250px - // Setting the buffersize manually prevents 122/8 truncating to a 15 byte width - // (Or something like that..) - + // Set dimensions in OLEDDisplay base class this->geometry = GEOMETRY_RAWMODE; - this->displayWidth = 250; - this->displayHeight = 122; - this->displayBufferSize = 250 * (128 / 8); + this->displayWidth = EINK_WIDTH; + this->displayHeight = EINK_HEIGHT; -#elif defined(HELTEC_WIRELESS_PAPER) - // GxEPD2_213_BN - 2.13 inch b/w 250x122 - setGeometry(GEOMETRY_RAWMODE, 250, 122); -#elif defined(MAKERPYTHON) - // GxEPD2_290_T5D - setGeometry(GEOMETRY_RAWMODE, 296, 128); + // Round shortest side up to nearest byte, to prevent truncation causing an undersized buffer + uint16_t shortSide = min(EINK_WIDTH, EINK_HEIGHT); + uint16_t longSide = max(EINK_WIDTH, EINK_HEIGHT); + if (shortSide % 8 != 0) + shortSide = (shortSide | 7) + 1; -#elif defined(PCA10059) - - // GxEPD2_420_M01 - setGeometry(GEOMETRY_RAWMODE, 300, 400); - -#elif defined(M5_COREINK) - - // M5Stack_CoreInk 200x200 - // 1.54 inch 200x200 - GxEPD2_154_M09 - setGeometry(GEOMETRY_RAWMODE, EPD_HEIGHT, EPD_WIDTH); -#elif defined(my) - - // GxEPD2_290_T5D - setGeometry(GEOMETRY_RAWMODE, 296, 128); - LOG_DEBUG("GEOMETRY_RAWMODE, 296, 128\n"); - -#elif defined(ESP32_S3_PICO) - - // GxEPD2_290_T94_V2 - setGeometry(GEOMETRY_RAWMODE, EPD_WIDTH, EPD_HEIGHT); - LOG_DEBUG("GEOMETRY_RAWMODE, 296, 128\n"); - -#endif - // setGeometry(GEOMETRY_RAWMODE, 128, 64); // old resolution - // setGeometry(GEOMETRY_128_64); // We originally used this because I wasn't sure if rawmode worked - it does + this->displayBufferSize = longSide * (shortSide / 8); } -// FIXME quick hack to limit drawing to a very slow rate -uint32_t lastDrawMsec; - /** * Force a display update if we haven't drawn within the specified msecLimit */ @@ -131,13 +53,6 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit) // No need to grab this lock because we are on our own SPI bus // concurrency::LockGuard g(spiLock); -#if defined(USE_EINK_DYNAMIC_REFRESH) - // Decide between full refresh, fast refresh, or skipping the update - bool continueUpdate = determineRefreshMode(); - if (!continueUpdate) - return false; -#else - uint32_t now = millis(); uint32_t sinceLast = now - lastDrawMsec; @@ -146,52 +61,34 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit) else return false; -#endif - // FIXME - only draw bits have changed (use backbuf similar to the other displays) - // tft.drawBitmap(0, 0, buffer, 128, 64, TFT_YELLOW, TFT_BLACK); for (uint32_t y = 0; y < displayHeight; y++) { for (uint32_t x = 0; x < displayWidth; x++) { // get src pixel in the page based ordering the OLED lib uses FIXME, super inefficient auto b = buffer[x + (y / 8) * displayWidth]; auto isset = b & (1 << (y & 7)); - adafruitDisplay->drawPixel(x, y, isset ? COLORED : UNCOLORED); + adafruitDisplay->drawPixel(x, y, isset ? GxEPD_BLACK : GxEPD_WHITE); } } LOG_DEBUG("Updating E-Paper... "); -#if defined(TTGO_T_ECHO) - adafruitDisplay->nextPage(); -#elif defined(RAK4630) || defined(MAKERPYTHON) - - // RAK14000 2.13 inch b/w 250x122 actually now does support fast refresh +#if false + // Currently unused; rescued from commented-out line during a refactor + // Use a meaningful macro here if variant doesn't want fast refresh // Full update mode (slow) - // adafruitDisplay->display(false); // FIXME, use fast refresh mode - - // Only enable for e-Paper with support for fast updates and comment out above adafruitDisplay->display(false); - // 1.54 inch 200x200 - GxEPD2_154_M09 - // 2.13 inch 250x122 - GxEPD2_213_BN - // 2.9 inch 296x128 - GxEPD2_290_T5D - // 4.2 inch 300x400 - GxEPD2_420_M01 - adafruitDisplay->nextPage(); - -#elif defined(PCA10059) || defined(M5_COREINK) - adafruitDisplay->nextPage(); -#elif defined(HELTEC_WIRELESS_PAPER_V1_0) - adafruitDisplay->nextPage(); -#elif defined(HELTEC_WIRELESS_PAPER) - adafruitDisplay->nextPage(); -#elif defined(ESP32_S3_PICO) - adafruitDisplay->nextPage(); -#elif defined(PRIVATE_HW) || defined(my) + adafruitDisplay->display(false) +#else + // Fast update mode adafruitDisplay->nextPage(); #endif +#ifndef EINK_NO_HIBERNATE // Only hibernate if controller IC will preserve image memory // Put screen to sleep to save power (possibly not necessary because we already did poweroff inside of display) adafruitDisplay->hibernate(); LOG_DEBUG("done\n"); +#endif return true; } @@ -203,15 +100,9 @@ void EInkDisplay::display(void) // at least one forceDisplay() keyframe. This prevents flashing when we should the critical // bootscreen (that we want to look nice) -#ifdef USE_EINK_DYNAMIC_REFRESH - lowPriority(); - forceDisplay(); - highPriority(); -#else if (lastDrawMsec) { forceDisplay(slowUpdateMsec); // Show the first screen a few seconds after boot, then slower } -#endif } // Send a command to the display (low level function) @@ -226,7 +117,7 @@ void EInkDisplay::setDetected(uint8_t detected) (void)detected; } -// Connect to the display +// Connect to the display - variant specific bool EInkDisplay::connect() { LOG_INFO("Doing EInk init\n"); @@ -244,9 +135,9 @@ bool EInkDisplay::connect() #if defined(TTGO_T_ECHO) { - auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY, SPI1); + auto lowLevel = new EINK_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY, SPI1); - adafruitDisplay = new GxEPD2_BW(*lowLevel); + adafruitDisplay = new GxEPD2_BW(*lowLevel); adafruitDisplay->init(); adafruitDisplay->setRotation(3); adafruitDisplay->setPartialWindow(0, 0, displayWidth, displayHeight); @@ -254,8 +145,8 @@ bool EInkDisplay::connect() #elif defined(RAK4630) || defined(MAKERPYTHON) { if (eink_found) { - auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); - adafruitDisplay = new GxEPD2_BW(*lowLevel); + auto lowLevel = new EINK_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); + adafruitDisplay = new GxEPD2_BW(*lowLevel); adafruitDisplay->init(115200, true, 10, false, SPI1, SPISettings(4000000, MSBFIRST, SPI_MODE0)); // RAK14000 2.13 inch b/w 250x122 does actually now support fast refresh adafruitDisplay->setRotation(3); @@ -296,8 +187,8 @@ bool EInkDisplay::connect() delay(100); // Create GxEPD2 objects - auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY, *hspi); - adafruitDisplay = new GxEPD2_BW(*lowLevel); + auto lowLevel = new EINK_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY, *hspi); + adafruitDisplay = new GxEPD2_BW(*lowLevel); // Init GxEPD2 adafruitDisplay->init(); @@ -311,228 +202,36 @@ bool EInkDisplay::connect() pinMode(Vext, OUTPUT); digitalWrite(Vext, LOW); delay(100); - auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY, *hspi); - adafruitDisplay = new GxEPD2_BW(*lowLevel); + auto lowLevel = new EINK_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY, *hspi); + adafruitDisplay = new GxEPD2_BW(*lowLevel); adafruitDisplay->init(); adafruitDisplay->setRotation(3); } #elif defined(PCA10059) { - auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); - adafruitDisplay = new GxEPD2_BW(*lowLevel); + auto lowLevel = new EINK_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); + adafruitDisplay = new GxEPD2_BW(*lowLevel); adafruitDisplay->init(115200, true, 10, false, SPI1, SPISettings(4000000, MSBFIRST, SPI_MODE0)); adafruitDisplay->setRotation(3); adafruitDisplay->setPartialWindow(0, 0, displayWidth, displayHeight); } #elif defined(M5_COREINK) - auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); - adafruitDisplay = new GxEPD2_BW(*lowLevel); + auto lowLevel = new EINK_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); + adafruitDisplay = new GxEPD2_BW(*lowLevel); adafruitDisplay->init(115200, true, 40, false, SPI, SPISettings(4000000, MSBFIRST, SPI_MODE0)); adafruitDisplay->setRotation(0); - adafruitDisplay->setPartialWindow(0, 0, EPD_WIDTH, EPD_HEIGHT); + adafruitDisplay->setPartialWindow(0, 0, EINK_WIDTH, EINK_HEIGHT); #elif defined(my) || defined(ESP32_S3_PICO) { - auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); - adafruitDisplay = new GxEPD2_BW(*lowLevel); + auto lowLevel = new EINK_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); + adafruitDisplay = new GxEPD2_BW(*lowLevel); adafruitDisplay->init(115200, true, 40, false, SPI, SPISettings(4000000, MSBFIRST, SPI_MODE0)); adafruitDisplay->setRotation(1); - adafruitDisplay->setPartialWindow(0, 0, EPD_WIDTH, EPD_HEIGHT); + adafruitDisplay->setPartialWindow(0, 0, EINK_WIDTH, EINK_HEIGHT); } #endif - // adafruitDisplay->setFullWindow(); - // adafruitDisplay->fillScreen(UNCOLORED); - // adafruitDisplay->drawCircle(100, 100, 20, COLORED); - // adafruitDisplay->display(false); return true; } -// Use a mix of full refresh, fast refresh, and update skipping, to balance urgency and display health -#if defined(USE_EINK_DYNAMIC_REFRESH) - -// Suggest that subsequent updates should use fast-refresh -void EInkDisplay::highPriority() -{ - isHighPriority = true; -} - -// Suggest that subsequent updates should use full-refresh -void EInkDisplay::lowPriority() -{ - isHighPriority = false; -} - -// Full-refresh is explicitly requested for next one update - no skipping please -void EInkDisplay::demandFullRefresh() -{ - demandingFull = true; -} - -// configure display for fast-refresh -void EInkDisplay::configForFastRefresh() -{ - // Display-specific code can go here -#if defined(PRIVATE_HW) -#else - // Otherwise: - adafruitDisplay->setPartialWindow(0, 0, adafruitDisplay->width(), adafruitDisplay->height()); -#endif -} - -// Configure display for full-refresh -void EInkDisplay::configForFullRefresh() -{ - // Display-specific code can go here -#if defined(PRIVATE_HW) -#else - // Otherwise: - adafruitDisplay->setFullWindow(); -#endif -} - -#ifdef EINK_FASTREFRESH_ERASURE_LIMIT -// Count black pixels in an image. Used for "erasure tracking" -int32_t EInkDisplay::countBlackPixels() -{ - int32_t blackCount = 0; // Signed, to avoid underflow when comparing - for (uint16_t b = 0; b < (displayWidth / 8) * displayHeight; b++) { - for (uint8_t i = 0; i < 7; i++) { - // Check if each bit is black or white - blackCount += (buffer[b] >> i) & 1; - } - } - return blackCount; -} - -// Evaluate the (rough) amount of black->white pixel change since last full refresh -bool EInkDisplay::tooManyErasures() -{ - // Ideally, we would compare the new and old buffers, to count *actual* white-to-black pixel changes - // but that would require substantially more "code tampering" - - // Get the black pixel stats for this image - int32_t blackCount = countBlackPixels(); - int32_t blackDifference = blackCount - prevBlackCount; - - // Update the running total of "erasures" - black pixels which have become white, since last full-refresh - if (blackDifference < 0) - erasedSinceFull -= blackDifference; - - // Store black pixel count for next time - prevBlackCount = blackCount; - - // Log the running total - help devs setup new boards - LOG_DEBUG("Dynamic Refresh: erasedSinceFull=%hu, EINK_FASTREFRESH_ERASURE_LIMIT=%hu\n", erasedSinceFull, - EINK_FASTREFRESH_ERASURE_LIMIT); - - // Check if too many pixels have been erased - if (erasedSinceFull > EINK_FASTREFRESH_ERASURE_LIMIT) - return true; // Too many - else - return false; // Still okay -} -#endif // ifdef EINK_FASTREFRESH_ERASURE_LIMIT - -bool EInkDisplay::newImageMatchesOld() -{ - uint32_t newImageHash = 0; - - // Generate hash: sum all bytes in the image buffer - for (uint16_t b = 0; b < (displayWidth / 8) * displayHeight; b++) { - newImageHash += buffer[b]; - } - - // Compare hashes - bool hashMatches = (newImageHash == prevImageHash); - - // Update the cached hash - prevImageHash = newImageHash; - - // Return the comparison result - return hashMatches; -} - -// Choose between, full-refresh, fast refresh, and update skipping, to balance urgency and display health. -bool EInkDisplay::determineRefreshMode() -{ - uint32_t now = millis(); - uint32_t sinceLast = now - lastUpdateMsec; - - // If rate-limiting dropped a high-priority update: - // promote this update, so it runs ASAP - if (missedHighPriorityUpdate) { - isHighPriority = true; - missedHighPriorityUpdate = false; - } - - // Abort: if too soon for a new frame (unless demanding full) - if (!demandingFull && isHighPriority && fastRefreshCount > 0 && sinceLast < highPriorityLimitMsec) { - LOG_DEBUG("Dynamic Refresh: update skipped. Exceeded EINK_HIGHPRIORITY_LIMIT_SECONDS\n"); - missedHighPriorityUpdate = true; - return false; - } - if (!demandingFull && !isHighPriority && !demandingFull && sinceLast < lowPriorityLimitMsec) { - return false; - } - - // If demanded full refresh: give it to them - if (demandingFull) - needsFull = true; - - // Check if old image (fast-refresh) should be redrawn (as full), for image quality - if (fastRefreshCount > 0 && !isHighPriority) - needsFull = true; - - // If too many fast updates, require a full-refresh (display health) - if (fastRefreshCount >= fastRefreshLimit) - needsFull = true; - -#ifdef EINK_FASTREFRESH_ERASURE_LIMIT - // Some displays struggle with erasing black pixels to white, during fast-refresh - if (tooManyErasures()) - needsFull = true; -#endif - - // If image matches - // (Block must run, even if full already selected, to store hash for next time) - if (newImageMatchesOld()) { - // If low priority: limit rate - // otherwise, every loop() will run the hash method - if (!isHighPriority) - lastUpdateMsec = now; - - // If update is *not* for display health or image quality, skip it - if (!needsFull) - return false; - } - - // Conditions assessed - not skipping - load the appropriate config - - // If options require a full refresh - if (!isHighPriority || needsFull) { - if (fastRefreshCount > 0) - configForFullRefresh(); - - LOG_DEBUG("Dynamic Refresh: conditions met for full-refresh\n"); - fastRefreshCount = 0; - needsFull = false; - demandingFull = false; - erasedSinceFull = 0; // Reset the count for EINK_FASTREFRESH_ERASURE_LIMIT - tracks ghosting buildup - } - - // If options allow a fast-refresh - else { - if (fastRefreshCount == 0) - configForFastRefresh(); - - LOG_DEBUG("Dynamic Refresh: conditions met for fast-refresh\n"); - fastRefreshCount++; - } - - lastUpdateMsec = now; // Mark time for rate limiting - return true; // Instruct calling method to continue with update -} - -#endif // End USE_EINK_DYNAMIC_REFRESH - #endif diff --git a/src/graphics/EInkDisplay2.h b/src/graphics/EInkDisplay2.h index 260a79755..f40747f26 100644 --- a/src/graphics/EInkDisplay2.h +++ b/src/graphics/EInkDisplay2.h @@ -1,5 +1,8 @@ #pragma once +#ifdef USE_EINK + +#include "GxEPD2_BW.h" #include #if defined(HELTEC_WIRELESS_PAPER_V1_0) @@ -16,6 +19,7 @@ * Use the fast NRF52 SPI API rather than the slow standard arduino version * * turn radio back on - currently with both on spi bus is fucked? or are we leaving chip select asserted? + * Suggestion: perhaps similar to HELTEC_WIRELESS_PAPER issue, which resolved with rtc_gpio_hold_dis() */ class EInkDisplay : public OLEDDisplay { @@ -55,80 +59,17 @@ class EInkDisplay : public OLEDDisplay // Connect to the display virtual bool connect() override; -#if defined(USE_EINK_DYNAMIC_REFRESH) - // Full, fast, or skip: balance urgency with display health + // AdafruitGFX display object - instantiated in connect(), variant specific + GxEPD2_BW *adafruitDisplay = NULL; - // Use fast refresh if EITHER: - // * highPriority() was set - // * a highPriority() update was previously skipped, for rate-limiting - (EINK_HIGHPRIORITY_LIMIT_SECONDS) - - // Use full refresh if EITHER: - // * lowPriority() was set - // * demandFullRefresh() was called - (single shot) - // * too many fast updates in a row: protect display - (EINK_FASTREFRESH_REPEAT_LIMIT) - // * no recent updates, and last update was fast: redraw for image quality (EINK_LOWPRIORITY_LIMIT_SECONDS) - // * (optional) too many "erasures" since full-refresh (black pixels cleared to white) - - // Rate limit if: - // * lowPriority() - (EINK_LOWPRIORITY_LIMIT_SECONDS) - // * highPriority(), if multiple fast updates have run back-to-back - (EINK_HIGHPRIORITY_LIMIT_SECONDS) - - // Skip update entirely if ALL criteria met: - // * new image matches old image - // * lowPriority() - // * no call to demandFullRefresh() - // * not redrawing for image quality - // * not refreshing for display health - - // ------------------------------------ - - // To implement for your E-Ink display: - // * edit configForFastRefresh() - // * edit configForFullRefresh() - // * add macros to variant.h, and adjust to taste: - - /* - #define USE_EINK_DYNAMIC_REFRESH - #define EINK_LOWPRIORITY_LIMIT_SECONDS 30 - #define EINK_HIGHPRIORITY_LIMIT_SECONDS 1 - #define EINK_FASTREFRESH_REPEAT_LIMIT 5 - #define EINK_FASTREFRESH_ERASURE_LIMIT 300 // optional - */ - - public: - void highPriority(); // Suggest fast refresh - void lowPriority(); // Suggest full refresh - void demandFullRefresh(); // For next update: explicitly request full refresh - - protected: - void configForFastRefresh(); // Display specific code to select fast refresh mode - void configForFullRefresh(); // Display specific code to return to full refresh mode - bool newImageMatchesOld(); // Is the new update actually different to the last image? - bool determineRefreshMode(); // Called immediately before data written to display - choose refresh mode, or abort update -#ifdef EINK_FASTREFRESH_ERASURE_LIMIT - int32_t countBlackPixels(); // Calculate the number of black pixels in the new image - bool tooManyErasures(); // Has too much "ghosting" (black pixels erased to white) accumulated since last full-refresh? + // If display uses HSPI +#if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0) + SPIClass *hspi = NULL; #endif - bool isHighPriority = true; // Does the method calling update believe that this is urgent? - bool needsFull = false; // Is a full refresh forced? (display health) - bool demandingFull = false; // Was full refresh specifically requested? (splash screens, etc) - bool missedHighPriorityUpdate = false; // Was a high priority update skipped for rate-limiting? - uint16_t fastRefreshCount = 0; // How many fast updates have occurred since last full refresh? - uint32_t lastUpdateMsec = 0; // When did the last update occur? - uint32_t prevImageHash = 0; // Used to check if update will change screen image (skippable or not) - int32_t prevBlackCount = 0; // How many black pixels were in the previous image - uint32_t erasedSinceFull = 0; // How many black pixels have been set back to white since last full-refresh? (roughly) - - // Set in variant.h - const uint32_t lowPriorityLimitMsec = (uint32_t)1000 * EINK_LOWPRIORITY_LIMIT_SECONDS; // Max rate for fast refreshes - const uint32_t highPriorityLimitMsec = (uint32_t)1000 * EINK_HIGHPRIORITY_LIMIT_SECONDS; // Max rate for full refreshes - const uint32_t fastRefreshLimit = EINK_FASTREFRESH_REPEAT_LIMIT; // Max consecutive fast updates, before full is triggered - -#else // !USE_EINK_DYNAMIC_REFRESH - // Tolerate calls to these methods anywhere, just to be safe - void highPriority() {} - void lowPriority() {} - void demandFullRefresh() {} -#endif + private: + // FIXME quick hack to limit drawing to a very slow rate + uint32_t lastDrawMsec = 0; }; + +#endif \ No newline at end of file diff --git a/variants/Dongle_nRF52840-pca10059-v1/platformio.ini b/variants/Dongle_nRF52840-pca10059-v1/platformio.ini index a937bfa98..b1608770e 100644 --- a/variants/Dongle_nRF52840-pca10059-v1/platformio.ini +++ b/variants/Dongle_nRF52840-pca10059-v1/platformio.ini @@ -4,6 +4,9 @@ board = nordic_pca10059 board_level = extra build_flags = ${nrf52840_base.build_flags} -Ivariants/Dongle_nRF52840-pca10059-v1 -D NORDIC_PCA10059 -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m4/fpv4-sp-d16-hard" + -DEINK_DISPLAY_MODEL=GxEPD2_420_M01 + -DEINK_WIDTH=300 + -DEINK_HEIGHT=400 build_src_filter = ${nrf52_base.build_src_filter} +<../variants/Dongle_nRF52840-pca10059-v1> lib_deps = ${nrf52840_base.lib_deps} diff --git a/variants/Dongle_nRF52840-pca10059-v1/variant.h b/variants/Dongle_nRF52840-pca10059-v1/variant.h index 81e2ad995..0f1bf15da 100644 --- a/variants/Dongle_nRF52840-pca10059-v1/variant.h +++ b/variants/Dongle_nRF52840-pca10059-v1/variant.h @@ -136,7 +136,7 @@ static const uint8_t SCK = PIN_SPI_SCK; #define USE_SX1262 #define SX126X_CS (0 + 31) // LORA_CS P0.31 #define SX126X_DIO1 (0 + 29) // DIO1 P0.29 -#define SX126X_BUSY (0 + 2) // LORA_BUSY P0.02 +#define SX126X_BUSY (0 + 2) // LORA_BUSY P0.02 #define SX126X_RESET (32 + 15) // LORA_RESET P1.15 #define SX126X_TXEN (32 + 13) // TXEN P1.13 NiceRF 868 dont use #define SX126X_RXEN (32 + 10) // RXEN P1.10 NiceRF 868 dont use diff --git a/variants/MakePython_nRF52840_eink/platformio.ini b/variants/MakePython_nRF52840_eink/platformio.ini index 3ac18bcf0..f421466ec 100644 --- a/variants/MakePython_nRF52840_eink/platformio.ini +++ b/variants/MakePython_nRF52840_eink/platformio.ini @@ -10,5 +10,8 @@ lib_deps = ${nrf52840_base.lib_deps} https://github.com/meshtastic/ESP32_Codec2.git#633326c78ac251c059ab3a8c430fcdf25b41672f zinggjm/GxEPD2@^1.4.9 + -DEINK_DISPLAY_MODEL=GxEPD2_290_T5D + -DEINK_WIDTH=296 + -DEINK_HEIGHT=128 debug_tool = jlink ;upload_port = /dev/ttyACM4 diff --git a/variants/esp32-s3-pico/platformio.ini b/variants/esp32-s3-pico/platformio.ini index f39004c36..ef737d98a 100644 --- a/variants/esp32-s3-pico/platformio.ini +++ b/variants/esp32-s3-pico/platformio.ini @@ -16,9 +16,9 @@ build_flags = ${esp32_base.build_flags} ;-DPRIVATE_HW -Ivariants/esp32-s3-pico -DBOARD_HAS_PSRAM - -DTECHO_DISPLAY_MODEL=GxEPD2_290_T94_V2 - -DEPD_HEIGHT=128 - -DEPD_WIDTH=296 + -DEINK_DISPLAY_MODEL=GxEPD2_290_T94_V2 + -DEINK_WIDTH=296 + -DEINK_HEIGHT=128 lib_deps = ${esp32s3_base.lib_deps} zinggjm/GxEPD2@^1.5.3 diff --git a/variants/esp32-s3-pico/variant.h b/variants/esp32-s3-pico/variant.h index 9e10183fb..87378d378 100644 --- a/variants/esp32-s3-pico/variant.h +++ b/variants/esp32-s3-pico/variant.h @@ -74,4 +74,4 @@ #define PIN_EINK_DC 33 #define PIN_EINK_RES 42 // 37 //(-1) // cant be MISO Waveshare ??) #define PIN_EINK_SCLK 35 -#define PIN_EINK_MOSI 36 +#define PIN_EINK_MOSI 36 \ No newline at end of file diff --git a/variants/heltec_wireless_paper/platformio.ini b/variants/heltec_wireless_paper/platformio.ini index dd93b52cb..56446dc8b 100644 --- a/variants/heltec_wireless_paper/platformio.ini +++ b/variants/heltec_wireless_paper/platformio.ini @@ -2,7 +2,12 @@ extends = esp32s3_base board = heltec_wifi_lora_32_V3 build_flags = - ${esp32s3_base.build_flags} -D HELTEC_WIRELESS_PAPER -I variants/heltec_wireless_paper + ${esp32s3_base.build_flags} + -I variants/heltec_wireless_paper + -D HELTEC_WIRELESS_PAPER + -D EINK_DISPLAY_MODEL=GxEPD2_213_FC1 + -D EINK_WIDTH=250 + -D EINK_HEIGHT=122 lib_deps = ${esp32s3_base.lib_deps} https://github.com/ixt/GxEPD2#39f325b677713eb04dfcc83b8e402e77523fb8bf diff --git a/variants/heltec_wireless_paper_v1/platformio.ini b/variants/heltec_wireless_paper_v1/platformio.ini index 7d7f4eb14..01b68f5f0 100644 --- a/variants/heltec_wireless_paper_v1/platformio.ini +++ b/variants/heltec_wireless_paper_v1/platformio.ini @@ -5,6 +5,9 @@ build_flags = ${esp32s3_base.build_flags} -I variants/heltec_wireless_paper_v1 -D HELTEC_WIRELESS_PAPER_V1_0 + -D EINK_DISPLAY_MODEL=GxEPD2_213_BN + -D EINK_WIDTH=250 + -D EINK_HEIGHT=122 lib_deps = ${esp32s3_base.lib_deps} https://github.com/meshtastic/GxEPD2/ diff --git a/variants/heltec_wireless_paper_v1/variant.h b/variants/heltec_wireless_paper_v1/variant.h index 25e061938..29b8bbbd1 100644 --- a/variants/heltec_wireless_paper_v1/variant.h +++ b/variants/heltec_wireless_paper_v1/variant.h @@ -6,13 +6,6 @@ #define USE_EINK -// Settings for Dynamic Refresh mode -// Change between full-refresh, fast-refresh, or update-skipping, to balance urgency and display health. -#define USE_EINK_DYNAMIC_REFRESH -#define EINK_LOWPRIORITY_LIMIT_SECONDS 30 -#define EINK_HIGHPRIORITY_LIMIT_SECONDS 1 -#define EINK_FASTREFRESH_REPEAT_LIMIT 5 - /* * eink display pins */ diff --git a/variants/m5stack_coreink/platformio.ini b/variants/m5stack_coreink/platformio.ini index ee6d340dc..dfb078a0a 100644 --- a/variants/m5stack_coreink/platformio.ini +++ b/variants/m5stack_coreink/platformio.ini @@ -9,8 +9,9 @@ build_flags = ;-D RADIOLIB_VERBOSE -Ofast -D__MCUXPRESSO - -DEPD_HEIGHT=200 - -DEPD_WIDTH=200 + -DEINK_DISPLAY_MODEL=GxEPD2_154_M09 + -DEINK_WIDTH=200 + -DEINK_HEIGHT=200 -DUSER_SETUP_LOADED -DM5_COREINK -DM5STACK diff --git a/variants/my_esp32s3_diy_eink/platformio.ini b/variants/my_esp32s3_diy_eink/platformio.ini index d3c55afda..966bc580e 100644 --- a/variants/my_esp32s3_diy_eink/platformio.ini +++ b/variants/my_esp32s3_diy_eink/platformio.ini @@ -19,9 +19,9 @@ build_flags = ;${esp32_base.build_flags} -D MY_ESP32S3_DIY -I variants/my_esp32s3_diy_eink ${esp32_base.build_flags} -D PRIVATE_HW -I variants/my_esp32s3_diy_eink -Dmy - -DTECHO_DISPLAY_MODEL=GxEPD2_290_T5D - -DEPD_HEIGHT=128 - -DEPD_WIDTH=296 + -DEINK_DISPLAY_MODEL=GxEPD2_290_T5D + -DEINK_WIDTH=296 + -DEINK_HEIGHT=128 -DBOARD_HAS_PSRAM -mfix-esp32-psram-cache-issue -DARDUINO_USB_MODE=0 diff --git a/variants/my_esp32s3_diy_eink/variant.h b/variants/my_esp32s3_diy_eink/variant.h index a5bebdacc..516fa7f34 100644 --- a/variants/my_esp32s3_diy_eink/variant.h +++ b/variants/my_esp32s3_diy_eink/variant.h @@ -53,4 +53,4 @@ #define PIN_EINK_DC 1 #define PIN_EINK_RES (-1) #define PIN_EINK_SCLK 5 -#define PIN_EINK_MOSI 6 +#define PIN_EINK_MOSI 6 \ No newline at end of file diff --git a/variants/rak10701/platformio.ini b/variants/rak10701/platformio.ini index 736329eb8..37f785e84 100644 --- a/variants/rak10701/platformio.ini +++ b/variants/rak10701/platformio.ini @@ -5,6 +5,9 @@ board = wiscore_rak4631 build_flags = ${nrf52840_base.build_flags} -Ivariants/rak10701 -D RAK_4631 -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m4/fpv4-sp-d16-hard" -DGPS_POWER_TOGGLE ; comment this line to disable triple press function on the user button to turn off gps entirely. + -DEINK_DISPLAY_MODEL=GxEPD2_213_BN + -DEINK_WIDTH=250 + -DEINK_HEIGHT=122 build_src_filter = ${nrf52_base.build_src_filter} +<../variants/rak10701> + + + lib_deps = ${nrf52840_base.lib_deps} diff --git a/variants/rak10701/variant.h b/variants/rak10701/variant.h index 5ff12a7de..837d081ff 100644 --- a/variants/rak10701/variant.h +++ b/variants/rak10701/variant.h @@ -202,13 +202,13 @@ static const uint8_t WB_SPI_MOSI = 30; // IO_SLOT /* Setup of the SX1262 LoRa module ( https://docs.rakwireless.com/Product-Categories/WisBlock/RAK4631/Datasheet/ ) -P1.10 NSS SPI NSS (Arduino GPIO number 42) -P1.11 SCK SPI CLK (Arduino GPIO number 43) -P1.12 MOSI SPI MOSI (Arduino GPIO number 44) -P1.13 MISO SPI MISO (Arduino GPIO number 45) -P1.14 BUSY BUSY signal (Arduino GPIO number 46) -P1.15 DIO1 DIO1 event interrupt (Arduino GPIO number 47) -P1.06 NRESET NRESET manual reset of the SX1262 (Arduino GPIO number 38) +P1.10 NSS SPI NSS (Arduino GPIO number 42) +P1.11 SCK SPI CLK (Arduino GPIO number 43) +P1.12 MOSI SPI MOSI (Arduino GPIO number 44) +P1.13 MISO SPI MISO (Arduino GPIO number 45) +P1.14 BUSY BUSY signal (Arduino GPIO number 46) +P1.15 DIO1 DIO1 event interrupt (Arduino GPIO number 47) +P1.06 NRESET NRESET manual reset of the SX1262 (Arduino GPIO number 38) Important for successful SX1262 initialization: diff --git a/variants/rak4631/platformio.ini b/variants/rak4631/platformio.ini index b9789166f..b1bc2d9b5 100644 --- a/variants/rak4631/platformio.ini +++ b/variants/rak4631/platformio.ini @@ -5,6 +5,9 @@ board = wiscore_rak4631 build_flags = ${nrf52840_base.build_flags} -Ivariants/rak4631 -D RAK_4631 -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m4/fpv4-sp-d16-hard" -DGPS_POWER_TOGGLE ; comment this line to disable triple press function on the user button to turn off gps entirely. + -DEINK_DISPLAY_MODEL=GxEPD2_213_BN + -DEINK_WIDTH=250 + -DEINK_HEIGHT=122 build_src_filter = ${nrf52_base.build_src_filter} +<../variants/rak4631> + + + lib_deps = ${nrf52840_base.lib_deps} diff --git a/variants/rak4631/variant.h b/variants/rak4631/variant.h index cc18a901f..e22ff0b63 100644 --- a/variants/rak4631/variant.h +++ b/variants/rak4631/variant.h @@ -181,13 +181,13 @@ static const uint8_t SCK = PIN_SPI_SCK; /* Setup of the SX1262 LoRa module ( https://docs.rakwireless.com/Product-Categories/WisBlock/RAK4631/Datasheet/ ) -P1.10 NSS SPI NSS (Arduino GPIO number 42) -P1.11 SCK SPI CLK (Arduino GPIO number 43) -P1.12 MOSI SPI MOSI (Arduino GPIO number 44) -P1.13 MISO SPI MISO (Arduino GPIO number 45) -P1.14 BUSY BUSY signal (Arduino GPIO number 46) -P1.15 DIO1 DIO1 event interrupt (Arduino GPIO number 47) -P1.06 NRESET NRESET manual reset of the SX1262 (Arduino GPIO number 38) +P1.10 NSS SPI NSS (Arduino GPIO number 42) +P1.11 SCK SPI CLK (Arduino GPIO number 43) +P1.12 MOSI SPI MOSI (Arduino GPIO number 44) +P1.13 MISO SPI MISO (Arduino GPIO number 45) +P1.14 BUSY BUSY signal (Arduino GPIO number 46) +P1.15 DIO1 DIO1 event interrupt (Arduino GPIO number 47) +P1.06 NRESET NRESET manual reset of the SX1262 (Arduino GPIO number 38) Important for successful SX1262 initialization: diff --git a/variants/rak4631_epaper/platformio.ini b/variants/rak4631_epaper/platformio.ini index 0871eee45..ced732d94 100644 --- a/variants/rak4631_epaper/platformio.ini +++ b/variants/rak4631_epaper/platformio.ini @@ -4,6 +4,9 @@ extends = nrf52840_base board = wiscore_rak4631 build_flags = ${nrf52840_base.build_flags} -Ivariants/rak4631_epaper -D RAK_4631 -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m4/fpv4-sp-d16-hard" + -DEINK_DISPLAY_MODEL=GxEPD2_213_BN + -DEINK_WIDTH=250 + -DEINK_HEIGHT=122 build_src_filter = ${nrf52_base.build_src_filter} +<../variants/rak4631_epaper> lib_deps = ${nrf52840_base.lib_deps} diff --git a/variants/rak4631_epaper_onrxtx/platformio.ini b/variants/rak4631_epaper_onrxtx/platformio.ini index 0a4f05344..c4a13ec82 100644 --- a/variants/rak4631_epaper_onrxtx/platformio.ini +++ b/variants/rak4631_epaper_onrxtx/platformio.ini @@ -6,6 +6,9 @@ board = wiscore_rak4631 build_flags = ${nrf52840_base.build_flags} -Ivariants/rak4631_epaper -D RAK_4631 -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m4/fpv4-sp-d16-hard" -D PIN_EINK_EN=34 + -D EINK_DISPLAY_MODEL=GxEPD2_213_BN + -D EINK_WIDTH=250 + -D EINK_HEIGHT=122 build_src_filter = ${nrf52_base.build_src_filter} +<../variants/rak4631_epaper_onrxtx> lib_deps = ${nrf52840_base.lib_deps} diff --git a/variants/t-echo/platformio.ini b/variants/t-echo/platformio.ini index 843bd88ff..49ba3bb34 100644 --- a/variants/t-echo/platformio.ini +++ b/variants/t-echo/platformio.ini @@ -8,6 +8,9 @@ debug_tool = jlink build_flags = ${nrf52840_base.build_flags} -Ivariants/t-echo -DGPS_POWER_TOGGLE -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m4/fpv4-sp-d16-hard" + -DEINK_DISPLAY_MODEL=GxEPD2_154_D67 + -DEINK_WIDTH=200 + -DEINK_HEIGHT=200 build_src_filter = ${nrf52_base.build_src_filter} +<../variants/t-echo> lib_deps = ${nrf52840_base.lib_deps} From bf88773b6b47386005e087e6a424f4aed97bf504 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 28 Feb 2024 13:44:15 -0600 Subject: [PATCH 236/472] Don't send anybody to null island ever (#3308) --- src/modules/PositionModule.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index 1e4ea5de1..addff8966 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -176,6 +176,11 @@ meshtastic_MeshPacket *PositionModule::allocReply() LOG_INFO("Providing time to mesh %u\n", p.time); } + if (p.latitude_i == 0 && p.longitude_i == 0) { + LOG_WARN("Skipping position send because lat/lon are zero!\n"); + return nullptr; + } + LOG_INFO("Position reply: time=%i, latI=%i, lonI=%i\n", p.time, p.latitude_i, p.longitude_i); // TAK Tracker devices should send their position in a TAK packet over the ATAK port From d20fa6e927b2aea46e6485f929cf0de24d1140e9 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sat, 2 Mar 2024 07:21:53 -0600 Subject: [PATCH 237/472] Comment out ReplyModule registration, but leave it in as example (#3312) --- src/modules/Modules.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/Modules.cpp b/src/modules/Modules.cpp index fd109b765..2d45868fd 100644 --- a/src/modules/Modules.cpp +++ b/src/modules/Modules.cpp @@ -13,7 +13,6 @@ #include "modules/NodeInfoModule.h" #include "modules/PositionModule.h" #include "modules/RemoteHardwareModule.h" -#include "modules/ReplyModule.h" #include "modules/RoutingModule.h" #include "modules/TextMessageModule.h" #include "modules/TraceRouteModule.h" @@ -67,7 +66,8 @@ void setupModules() // to a global variable. new RemoteHardwareModule(); - new ReplyModule(); + // Example: Put your module here + // new ReplyModule(); #if HAS_BUTTON || ARCH_PORTDUINO rotaryEncoderInterruptImpl1 = new RotaryEncoderInterruptImpl1(); if (!rotaryEncoderInterruptImpl1->init()) { From a58348369d0ffeaef28bd585c89a649ee7840d93 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sat, 2 Mar 2024 10:20:27 -0600 Subject: [PATCH 238/472] Update protos and add new fields to type conversions (#3315) --- protobufs | 2 +- src/mesh/TypeConversions.cpp | 2 ++ src/mesh/generated/meshtastic/deviceonly.pb.h | 18 ++++++++--- src/mesh/generated/meshtastic/mesh.pb.h | 32 +++++++++++++------ 4 files changed, 38 insertions(+), 16 deletions(-) diff --git a/protobufs b/protobufs index 524158356..62b7d8b88 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 5241583565ccbbb4986180bf4c6eb7f8a0dec285 +Subproject commit 62b7d8b884d70aed5ff18c3b0e228095eeb48de2 diff --git a/src/mesh/TypeConversions.cpp b/src/mesh/TypeConversions.cpp index 4e0fdd385..20b1cb31e 100644 --- a/src/mesh/TypeConversions.cpp +++ b/src/mesh/TypeConversions.cpp @@ -10,6 +10,8 @@ meshtastic_NodeInfo TypeConversions::ConvertToNodeInfo(const meshtastic_NodeInfo info.snr = lite->snr; info.last_heard = lite->last_heard; info.channel = lite->channel; + info.via_mqtt = lite->via_mqtt; + info.hops_away = lite->hops_away; if (lite->has_position) { info.has_position = true; diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index 735644c47..ca4b2176b 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -65,6 +65,10 @@ typedef struct _meshtastic_NodeInfoLite { meshtastic_DeviceMetrics device_metrics; /* local channel index we heard that node on. Only populated if its not the default channel. */ uint8_t channel; + /* True if we witnessed the node over MQTT instead of LoRA transport */ + bool via_mqtt; + /* Number of hops away from us this node is (0 if adjacent) */ + uint8_t hops_away; } meshtastic_NodeInfoLite; /* The on-disk saved channels */ @@ -175,13 +179,13 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_DeviceState_init_default {false, meshtastic_MyNodeInfo_init_default, false, meshtastic_User_init_default, 0, {meshtastic_MeshPacket_init_default}, false, meshtastic_MeshPacket_init_default, 0, 0, 0, false, meshtastic_MeshPacket_init_default, 0, {meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default}, 0, {meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default}} -#define meshtastic_NodeInfoLite_init_default {0, false, meshtastic_User_init_default, false, meshtastic_PositionLite_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0} +#define meshtastic_NodeInfoLite_init_default {0, false, meshtastic_User_init_default, false, meshtastic_PositionLite_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0, 0, 0} #define meshtastic_PositionLite_init_default {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN} #define meshtastic_ChannelFile_init_default {0, {meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default}, 0} #define meshtastic_OEMStore_init_default {0, 0, {0, {0}}, _meshtastic_ScreenFonts_MIN, "", {0, {0}}, false, meshtastic_LocalConfig_init_default, false, meshtastic_LocalModuleConfig_init_default} #define meshtastic_NodeRemoteHardwarePin_init_default {0, false, meshtastic_RemoteHardwarePin_init_default} #define meshtastic_DeviceState_init_zero {false, meshtastic_MyNodeInfo_init_zero, false, meshtastic_User_init_zero, 0, {meshtastic_MeshPacket_init_zero}, false, meshtastic_MeshPacket_init_zero, 0, 0, 0, false, meshtastic_MeshPacket_init_zero, 0, {meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero}, 0, {meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero}} -#define meshtastic_NodeInfoLite_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_PositionLite_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0} +#define meshtastic_NodeInfoLite_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_PositionLite_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0, 0, 0} #define meshtastic_PositionLite_init_zero {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN} #define meshtastic_ChannelFile_init_zero {0, {meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero}, 0} #define meshtastic_OEMStore_init_zero {0, 0, {0, {0}}, _meshtastic_ScreenFonts_MIN, "", {0, {0}}, false, meshtastic_LocalConfig_init_zero, false, meshtastic_LocalModuleConfig_init_zero} @@ -200,6 +204,8 @@ extern "C" { #define meshtastic_NodeInfoLite_last_heard_tag 5 #define meshtastic_NodeInfoLite_device_metrics_tag 6 #define meshtastic_NodeInfoLite_channel_tag 7 +#define meshtastic_NodeInfoLite_via_mqtt_tag 8 +#define meshtastic_NodeInfoLite_hops_away_tag 9 #define meshtastic_ChannelFile_channels_tag 1 #define meshtastic_ChannelFile_version_tag 2 #define meshtastic_OEMStore_oem_icon_width_tag 1 @@ -252,7 +258,9 @@ X(a, STATIC, OPTIONAL, MESSAGE, position, 3) \ X(a, STATIC, SINGULAR, FLOAT, snr, 4) \ X(a, STATIC, SINGULAR, FIXED32, last_heard, 5) \ X(a, STATIC, OPTIONAL, MESSAGE, device_metrics, 6) \ -X(a, STATIC, SINGULAR, UINT32, channel, 7) +X(a, STATIC, SINGULAR, UINT32, channel, 7) \ +X(a, STATIC, SINGULAR, BOOL, via_mqtt, 8) \ +X(a, STATIC, SINGULAR, UINT32, hops_away, 9) #define meshtastic_NodeInfoLite_CALLBACK NULL #define meshtastic_NodeInfoLite_DEFAULT NULL #define meshtastic_NodeInfoLite_user_MSGTYPE meshtastic_User @@ -313,8 +321,8 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg; /* Maximum encoded size of messages (where known) */ #define meshtastic_ChannelFile_size 702 -#define meshtastic_DeviceState_size 17062 -#define meshtastic_NodeInfoLite_size 153 +#define meshtastic_DeviceState_size 17571 +#define meshtastic_NodeInfoLite_size 158 #define meshtastic_NodeRemoteHardwarePin_size 29 #define meshtastic_OEMStore_size 3246 #define meshtastic_PositionLite_size 28 diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index 6ffd93294..04590210e 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -534,8 +534,7 @@ typedef struct _meshtastic_MeshPacket { Note: Our crypto implementation uses this field as well. See [crypto](/docs/overview/encryption) for details. */ uint32_t from; - /* The (immediatSee Priority description for more details.y should be fixed32 instead, this encoding only - hurts the ble link though. */ + /* The (immediate) destination for this packet */ uint32_t to; /* (Usually) If set, this indicates the index in the secondary_channels table that this packet was sent/received on. If unset, packet was on the primary channel. @@ -594,6 +593,9 @@ typedef struct _meshtastic_MeshPacket { meshtastic_MeshPacket_Delayed delayed; /* Describes whether this packet passed via MQTT somewhere along the path it currently took. */ bool via_mqtt; + /* Hop limit with which the original packet started. Sent via LoRa using three bits in the unencrypted header. + When receiving a packet, the difference between hop_start and hop_limit gives how many hops it traveled. */ + uint8_t hop_start; } meshtastic_MeshPacket; /* The bluetooth to device link: @@ -632,6 +634,10 @@ typedef struct _meshtastic_NodeInfo { meshtastic_DeviceMetrics device_metrics; /* local channel index we heard that node on. Only populated if its not the default channel. */ uint8_t channel; + /* True if we witnessed the node over MQTT instead of LoRA transport */ + bool via_mqtt; + /* Number of hops away from us this node is (0 if adjacent) */ + uint8_t hops_away; } meshtastic_NodeInfo; /* Unique local debugging info for this node @@ -890,8 +896,8 @@ extern "C" { #define meshtastic_Data_init_default {_meshtastic_PortNum_MIN, {0, {0}}, 0, 0, 0, 0, 0, 0} #define meshtastic_Waypoint_init_default {0, 0, 0, 0, 0, "", "", 0} #define meshtastic_MqttClientProxyMessage_init_default {"", 0, {{0, {0}}}, 0} -#define meshtastic_MeshPacket_init_default {0, 0, 0, 0, {meshtastic_Data_init_default}, 0, 0, 0, 0, 0, _meshtastic_MeshPacket_Priority_MIN, 0, _meshtastic_MeshPacket_Delayed_MIN, 0} -#define meshtastic_NodeInfo_init_default {0, false, meshtastic_User_init_default, false, meshtastic_Position_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0} +#define meshtastic_MeshPacket_init_default {0, 0, 0, 0, {meshtastic_Data_init_default}, 0, 0, 0, 0, 0, _meshtastic_MeshPacket_Priority_MIN, 0, _meshtastic_MeshPacket_Delayed_MIN, 0, 0} +#define meshtastic_NodeInfo_init_default {0, false, meshtastic_User_init_default, false, meshtastic_Position_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0, 0, 0} #define meshtastic_MyNodeInfo_init_default {0, 0, 0} #define meshtastic_LogRecord_init_default {"", 0, "", _meshtastic_LogRecord_Level_MIN} #define meshtastic_QueueStatus_init_default {0, 0, 0, 0} @@ -908,8 +914,8 @@ extern "C" { #define meshtastic_Data_init_zero {_meshtastic_PortNum_MIN, {0, {0}}, 0, 0, 0, 0, 0, 0} #define meshtastic_Waypoint_init_zero {0, 0, 0, 0, 0, "", "", 0} #define meshtastic_MqttClientProxyMessage_init_zero {"", 0, {{0, {0}}}, 0} -#define meshtastic_MeshPacket_init_zero {0, 0, 0, 0, {meshtastic_Data_init_zero}, 0, 0, 0, 0, 0, _meshtastic_MeshPacket_Priority_MIN, 0, _meshtastic_MeshPacket_Delayed_MIN, 0} -#define meshtastic_NodeInfo_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_Position_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0} +#define meshtastic_MeshPacket_init_zero {0, 0, 0, 0, {meshtastic_Data_init_zero}, 0, 0, 0, 0, 0, _meshtastic_MeshPacket_Priority_MIN, 0, _meshtastic_MeshPacket_Delayed_MIN, 0, 0} +#define meshtastic_NodeInfo_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_Position_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0, 0, 0} #define meshtastic_MyNodeInfo_init_zero {0, 0, 0} #define meshtastic_LogRecord_init_zero {"", 0, "", _meshtastic_LogRecord_Level_MIN} #define meshtastic_QueueStatus_init_zero {0, 0, 0, 0} @@ -989,6 +995,7 @@ extern "C" { #define meshtastic_MeshPacket_rx_rssi_tag 12 #define meshtastic_MeshPacket_delayed_tag 13 #define meshtastic_MeshPacket_via_mqtt_tag 14 +#define meshtastic_MeshPacket_hop_start_tag 15 #define meshtastic_NodeInfo_num_tag 1 #define meshtastic_NodeInfo_user_tag 2 #define meshtastic_NodeInfo_position_tag 3 @@ -996,6 +1003,8 @@ extern "C" { #define meshtastic_NodeInfo_last_heard_tag 5 #define meshtastic_NodeInfo_device_metrics_tag 6 #define meshtastic_NodeInfo_channel_tag 7 +#define meshtastic_NodeInfo_via_mqtt_tag 8 +#define meshtastic_NodeInfo_hops_away_tag 9 #define meshtastic_MyNodeInfo_my_node_num_tag 1 #define meshtastic_MyNodeInfo_reboot_count_tag 8 #define meshtastic_MyNodeInfo_min_app_version_tag 11 @@ -1146,7 +1155,8 @@ X(a, STATIC, SINGULAR, BOOL, want_ack, 10) \ X(a, STATIC, SINGULAR, UENUM, priority, 11) \ X(a, STATIC, SINGULAR, INT32, rx_rssi, 12) \ X(a, STATIC, SINGULAR, UENUM, delayed, 13) \ -X(a, STATIC, SINGULAR, BOOL, via_mqtt, 14) +X(a, STATIC, SINGULAR, BOOL, via_mqtt, 14) \ +X(a, STATIC, SINGULAR, UINT32, hop_start, 15) #define meshtastic_MeshPacket_CALLBACK NULL #define meshtastic_MeshPacket_DEFAULT NULL #define meshtastic_MeshPacket_payload_variant_decoded_MSGTYPE meshtastic_Data @@ -1158,7 +1168,9 @@ X(a, STATIC, OPTIONAL, MESSAGE, position, 3) \ X(a, STATIC, SINGULAR, FLOAT, snr, 4) \ X(a, STATIC, SINGULAR, FIXED32, last_heard, 5) \ X(a, STATIC, OPTIONAL, MESSAGE, device_metrics, 6) \ -X(a, STATIC, SINGULAR, UINT32, channel, 7) +X(a, STATIC, SINGULAR, UINT32, channel, 7) \ +X(a, STATIC, SINGULAR, BOOL, via_mqtt, 8) \ +X(a, STATIC, SINGULAR, UINT32, hops_away, 9) #define meshtastic_NodeInfo_CALLBACK NULL #define meshtastic_NodeInfo_DEFAULT NULL #define meshtastic_NodeInfo_user_MSGTYPE meshtastic_User @@ -1311,12 +1323,12 @@ extern const pb_msgdesc_t meshtastic_DeviceMetadata_msg; #define meshtastic_DeviceMetadata_size 46 #define meshtastic_FromRadio_size 510 #define meshtastic_LogRecord_size 81 -#define meshtastic_MeshPacket_size 323 +#define meshtastic_MeshPacket_size 326 #define meshtastic_MqttClientProxyMessage_size 501 #define meshtastic_MyNodeInfo_size 18 #define meshtastic_NeighborInfo_size 258 #define meshtastic_Neighbor_size 22 -#define meshtastic_NodeInfo_size 270 +#define meshtastic_NodeInfo_size 275 #define meshtastic_Position_size 144 #define meshtastic_QueueStatus_size 23 #define meshtastic_RouteDiscovery_size 40 From 905718e2ac88138d7ddf975a6fe2d38e84fe7390 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sat, 2 Mar 2024 15:45:59 -0600 Subject: [PATCH 239/472] Remove problematic IO2 3V3 toggling (again) as GPS EN pin (#3317) * Remove problematic IO2 3V3 toggling (again) as GPS EN pin * Comment * Trunk --- src/gps/GPS.cpp | 13 ------------- variants/rak4631/variant.h | 1 + 2 files changed, 1 insertion(+), 13 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 3a3660308..2bdb8e176 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -255,19 +255,6 @@ bool GPS::setup() if (!didSerialInit) { #if !defined(GPS_UC6580) -#if defined(RAK4630) && defined(PIN_3V3_EN) - // If we are using the RAK4630 and we have no other peripherals on the I2C bus or module interest in 3V3_S, - // then we can safely set en_gpio turn off power to 3V3 (IO2) to hard sleep the GPS - if (rtc_found.port == ScanI2C::DeviceType::NONE && rgb_found.type == ScanI2C::DeviceType::NONE && - accelerometer_found.port == ScanI2C::DeviceType::NONE && !moduleConfig.detection_sensor.enabled && - !moduleConfig.telemetry.air_quality_enabled && !moduleConfig.telemetry.environment_measurement_enabled && - config.power.device_battery_ina_address == 0 && en_gpio == 0) { - LOG_DEBUG("Since no problematic peripherals or interested modules were found, setting power save GPS_EN to pin %i\n", - PIN_3V3_EN); - en_gpio = PIN_3V3_EN; - } -#endif - if (tx_gpio && gnssModel == GNSS_MODEL_UNKNOWN) { LOG_DEBUG("Probing for GPS at %d \n", serialSpeeds[speedSelect]); gnssModel = probe(serialSpeeds[speedSelect]); diff --git a/variants/rak4631/variant.h b/variants/rak4631/variant.h index e22ff0b63..4ad99df44 100644 --- a/variants/rak4631/variant.h +++ b/variants/rak4631/variant.h @@ -219,6 +219,7 @@ SO GPIO 39/TXEN MAY NOT BE DEFINED FOR SUCCESSFUL OPERATION OF THE SX1262 - TG #define NRF_APM // enables 3.3V periphery like GPS or IO Module +// Do not toggle this for GPS power savings #define PIN_3V3_EN (34) // RAK1910 GPS module From c65929283647b8af1388a765a816d7ebb60782d5 Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Sun, 3 Mar 2024 15:07:29 +1300 Subject: [PATCH 240/472] Reimplement "Dynamic E-Ink" as a derived class (#3316) Co-authored-by: Ben Meadors --- src/graphics/EInkDisplay2.cpp | 2 +- src/graphics/EInkDisplay2.h | 4 +- src/graphics/EInkDynamicDisplay.cpp | 384 ++++++++++++++++++ src/graphics/EInkDynamicDisplay.h | 104 +++++ src/graphics/Screen.cpp | 5 +- src/graphics/Screen.h | 1 + .../heltec_wireless_paper_v1/platformio.ini | 6 + 7 files changed, 503 insertions(+), 3 deletions(-) create mode 100644 src/graphics/EInkDynamicDisplay.cpp create mode 100644 src/graphics/EInkDynamicDisplay.h diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index d715d398b..d790e30c1 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -87,9 +87,9 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit) #ifndef EINK_NO_HIBERNATE // Only hibernate if controller IC will preserve image memory // Put screen to sleep to save power (possibly not necessary because we already did poweroff inside of display) adafruitDisplay->hibernate(); - LOG_DEBUG("done\n"); #endif + LOG_DEBUG("done\n"); return true; } diff --git a/src/graphics/EInkDisplay2.h b/src/graphics/EInkDisplay2.h index f40747f26..369378132 100644 --- a/src/graphics/EInkDisplay2.h +++ b/src/graphics/EInkDisplay2.h @@ -13,6 +13,8 @@ /** * An adapter class that allows using the GxEPD2 library as if it was an OLEDDisplay implementation. * + * Note: EInkDynamicDisplay derives from this class. + * * Remaining TODO: * optimize display() to only draw changed pixels (see other OLED subclasses for examples) * implement displayOn/displayOff to turn off the TFT device (and backlight) @@ -41,7 +43,7 @@ class EInkDisplay : public OLEDDisplay * * @return true if we did draw the screen */ - bool forceDisplay(uint32_t msecLimit = 1000); + virtual bool forceDisplay(uint32_t msecLimit = 1000); /** * shim to make the abstraction happy diff --git a/src/graphics/EInkDynamicDisplay.cpp b/src/graphics/EInkDynamicDisplay.cpp new file mode 100644 index 000000000..ae1e30fe1 --- /dev/null +++ b/src/graphics/EInkDynamicDisplay.cpp @@ -0,0 +1,384 @@ +#include "configuration.h" + +#if defined(USE_EINK) && defined(USE_EINK_DYNAMICDISPLAY) +#include "EInkDynamicDisplay.h" + +// Constructor +EInkDynamicDisplay::EInkDynamicDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY geometry, HW_I2C i2cBus) + : EInkDisplay(address, sda, scl, geometry, i2cBus) +{ + // If tracking ghost pixels, grab memory +#ifdef EINK_LIMIT_GHOSTING_PX + dirtyPixels = new uint8_t[EInkDisplay::displayBufferSize](); // Init with zeros +#endif +} + +// Destructor +EInkDynamicDisplay::~EInkDynamicDisplay() +{ + // If we were tracking ghost pixels, free the memory +#ifdef EINK_LIMIT_GHOSTING_PX + delete[] dirtyPixels; +#endif +} + +// Screen requests a BACKGROUND frame +void EInkDynamicDisplay::display() +{ + setFrameFlag(BACKGROUND); + update(); +} + +// Screen requests a RESPONSIVE frame +bool EInkDynamicDisplay::forceDisplay(uint32_t msecLimit) +{ + setFrameFlag(RESPONSIVE); + return update(); // (Unutilized) Base class promises to return true if update ran +} + +// Add flag for the next frame +void EInkDynamicDisplay::setFrameFlag(frameFlagTypes flag) +{ + // OR the new flag into the existing flags + this->frameFlags = (frameFlagTypes)(this->frameFlags | flag); +} + +// GxEPD2 code to set fast refresh +void EInkDynamicDisplay::configForFastRefresh() +{ + // Variant-specific code can go here +#if defined(PRIVATE_HW) +#else + // Otherwise: + adafruitDisplay->setPartialWindow(0, 0, adafruitDisplay->width(), adafruitDisplay->height()); +#endif +} + +// GxEPD2 code to set full refresh +void EInkDynamicDisplay::configForFullRefresh() +{ + // Variant-specific code can go here +#if defined(PRIVATE_HW) +#else + // Otherwise: + adafruitDisplay->setFullWindow(); +#endif +} + +// Run any relevant GxEPD2 code, so next update will use correct refresh type +void EInkDynamicDisplay::applyRefreshMode() +{ + // Change from FULL to FAST + if (currentConfig == FULL && refresh == FAST) { + configForFastRefresh(); + currentConfig = FAST; + } + + // Change from FAST back to FULL + else if (currentConfig == FAST && refresh == FULL) { + configForFullRefresh(); + currentConfig = FULL; + } +} + +// Update fastRefreshCount +void EInkDynamicDisplay::adjustRefreshCounters() +{ + if (refresh == FAST) + fastRefreshCount++; + + else if (refresh == FULL) + fastRefreshCount = 0; +} + +// Trigger the display update by calling base class +bool EInkDynamicDisplay::update() +{ + bool refreshApproved = determineMode(); + if (refreshApproved) + EInkDisplay::forceDisplay(0); // Bypass base class' own rate-limiting system + return refreshApproved; // (Unutilized) Base class promises to return true if update ran +} + +// Assess situation, pick a refresh type +bool EInkDynamicDisplay::determineMode() +{ + checkWasFlooded(); + checkRateLimiting(); + + // If too soon for a new time, abort here + if (refresh == SKIPPED) { + storeAndReset(); + return false; // No refresh + } + + // -- New frame is due -- + + resetRateLimiting(); // Once determineMode() ends, will have to wait again + hashImage(); // Generate here, so we can still copy it to previousImageHash, even if we skip the comparison check + LOG_DEBUG("EInkDynamicDisplay: "); // Begin log entry + + // Once mode determined, any remaining checks will bypass + checkCosmetic(); + checkDemandingFast(); + checkConsecutiveFastRefreshes(); +#ifdef EINK_LIMIT_GHOSTING_PX + checkExcessiveGhosting(); +#endif + checkFrameMatchesPrevious(); + checkFastRequested(); + + if (refresh == UNSPECIFIED) + LOG_WARN("There was a flaw in the determineMode() logic.\n"); + + // -- Decision has been reached -- + applyRefreshMode(); + adjustRefreshCounters(); + +#ifdef EINK_LIMIT_GHOSTING_PX + // Full refresh clears any ghosting + if (refresh == FULL) + resetGhostPixelTracking(); +#endif + + // Return - call a refresh or not? + if (refresh == SKIPPED) { + storeAndReset(); + return false; // Don't trigger a refresh + } else { + storeAndReset(); + return true; // Do trigger a refresh + } +} + +// Did RESPONSIVE frames previously exceed the rate-limit for fast refresh? +void EInkDynamicDisplay::checkWasFlooded() +{ + if (previousReason == EXCEEDED_RATELIMIT_FAST) { + // If so, allow a BACKGROUND frame to draw as RESPONSIVE + // Because we DID want a RESPONSIVE frame last time, we just didn't get it + setFrameFlag(RESPONSIVE); + } +} + +// Is it too soon for another frame of this type? +void EInkDynamicDisplay::checkRateLimiting() +{ + uint32_t now = millis(); + + // Sanity check: millis() overflow - just let the update run.. + if (previousRunMs > now) + return; + + // Skip update: too soon for BACKGROUND + if (frameFlags == BACKGROUND) { + if (now - previousRunMs < EINK_LIMIT_RATE_BACKGROUND_SEC * 1000) { + refresh = SKIPPED; + reason = EXCEEDED_RATELIMIT_FULL; + return; + } + } + + // No rate-limit for these special cases + if (frameFlags & COSMETIC || frameFlags & DEMAND_FAST) + return; + + // Skip update: too soon for RESPONSIVE + if (frameFlags & RESPONSIVE) { + if (now - previousRunMs < EINK_LIMIT_RATE_RESPONSIVE_SEC * 1000) { + refresh = SKIPPED; + reason = EXCEEDED_RATELIMIT_FAST; + return; + } + } +} + +// Is this frame COSMETIC (splash screens?) +void EInkDynamicDisplay::checkCosmetic() +{ + // If a decision was already reached, don't run the check + if (refresh != UNSPECIFIED) + return; + + // A full refresh is requested for cosmetic purposes: we have a decision + if (frameFlags & COSMETIC) { + refresh = FULL; + reason = FLAGGED_COSMETIC; + LOG_DEBUG("refresh=FULL, reason=FLAGGED_COSMETIC\n"); + } +} + +// Is this a one-off special circumstance, where we REALLY want a fast refresh? +void EInkDynamicDisplay::checkDemandingFast() +{ + // If a decision was already reached, don't run the check + if (refresh != UNSPECIFIED) + return; + + // A fast refresh is demanded: we have a decision + if (frameFlags & DEMAND_FAST) { + refresh = FAST; + reason = FLAGGED_DEMAND_FAST; + LOG_DEBUG("refresh=FAST, reason=FLAGGED_DEMAND_FAST\n"); + } +} + +// Have too many fast-refreshes occured consecutively, since last full refresh? +void EInkDynamicDisplay::checkConsecutiveFastRefreshes() +{ + // If a decision was already reached, don't run the check + if (refresh != UNSPECIFIED) + return; + + // If too many FAST refreshes consecutively - force a FULL refresh + if (fastRefreshCount >= EINK_LIMIT_FASTREFRESH) { + refresh = FULL; + reason = EXCEEDED_LIMIT_FASTREFRESH; + LOG_DEBUG("refresh=FULL, reason=EXCEEDED_LIMIT_FASTREFRESH\n"); + } +} + +// Does the new frame match the currently displayed image? +void EInkDynamicDisplay::checkFrameMatchesPrevious() +{ + // If a decision was already reached, don't run the check + if (refresh != UNSPECIFIED) + return; + + // If frame is *not* a duplicate, abort the check + if (imageHash != previousImageHash) + return; + +#if !defined(EINK_BACKGROUND_USES_FAST) + // If BACKGROUND, and last update was FAST: redraw the same image in FULL (for display health + image quality) + if (frameFlags == BACKGROUND && fastRefreshCount > 0) { + refresh = FULL; + reason = REDRAW_WITH_FULL; + LOG_DEBUG("refresh=FULL, reason=REDRAW_WITH_FULL\n"); + return; + } +#endif + + // Not redrawn, not COSMETIC, not DEMAND_FAST + refresh = SKIPPED; + reason = FRAME_MATCHED_PREVIOUS; + LOG_DEBUG("refresh=SKIPPED, reason=FRAME_MATCHED_PREVIOUS\n"); +} + +// No objections, we can perform fast-refresh, if desired +void EInkDynamicDisplay::checkFastRequested() +{ + if (refresh != UNSPECIFIED) + return; + + if (frameFlags == BACKGROUND) { +#ifdef EINK_BACKGROUND_USES_FAST + // If we want BACKGROUND to use fast. (FULL only when a limit is hit) + refresh = FAST; + reason = BACKGROUND_USES_FAST; + LOG_DEBUG("refresh=FAST, reason=BACKGROUND_USES_FAST, fastRefreshCount=%lu\n", fastRefreshCount); +#else + // If we do want to use FULL for BACKGROUND updates + refresh = FULL; + reason = FLAGGED_BACKGROUND; + LOG_DEBUG("refresh=FULL, reason=FLAGGED_BACKGROUND\n"); +#endif + } + + // Sanity: confirm that we did ask for a RESPONSIVE frame. + if (frameFlags & RESPONSIVE) { + refresh = FAST; + reason = NO_OBJECTIONS; + LOG_DEBUG("refresh=FAST, reason=NO_OBJECTIONS, fastRefreshCount=%lu\n", fastRefreshCount); + } +} + +// Reset the timer used for rate-limiting +void EInkDynamicDisplay::resetRateLimiting() +{ + previousRunMs = millis(); +} + +// Generate a hash of this frame, to compare against previous update +void EInkDynamicDisplay::hashImage() +{ + imageHash = 0; + + // Sum all bytes of the image buffer together + for (uint16_t b = 0; b < (displayWidth / 8) * displayHeight; b++) { + imageHash += buffer[b]; + } +} + +// Store the results of determineMode() for future use, and reset for next call +void EInkDynamicDisplay::storeAndReset() +{ + previousRefresh = refresh; + previousReason = reason; + + // Only store image hash if the display will update + if (refresh != SKIPPED) { + previousImageHash = imageHash; + } + + frameFlags = BACKGROUND; + refresh = UNSPECIFIED; +} + +#ifdef EINK_LIMIT_GHOSTING_PX +// Count how many ghost pixels the new image will display +void EInkDynamicDisplay::countGhostPixels() +{ + // If a decision was already reached, don't run the check + if (refresh != UNSPECIFIED) + return; + + // Start a new count + ghostPixelCount = 0; + + // Check new image, bit by bit, for any white pixels at locations marked "dirty" + for (uint16_t i = 0; i < displayBufferSize; i++) { + for (uint8_t bit = 0; bit < 7; bit++) { + + const bool dirty = (dirtyPixels[i] >> bit) & 1; // Has pixel location been drawn to since full-refresh? + const bool shouldBeBlank = !((buffer[i] >> bit) & 1); // Is pixel location white in the new image? + + // If pixel is (or has been) black since last full-refresh, and now is white: ghosting + if (dirty && shouldBeBlank) + ghostPixelCount++; + + // Update the dirty status for this pixel - will this location become a ghost if set white in future? + if (!dirty && !shouldBeBlank) + dirtyPixels[i] |= (1 << bit); + } + } + + LOG_DEBUG("ghostPixels=%hu, ", ghostPixelCount); +} + +// Check if ghost pixel count exceeds the defined limit +void EInkDynamicDisplay::checkExcessiveGhosting() +{ + // If a decision was already reached, don't run the check + if (refresh != UNSPECIFIED) + return; + + countGhostPixels(); + + // If too many ghost pixels, select full refresh + if (ghostPixelCount > EINK_LIMIT_GHOSTING_PX) { + refresh = FULL; + reason = EXCEEDED_GHOSTINGLIMIT; + LOG_DEBUG("refresh=FULL, reason=EXCEEDED_GHOSTINGLIMIT\n"); + } +} + +// Clear the dirty pixels array. Call when full-refresh cleans the display. +void EInkDynamicDisplay::resetGhostPixelTracking() +{ + // Copy the current frame into dirtyPixels[] from the display buffer + memcpy(dirtyPixels, EInkDisplay::buffer, EInkDisplay::displayBufferSize); +} +#endif // EINK_LIMIT_GHOSTING_PX + +#endif // USE_EINK_DYNAMICDISPLAY \ No newline at end of file diff --git a/src/graphics/EInkDynamicDisplay.h b/src/graphics/EInkDynamicDisplay.h new file mode 100644 index 000000000..2880c716b --- /dev/null +++ b/src/graphics/EInkDynamicDisplay.h @@ -0,0 +1,104 @@ +#pragma once + +#include "configuration.h" + +#if defined(USE_EINK) && defined(USE_EINK_DYNAMICDISPLAY) + +#include "EInkDisplay2.h" +#include "GxEPD2_BW.h" + +/* + Derives from the EInkDisplay adapter class. + Accepts suggestions from Screen class about frame type. + Determines which refresh type is most suitable. + (Full, Fast, Skip) +*/ + +class EInkDynamicDisplay : public EInkDisplay +{ + public: + // Constructor + // ( Parameters unused, passed to EInkDisplay. Maintains compatibility OLEDDisplay class ) + EInkDynamicDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY geometry, HW_I2C i2cBus); + ~EInkDynamicDisplay(); + + // What kind of frame is this + enum frameFlagTypes : uint8_t { + BACKGROUND = (1 << 0), // For frames via display() + RESPONSIVE = (1 << 1), // For frames via forceDisplay() + COSMETIC = (1 << 2), // For splashes + DEMAND_FAST = (1 << 3), // Special case only + }; + void setFrameFlag(frameFlagTypes flag); + + // Set the correct frame flag, then call universal "update()" method + void display() override; + bool forceDisplay(uint32_t msecLimit) override; // Shadows base class. Parameter and return val unused. + + protected: + enum refreshTypes : uint8_t { // Which refresh operation will be used + UNSPECIFIED, + FULL, + FAST, + SKIPPED, + }; + enum reasonTypes : uint8_t { // How was the decision reached + NO_OBJECTIONS, + EXCEEDED_RATELIMIT_FAST, + EXCEEDED_RATELIMIT_FULL, + FLAGGED_COSMETIC, + FLAGGED_DEMAND_FAST, + EXCEEDED_LIMIT_FASTREFRESH, + EXCEEDED_GHOSTINGLIMIT, + FRAME_MATCHED_PREVIOUS, + BACKGROUND_USES_FAST, + FLAGGED_BACKGROUND, + REDRAW_WITH_FULL, + }; + + void configForFastRefresh(); // GxEPD2 code to set fast-refresh + void configForFullRefresh(); // GxEPD2 code to set full-refresh + bool determineMode(); // Assess situation, pick a refresh type + void applyRefreshMode(); // Run any relevant GxEPD2 code, so next update will use correct refresh type + void adjustRefreshCounters(); // Update fastRefreshCount + bool update(); // Trigger the display update - determine mode, then call base class + + // Checks as part of determineMode() + void checkWasFlooded(); // Was the previous frame skipped for exceeding EINK_LIMIT_RATE_RESPONSIVE_SEC? + void checkRateLimiting(); // Is this frame too soon? + void checkCosmetic(); // Was the COSMETIC flag set? + void checkDemandingFast(); // Was the DEMAND_FAST flag set? + void checkConsecutiveFastRefreshes(); // Too many fast-refreshes consecutively? + void checkFrameMatchesPrevious(); // Does the new frame match the existing display image? + void checkFastRequested(); // Was the flag set for RESPONSIVE, or only BACKGROUND? + + void resetRateLimiting(); // Set previousRunMs - this now counts as an update, for rate-limiting + void hashImage(); // Generate a hashed version of this frame, to compare against previous update + void storeAndReset(); // Keep results of determineMode() for later, tidy-up for next call + + // What we are determining for this frame + frameFlagTypes frameFlags = BACKGROUND; // Frame type(s) - determineMode() input + refreshTypes refresh = UNSPECIFIED; // Refresh type - determineMode() output + reasonTypes reason = NO_OBJECTIONS; // Reason - why was refresh type used + + // What happened last time determineMode() ran + refreshTypes previousRefresh = UNSPECIFIED; // (Previous) Outcome + reasonTypes previousReason = NO_OBJECTIONS; // (Previous) Reason + + uint32_t previousRunMs = -1; // When did determineMode() last run (rather than rejecting for rate-limiting) + uint32_t imageHash = 0; // Hash of the current frame. Don't bother updating if nothing has changed! + uint32_t previousImageHash = 0; // Hash of the previous update's frame + uint32_t fastRefreshCount = 0; // How many fast-refreshes consecutively since last full refresh? + refreshTypes currentConfig = FULL; // Which refresh type is GxEPD2 currently configured for + + // Optional - track ghosting, pixel by pixel +#ifdef EINK_LIMIT_GHOSTING_PX + void countGhostPixels(); // Count any pixels which have moved from black to white since last full-refresh + void checkExcessiveGhosting(); // Check if ghosting exceeds defined limit + void resetGhostPixelTracking(); // Clear the dirty pixels array. Call when full-refresh cleans the display. + uint8_t *dirtyPixels; // Any pixels that have been black since last full-refresh (dynamically allocated mem) + uint32_t ghostPixelCount = 0; // Number of pixels with problematic ghosting. Retained here for LOG_DEBUG use +#endif +}; + +#endif \ No newline at end of file diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index c92877d41..33df78462 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -898,9 +898,12 @@ Screen::Screen(ScanI2C::DeviceAddress address, meshtastic_Config_DisplayConfig_O #elif defined(ST7735_CS) || defined(ILI9341_DRIVER) || defined(ST7789_CS) || defined(RAK14014) dispdev = new TFTDisplay(address.address, -1, -1, geometry, (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); -#elif defined(USE_EINK) +#elif defined(USE_EINK) && !defined(USE_EINK_DYNAMICDISPLAY) dispdev = new EInkDisplay(address.address, -1, -1, geometry, (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); +#elif defined(USE_EINK) && defined(USE_EINK_DYNAMICDISPLAY) + dispdev = new EInkDynamicDisplay(address.address, -1, -1, geometry, + (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); #elif defined(USE_ST7567) dispdev = new ST7567Wire(address.address, -1, -1, geometry, (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); diff --git a/src/graphics/Screen.h b/src/graphics/Screen.h index baee4b140..69e858dd2 100644 --- a/src/graphics/Screen.h +++ b/src/graphics/Screen.h @@ -47,6 +47,7 @@ class Screen #endif #include "EInkDisplay2.h" +#include "EInkDynamicDisplay.h" #include "TFTDisplay.h" #include "TypedQueue.h" #include "commands.h" diff --git a/variants/heltec_wireless_paper_v1/platformio.ini b/variants/heltec_wireless_paper_v1/platformio.ini index 01b68f5f0..4e5e291e0 100644 --- a/variants/heltec_wireless_paper_v1/platformio.ini +++ b/variants/heltec_wireless_paper_v1/platformio.ini @@ -8,6 +8,12 @@ build_flags = -D EINK_DISPLAY_MODEL=GxEPD2_213_BN -D EINK_WIDTH=250 -D EINK_HEIGHT=122 + -D USE_EINK_DYNAMICDISPLAY ; Enable Dynamic EInk + -D EINK_LIMIT_FASTREFRESH=5 ; How many consecutive fast-refreshes are permitted + -D EINK_LIMIT_RATE_BACKGROUND_SEC=30 ; Minimum interval between BACKGROUND updates + -D EINK_LIMIT_RATE_RESPONSIVE_SEC=1 ; Minimum interval between RESPONSIVE updates + -D EINK_LIMIT_GHOSTING_PX=2000 ; (Optional) How much image ghosting is tolerated + ;-D EINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. lib_deps = ${esp32s3_base.lib_deps} https://github.com/meshtastic/GxEPD2/ From 5865add857faff2f4e08d1a12059a77f4bfe55ca Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Mon, 4 Mar 2024 02:13:56 +1300 Subject: [PATCH 241/472] E-Ink: fast refresh for Wireless Paper V1.1 (#3320) --- src/graphics/EInkDisplay2.cpp | 15 +-------------- src/graphics/EInkDisplay2.h | 2 +- variants/heltec_wireless_paper/platformio.ini | 8 +++++++- variants/heltec_wireless_paper/variant.h | 2 ++ 4 files changed, 11 insertions(+), 16 deletions(-) diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index d790e30c1..aee30c7f8 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -158,7 +158,7 @@ bool EInkDisplay::connect() } } -#elif defined(HELTEC_WIRELESS_PAPER_V1_0) +#elif defined(HELTEC_WIRELESS_PAPER_V1_0) || defined(HELTEC_WIRELESS_PAPER) { // Is this a normal boot, or a wake from deep sleep? esp_sleep_wakeup_cause_t wakeReason = esp_sleep_get_wakeup_cause(); @@ -194,19 +194,6 @@ bool EInkDisplay::connect() adafruitDisplay->init(); adafruitDisplay->setRotation(3); } -#elif defined(HELTEC_WIRELESS_PAPER) - { - hspi = new SPIClass(HSPI); - hspi->begin(PIN_EINK_SCLK, -1, PIN_EINK_MOSI, PIN_EINK_CS); // SCLK, MISO, MOSI, SS - delay(100); - pinMode(Vext, OUTPUT); - digitalWrite(Vext, LOW); - delay(100); - auto lowLevel = new EINK_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY, *hspi); - adafruitDisplay = new GxEPD2_BW(*lowLevel); - adafruitDisplay->init(); - adafruitDisplay->setRotation(3); - } #elif defined(PCA10059) { auto lowLevel = new EINK_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY); diff --git a/src/graphics/EInkDisplay2.h b/src/graphics/EInkDisplay2.h index 369378132..75770a3bc 100644 --- a/src/graphics/EInkDisplay2.h +++ b/src/graphics/EInkDisplay2.h @@ -5,7 +5,7 @@ #include "GxEPD2_BW.h" #include -#if defined(HELTEC_WIRELESS_PAPER_V1_0) +#if defined(HELTEC_WIRELESS_PAPER_V1_0) || defined(HELTEC_WIRELESS_PAPER) // Re-enable SPI after deep sleep: rtc_gpio_hold_dis() #include "driver/rtc_io.h" #endif diff --git a/variants/heltec_wireless_paper/platformio.ini b/variants/heltec_wireless_paper/platformio.ini index 56446dc8b..0abbe085e 100644 --- a/variants/heltec_wireless_paper/platformio.ini +++ b/variants/heltec_wireless_paper/platformio.ini @@ -8,9 +8,15 @@ build_flags = -D EINK_DISPLAY_MODEL=GxEPD2_213_FC1 -D EINK_WIDTH=250 -D EINK_HEIGHT=122 + -D USE_EINK_DYNAMICDISPLAY ; Enable Dynamic EInk + -D EINK_LIMIT_FASTREFRESH=10 ; How many consecutive fast-refreshes are permitted + -D EINK_LIMIT_RATE_BACKGROUND_SEC=30 ; Minimum interval between BACKGROUND updates + -D EINK_LIMIT_RATE_RESPONSIVE_SEC=1 ; Minimum interval between RESPONSIVE updates + -D EINK_LIMIT_GHOSTING_PX=2000 ; (Optional) How much image ghosting is tolerated + -D EINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. lib_deps = ${esp32s3_base.lib_deps} - https://github.com/ixt/GxEPD2#39f325b677713eb04dfcc83b8e402e77523fb8bf + https://github.com/meshtastic/GxEPD2 adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 upload_speed = 115200 \ No newline at end of file diff --git a/variants/heltec_wireless_paper/variant.h b/variants/heltec_wireless_paper/variant.h index c2a030ed0..28bc8628a 100644 --- a/variants/heltec_wireless_paper/variant.h +++ b/variants/heltec_wireless_paper/variant.h @@ -5,6 +5,8 @@ #define I2C_SCL SCL #define USE_EINK +#define EINK_NO_HIBERNATE + /* * eink display pins */ From 495840c777d1b31bad92263da6c1b1c29b4bcef0 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 3 Mar 2024 08:36:36 -0600 Subject: [PATCH 242/472] Filter out neighborinfo if we don't have the module enabled (#3314) * Filter out neighborinfo if we don't have the module enabled * Handlereceived instead * Add debug message --- src/mesh/Router.cpp | 15 +++++++++++++-- 1 file changed, 13 insertions(+), 2 deletions(-) diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp index 4a6dc9007..1d6a2d96b 100644 --- a/src/mesh/Router.cpp +++ b/src/mesh/Router.cpp @@ -435,6 +435,7 @@ NodeNum Router::getNodeNum() */ void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src) { + bool skipHandle = false; // Also, we should set the time from the ISR and it should have msec level resolution p->rx_time = getValidTime(RTCQualityFromNet); // store the arrival timestamp for the phone // Store a copy of encrypted packet for MQTT @@ -451,8 +452,17 @@ void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src) else printPacket("handleReceived(REMOTE)", p); + // Neighbor info module is disabled, ignore expensive neighbor info packets + if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag && + p->decoded.portnum == meshtastic_PortNum_NEIGHBORINFO_APP && + (!moduleConfig.has_neighbor_info || !moduleConfig.neighbor_info.enabled)) { + LOG_DEBUG("Neighbor info module is disabled, ignoring neighbor packet\n"); + cancelSending(p->from, p->id); + skipHandle = true; + } + // Publish received message to MQTT if we're not the original transmitter of the packet - if (moduleConfig.mqtt.enabled && getFrom(p) != nodeDB.getNodeNum() && mqtt) + if (!skipHandle && moduleConfig.mqtt.enabled && getFrom(p) != nodeDB.getNodeNum() && mqtt) mqtt->onSend(*p_encrypted, *p, p->channel); } else { printPacket("packet decoding failed or skipped (no PSK?)", p); @@ -461,7 +471,8 @@ void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src) packetPool.release(p_encrypted); // Release the encrypted packet // call modules here - MeshModule::callPlugins(*p, src); + if (!skipHandle) + MeshModule::callPlugins(*p, src); } void Router::perhapsHandleReceived(meshtastic_MeshPacket *p) From 9b3e519487ed421a29112bcd047096d2cd3131a5 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 3 Mar 2024 08:55:52 -0600 Subject: [PATCH 243/472] Revert "Fix LED pinout for T-Echo board marked v1.0" (#3304) * Revert "Fix LED pinout for T-Echo board marked v1.0, date 2021-6-28 (#3051)" This reverts commit c2afa879b879371d7f19d5b4c088f4ba66ab8ecd. * Remove / comment out unused LED pins --- variants/t-echo/variant.h | 16 ++++++---------- 1 file changed, 6 insertions(+), 10 deletions(-) diff --git a/variants/t-echo/variant.h b/variants/t-echo/variant.h index 345091c2f..dffa08698 100644 --- a/variants/t-echo/variant.h +++ b/variants/t-echo/variant.h @@ -43,16 +43,12 @@ extern "C" { #define NUM_ANALOG_OUTPUTS (0) // LEDs -#define PIN_LED1 (0 + 14) // blue (confirmed on boards marked v1.0, date 2021-6-28) -#define PIN_LED2 (32 + 1) // green -#define PIN_LED3 (32 + 3) // red +#define PIN_LED1 (0 + 14) // 13 red (confirmed on 1.0 board) +// Unused(by firmware) LEDs: +// #define PIN_LED2 (0 + 15) // 14 blue +// #define PIN_LED3 (0 + 13) // 15 green -#define LED_RED PIN_LED3 -#define LED_BLUE PIN_LED1 -#define LED_GREEN PIN_LED2 - -#define LED_BUILTIN LED_BLUE -#define LED_CONN PIN_GREEN +#define LED_BUILTIN PIN_LED1 #define LED_STATE_ON 0 // State when LED is lit #define LED_INVERTED 1 @@ -232,4 +228,4 @@ External serial flash WP25R1635FZUIL0 * Arduino objects - C++ only *----------------------------------------------------------------------------*/ -#endif \ No newline at end of file +#endif From 6dbb6583ef50e8b3d5a297ac50046a139eafb485 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 3 Mar 2024 09:33:18 -0600 Subject: [PATCH 244/472] Put these back --- variants/t-echo/variant.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/variants/t-echo/variant.h b/variants/t-echo/variant.h index dffa08698..71795dce0 100644 --- a/variants/t-echo/variant.h +++ b/variants/t-echo/variant.h @@ -45,8 +45,8 @@ extern "C" { // LEDs #define PIN_LED1 (0 + 14) // 13 red (confirmed on 1.0 board) // Unused(by firmware) LEDs: -// #define PIN_LED2 (0 + 15) // 14 blue -// #define PIN_LED3 (0 + 13) // 15 green +#define PIN_LED2 (0 + 15) // 14 blue +#define PIN_LED3 (0 + 13) // 15 green #define LED_BUILTIN PIN_LED1 @@ -228,4 +228,4 @@ External serial flash WP25R1635FZUIL0 * Arduino objects - C++ only *----------------------------------------------------------------------------*/ -#endif +#endif \ No newline at end of file From e3063a278506beab50e62d57e61538282f269bf3 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 3 Mar 2024 09:46:36 -0600 Subject: [PATCH 245/472] Turns out bluefruit uses some of these macros even though "we" don't :-/ --- variants/t-echo/variant.h | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/variants/t-echo/variant.h b/variants/t-echo/variant.h index 71795dce0..1af68863e 100644 --- a/variants/t-echo/variant.h +++ b/variants/t-echo/variant.h @@ -48,7 +48,12 @@ extern "C" { #define PIN_LED2 (0 + 15) // 14 blue #define PIN_LED3 (0 + 13) // 15 green -#define LED_BUILTIN PIN_LED1 +#define LED_RED PIN_LED3 +#define LED_BLUE PIN_LED1 +#define LED_GREEN PIN_LED2 + +#define LED_BUILTIN LED_BLUE +#define LED_CONN PIN_GREEN #define LED_STATE_ON 0 // State when LED is lit #define LED_INVERTED 1 From 3c3d3910446cd85784693aca3bd56cfd765025ac Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 3 Mar 2024 10:33:30 -0600 Subject: [PATCH 246/472] Remove rangetest file on factory reset (#3322) --- src/mesh/NodeDB.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 506adda5c..dc8d7540c 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -130,6 +130,9 @@ bool NodeDB::factoryReset() LOG_INFO("Performing factory reset!\n"); // first, remove the "/prefs" (this removes most prefs) rmDir("/prefs"); + if (FSCom.exists("/static/rangetest.csv") && !FSCom.remove("/static/rangetest.csv")) { + LOG_WARN("Could not remove rangetest.csv file\n"); + } // second, install default state (this will deal with the duplicate mac address issue) installDefaultDeviceState(); installDefaultConfig(); From 7ab9a94edbb62f709599050a07ec13f25140fb36 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 3 Mar 2024 11:19:30 -0600 Subject: [PATCH 247/472] just off the coast of NULL Island isn't OK either. --- src/modules/PositionModule.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index addff8966..4634f8fef 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -116,6 +116,11 @@ meshtastic_MeshPacket *PositionModule::allocReply() } localPosition.seq_number++; + if (localPosition.latitude_i == 0 && localPosition.longitude_i == 0) { + LOG_WARN("Skipping position send because lat/lon are zero!\n"); + return nullptr; + } + // lat/lon are unconditionally included - IF AVAILABLE! LOG_DEBUG("Sending location with precision %i\n", precision); if (precision < 32 && precision > 0) { @@ -176,11 +181,6 @@ meshtastic_MeshPacket *PositionModule::allocReply() LOG_INFO("Providing time to mesh %u\n", p.time); } - if (p.latitude_i == 0 && p.longitude_i == 0) { - LOG_WARN("Skipping position send because lat/lon are zero!\n"); - return nullptr; - } - LOG_INFO("Position reply: time=%i, latI=%i, lonI=%i\n", p.time, p.latitude_i, p.longitude_i); // TAK Tracker devices should send their position in a TAK packet over the ATAK port From e5bf07d4fbeba7c914288ed5774f9bb74b8dc8ce Mon Sep 17 00:00:00 2001 From: Ken McGuire Date: Sun, 3 Mar 2024 12:08:47 -0700 Subject: [PATCH 248/472] Fix for issue #3310 (#3327) * Portduino multiple logging levels * Fixes based on GPSFan work * Fix derped logic * Correct size field for AID message * Reformat to add comments, beginning of GPS rework * Update PM2 message for Neo-6 * Correct ECO mode logic as ECO mode is only for Neo-6 * Cleanup ubx.h add a few more comments * GPS rework, changes for M8 and stub for M10 * Add VALSET commands for u-blox M10 receivers * Add VALSET commands for u-blox M10 receivers tweak M8 commands add comments for VALSET configuration commands * Add commands to init M10 receivers, tweak the M8 init sequence, this is a WIP as there are still some issues during init. Add M10 version of PMREQ. * Add wakeup source of uartrx to PMREQ_10 The M10 does not respond to commands when asleep, may need to do this for the M8 as well * Enable NMEA messages on USB port. Normally, it is a good idea to disable messages on unused ports. Native Linux needs to be able to use GNSS modules connected via via either serial or USB. In the future I2C connections may be required, but are not enabled for now. * Save the config for all u-blox receiver types. The M10 supports this command in addition to saving using the VALSET commands for the RAM & BBR layers. --------- Co-authored-by: Jonathan Bennett Co-authored-by: Ben Meadors --- src/gps/GPS.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 2bdb8e176..849c38794 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -476,13 +476,6 @@ bool GPS::setup() } } - msglen = makeUBXPacket(0x06, 0x09, sizeof(_message_SAVE), _message_SAVE); - _serial_gps->write(UBXscratch, msglen); - if (getACK(0x06, 0x09, 2000) != GNSS_RESPONSE_OK) { - LOG_WARN("Unable to save GNSS module configuration.\n"); - } else { - LOG_INFO("GNSS module configuration saved!\n"); - } } else { // LOG_INFO("u-blox M10 hardware found.\n"); delay(1000); @@ -575,6 +568,13 @@ bool GPS::setup() // BBR will survive a restart, and power off for a while, but modules with small backup // batteries or super caps will not retain the config for a long power off time. } + msglen = makeUBXPacket(0x06, 0x09, sizeof(_message_SAVE), _message_SAVE); + _serial_gps->write(UBXscratch, msglen); + if (getACK(0x06, 0x09, 2000) != GNSS_RESPONSE_OK) { + LOG_WARN("Unable to save GNSS module configuration.\n"); + } else { + LOG_INFO("GNSS module configuration saved!\n"); + } } didSerialInit = true; } From 72050530f119853707192b78b999552224c1bf20 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 3 Mar 2024 13:56:55 -0600 Subject: [PATCH 249/472] NRF52 bluetooth cleanup and fix (#3328) * NRF52 bluetooth cleanup. Fixes BLE not returning after serial PhoneAPI connection * Use new var name in esp32 arch --- src/nimble/NimbleBluetooth.h | 4 ++-- src/platform/esp32/main-esp32.cpp | 8 +++---- src/platform/nrf52/NRF52Bluetooth.cpp | 12 +++++++++- src/platform/nrf52/NRF52Bluetooth.h | 3 ++- src/platform/nrf52/main-nrf52.cpp | 29 ++++++++++++------------ src/platform/portduino/PortduinoGlue.cpp | 2 +- src/platform/rp2040/main-rp2040.cpp | 2 +- src/platform/stm32wl/main-stm32wl.cpp | 4 ++-- src/target_specific.h | 2 +- 9 files changed, 39 insertions(+), 27 deletions(-) diff --git a/src/nimble/NimbleBluetooth.h b/src/nimble/NimbleBluetooth.h index 4080a7cbc..df2d3e45a 100644 --- a/src/nimble/NimbleBluetooth.h +++ b/src/nimble/NimbleBluetooth.h @@ -16,5 +16,5 @@ class NimbleBluetooth : BluetoothApi void startAdvertising(); }; -void setBluetoothEnable(bool on); -void clearNVS(); +void setBluetoothEnable(bool enable); +void clearNVS(); \ No newline at end of file diff --git a/src/platform/esp32/main-esp32.cpp b/src/platform/esp32/main-esp32.cpp index c994eea48..f97f6d121 100644 --- a/src/platform/esp32/main-esp32.cpp +++ b/src/platform/esp32/main-esp32.cpp @@ -20,21 +20,21 @@ #if !defined(CONFIG_IDF_TARGET_ESP32S2) -void setBluetoothEnable(bool on) +void setBluetoothEnable(bool enable) { if (!isWifiAvailable() && config.bluetooth.enabled == true) { if (!nimbleBluetooth) { nimbleBluetooth = new NimbleBluetooth(); } - if (on && !nimbleBluetooth->isActive()) { + if (enable && !nimbleBluetooth->isActive()) { nimbleBluetooth->setup(); - } else if (!on) { + } else if (!enable) { nimbleBluetooth->shutdown(); } } } #else -void setBluetoothEnable(bool on) {} +void setBluetoothEnable(bool enable) {} void updateBatteryLevel(uint8_t level) {} #endif diff --git a/src/platform/nrf52/NRF52Bluetooth.cpp b/src/platform/nrf52/NRF52Bluetooth.cpp index dd81929c8..9a93f5cc6 100644 --- a/src/platform/nrf52/NRF52Bluetooth.cpp +++ b/src/platform/nrf52/NRF52Bluetooth.cpp @@ -210,8 +210,10 @@ void NRF52Bluetooth::shutdown() { // Shutdown bluetooth for minimum power draw LOG_INFO("Disable NRF52 bluetooth\n"); + if (connectionHandle != 0) { + Bluefruit.disconnect(connectionHandle); + } Bluefruit.Advertising.stop(); - Bluefruit.setTxPower(0); // Minimum power } bool NRF52Bluetooth::isConnected() @@ -289,6 +291,14 @@ void NRF52Bluetooth::setup() } } +void NRF52Bluetooth::resumeAdverising() +{ + Bluefruit.Advertising.restartOnDisconnect(true); + Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms + Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode + Bluefruit.Advertising.start(0); +} + /// Given a level between 0-100, update the BLE attribute void updateBatteryLevel(uint8_t level) { diff --git a/src/platform/nrf52/NRF52Bluetooth.h b/src/platform/nrf52/NRF52Bluetooth.h index 193e86cf8..fd27bbf04 100644 --- a/src/platform/nrf52/NRF52Bluetooth.h +++ b/src/platform/nrf52/NRF52Bluetooth.h @@ -8,6 +8,7 @@ class NRF52Bluetooth : BluetoothApi public: void setup(); void shutdown(); + void resumeAdverising(); void clearBonds(); bool isConnected(); int getRssi(); @@ -17,4 +18,4 @@ class NRF52Bluetooth : BluetoothApi void convertToUint8(uint8_t target[4], uint32_t source); static bool onPairingPasskey(uint16_t conn_handle, uint8_t const passkey[6], bool match_request); static void onPairingCompleted(uint16_t conn_handle, uint8_t auth_status); -}; +}; \ No newline at end of file diff --git a/src/platform/nrf52/main-nrf52.cpp b/src/platform/nrf52/main-nrf52.cpp index 63b014c46..9e8798e37 100644 --- a/src/platform/nrf52/main-nrf52.cpp +++ b/src/platform/nrf52/main-nrf52.cpp @@ -63,28 +63,29 @@ static void initBrownout() // We don't bother with setting up brownout if soft device is disabled - because during production we always use softdevice } -static bool bleOn = false; static const bool useSoftDevice = true; // Set to false for easier debugging -void setBluetoothEnable(bool on) +void setBluetoothEnable(bool enable) { - if (on != bleOn && config.bluetooth.enabled == true) { - if (on) { + if (enable && config.bluetooth.enabled) { + if (!useSoftDevice) { + LOG_INFO("DISABLING NRF52 BLUETOOTH WHILE DEBUGGING\n"); + } else { if (!nrf52Bluetooth) { - if (!useSoftDevice) - LOG_INFO("DISABLING NRF52 BLUETOOTH WHILE DEBUGGING\n"); - else { - nrf52Bluetooth = new NRF52Bluetooth(); - nrf52Bluetooth->setup(); + LOG_DEBUG("Initializing NRF52 Bluetooth\n"); + nrf52Bluetooth = new NRF52Bluetooth(); + nrf52Bluetooth->setup(); - // We delay brownout init until after BLE because BLE starts soft device - initBrownout(); - } + // We delay brownout init until after BLE because BLE starts soft device + initBrownout(); + } else { + nrf52Bluetooth->resumeAdverising(); } - } else if (nrf52Bluetooth) { + } + } else { + if (nrf52Bluetooth) { nrf52Bluetooth->shutdown(); } - bleOn = on; } } diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index c8fcc3d13..046509fab 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -20,7 +20,7 @@ std::map settingsStrings; char *configPath = nullptr; // FIXME - move setBluetoothEnable into a HALPlatform class -void setBluetoothEnable(bool on) +void setBluetoothEnable(bool enable) { // not needed } diff --git a/src/platform/rp2040/main-rp2040.cpp b/src/platform/rp2040/main-rp2040.cpp index 3359263e9..283b801f1 100644 --- a/src/platform/rp2040/main-rp2040.cpp +++ b/src/platform/rp2040/main-rp2040.cpp @@ -2,7 +2,7 @@ #include #include -void setBluetoothEnable(bool on) +void setBluetoothEnable(bool enable) { // not needed } diff --git a/src/platform/stm32wl/main-stm32wl.cpp b/src/platform/stm32wl/main-stm32wl.cpp index f57928c60..60c3cce10 100644 --- a/src/platform/stm32wl/main-stm32wl.cpp +++ b/src/platform/stm32wl/main-stm32wl.cpp @@ -3,7 +3,7 @@ #include #include -void setBluetoothEnable(bool on) {} +void setBluetoothEnable(bool enable) {} void playStartMelody() {} @@ -33,4 +33,4 @@ int _gettimeofday(struct timeval *tv, void *tzvp) { return -1; } -} +} \ No newline at end of file diff --git a/src/target_specific.h b/src/target_specific.h index 1e79df510..7404a3720 100644 --- a/src/target_specific.h +++ b/src/target_specific.h @@ -5,6 +5,6 @@ // Functions that are unique to particular target types (esp32, bare, nrf52 etc...) // Enable/disable bluetooth. -void setBluetoothEnable(bool on); +void setBluetoothEnable(bool enable); void getMacAddr(uint8_t *dmac); \ No newline at end of file From f5ff77c2b94c5aaea4dc049baefc158fede7dd4c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Tue, 5 Mar 2024 14:50:52 +0100 Subject: [PATCH 250/472] Turn off certain modules not wanted in custom builds (#3337) --- src/configuration.h | 20 +++++++++++- src/modules/Modules.cpp | 72 ++++++++++++++++++++++++++++++++++------- 2 files changed, 80 insertions(+), 12 deletions(-) diff --git a/src/configuration.h b/src/configuration.h index d8b0dba5f..03170c1c7 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -221,4 +221,22 @@ along with this program. If not, see . #ifndef HW_VENDOR #error HW_VENDOR must be defined -#endif \ No newline at end of file +#endif + +// global switch to turn off all optional modules for a minimzed build +#ifdef MESHTASTIC_EXCLUDE_MODULES +#define MESHTASTIC_EXCLUDE_AUDIO 1 +#define MESHTASTIC_EXCLUDE_DETECTIONSENSOR 1 +#define MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR 1 +#define MESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION 1 +#define MESHTASTIC_EXCLUDE_PAXCOUNTER 1 +#define MESHTASTIC_EXCLUDE_POWER_TELEMETRY 1 +#define MESHTASTIC_EXCLUDE_RANGETEST 1 +#define MESHTASTIC_EXCLUDE_REMOTEHARDWARE 1 +#define MESHTASTIC_EXCLUDE_STOREFORWARD 1 +#define MESHTASTIC_EXCLUDE_ATAK 1 +#define MESHTASTIC_EXCLUDE_CANNEDMESSAGES 1 +#define MESHTASTIC_EXCLUDE_NEIGHBORINFO 1 +#define MESHTASTIC_EXCLUDE_TRACEROUTE 1 +#define MESHTASTIC_EXCLUDE_WAYPOINT 1 +#endif diff --git a/src/modules/Modules.cpp b/src/modules/Modules.cpp index 2d45868fd..4f0b8f2b0 100644 --- a/src/modules/Modules.cpp +++ b/src/modules/Modules.cpp @@ -1,74 +1,112 @@ #include "configuration.h" +#if !MESHTASTIC_EXCLUDE_INPUTBROKER #include "input/InputBroker.h" #include "input/RotaryEncoderInterruptImpl1.h" #include "input/TrackballInterruptImpl1.h" #include "input/UpDownInterruptImpl1.h" #include "input/cardKbI2cImpl.h" #include "input/kbMatrixImpl.h" +#endif #include "modules/AdminModule.h" +#if !MESHTASTIC_EXCLUDE_ATAK #include "modules/AtakPluginModule.h" +#endif +#if !MESHTASTIC_EXCLUDE_CANNEDMESSAGES #include "modules/CannedMessageModule.h" +#endif +#if !MESHTASTIC_EXCLUDE_DETECTIONSENSOR #include "modules/DetectionSensorModule.h" +#endif +#if !MESHTASTIC_EXCLUDE_NEIGHBORINFO #include "modules/NeighborInfoModule.h" +#endif #include "modules/NodeInfoModule.h" #include "modules/PositionModule.h" +#if !MESHTASTIC_EXCLUDE_REMOTEHARDWARE #include "modules/RemoteHardwareModule.h" +#endif #include "modules/RoutingModule.h" #include "modules/TextMessageModule.h" +#if !MESHTASTIC_EXCLUDE_TRACEROUTE #include "modules/TraceRouteModule.h" +#endif +#if !MESHTASTIC_EXCLUDE_WAYPOINT #include "modules/WaypointModule.h" +#endif #if ARCH_PORTDUINO #include "input/LinuxInputImpl.h" #endif #if HAS_TELEMETRY #include "modules/Telemetry/DeviceTelemetry.h" #endif -#if HAS_SENSOR +#if HAS_SENSOR && !EXCLUDE_ENVIRONMENTAL_SENSOR #include "modules/Telemetry/AirQualityTelemetry.h" #include "modules/Telemetry/EnvironmentTelemetry.h" #endif -#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) +#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) && !EXCLUDE_POWER_TELEMETRY #include "modules/Telemetry/PowerTelemetry.h" #endif #ifdef ARCH_ESP32 -#ifdef USE_SX1280 +#if defined(USE_SX1280) && !MESHTASTIC_EXCLUDE_AUDIO #include "modules/esp32/AudioModule.h" #endif +#if !MESHTASTIC_EXCLUDE_PAXCOUNTER #include "modules/esp32/PaxcounterModule.h" +#endif +#if !MESHTASTIC_EXCLUDE_STOREFORWARD #include "modules/esp32/StoreForwardModule.h" #endif +#endif #if defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040) +#if !MESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION #include "modules/ExternalNotificationModule.h" +#endif +#if !MESHTASTIC_EXCLUDE_RANGETEST #include "modules/RangeTestModule.h" +#endif #if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)) && !defined(CONFIG_IDF_TARGET_ESP32S2) +#if !MESHTASTIC_EXCLUDE_SERIAL #include "modules/SerialModule.h" #endif #endif +#endif /** * Create module instances here. If you are adding a new module, you must 'new' it here (or somewhere else) */ void setupModules() { if (config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER) { -#if HAS_BUTTON || ARCH_PORTDUINO +#if (HAS_BUTTON || ARCH_PORTDUINO) && !MESHTASTIC_EXCLUDE_INPUTBROKER inputBroker = new InputBroker(); #endif adminModule = new AdminModule(); nodeInfoModule = new NodeInfoModule(); positionModule = new PositionModule(); +#if !MESHTASTIC_EXCLUDE_WAYPOINT waypointModule = new WaypointModule(); +#endif textMessageModule = new TextMessageModule(); +#if !MESHTASTIC_EXCLUDE_TRACEROUTE traceRouteModule = new TraceRouteModule(); +#endif +#if !MESHTASTIC_EXCLUDE_NEIGHBORINFO neighborInfoModule = new NeighborInfoModule(); +#endif +#if !MESHTASTIC_EXCLUDE_DETECTIONSENSOR detectionSensorModule = new DetectionSensorModule(); +#endif +#if !MESHTASTIC_EXCLUDE_ATAK atakPluginModule = new AtakPluginModule(); +#endif // Note: if the rest of meshtastic doesn't need to explicitly use your module, you do not need to assign the instance // to a global variable. +#if !MESHTASTIC_EXCLUDE_REMOTEHARDWARE new RemoteHardwareModule(); +#endif // Example: Put your module here // new ReplyModule(); -#if HAS_BUTTON || ARCH_PORTDUINO +#if (HAS_BUTTON || ARCH_PORTDUINO) && !MESHTASTIC_EXCLUDE_INPUTBROKER rotaryEncoderInterruptImpl1 = new RotaryEncoderInterruptImpl1(); if (!rotaryEncoderInterruptImpl1->init()) { delete rotaryEncoderInterruptImpl1; @@ -90,47 +128,59 @@ void setupModules() aLinuxInputImpl = new LinuxInputImpl(); aLinuxInputImpl->init(); #endif -#if HAS_TRACKBALL +#if HAS_TRACKBALL && !MESHTASTIC_EXCLUDE_INPUTBROKER trackballInterruptImpl1 = new TrackballInterruptImpl1(); trackballInterruptImpl1->init(); #endif -#if HAS_SCREEN +#if HAS_SCREEN && !MESHTASTIC_EXCLUDE_CANNEDMESSAGES cannedMessageModule = new CannedMessageModule(); #endif -#if HAS_TELEMETRY +#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) new DeviceTelemetryModule(); #endif -#if HAS_SENSOR +#if HAS_SENSOR && !EXCLUDE_ENVIRONMENTAL_SENSOR new EnvironmentTelemetryModule(); if (nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_PMSA003I].first > 0) { new AirQualityTelemetryModule(); } #endif -#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) +#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) && !EXCLUDE_POWER_TELEMETRY new PowerTelemetryModule(); #endif #if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)) && !defined(CONFIG_IDF_TARGET_ESP32S2) && \ !defined(CONFIG_IDF_TARGET_ESP32C3) +#if !MESHTASTIC_EXCLUDE_SERIAL new SerialModule(); #endif +#endif #ifdef ARCH_ESP32 // Only run on an esp32 based device. -#ifdef USE_SX1280 +#if defined(USE_SX1280) && !MESHTASTIC_EXCLUDE_AUDIO audioModule = new AudioModule(); #endif +#if !MESHTASTIC_EXCLUDE_STOREFORWARD storeForwardModule = new StoreForwardModule(); +#endif +#if !MESHTASTIC_EXCLUDE_PAXCOUNTER paxcounterModule = new PaxcounterModule(); #endif +#endif #if defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040) +#if !MESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION externalNotificationModule = new ExternalNotificationModule(); +#endif +#if !MESHTASTIC_EXCLUDE_RANGETEST new RangeTestModule(); +#endif #endif } else { adminModule = new AdminModule(); #if HAS_TELEMETRY new DeviceTelemetryModule(); #endif +#if !MESHTASTIC_EXCLUDE_TRACEROUTE traceRouteModule = new TraceRouteModule(); +#endif } // NOTE! This module must be added LAST because it likes to check for replies from other modules and avoid sending extra // acks From 9d37a8d17fcebfee819986b69104e820ba521994 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Wed, 6 Mar 2024 13:09:46 -0600 Subject: [PATCH 251/472] Stop Fiddling with Newlines! (#3341) --- .vscode/settings.json | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/.vscode/settings.json b/.vscode/settings.json index 03922dc72..e86d31c7d 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -1,5 +1,7 @@ { "editor.formatOnSave": true, "editor.defaultFormatter": "trunk.io", - "trunk.enableWindows": true + "trunk.enableWindows": true, + "files.insertFinalNewline": false, + "files.trimFinalNewlines": false } From e174328de36bc9a989986cf7a1d8b59802ec5e29 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Wed, 6 Mar 2024 16:23:04 -0600 Subject: [PATCH 252/472] Native Webserver (#3343) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Added WebServer/WebServices for Native Linux Meshtastic and web gui * Fix bug in login functionality * Added customized config of portdunio.ini with LovyannGFX from marelab repro * Compile Problem resolved with developer version of LovyanGFX.git * Compile against dev version * Fixes to fit into main branch * Update variant.h, main.cpp, .gitignore, WebServer.cpp, esp32s2.ini, WebServer.h, ContentHandler.cpp, rp2040.ini, nrf52.ini, ContentHelper.cpp, Dockerfile, ContentHandler.h, esp32.ini, stm32wl5e.ini * Added linux pi std /usr/include dir * Adding /usr/innclude for Linux compile against native libs that are not hadled by platformio * Review log level changes & translation * Update Dockerfile * Fix Typo & VFS ref. Part1 * Fix Typo & VFS ref. * Dev Version for ulfius web lib * Update platformio.ini * Free VFS path string * Remove unintended changes * More unintentional changes * Make the HTTP server optional on native * Tune-up for Native web defaults * Don't modify build system yet * Remove more unneeded changes --------- Co-authored-by: marc hammermann Co-authored-by: Ben Meadors Co-authored-by: Thomas Göttgens --- .gitignore | 2 + arch/esp32/esp32.ini | 2 +- arch/esp32/esp32s2.ini | 5 +- arch/nrf52/nrf52.ini | 2 +- arch/portduino/portduino.ini | 1 + arch/rp2040/rp2040.ini | 2 +- arch/stm32/stm32wl5e.ini | 2 +- bin/config-dist.yaml | 4 + src/main.cpp | 6 + src/mesh/raspihttp/PiWebServer.cpp | 530 +++++++++++++++++++++++ src/mesh/raspihttp/PiWebServer.h | 61 +++ src/platform/portduino/PortduinoGlue.cpp | 5 + src/platform/portduino/PortduinoGlue.h | 5 +- variants/portduino/platformio.ini | 8 +- 14 files changed, 625 insertions(+), 10 deletions(-) create mode 100644 src/mesh/raspihttp/PiWebServer.cpp create mode 100644 src/mesh/raspihttp/PiWebServer.h diff --git a/.gitignore b/.gitignore index 89f8ee065..0f2202f8d 100644 --- a/.gitignore +++ b/.gitignore @@ -31,3 +31,5 @@ venv/ release/ .vscode/extensions.json /compile_commands.json +src/mesh/raspihttp/certificate.pem +src/mesh/raspihttp/private_key.pem \ No newline at end of file diff --git a/arch/esp32/esp32.ini b/arch/esp32/esp32.ini index bf84dd939..39935b849 100644 --- a/arch/esp32/esp32.ini +++ b/arch/esp32/esp32.ini @@ -4,7 +4,7 @@ extends = arduino_base platform = platformio/espressif32@6.3.2 # This is a temporary fix to the S3-based devices bluetooth issues until we can determine what within ESP-IDF changed and can develop a suitable patch. build_src_filter = - ${arduino_base.build_src_filter} - - - - + ${arduino_base.build_src_filter} - - - - - upload_speed = 921600 debug_init_break = tbreak setup diff --git a/arch/esp32/esp32s2.ini b/arch/esp32/esp32s2.ini index 3bde3465a..5de0fa549 100644 --- a/arch/esp32/esp32s2.ini +++ b/arch/esp32/esp32s2.ini @@ -2,7 +2,7 @@ extends = esp32_base build_src_filter = - ${esp32_base.build_src_filter} - + ${esp32_base.build_src_filter} - - monitor_speed = 115200 @@ -12,5 +12,4 @@ build_flags = lib_ignore = ${esp32_base.lib_ignore} - NimBLE-Arduino - + NimBLE-Arduino \ No newline at end of file diff --git a/arch/nrf52/nrf52.ini b/arch/nrf52/nrf52.ini index 04ca89a54..5155eaadc 100644 --- a/arch/nrf52/nrf52.ini +++ b/arch/nrf52/nrf52.ini @@ -11,7 +11,7 @@ build_flags = -Isrc/platform/nrf52 build_src_filter = - ${arduino_base.build_src_filter} - - - - - - - - - + ${arduino_base.build_src_filter} - - - - - - - - - - lib_deps= ${arduino_base.lib_deps} diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index 0dcc9afc2..368fb5d0e 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -12,6 +12,7 @@ build_src_filter = - - - + + - - - diff --git a/arch/rp2040/rp2040.ini b/arch/rp2040/rp2040.ini index 48fe0dae6..edc4373ad 100644 --- a/arch/rp2040/rp2040.ini +++ b/arch/rp2040/rp2040.ini @@ -12,7 +12,7 @@ build_flags = -D__PLAT_RP2040__ # -D _POSIX_THREADS build_src_filter = - ${arduino_base.build_src_filter} - - - - - - - - + ${arduino_base.build_src_filter} - - - - - - - - - lib_ignore = BluetoothOTA diff --git a/arch/stm32/stm32wl5e.ini b/arch/stm32/stm32wl5e.ini index 4483ff526..4d74ade8f 100644 --- a/arch/stm32/stm32wl5e.ini +++ b/arch/stm32/stm32wl5e.ini @@ -13,7 +13,7 @@ build_flags = -DVECT_TAB_OFFSET=0x08000000 build_src_filter = - ${arduino_base.build_src_filter} - - - - - - - - - - - - - + ${arduino_base.build_src_filter} - - - - - - - - - - - - - - board_upload.offset_address = 0x08000000 upload_protocol = stlink diff --git a/bin/config-dist.yaml b/bin/config-dist.yaml index b5b105e4c..a241a929a 100644 --- a/bin/config-dist.yaml +++ b/bin/config-dist.yaml @@ -117,3 +117,7 @@ Input: Logging: LogLevel: info # debug, info, warn, error + +Webserver: +# Port: 443 # Port for Webserver & Webservices +# RootPath: /usr/share/doc/meshtasticd/web # Root Dir of WebServer diff --git a/src/main.cpp b/src/main.cpp index fbfb983d2..3619b0053 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -68,6 +68,7 @@ NRF52Bluetooth *nrf52Bluetooth; #ifdef ARCH_PORTDUINO #include "linux/LinuxHardwareI2C.h" +#include "mesh/raspihttp/PiWebServer.h" #include "platform/portduino/PortduinoGlue.h" #include #include @@ -857,6 +858,11 @@ void setup() #endif #ifdef ARCH_PORTDUINO +#if __has_include() + if (settingsMap[webserverport] != -1) { + piwebServerThread = new PiWebServerThread(); + } +#endif initApiServer(TCPPort); #endif diff --git a/src/mesh/raspihttp/PiWebServer.cpp b/src/mesh/raspihttp/PiWebServer.cpp new file mode 100644 index 000000000..41f6727a4 --- /dev/null +++ b/src/mesh/raspihttp/PiWebServer.cpp @@ -0,0 +1,530 @@ +/* +Adds a WebServer and WebService callbacks to meshtastic as Linux Version. The WebServer & Webservices +runs in a real linux thread beside the portdunio threading emulation. It replaces the complete ESP32 +Webserver libs including generation of SSL certifcicates, because the use ESP specific details in +the lib that can't be emulated. + +The WebServices adapt to the two major phoneapi functions "handleAPIv1FromRadio,handleAPIv1ToRadio" +The WebServer just adds basaic support to deliver WebContent, so it can be used to +deliver the WebGui definded by the WebClient Project. + +Steps to get it running: +1.) Add these Linux Libs to the compile and target machine: + + sudo apt update && \ + apt -y install openssl libssl-dev libopenssl libsdl2-dev \ + libulfius-dev liborcania-dev + +2.) Configure the root directory of the web Content in the config.yaml file. + The followinng tags should be included and set at your needs + + Example entry in the config.yaml + Webserver: + Port: 9001 # Port for Webserver & Webservices + RootPath: /home/marc/web # Root Dir of WebServer + +3.) Checkout the web project + https://github.com/meshtastic/web.git + + Build it and copy the content of the folder web/dist/* to the folder you did set as "RootPath" + +!!!The WebServer should not be used as production system or exposed to the Internet. Its a raw basic version!!! + +Author: Marc Philipp Hammermann +mail: marchammermann@googlemail.com + +*/ +#ifdef PORTDUINO_LINUX_HARDWARE +#if __has_include() +#include "PiWebServer.h" +#include "NodeDB.h" +#include "PhoneAPI.h" +#include "PowerFSM.h" +#include "RadioLibInterface.h" +#include "airtime.h" +#include "graphics/Screen.h" +#include "main.h" +#include "mesh/wifi/WiFiAPClient.h" +#include "sleep.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "PortduinoFS.h" +#include "platform/portduino/PortduinoGlue.h" + +#define DEFAULT_REALM "default_realm" +#define PREFIX "" + +struct _file_config configWeb; + +// We need to specify some content-type mapping, so the resources get delivered with the +// right content type and are displayed correctly in the browser +char contentTypes[][2][32] = {{".txt", "text/plain"}, {".html", "text/html"}, + {".js", "text/javascript"}, {".png", "image/png"}, + {".jpg", "image/jpg"}, {".gz", "application/gzip"}, + {".gif", "image/gif"}, {".json", "application/json"}, + {".css", "text/css"}, {".ico", "image/vnd.microsoft.icon"}, + {".svg", "image/svg+xml"}, {".ts", "text/javascript"}, + {".tsx", "text/javascript"}, {"", ""}}; + +#undef str + +volatile bool isWebServerReady; +volatile bool isCertReady; + +HttpAPI webAPI; + +PiWebServerThread *piwebServerThread; + +/** + * Return the filename extension + */ +const char *get_filename_ext(const char *path) +{ + const char *dot = strrchr(path, '.'); + if (!dot || dot == path) + return "*"; + if (strchr(dot, '?') != NULL) { + //*strchr(dot, '?') = '\0'; + const char *empty = "\0"; + return empty; + } + return dot; +} + +/** + * Streaming callback function to ease sending large files + */ +static ssize_t callback_static_file_stream(void *cls, uint64_t pos, char *buf, size_t max) +{ + (void)(pos); + if (cls != NULL) { + return fread(buf, 1, max, (FILE *)cls); + } else { + return U_STREAM_END; + } +} + +/** + * Cleanup FILE* structure when streaming is complete + */ +static void callback_static_file_stream_free(void *cls) +{ + if (cls != NULL) { + fclose((FILE *)cls); + } +} + +/** + * static file callback endpoint that delivers the content for WebServer calls + */ +int callback_static_file(const struct _u_request *request, struct _u_response *response, void *user_data) +{ + size_t length; + FILE *f; + char *file_requested, *file_path, *url_dup_save, *real_path = NULL; + const char *content_type; + + /* + * Comment this if statement if you don't access static files url from root dir, like /app + */ + if (request->callback_position > 0) { + return U_CALLBACK_CONTINUE; + } else if (user_data != NULL && (configWeb.files_path != NULL)) { + file_requested = o_strdup(request->http_url); + url_dup_save = file_requested; + + while (file_requested[0] == '/') { + file_requested++; + } + file_requested += o_strlen(configWeb.url_prefix); + while (file_requested[0] == '/') { + file_requested++; + } + + if (strchr(file_requested, '#') != NULL) { + *strchr(file_requested, '#') = '\0'; + } + + if (strchr(file_requested, '?') != NULL) { + *strchr(file_requested, '?') = '\0'; + } + + if (file_requested == NULL || o_strlen(file_requested) == 0 || 0 == o_strcmp("/", file_requested)) { + o_free(url_dup_save); + url_dup_save = file_requested = o_strdup("index.html"); + } + + file_path = msprintf("%s/%s", configWeb.files_path, file_requested); + real_path = realpath(file_path, NULL); + if (0 == o_strncmp(configWeb.files_path, real_path, o_strlen(configWeb.files_path))) { + if (access(file_path, F_OK) != -1) { + f = fopen(file_path, "rb"); + if (f) { + fseek(f, 0, SEEK_END); + length = ftell(f); + fseek(f, 0, SEEK_SET); + + content_type = u_map_get_case(&configWeb.mime_types, get_filename_ext(file_requested)); + if (content_type == NULL) { + content_type = u_map_get(&configWeb.mime_types, "*"); + LOG_DEBUG("Static File Server - Unknown mime type for extension %s \n", get_filename_ext(file_requested)); + } + u_map_put(response->map_header, "Content-Type", content_type); + u_map_copy_into(response->map_header, &configWeb.map_header); + + if (ulfius_set_stream_response(response, 200, callback_static_file_stream, callback_static_file_stream_free, + length, STATIC_FILE_CHUNK, f) != U_OK) { + LOG_DEBUG("callback_static_file - Error ulfius_set_stream_response\n "); + } + } + } else { + if (configWeb.redirect_on_404 == NULL) { + ulfius_set_string_body_response(response, 404, "File not found"); + } else { + ulfius_add_header_to_response(response, "Location", configWeb.redirect_on_404); + response->status = 302; + } + } + } else { + if (configWeb.redirect_on_404 == NULL) { + ulfius_set_string_body_response(response, 404, "File not found"); + } else { + ulfius_add_header_to_response(response, "Location", configWeb.redirect_on_404); + response->status = 302; + } + } + + o_free(file_path); + o_free(url_dup_save); + free(real_path); // realpath uses malloc + return U_CALLBACK_CONTINUE; + } else { + LOG_DEBUG("Static File Server - Error, user_data is NULL or inconsistent\n"); + return U_CALLBACK_ERROR; + } +} + +static void handleWebResponse() {} + +/* + * Adapt the radioapi to the Webservice handleAPIv1ToRadio + * Trigger : WebGui(SAVE)->WebServcice->phoneApi + */ +int handleAPIv1ToRadio(const struct _u_request *req, struct _u_response *res, void *user_data) +{ + LOG_DEBUG("handleAPIv1ToRadio web -> radio \n"); + + ulfius_add_header_to_response(res, "Content-Type", "application/x-protobuf"); + ulfius_add_header_to_response(res, "Access-Control-Allow-Headers", "Content-Type"); + ulfius_add_header_to_response(res, "Access-Control-Allow-Origin", "*"); + ulfius_add_header_to_response(res, "Access-Control-Allow-Methods", "PUT, OPTIONS"); + ulfius_add_header_to_response(res, "X-Protobuf-Schema", + "https://raw.githubusercontent.com/meshtastic/protobufs/master/mesh.proto"); + + if (req->http_verb == "OPTIONS") { + ulfius_set_response_properties(res, U_OPT_STATUS, 204); + return U_CALLBACK_CONTINUE; + } + + byte buffer[MAX_TO_FROM_RADIO_SIZE]; + size_t s = req->binary_body_length; + + memcpy(buffer, req->binary_body, MAX_TO_FROM_RADIO_SIZE); + + // FIXME* Problem with portdunio loosing mountpoint maybe because of running in a real sep. thread + + portduinoVFS->mountpoint("/home/marc/.portduino/default"); + + LOG_DEBUG("Received %d bytes from PUT request\n", s); + webAPI.handleToRadio(buffer, s); + LOG_DEBUG("end web->radio \n"); + return U_CALLBACK_COMPLETE; +} + +/* + * Adapt the radioapi to the Webservice handleAPIv1FromRadio + * Trigger : WebGui(POLL)->handleAPIv1FromRadio->phoneapi->Meshtastic(Radio) events + */ +int handleAPIv1FromRadio(const struct _u_request *req, struct _u_response *res, void *user_data) +{ + + // LOG_DEBUG("handleAPIv1FromRadio radio -> web\n"); + std::string valueAll; + + // Status code is 200 OK by default. + ulfius_add_header_to_response(res, "Content-Type", "application/x-protobuf"); + ulfius_add_header_to_response(res, "Access-Control-Allow-Origin", "*"); + ulfius_add_header_to_response(res, "Access-Control-Allow-Methods", "GET"); + ulfius_add_header_to_response(res, "X-Protobuf-Schema", + "https://raw.githubusercontent.com/meshtastic/protobufs/master/mesh.proto"); + + uint8_t txBuf[MAX_STREAM_BUF_SIZE]; + uint32_t len = 1; + + if (valueAll == "true") { + while (len) { + len = webAPI.getFromRadio(txBuf); + ulfius_set_response_properties(res, U_OPT_STATUS, 200, U_OPT_BINARY_BODY, txBuf, len); + const char *tmpa = (const char *)txBuf; + ulfius_set_string_body_response(res, 200, tmpa); + // LOG_DEBUG("\n----webAPI response all:----\n"); + LOG_DEBUG(tmpa); + LOG_DEBUG("\n"); + } + // Otherwise, just return one protobuf + } else { + len = webAPI.getFromRadio(txBuf); + const char *tmpa = (const char *)txBuf; + ulfius_set_binary_body_response(res, 200, tmpa, len); + // LOG_DEBUG("\n----webAPI response:\n"); + LOG_DEBUG(tmpa); + LOG_DEBUG("\n"); + } + + // LOG_DEBUG("end radio->web\n", len); + return U_CALLBACK_COMPLETE; +} + +/* +OpenSSL RSA Key Gen +*/ +int generate_rsa_key(EVP_PKEY **pkey) +{ + EVP_PKEY_CTX *pkey_ctx = EVP_PKEY_CTX_new_id(EVP_PKEY_RSA, NULL); + if (!pkey_ctx) + return -1; + if (EVP_PKEY_keygen_init(pkey_ctx) <= 0) + return -1; + if (EVP_PKEY_CTX_set_rsa_keygen_bits(pkey_ctx, 2048) <= 0) + return -1; + if (EVP_PKEY_keygen(pkey_ctx, pkey) <= 0) + return -1; + EVP_PKEY_CTX_free(pkey_ctx); + return 0; // SUCCESS +} + +int generate_self_signed_x509(EVP_PKEY *pkey, X509 **x509) +{ + *x509 = X509_new(); + if (!*x509) + return -1; + if (X509_set_version(*x509, 2) != 1) + return -1; + ASN1_INTEGER_set(X509_get_serialNumber(*x509), 1); + X509_gmtime_adj(X509_get_notBefore(*x509), 0); + X509_gmtime_adj(X509_get_notAfter(*x509), 31536000L); // 1 YEAR ACCESS + + X509_set_pubkey(*x509, pkey); + + // SET Subject Name + X509_NAME *name = X509_get_subject_name(*x509); + X509_NAME_add_entry_by_txt(name, "C", MBSTRING_ASC, (unsigned char *)"DE", -1, -1, 0); + X509_NAME_add_entry_by_txt(name, "O", MBSTRING_ASC, (unsigned char *)"Meshtastic", -1, -1, 0); + X509_NAME_add_entry_by_txt(name, "CN", MBSTRING_ASC, (unsigned char *)"meshtastic.local", -1, -1, 0); + // Selfsigned, Issuer = Subject + X509_set_issuer_name(*x509, name); + + // Certificate signed with our privte key + if (X509_sign(*x509, pkey, EVP_sha256()) <= 0) + return -1; + + return 0; +} + +char *read_file_into_string(const char *filename) +{ + FILE *file = fopen(filename, "rb"); + if (file == NULL) { + LOG_ERROR("Error reading File : %s \n", filename); + return NULL; + } + + // Size of file + fseek(file, 0, SEEK_END); + long filesize = ftell(file); + rewind(file); + + // reserve mem for file + 1 byte + char *buffer = (char *)malloc(filesize + 1); + if (buffer == NULL) { + LOG_ERROR("Malloc of mem failed for file : %s \n", filename); + fclose(file); + return NULL; + } + + // read content + size_t readSize = fread(buffer, 1, filesize, file); + if (readSize != filesize) { + LOG_ERROR("Error reading file into buffer\n"); + free(buffer); + fclose(file); + return NULL; + } + + // add terminator sign at the end + buffer[filesize] = '\0'; + fclose(file); + return buffer; // return pointer +} + +int PiWebServerThread::CheckSSLandLoad() +{ + // read certificate + cert_pem = read_file_into_string("certificate.pem"); + if (cert_pem == NULL) { + LOG_ERROR("ERROR SSL Certificate File can't be loaded or is missing\n"); + return 1; + } + // read private key + key_pem = read_file_into_string("private_key.pem"); + if (key_pem == NULL) { + LOG_ERROR("ERROR file private_key can't be loaded or is missing\n"); + return 2; + } + + return 0; +} + +int PiWebServerThread::CreateSSLCertificate() +{ + + EVP_PKEY *pkey = NULL; + X509 *x509 = NULL; + + if (generate_rsa_key(&pkey) != 0) { + LOG_ERROR("Error generating RSA-Key.\n"); + return 1; + } + + if (generate_self_signed_x509(pkey, &x509) != 0) { + LOG_ERROR("Error generating of X509-Certificat.\n"); + return 2; + } + + // Ope file to write private key file + FILE *pkey_file = fopen("private_key.pem", "wb"); + if (!pkey_file) { + LOG_ERROR("Error opening private key file.\n"); + return 3; + } + // write private key file + PEM_write_PrivateKey(pkey_file, pkey, NULL, NULL, 0, NULL, NULL); + fclose(pkey_file); + + // open Certificate file + FILE *x509_file = fopen("certificate.pem", "wb"); + if (!x509_file) { + LOG_ERROR("Error opening certificate.\n"); + return 4; + } + // write cirtificate + PEM_write_X509(x509_file, x509); + fclose(x509_file); + + EVP_PKEY_free(pkey); + X509_free(x509); + LOG_INFO("Create SSL Certifictate -certificate.pem- succesfull \n"); + return 0; +} + +void initWebServer() {} + +PiWebServerThread::PiWebServerThread() +{ + int ret, retssl, webservport; + + if (CheckSSLandLoad() != 0) { + CreateSSLCertificate(); + if (CheckSSLandLoad() != 0) { + LOG_ERROR("Major Error Gen & Read SSL Certificate\n"); + } + } + + if (settingsMap[webserverport] != 0) { + webservport = settingsMap[webserverport]; + LOG_INFO("Using webserver port from yaml config. %i \n", webservport); + } else { + LOG_INFO("Webserver port in yaml config set to 0, so defaulting to port 443.\n"); + webservport = 443; + } + + // Web Content Service Instance + if (ulfius_init_instance(&instanceWeb, webservport, NULL, DEFAULT_REALM) != U_OK) { + LOG_ERROR("Webserver couldn't be started, abort execution\n"); + } else { + + LOG_INFO("Webserver started ....\n"); + u_map_init(&configWeb.mime_types); + u_map_put(&configWeb.mime_types, "*", "application/octet-stream"); + u_map_put(&configWeb.mime_types, ".html", "text/html"); + u_map_put(&configWeb.mime_types, ".htm", "text/html"); + u_map_put(&configWeb.mime_types, ".tsx", "application/javascript"); + u_map_put(&configWeb.mime_types, ".ts", "application/javascript"); + u_map_put(&configWeb.mime_types, ".css", "text/css"); + u_map_put(&configWeb.mime_types, ".js", "application/javascript"); + u_map_put(&configWeb.mime_types, ".json", "application/json"); + u_map_put(&configWeb.mime_types, ".png", "image/png"); + u_map_put(&configWeb.mime_types, ".gif", "image/gif"); + u_map_put(&configWeb.mime_types, ".jpeg", "image/jpeg"); + u_map_put(&configWeb.mime_types, ".jpg", "image/jpeg"); + u_map_put(&configWeb.mime_types, ".ttf", "font/ttf"); + u_map_put(&configWeb.mime_types, ".woff", "font/woff"); + u_map_put(&configWeb.mime_types, ".ico", "image/x-icon"); + u_map_put(&configWeb.mime_types, ".svg", "image/svg+xml"); + + webrootpath = settingsStrings[webserverrootpath]; + + configWeb.files_path = (char *)webrootpath.c_str(); + configWeb.url_prefix = ""; + configWeb.rootPath = strdup(portduinoVFS->mountpoint()); + + u_map_put(instanceWeb.default_headers, "Access-Control-Allow-Origin", "*"); + // Maximum body size sent by the client is 1 Kb + instanceWeb.max_post_body_size = 1024; + ulfius_add_endpoint_by_val(&instanceWeb, "GET", PREFIX, "/api/v1/fromradio/*", 1, &handleAPIv1FromRadio, NULL); + ulfius_add_endpoint_by_val(&instanceWeb, "PUT", PREFIX, "/api/v1/toradio/*", 1, &handleAPIv1ToRadio, configWeb.rootPath); + + // Add callback function to all endpoints for the Web Server + ulfius_add_endpoint_by_val(&instanceWeb, "GET", NULL, "/*", 2, &callback_static_file, &configWeb); + + // thats for serving without SSL + // retssl = ulfius_start_framework(&instanceWeb); + + // thats for serving with SSL + retssl = ulfius_start_secure_framework(&instanceWeb, key_pem, cert_pem); + + if (retssl == U_OK) { + LOG_INFO("Web Server framework started on port: %i \n", webservport); + LOG_INFO("Web Server root %s\n", (char *)webrootpath.c_str()); + } else { + LOG_ERROR("Error starting Web Server framework\n"); + } + } +} + +PiWebServerThread::~PiWebServerThread() +{ + u_map_clean(&configWeb.mime_types); + + ulfius_stop_framework(&instanceWeb); + ulfius_stop_framework(&instanceWeb); + free(configWeb.rootPath); + ulfius_clean_instance(&instanceService); + ulfius_clean_instance(&instanceService); + free(cert_pem); + LOG_INFO("End framework"); +} + +#endif +#endif \ No newline at end of file diff --git a/src/mesh/raspihttp/PiWebServer.h b/src/mesh/raspihttp/PiWebServer.h new file mode 100644 index 000000000..c4c49e919 --- /dev/null +++ b/src/mesh/raspihttp/PiWebServer.h @@ -0,0 +1,61 @@ +#pragma once +#ifdef PORTDUINO_LINUX_HARDWARE +#if __has_include() +#include "PhoneAPI.h" +#include "ulfius-cfg.h" +#include "ulfius.h" +#include +#include + +#define STATIC_FILE_CHUNK 256 + +void initWebServer(); +void createSSLCert(); +int callback_static_file(const struct _u_request *request, struct _u_response *response, void *user_data); +const char *get_filename_ext(const char *path); + +struct _file_config { + char *files_path; + char *url_prefix; + struct _u_map mime_types; + struct _u_map map_header; + char *redirect_on_404; + char *rootPath; +}; + +class PiWebServerThread +{ + private: + char *key_pem = NULL; + char *cert_pem = NULL; + // struct _u_map mime_types; + std::string webrootpath; + + public: + PiWebServerThread(); + ~PiWebServerThread(); + int CreateSSLCertificate(); + int CheckSSLandLoad(); + uint32_t requestRestart = 0; + struct _u_instance instanceWeb; + struct _u_instance instanceService; +}; + +class HttpAPI : public PhoneAPI +{ + + public: + // Nothing here yet + + private: + // Nothing here yet + + protected: + /// Check the current underlying physical link to see if the client is currently connected + virtual bool checkIsConnected() override { return true; } // FIXME, be smarter about this +}; + +extern PiWebServerThread *piwebServerThread; + +#endif +#endif \ No newline at end of file diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index 046509fab..997058406 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -195,6 +195,11 @@ void portduinoSetup() settingsStrings[keyboardDevice] = (yamlConfig["Input"]["KeyboardDevice"]).as(""); } + if (yamlConfig["Webserver"]) { + settingsMap[webserverport] = (yamlConfig["Webserver"]["Port"]).as(-1); + settingsStrings[webserverrootpath] = (yamlConfig["Webserver"]["RootPath"]).as(""); + } + } catch (YAML::Exception e) { std::cout << "*** Exception " << e.what() << std::endl; exit(EXIT_FAILURE); diff --git a/src/platform/portduino/PortduinoGlue.h b/src/platform/portduino/PortduinoGlue.h index f8da20e37..3fe5f74bf 100644 --- a/src/platform/portduino/PortduinoGlue.h +++ b/src/platform/portduino/PortduinoGlue.h @@ -33,7 +33,10 @@ enum configNames { displayOffsetY, displayInvert, keyboardDevice, - logoutputlevel + logoutputlevel, + webserver, + webserverport, + webserverrootpath }; enum { no_screen, st7789, st7735, st7735s, ili9341 }; enum { no_touchscreen, xpt2046, stmpe610 }; diff --git a/variants/portduino/platformio.ini b/variants/portduino/platformio.ini index d37c6be21..46417e388 100644 --- a/variants/portduino/platformio.ini +++ b/variants/portduino/platformio.ini @@ -1,6 +1,10 @@ [env:native] extends = portduino_base -build_flags = ${portduino_base.build_flags} -O0 -I variants/portduino +; The pkg-config commands below optionally add link flags. +; the || : is just a "or run the null command" to avoid returning an error code +build_flags = ${portduino_base.build_flags} -O0 -I variants/portduino -I /usr/include + !pkg-config --libs libulfius --silence-errors || : + !pkg-config --libs openssl --silence-errors || : board = cross_platform lib_deps = ${portduino_base.lib_deps} -build_src_filter = ${portduino_base.build_src_filter} \ No newline at end of file +build_src_filter = ${portduino_base.build_src_filter} From 46ad6237859e60eb1e54b3bb5c69baa895d95c3b Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Wed, 6 Mar 2024 17:00:23 -0600 Subject: [PATCH 253/472] Add webroot to .deb --- .github/workflows/package_raspbian.yml | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/.github/workflows/package_raspbian.yml b/.github/workflows/package_raspbian.yml index 2f9a99e58..ee1643fbf 100644 --- a/.github/workflows/package_raspbian.yml +++ b/.github/workflows/package_raspbian.yml @@ -23,6 +23,14 @@ jobs: ref: ${{github.event.pull_request.head.ref}} repository: ${{github.event.pull_request.head.repo.full_name}} + - name: Pull web ui + uses: dsaltares/fetch-gh-release-asset@a40c8b4a0471f9ab81bdf73a010f74cc51476ad4 + with: + repo: meshtastic/web + file: build.tar + target: build.tar + token: ${{ secrets.GITHUB_TOKEN }} + - name: Get release version string run: echo "version=$(./bin/buildinfo.py long)" >> $GITHUB_OUTPUT id: version @@ -37,9 +45,12 @@ jobs: - name: build .debpkg run: | + mkdir -p .debpkg/usr/share/doc/meshtasticd/web mkdir -p .debpkg/usr/sbin mkdir -p .debpkg/etc/meshtasticd mkdir -p .debpkg/usr/lib/systemd/system/ + tar -xf build.tar -C .debpkg/usr/share/doc/meshtasticd/web + gunzip .debpkg/usr/share/doc/meshtasticd/web/*.gz cp release/meshtasticd_linux_aarch64 .debpkg/usr/sbin/meshtasticd cp bin/config-dist.yaml .debpkg/etc/meshtasticd/config.yaml chmod +x .debpkg/usr/sbin/meshtasticd From bfce3938d24b7190ec78e2faf64041b916550139 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Wed, 6 Mar 2024 18:54:09 -0600 Subject: [PATCH 254/472] Add openssl as dependency to meshtasticd .deb --- .github/workflows/package_raspbian.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/package_raspbian.yml b/.github/workflows/package_raspbian.yml index ee1643fbf..377074e95 100644 --- a/.github/workflows/package_raspbian.yml +++ b/.github/workflows/package_raspbian.yml @@ -63,7 +63,7 @@ jobs: maintainer: Jonathan Bennett version: ${{ steps.version.outputs.version }} # refs/tags/v*.*.* arch: arm64 - depends: libyaml-cpp0.7 + depends: libyaml-cpp0.7, openssl desc: Native Linux Meshtastic binary. - uses: actions/upload-artifact@v3 From 2dd751e3391e9c676f78e7b329a0cdccb03f3c40 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 7 Mar 2024 07:06:47 -0600 Subject: [PATCH 255/472] [create-pull-request] automated change (#3346) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/portnums.pb.h | 10 +++++----- src/mesh/generated/meshtastic/telemetry.pb.h | 8 +++++--- 3 files changed, 11 insertions(+), 9 deletions(-) diff --git a/protobufs b/protobufs index 62b7d8b88..5a97acb17 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 62b7d8b884d70aed5ff18c3b0e228095eeb48de2 +Subproject commit 5a97acb17543a10e114675a205e3274a83e721af diff --git a/src/mesh/generated/meshtastic/portnums.pb.h b/src/mesh/generated/meshtastic/portnums.pb.h index 88342e5dc..3f3e9aaee 100644 --- a/src/mesh/generated/meshtastic/portnums.pb.h +++ b/src/mesh/generated/meshtastic/portnums.pb.h @@ -38,19 +38,19 @@ typedef enum _meshtastic_PortNum { ENCODING: Protobuf */ meshtastic_PortNum_REMOTE_HARDWARE_APP = 2, /* The built-in position messaging app. - Payload is a [Position](/docs/developers/protobufs/api#position) message + Payload is a Position message. ENCODING: Protobuf */ meshtastic_PortNum_POSITION_APP = 3, /* The built-in user info app. - Payload is a [User](/docs/developers/protobufs/api#user) message + Payload is a User message. ENCODING: Protobuf */ meshtastic_PortNum_NODEINFO_APP = 4, /* Protocol control packets for mesh protocol use. - Payload is a [Routing](/docs/developers/protobufs/api#routing) message + Payload is a Routing message. ENCODING: Protobuf */ meshtastic_PortNum_ROUTING_APP = 5, /* Admin control packets. - Payload is a [AdminMessage](/docs/developers/protobufs/api#adminmessage) message + Payload is a AdminMessage message. ENCODING: Protobuf */ meshtastic_PortNum_ADMIN_APP = 6, /* Compressed TEXT_MESSAGE payloads. @@ -60,7 +60,7 @@ typedef enum _meshtastic_PortNum { any incoming TEXT_MESSAGE_COMPRESSED_APP payload and convert to TEXT_MESSAGE_APP. */ meshtastic_PortNum_TEXT_MESSAGE_COMPRESSED_APP = 7, /* Waypoint payloads. - Payload is a [Waypoint](/docs/developers/protobufs/api#waypoint) message + Payload is a Waypoint message. ENCODING: Protobuf */ meshtastic_PortNum_WAYPOINT_APP = 8, /* Audio Payloads. diff --git a/src/mesh/generated/meshtastic/telemetry.pb.h b/src/mesh/generated/meshtastic/telemetry.pb.h index fc2780a96..d73c6baa1 100644 --- a/src/mesh/generated/meshtastic/telemetry.pb.h +++ b/src/mesh/generated/meshtastic/telemetry.pb.h @@ -41,7 +41,9 @@ typedef enum _meshtastic_TelemetrySensorType { /* PM2.5 air quality sensor */ meshtastic_TelemetrySensorType_PMSA003I = 13, /* INA3221 3 Channel Voltage / Current Sensor */ - meshtastic_TelemetrySensorType_INA3221 = 14 + meshtastic_TelemetrySensorType_INA3221 = 14, + /* BMP085/BMP180 High accuracy temperature and pressure (older Version of BMP280) */ + meshtastic_TelemetrySensorType_BMP085 = 15 } meshtastic_TelemetrySensorType; /* Struct definitions */ @@ -141,8 +143,8 @@ extern "C" { /* Helper constants for enums */ #define _meshtastic_TelemetrySensorType_MIN meshtastic_TelemetrySensorType_SENSOR_UNSET -#define _meshtastic_TelemetrySensorType_MAX meshtastic_TelemetrySensorType_INA3221 -#define _meshtastic_TelemetrySensorType_ARRAYSIZE ((meshtastic_TelemetrySensorType)(meshtastic_TelemetrySensorType_INA3221+1)) +#define _meshtastic_TelemetrySensorType_MAX meshtastic_TelemetrySensorType_BMP085 +#define _meshtastic_TelemetrySensorType_ARRAYSIZE ((meshtastic_TelemetrySensorType)(meshtastic_TelemetrySensorType_BMP085+1)) From c860493e68112d83f5c3707bd4bc4401d8d681de Mon Sep 17 00:00:00 2001 From: Steven Osborn Date: Thu, 7 Mar 2024 05:11:25 -0800 Subject: [PATCH 256/472] Add delay so GPS and Radio have time to power up (#3334) * Add delay so GPS and Radio have time to power up * reduce the delay a bit * make delay more generic / configurable * remove whitespace changes --- boards/canaryone.json | 2 +- src/main.cpp | 5 +++++ variants/canaryone/variant.h | 3 +++ 3 files changed, 9 insertions(+), 1 deletion(-) diff --git a/boards/canaryone.json b/boards/canaryone.json index d8f966a47..da7c0986f 100644 --- a/boards/canaryone.json +++ b/boards/canaryone.json @@ -7,7 +7,7 @@ "cpu": "cortex-m4", "extra_flags": "-DARDUINO_NRF52840_CANARY -DNRF52840_XXAA", "f_cpu": "64000000L", - "hwids": [["0x239A", "0x4405"]], + "hwids": [["0x239A", "0x4405"], ["0x239A", "0x009F"]], "usb_product": "CanaryOne", "mcu": "nrf52840", "variant": "canaryone", diff --git a/src/main.cpp b/src/main.cpp index 3619b0053..80706d044 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -680,6 +680,11 @@ void setup() digitalWrite(SX126X_ANT_SW, 1); #endif +#ifdef PIN_PWR_DELAY_MS + // This may be required to give the peripherals time to power up. + delay(PIN_PWR_DELAY_MS); +#endif + #ifdef ARCH_PORTDUINO if (settingsMap[use_sx1262]) { if (!rIf) { diff --git a/variants/canaryone/variant.h b/variants/canaryone/variant.h index e31ba3c58..21aa921ce 100644 --- a/variants/canaryone/variant.h +++ b/variants/canaryone/variant.h @@ -103,6 +103,9 @@ static const uint8_t A0 = PIN_A0; #define EXTERNAL_FLASH_DEVICES MX25R1635F #define EXTERNAL_FLASH_USE_QSPI +// Add a delay on startup to allow LoRa and GPS to power up +#define PIN_PWR_DELAY_MS 100 + /* * Lora radio */ From b4940b476daa6817d990f8a019bda741589c76ed Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 7 Mar 2024 15:51:28 -0600 Subject: [PATCH 257/472] Trunk --- boards/canaryone.json | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/boards/canaryone.json b/boards/canaryone.json index da7c0986f..f64a4a7c7 100644 --- a/boards/canaryone.json +++ b/boards/canaryone.json @@ -7,7 +7,10 @@ "cpu": "cortex-m4", "extra_flags": "-DARDUINO_NRF52840_CANARY -DNRF52840_XXAA", "f_cpu": "64000000L", - "hwids": [["0x239A", "0x4405"], ["0x239A", "0x009F"]], + "hwids": [ + ["0x239A", "0x4405"], + ["0x239A", "0x009F"] + ], "usb_product": "CanaryOne", "mcu": "nrf52840", "variant": "canaryone", From 7f1250571679131424952f01a0e44e489a332793 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 7 Mar 2024 15:52:08 -0600 Subject: [PATCH 258/472] Update trunk --- .trunk/trunk.yaml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/.trunk/trunk.yaml b/.trunk/trunk.yaml index af7d3d21d..0826b71d9 100644 --- a/.trunk/trunk.yaml +++ b/.trunk/trunk.yaml @@ -4,19 +4,19 @@ cli: plugins: sources: - id: trunk - ref: v1.4.3 + ref: v1.4.4 uri: https://github.com/trunk-io/plugins lint: enabled: - - trufflehog@3.68.2 + - trufflehog@3.68.5 - yamllint@1.35.1 - bandit@1.7.7 - - checkov@3.2.26 - - terrascan@1.18.11 + - checkov@3.2.32 + - terrascan@1.19.1 - trivy@0.49.1 #- trufflehog@3.63.2-rc0 - taplo@0.8.1 - - ruff@0.2.2 + - ruff@0.3.1 - isort@5.13.2 - markdownlint@0.39.0 - oxipng@9.0.0 From 763ae9f2e2e7db779c80021474162a212fa409e8 Mon Sep 17 00:00:00 2001 From: Thomas Herrmann Date: Sat, 2 Mar 2024 22:14:34 +0100 Subject: [PATCH 259/472] add BMP085 (and BMP180) sensor (temperature and air pressure) --- platformio.ini | 1 + src/detect/ScanI2C.h | 1 + src/detect/ScanI2CTwoWire.cpp | 4 +++ src/main.cpp | 1 + .../Telemetry/EnvironmentTelemetry.cpp | 6 ++++ src/modules/Telemetry/Sensor/BMP085Sensor.cpp | 31 +++++++++++++++++++ src/modules/Telemetry/Sensor/BMP085Sensor.h | 17 ++++++++++ 7 files changed, 61 insertions(+) create mode 100644 src/modules/Telemetry/Sensor/BMP085Sensor.cpp create mode 100644 src/modules/Telemetry/Sensor/BMP085Sensor.h diff --git a/platformio.ini b/platformio.ini index 0033b6e46..b67ddc50a 100644 --- a/platformio.ini +++ b/platformio.ini @@ -116,6 +116,7 @@ lib_deps = adafruit/Adafruit BusIO@^1.11.4 adafruit/Adafruit Unified Sensor@^1.1.11 adafruit/Adafruit BMP280 Library@^2.6.8 + adafruit/Adafruit BMP085 Library@^1.2.4 adafruit/Adafruit BME280 Library@^2.2.2 https://github.com/boschsensortec/Bosch-BSEC2-Library#v1.5.2400 boschsensortec/BME68x Sensor Library@^1.1.40407 diff --git a/src/detect/ScanI2C.h b/src/detect/ScanI2C.h index 2b4b8a735..66e683982 100644 --- a/src/detect/ScanI2C.h +++ b/src/detect/ScanI2C.h @@ -23,6 +23,7 @@ class ScanI2C BME_680, BME_280, BMP_280, + BMP_085, INA260, INA219, INA3221, diff --git a/src/detect/ScanI2CTwoWire.cpp b/src/detect/ScanI2CTwoWire.cpp index 990fb36ea..b6eca5fa4 100644 --- a/src/detect/ScanI2CTwoWire.cpp +++ b/src/detect/ScanI2CTwoWire.cpp @@ -242,6 +242,10 @@ void ScanI2CTwoWire::scanPort(I2CPort port) LOG_INFO("BME-280 sensor found at address 0x%x\n", (uint8_t)addr.address); type = BME_280; break; + case 0x55: + LOG_INFO("BMP-085 or BMP-180 sensor found at address 0x%x\n", (uint8_t)addr.address); + type = BMP_085; + break; default: LOG_INFO("BMP-280 sensor found at address 0x%x\n", (uint8_t)addr.address); type = BMP_280; diff --git a/src/main.cpp b/src/main.cpp index 80706d044..b62ccf986 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -500,6 +500,7 @@ void setup() SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::BME_680, meshtastic_TelemetrySensorType_BME680) SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::BME_280, meshtastic_TelemetrySensorType_BME280) SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::BMP_280, meshtastic_TelemetrySensorType_BMP280) + SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::BMP_085, meshtastic_TelemetrySensorType_BMP085) SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::INA260, meshtastic_TelemetrySensorType_INA260) SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::INA219, meshtastic_TelemetrySensorType_INA219) SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::INA3221, meshtastic_TelemetrySensorType_INA3221) diff --git a/src/modules/Telemetry/EnvironmentTelemetry.cpp b/src/modules/Telemetry/EnvironmentTelemetry.cpp index e501f17c2..d4f423e54 100644 --- a/src/modules/Telemetry/EnvironmentTelemetry.cpp +++ b/src/modules/Telemetry/EnvironmentTelemetry.cpp @@ -16,12 +16,14 @@ // Sensors #include "Sensor/BME280Sensor.h" #include "Sensor/BME680Sensor.h" +#include "Sensor/BMP085Sensor.h" #include "Sensor/BMP280Sensor.h" #include "Sensor/LPS22HBSensor.h" #include "Sensor/MCP9808Sensor.h" #include "Sensor/SHT31Sensor.h" #include "Sensor/SHTC3Sensor.h" +BMP085Sensor bmp085Sensor; BMP280Sensor bmp280Sensor; BME280Sensor bme280Sensor; BME680Sensor bme680Sensor; @@ -67,6 +69,8 @@ int32_t EnvironmentTelemetryModule::runOnce() LOG_INFO("Environment Telemetry: Initializing\n"); // it's possible to have this module enabled, only for displaying values on the screen. // therefore, we should only enable the sensor loop if measurement is also enabled + if (bmp085Sensor.hasSensor()) + result = bmp085Sensor.runOnce(); if (bmp280Sensor.hasSensor()) result = bmp280Sensor.runOnce(); if (bme280Sensor.hasSensor()) @@ -219,6 +223,8 @@ bool EnvironmentTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly) valid = lps22hbSensor.getMetrics(&m); if (shtc3Sensor.hasSensor()) valid = shtc3Sensor.getMetrics(&m); + if (bmp085Sensor.hasSensor()) + valid = bmp085Sensor.getMetrics(&m); if (bmp280Sensor.hasSensor()) valid = bmp280Sensor.getMetrics(&m); if (bme280Sensor.hasSensor()) diff --git a/src/modules/Telemetry/Sensor/BMP085Sensor.cpp b/src/modules/Telemetry/Sensor/BMP085Sensor.cpp new file mode 100644 index 000000000..b0991749b --- /dev/null +++ b/src/modules/Telemetry/Sensor/BMP085Sensor.cpp @@ -0,0 +1,31 @@ +#include "BMP085Sensor.h" +#include "../mesh/generated/meshtastic/telemetry.pb.h" +#include "TelemetrySensor.h" +#include "configuration.h" +#include +#include + +BMP085Sensor::BMP085Sensor() : TelemetrySensor(meshtastic_TelemetrySensorType_BMP085, "BMP085") {} + +int32_t BMP085Sensor::runOnce() +{ + LOG_INFO("Init sensor: %s\n", sensorName); + if (!hasSensor()) { + return DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS; + } + bmp085 = Adafruit_BMP085(); + status = bmp085.begin(nodeTelemetrySensorsMap[sensorType].first, nodeTelemetrySensorsMap[sensorType].second); + + return initI2CSensor(); +} + +void BMP085Sensor::setup() {} + +bool BMP085Sensor::getMetrics(meshtastic_Telemetry *measurement) +{ + LOG_DEBUG("BMP085Sensor::getMetrics\n"); + measurement->variant.environment_metrics.temperature = bmp085.readTemperature(); + measurement->variant.environment_metrics.barometric_pressure = bmp085.readPressure() / 100.0F; + + return true; +} diff --git a/src/modules/Telemetry/Sensor/BMP085Sensor.h b/src/modules/Telemetry/Sensor/BMP085Sensor.h new file mode 100644 index 000000000..c4a9479b9 --- /dev/null +++ b/src/modules/Telemetry/Sensor/BMP085Sensor.h @@ -0,0 +1,17 @@ +#include "../mesh/generated/meshtastic/telemetry.pb.h" +#include "TelemetrySensor.h" +#include + +class BMP085Sensor : public TelemetrySensor +{ + private: + Adafruit_BMP085 bmp085; + + protected: + virtual void setup() override; + + public: + BMP085Sensor(); + virtual int32_t runOnce() override; + virtual bool getMetrics(meshtastic_Telemetry *measurement) override; +}; \ No newline at end of file From 585805c3b96d58224ffd2327fd6b4e1712a84abd Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Fri, 8 Mar 2024 14:13:57 +0100 Subject: [PATCH 260/472] Add original hop limit to header to determine hops used (#3321) * Set `hop_start` in header to determine how many hops each packet traveled * Set hopLimit of response according to hops used by request * Identify neighbors based on `hopStart` and `hopLimit` * NeighborInfo: get all packets and assume a default broadcast interval * Add fail-safe in case node in between is running modified firmware * Add `viaMQTT` and `hopsAway` to NodeInfo * Replace `HOP_RELIABLE` with hopStart for repeated packet --------- Co-authored-by: Ben Meadors --- src/mesh/MeshModule.cpp | 9 ++++++--- src/mesh/MeshModule.h | 3 ++- src/mesh/NodeDB.cpp | 6 ++++++ src/mesh/RadioInterface.cpp | 5 ++++- src/mesh/RadioInterface.h | 6 ++++-- src/mesh/RadioLibInterface.cpp | 7 ++++--- src/mesh/ReliableRouter.cpp | 13 +++++++------ src/mesh/Router.cpp | 9 +++++++-- src/mesh/Router.h | 3 ++- src/modules/NeighborInfoModule.cpp | 12 +++++++++--- src/modules/NeighborInfoModule.h | 3 +++ src/modules/RoutingModule.cpp | 19 +++++++++++++++++-- src/modules/RoutingModule.h | 6 +++++- 13 files changed, 76 insertions(+), 25 deletions(-) diff --git a/src/mesh/MeshModule.cpp b/src/mesh/MeshModule.cpp index 9c6ca78ee..ad0c78108 100644 --- a/src/mesh/MeshModule.cpp +++ b/src/mesh/MeshModule.cpp @@ -32,7 +32,8 @@ MeshModule::~MeshModule() assert(0); // FIXME - remove from list of modules once someone needs this feature } -meshtastic_MeshPacket *MeshModule::allocAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex) +meshtastic_MeshPacket *MeshModule::allocAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex, + uint8_t hopStart, uint8_t hopLimit) { meshtastic_Routing c = meshtastic_Routing_init_default; @@ -49,7 +50,7 @@ meshtastic_MeshPacket *MeshModule::allocAckNak(meshtastic_Routing_Error err, Nod p->priority = meshtastic_MeshPacket_Priority_ACK; - p->hop_limit = config.lora.hop_limit; // Flood ACK back to original sender + p->hop_limit = routingModule->getHopLimitForResponse(hopStart, hopLimit); // Flood ACK back to original sender p->to = to; p->decoded.request_id = idFrom; p->channel = chIndex; @@ -176,7 +177,8 @@ void MeshModule::callPlugins(meshtastic_MeshPacket &mp, RxSource src) // SECURITY NOTE! I considered sending back a different error code if we didn't find the psk (i.e. !isDecoded) // but opted NOT TO. Because it is not a good idea to let remote nodes 'probe' to find out which PSKs were "good" vs // bad. - routingModule->sendAckNak(meshtastic_Routing_Error_NO_RESPONSE, getFrom(&mp), mp.id, mp.channel); + routingModule->sendAckNak(meshtastic_Routing_Error_NO_RESPONSE, getFrom(&mp), mp.id, mp.channel, mp.hop_start, + mp.hop_limit); } } @@ -217,6 +219,7 @@ void setReplyTo(meshtastic_MeshPacket *p, const meshtastic_MeshPacket &to) assert(p->which_payload_variant == meshtastic_MeshPacket_decoded_tag); // Should already be set by now p->to = getFrom(&to); // Make sure that if we are sending to the local node, we use our local node addr, not 0 p->channel = to.channel; // Use the same channel that the request came in on + p->hop_limit = routingModule->getHopLimitForResponse(to.hop_start, to.hop_limit); // No need for an ack if we are just delivering locally (it just generates an ignored ack) p->want_ack = (to.from != 0) ? to.want_ack : false; diff --git a/src/mesh/MeshModule.h b/src/mesh/MeshModule.h index ebe3af1a0..6c431adb4 100644 --- a/src/mesh/MeshModule.h +++ b/src/mesh/MeshModule.h @@ -153,7 +153,8 @@ class MeshModule virtual bool wantUIFrame() { return false; } virtual Observable *getUIFrameObservable() { return NULL; } - meshtastic_MeshPacket *allocAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex); + meshtastic_MeshPacket *allocAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex, + uint8_t hopStart = 0, uint8_t hopLimit = 0); /// Send an error response for the specified packet. meshtastic_MeshPacket *allocErrorResponse(meshtastic_Routing_Error err, const meshtastic_MeshPacket *p); diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index dc8d7540c..787c16a79 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -875,6 +875,12 @@ void NodeDB::updateFrom(const meshtastic_MeshPacket &mp) if (mp.rx_snr) info->snr = mp.rx_snr; // keep the most recent SNR we received for this node. + + info->via_mqtt = mp.via_mqtt; // Store if we received this packet via MQTT + + // If hopStart was set and there wasn't someone messing with the limit in the middle, add hopsAway + if (mp.hop_start != 0 && mp.hop_limit <= mp.hop_start) + info->hops_away = mp.hop_start - mp.hop_limit; } } diff --git a/src/mesh/RadioInterface.cpp b/src/mesh/RadioInterface.cpp index cea3968ce..c10eb26f6 100644 --- a/src/mesh/RadioInterface.cpp +++ b/src/mesh/RadioInterface.cpp @@ -302,6 +302,8 @@ void printPacket(const char *prefix, const meshtastic_MeshPacket *p) out += DEBUG_PORT.mt_sprintf(" rxRSSI=%i", p->rx_rssi); if (p->via_mqtt != 0) out += DEBUG_PORT.mt_sprintf(" via MQTT"); + if (p->hop_start != 0) + out += DEBUG_PORT.mt_sprintf(" hopStart=%d", p->hop_start); if (p->priority != 0) out += DEBUG_PORT.mt_sprintf(" priority=%d", p->priority); @@ -561,6 +563,7 @@ size_t RadioInterface::beginSending(meshtastic_MeshPacket *p) p->hop_limit = HOP_RELIABLE; } h->flags = p->hop_limit | (p->want_ack ? PACKET_FLAGS_WANT_ACK_MASK : 0) | (p->via_mqtt ? PACKET_FLAGS_VIA_MQTT_MASK : 0); + h->flags |= (p->hop_start << PACKET_FLAGS_HOP_START_SHIFT) & PACKET_FLAGS_HOP_START_MASK; // if the sender nodenum is zero, that means uninitialized assert(h->from); @@ -569,4 +572,4 @@ size_t RadioInterface::beginSending(meshtastic_MeshPacket *p) sendingPacket = p; return p->encrypted.size + sizeof(PacketHeader); -} +} \ No newline at end of file diff --git a/src/mesh/RadioInterface.h b/src/mesh/RadioInterface.h index 83c5dae64..f85b3bfa5 100644 --- a/src/mesh/RadioInterface.h +++ b/src/mesh/RadioInterface.h @@ -10,9 +10,11 @@ #define MAX_RHPACKETLEN 256 -#define PACKET_FLAGS_HOP_MASK 0x07 +#define PACKET_FLAGS_HOP_LIMIT_MASK 0x07 #define PACKET_FLAGS_WANT_ACK_MASK 0x08 #define PACKET_FLAGS_VIA_MQTT_MASK 0x10 +#define PACKET_FLAGS_HOP_START_MASK 0xE0 +#define PACKET_FLAGS_HOP_START_SHIFT 5 /** * This structure has to exactly match the wire layout when sent over the radio link. Used to keep compatibility @@ -224,4 +226,4 @@ class RadioInterface }; /// Debug printing for packets -void printPacket(const char *prefix, const meshtastic_MeshPacket *p); +void printPacket(const char *prefix, const meshtastic_MeshPacket *p); \ No newline at end of file diff --git a/src/mesh/RadioLibInterface.cpp b/src/mesh/RadioLibInterface.cpp index 8a2bc53e5..9f42afa6d 100644 --- a/src/mesh/RadioLibInterface.cpp +++ b/src/mesh/RadioLibInterface.cpp @@ -359,8 +359,9 @@ void RadioLibInterface::handleReceiveInterrupt() mp->to = h->to; mp->id = h->id; mp->channel = h->channel; - assert(HOP_MAX <= PACKET_FLAGS_HOP_MASK); // If hopmax changes, carefully check this code - mp->hop_limit = h->flags & PACKET_FLAGS_HOP_MASK; + assert(HOP_MAX <= PACKET_FLAGS_HOP_LIMIT_MASK); // If hopmax changes, carefully check this code + mp->hop_limit = h->flags & PACKET_FLAGS_HOP_LIMIT_MASK; + mp->hop_start = (h->flags & PACKET_FLAGS_HOP_START_MASK) >> PACKET_FLAGS_HOP_START_SHIFT; mp->want_ack = !!(h->flags & PACKET_FLAGS_WANT_ACK_MASK); mp->via_mqtt = !!(h->flags & PACKET_FLAGS_VIA_MQTT_MASK); @@ -407,4 +408,4 @@ void RadioLibInterface::startSend(meshtastic_MeshPacket *txp) // bits enableInterrupt(isrTxLevel0); } -} +} \ No newline at end of file diff --git a/src/mesh/ReliableRouter.cpp b/src/mesh/ReliableRouter.cpp index a1e9f281d..167a248ab 100644 --- a/src/mesh/ReliableRouter.cpp +++ b/src/mesh/ReliableRouter.cpp @@ -71,12 +71,12 @@ bool ReliableRouter::shouldFilterReceived(const meshtastic_MeshPacket *p) i->second.nextTxMsec += iface->getPacketTime(p); } - /* Resend implicit ACKs for repeated packets (assuming the original packet was sent with HOP_RELIABLE) + /* Resend implicit ACKs for repeated packets (hopStart equals hopLimit); * this way if an implicit ACK is dropped and a packet is resent we'll rebroadcast again. * Resending real ACKs is omitted, as you might receive a packet multiple times due to flooding and * flooding this ACK back to the original sender already adds redundancy. */ - if (wasSeenRecently(p, false) && p->hop_limit == HOP_RELIABLE && !MeshModule::currentReply && p->to != nodeDB.getNodeNum()) { - // retransmission on broadcast has hop_limit still equal to HOP_RELIABLE + bool isRepeated = p->hop_start == 0 ? (p->hop_limit == HOP_RELIABLE) : (p->hop_start == p->hop_limit); + if (wasSeenRecently(p, false) && isRepeated && !MeshModule::currentReply && p->to != nodeDB.getNodeNum()) { LOG_DEBUG("Resending implicit ack for a repeated floodmsg\n"); meshtastic_MeshPacket *tosend = packetPool.allocCopy(*p); tosend->hop_limit--; // bump down the hop count @@ -107,10 +107,11 @@ void ReliableRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtas if (MeshModule::currentReply) { LOG_DEBUG("Some other module has replied to this message, no need for a 2nd ack\n"); } else if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) { - sendAckNak(meshtastic_Routing_Error_NONE, getFrom(p), p->id, p->channel); + sendAckNak(meshtastic_Routing_Error_NONE, getFrom(p), p->id, p->channel, p->hop_start, p->hop_limit); } else { // Send a 'NO_CHANNEL' error on the primary channel if want_ack packet destined for us cannot be decoded - sendAckNak(meshtastic_Routing_Error_NO_CHANNEL, getFrom(p), p->id, channels.getPrimaryIndex()); + sendAckNak(meshtastic_Routing_Error_NO_CHANNEL, getFrom(p), p->id, channels.getPrimaryIndex(), p->hop_start, + p->hop_limit); } } @@ -255,4 +256,4 @@ void ReliableRouter::setNextTx(PendingPacket *pending) LOG_DEBUG("Setting next retransmission in %u msecs: ", d); printPacket("", pending->packet); setReceivedMessage(); // Run ASAP, so we can figure out our correct sleep time -} +} \ No newline at end of file diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp index 1d6a2d96b..7657d2268 100644 --- a/src/mesh/Router.cpp +++ b/src/mesh/Router.cpp @@ -132,9 +132,10 @@ meshtastic_MeshPacket *Router::allocForSending() /** * Send an ack or a nak packet back towards whoever sent idFrom */ -void Router::sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex) +void Router::sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex, uint8_t hopStart, + uint8_t hopLimit) { - routingModule->sendAckNak(err, to, idFrom, chIndex); + routingModule->sendAckNak(err, to, idFrom, chIndex, hopStart, hopLimit); } void Router::abortSendAndNak(meshtastic_Routing_Error err, meshtastic_MeshPacket *p) @@ -240,6 +241,10 @@ ErrorCode Router::send(meshtastic_MeshPacket *p) // the lora we need to make sure we have replaced it with our local address p->from = getFrom(p); + // If we are the original transmitter, set the hop limit with which we start + if (p->from == getNodeNum()) + p->hop_start = p->hop_limit; + // If the packet hasn't yet been encrypted, do so now (it might already be encrypted if we are just forwarding it) assert(p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag || diff --git a/src/mesh/Router.h b/src/mesh/Router.h index db810e42e..98486745b 100644 --- a/src/mesh/Router.h +++ b/src/mesh/Router.h @@ -104,7 +104,8 @@ class Router : protected concurrency::OSThread /** * Send an ack or a nak packet back towards whoever sent idFrom */ - void sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex); + void sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex, uint8_t hopStart = 0, + uint8_t hopLimit = 0); private: /** diff --git a/src/modules/NeighborInfoModule.cpp b/src/modules/NeighborInfoModule.cpp index 4541958fa..2e0b04afa 100644 --- a/src/modules/NeighborInfoModule.cpp +++ b/src/modules/NeighborInfoModule.cpp @@ -95,6 +95,7 @@ NeighborInfoModule::NeighborInfoModule() ourPortNum = meshtastic_PortNum_NEIGHBORINFO_APP; if (moduleConfig.neighbor_info.enabled) { + isPromiscuous = true; // Update neighbors from all packets this->loadProtoForModule(); setIntervalFromNow(35 * 1000); } else { @@ -202,9 +203,12 @@ Pass it to an upper client; do not persist this data on the mesh */ bool NeighborInfoModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_NeighborInfo *np) { - if (enabled) { + if (np) { printNeighborInfo("RECEIVED", np); updateNeighbors(mp, np); + } else if (mp.hop_start != 0 && mp.hop_start == mp.hop_limit) { + // If the hopLimit is the same as hopStart, then it is a neighbor + getOrCreateNeighbor(mp.from, mp.from, 0, mp.rx_snr); // Set the broadcast interval to 0, as we don't know it } // Allow others to handle this packet return false; @@ -261,7 +265,7 @@ meshtastic_Neighbor *NeighborInfoModule::getOrCreateNeighbor(NodeNum originalSen nbr->snr = snr; nbr->last_rx_time = getTime(); // Only if this is the original sender, the broadcast interval corresponds to it - if (originalSender == n) + if (originalSender == n && node_broadcast_interval_secs != 0) nbr->node_broadcast_interval_secs = node_broadcast_interval_secs; saveProtoForModule(); // Save the updated neighbor return nbr; @@ -277,8 +281,10 @@ meshtastic_Neighbor *NeighborInfoModule::getOrCreateNeighbor(NodeNum originalSen new_nbr->snr = snr; new_nbr->last_rx_time = getTime(); // Only if this is the original sender, the broadcast interval corresponds to it - if (originalSender == n) + if (originalSender == n && node_broadcast_interval_secs != 0) new_nbr->node_broadcast_interval_secs = node_broadcast_interval_secs; + else // Assume the same broadcast interval as us for the neighbor if we don't know it + new_nbr->node_broadcast_interval_secs = moduleConfig.neighbor_info.update_interval; saveProtoForModule(); // Save the new neighbor return new_nbr; } diff --git a/src/modules/NeighborInfoModule.h b/src/modules/NeighborInfoModule.h index 0e3ec09ca..df5c2c948 100644 --- a/src/modules/NeighborInfoModule.h +++ b/src/modules/NeighborInfoModule.h @@ -75,6 +75,9 @@ class NeighborInfoModule : public ProtobufModule, priva /* Does our periodic broadcast */ int32_t runOnce() override; + // Override wantPacket to say we want to see all packets when enabled, not just those for our port number + virtual bool wantPacket(const meshtastic_MeshPacket *p) override { return enabled; } + /* These are for debugging only */ void printNeighborInfo(const char *header, const meshtastic_NeighborInfo *np); void printNodeDBNodes(const char *header); diff --git a/src/modules/RoutingModule.cpp b/src/modules/RoutingModule.cpp index edeb1fb86..37a7c3755 100644 --- a/src/modules/RoutingModule.cpp +++ b/src/modules/RoutingModule.cpp @@ -36,13 +36,28 @@ meshtastic_MeshPacket *RoutingModule::allocReply() return NULL; } -void RoutingModule::sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex) +void RoutingModule::sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex, uint8_t hopStart, + uint8_t hopLimit) { - auto p = allocAckNak(err, to, idFrom, chIndex); + auto p = allocAckNak(err, to, idFrom, chIndex, hopStart, hopLimit); router->sendLocal(p); // we sometimes send directly to the local node } +uint8_t RoutingModule::getHopLimitForResponse(uint8_t hopStart, uint8_t hopLimit) +{ + if (hopStart != 0) { + // Hops used by the request. If somebody in between running modified firmware modified it, ignore it + uint8_t hopsUsed = hopStart < hopLimit ? config.lora.hop_limit : hopStart - hopLimit; + if (hopsUsed > config.lora.hop_limit) { + return hopsUsed; // If the request used more hops than the limit, use the same amount of hops + } else if (hopsUsed + 2 < config.lora.hop_limit) { + return hopsUsed + 2; // Use only the amount of hops needed with some margin as the way back may be different + } + } + return config.lora.hop_limit; // Use the default hop limit +} + RoutingModule::RoutingModule() : ProtobufModule("routing", meshtastic_PortNum_ROUTING_APP, &meshtastic_Routing_msg) { isPromiscuous = true; diff --git a/src/modules/RoutingModule.h b/src/modules/RoutingModule.h index 06e76cfb4..f085b307b 100644 --- a/src/modules/RoutingModule.h +++ b/src/modules/RoutingModule.h @@ -13,7 +13,11 @@ class RoutingModule : public ProtobufModule */ RoutingModule(); - void sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex); + void sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex, uint8_t hopStart = 0, + uint8_t hopLimit = 0); + + // Given the hopStart and hopLimit upon reception of a request, return the hop limit to use for the response + uint8_t getHopLimitForResponse(uint8_t hopStart, uint8_t hopLimit); protected: friend class Router; From 7da1153c2c913903cc0c8603a81ade22f8cf34a8 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 8 Mar 2024 08:31:49 -0600 Subject: [PATCH 261/472] Fix known_only panic by short circuiting for NULL before checking has_user (#3352) --- src/mesh/Router.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp index 7657d2268..7c739b8f2 100644 --- a/src/mesh/Router.cpp +++ b/src/mesh/Router.cpp @@ -297,7 +297,7 @@ bool perhapsDecode(meshtastic_MeshPacket *p) return false; if (config.device.rebroadcast_mode == meshtastic_Config_DeviceConfig_RebroadcastMode_KNOWN_ONLY && - !nodeDB.getMeshNode(p->from)->has_user) { + (nodeDB.getMeshNode(p->from) == NULL || !nodeDB.getMeshNode(p->from)->has_user)) { LOG_DEBUG("Node 0x%x not in NodeDB. Rebroadcast mode KNOWN_ONLY will ignore packet\n", p->from); return false; } From 5d4d91f77512ca7aa2f0dd07cbb09385f397834c Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Tue, 5 Mar 2024 14:53:42 +1300 Subject: [PATCH 262/472] Move Wireless Paper V1.1 custom hibernate behavior to GxEPD2 --- src/graphics/EInkDisplay2.cpp | 6 +++--- variants/heltec_wireless_paper/variant.h | 1 - 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index aee30c7f8..026a65e6d 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -84,10 +84,10 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit) adafruitDisplay->nextPage(); #endif -#ifndef EINK_NO_HIBERNATE // Only hibernate if controller IC will preserve image memory - // Put screen to sleep to save power (possibly not necessary because we already did poweroff inside of display) + // Power off display hardware + // Most models: deep sleep. + // Wireless Paper V1.1: power off only. Deep sleep clears memory - problems with fast refresh adafruitDisplay->hibernate(); -#endif LOG_DEBUG("done\n"); return true; diff --git a/variants/heltec_wireless_paper/variant.h b/variants/heltec_wireless_paper/variant.h index 28bc8628a..29b8bbbd1 100644 --- a/variants/heltec_wireless_paper/variant.h +++ b/variants/heltec_wireless_paper/variant.h @@ -5,7 +5,6 @@ #define I2C_SCL SCL #define USE_EINK -#define EINK_NO_HIBERNATE /* * eink display pins From 07da13058684b0d5517d3bfd54a3e2d857e9e5a8 Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Thu, 7 Mar 2024 03:26:31 +1300 Subject: [PATCH 263/472] Async full-refresh for EInkDynamicDisplay --- src/graphics/EInkDisplay2.cpp | 25 +++--- src/graphics/EInkDisplay2.h | 7 ++ src/graphics/EInkDynamicDisplay.cpp | 90 +++++++++++++++++-- src/graphics/EInkDynamicDisplay.h | 15 +++- variants/heltec_wireless_paper/platformio.ini | 3 +- .../heltec_wireless_paper_v1/platformio.ini | 3 +- 6 files changed, 117 insertions(+), 26 deletions(-) diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index 026a65e6d..a544833c1 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -71,28 +71,24 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit) } } + // Trigger the refresh in GxEPD2 LOG_DEBUG("Updating E-Paper... "); - -#if false - // Currently unused; rescued from commented-out line during a refactor - // Use a meaningful macro here if variant doesn't want fast refresh - - // Full update mode (slow) - adafruitDisplay->display(false) -#else - // Fast update mode adafruitDisplay->nextPage(); -#endif - // Power off display hardware - // Most models: deep sleep. - // Wireless Paper V1.1: power off only. Deep sleep clears memory - problems with fast refresh - adafruitDisplay->hibernate(); + // End the update process + endUpdate(); LOG_DEBUG("done\n"); return true; } +// End the update process - virtual method, overriden in derived class +void EInkDisplay::endUpdate() +{ + // Power off display hardware, then deep-sleep (Except Wireless Paper V1.1, no deep-sleep) + adafruitDisplay->hibernate(); +} + // Write the buffer to the display memory void EInkDisplay::display(void) { @@ -193,6 +189,7 @@ bool EInkDisplay::connect() // Init GxEPD2 adafruitDisplay->init(); adafruitDisplay->setRotation(3); + adafruitDisplay->clearScreen(); // Clearing now, so the boot logo will draw nice and smoothe (fast refresh) } #elif defined(PCA10059) { diff --git a/src/graphics/EInkDisplay2.h b/src/graphics/EInkDisplay2.h index 75770a3bc..f74416494 100644 --- a/src/graphics/EInkDisplay2.h +++ b/src/graphics/EInkDisplay2.h @@ -45,6 +45,13 @@ class EInkDisplay : public OLEDDisplay */ virtual bool forceDisplay(uint32_t msecLimit = 1000); + /** + * Run any code needed to complete an update, after the physical refresh has completed. + * Split from forceDisplay(), to enable async refresh in derived EInkDynamicDisplay class. + * + */ + virtual void endUpdate(); + /** * shim to make the abstraction happy * diff --git a/src/graphics/EInkDynamicDisplay.cpp b/src/graphics/EInkDynamicDisplay.cpp index ae1e30fe1..75db0e33f 100644 --- a/src/graphics/EInkDynamicDisplay.cpp +++ b/src/graphics/EInkDynamicDisplay.cpp @@ -94,19 +94,29 @@ void EInkDynamicDisplay::adjustRefreshCounters() // Trigger the display update by calling base class bool EInkDynamicDisplay::update() { + // Detemine the refresh mode to use, and start the update bool refreshApproved = determineMode(); if (refreshApproved) EInkDisplay::forceDisplay(0); // Bypass base class' own rate-limiting system - return refreshApproved; // (Unutilized) Base class promises to return true if update ran + +#if defined(HAS_EINK_ASYNCFULL) + if (refreshApproved) + endOrDetach(); // Either endUpdate() right now (fast refresh), or set the async flag (full refresh) +#endif + + return refreshApproved; // (Unutilized) Base class promises to return true if update ran } // Assess situation, pick a refresh type bool EInkDynamicDisplay::determineMode() { - checkWasFlooded(); + checkForPromotion(); +#if defined(HAS_EINK_ASYNCFULL) + checkAsyncFullRefresh(); +#endif checkRateLimiting(); - // If too soon for a new time, abort here + // If too soon for a new frame, or display busy, abort early if (refresh == SKIPPED) { storeAndReset(); return false; // No refresh @@ -116,7 +126,7 @@ bool EInkDynamicDisplay::determineMode() resetRateLimiting(); // Once determineMode() ends, will have to wait again hashImage(); // Generate here, so we can still copy it to previousImageHash, even if we skip the comparison check - LOG_DEBUG("EInkDynamicDisplay: "); // Begin log entry + LOG_DEBUG("determineMode(): "); // Begin log entry // Once mode determined, any remaining checks will bypass checkCosmetic(); @@ -151,13 +161,25 @@ bool EInkDynamicDisplay::determineMode() } } -// Did RESPONSIVE frames previously exceed the rate-limit for fast refresh? -void EInkDynamicDisplay::checkWasFlooded() +// Was a frame skipped (rate, display busy) that should have been a FAST refresh? +void EInkDynamicDisplay::checkForPromotion() { - if (previousReason == EXCEEDED_RATELIMIT_FAST) { - // If so, allow a BACKGROUND frame to draw as RESPONSIVE - // Because we DID want a RESPONSIVE frame last time, we just didn't get it + // If a frame was skipped (rate, display busy), then promote a BACKGROUND frame + // Because we DID want a RESPONSIVE/COSMETIC/DEMAND_FULL frame last time, we just didn't get it + + switch (previousReason) { + case ASYNC_REFRESH_BLOCKED_DEMANDFAST: + setFrameFlag(DEMAND_FAST); + break; + case ASYNC_REFRESH_BLOCKED_COSMETIC: + setFrameFlag(COSMETIC); + break; + case ASYNC_REFRESH_BLOCKED_RESPONSIVE: + case EXCEEDED_RATELIMIT_FAST: setFrameFlag(RESPONSIVE); + break; + default: + break; } } @@ -381,4 +403,54 @@ void EInkDynamicDisplay::resetGhostPixelTracking() } #endif // EINK_LIMIT_GHOSTING_PX +#ifdef HAS_EINK_ASYNCFULL +// Check the status of an "async full-refresh", and run the finish-up code if the hardware is ready +void EInkDynamicDisplay::checkAsyncFullRefresh() +{ + // No refresh taking place, continue with determineMode() + if (!asyncRefreshRunning) + return; + + // Full refresh still running + if (adafruitDisplay->epd2.isBusy()) { + // No refresh + refresh = SKIPPED; + + // Set the reason, marking what type of frame we're skipping + if (frameFlags & DEMAND_FAST) + reason = ASYNC_REFRESH_BLOCKED_DEMANDFAST; + else if (frameFlags & COSMETIC) + reason = ASYNC_REFRESH_BLOCKED_COSMETIC; + else if (frameFlags & RESPONSIVE) + reason = ASYNC_REFRESH_BLOCKED_RESPONSIVE; + else + reason = ASYNC_REFRESH_BLOCKED_BACKGROUND; + + return; + } + + // If we asyncRefreshRunning flag is still set, but display's BUSY pin reports the refresh is done + adafruitDisplay->endAsyncFull(); // Run the end of nextPage() code + EInkDisplay::endUpdate(); // Run base-class code to finish off update (NOT our derived class override) + asyncRefreshRunning = false; // Unset the flag + LOG_DEBUG("Async full-refresh complete\n"); + + // Note: this code only works because of a modification to meshtastic/GxEPD2. + // It is only equipped to intercept calls to nextPage() +} + +// Figure out who runs the post-update code +void EInkDynamicDisplay::endOrDetach() +{ + if (previousRefresh == FULL) { // Note: previousRefresh is the refresh from this loop. + asyncRefreshRunning = true; // Set the flag - picked up at start of determineMode(), next loop. + LOG_DEBUG("Async full-refresh begins\n"); + } + + // Fast Refresh + else + EInkDisplay::endUpdate(); // Still block while updating, but EInkDisplay needs us to call endUpdate() ourselves. +} +#endif // HAS_EINK_ASYNCFULL + #endif // USE_EINK_DYNAMICDISPLAY \ No newline at end of file diff --git a/src/graphics/EInkDynamicDisplay.h b/src/graphics/EInkDynamicDisplay.h index 2880c716b..3dc00ba7c 100644 --- a/src/graphics/EInkDynamicDisplay.h +++ b/src/graphics/EInkDynamicDisplay.h @@ -44,6 +44,11 @@ class EInkDynamicDisplay : public EInkDisplay }; enum reasonTypes : uint8_t { // How was the decision reached NO_OBJECTIONS, + ASYNC_REFRESH_BLOCKED_DEMANDFAST, + ASYNC_REFRESH_BLOCKED_COSMETIC, + ASYNC_REFRESH_BLOCKED_RESPONSIVE, + ASYNC_REFRESH_BLOCKED_BACKGROUND, + DISPLAY_NOT_READY_FOR_FULL, EXCEEDED_RATELIMIT_FAST, EXCEEDED_RATELIMIT_FULL, FLAGGED_COSMETIC, @@ -64,7 +69,7 @@ class EInkDynamicDisplay : public EInkDisplay bool update(); // Trigger the display update - determine mode, then call base class // Checks as part of determineMode() - void checkWasFlooded(); // Was the previous frame skipped for exceeding EINK_LIMIT_RATE_RESPONSIVE_SEC? + void checkForPromotion(); // Was a frame skipped (rate, display busy) that should have been a FAST refresh? void checkRateLimiting(); // Is this frame too soon? void checkCosmetic(); // Was the COSMETIC flag set? void checkDemandingFast(); // Was the DEMAND_FAST flag set? @@ -99,6 +104,14 @@ class EInkDynamicDisplay : public EInkDisplay uint8_t *dirtyPixels; // Any pixels that have been black since last full-refresh (dynamically allocated mem) uint32_t ghostPixelCount = 0; // Number of pixels with problematic ghosting. Retained here for LOG_DEBUG use #endif + + // Conditional - async full refresh - only with modified meshtastic/GxEPD2 +#if defined(HAS_EINK_ASYNCFULL) + void checkAsyncFullRefresh(); // Check the status of "async full-refresh"; run the post-update code if the hardware is ready + void endOrDetach(); // Run the post-update code, or delegate it off to checkAsyncFullRefresh() + void endUpdate() override {} // Disable base-class behavior of running post-update immediately after forceDisplay() + bool asyncRefreshRunning = false; // Flag, checked by checkAsyncFullRefresh() +#endif }; #endif \ No newline at end of file diff --git a/variants/heltec_wireless_paper/platformio.ini b/variants/heltec_wireless_paper/platformio.ini index 0abbe085e..7aebef014 100644 --- a/variants/heltec_wireless_paper/platformio.ini +++ b/variants/heltec_wireless_paper/platformio.ini @@ -16,7 +16,8 @@ build_flags = -D EINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. lib_deps = ${esp32s3_base.lib_deps} - https://github.com/meshtastic/GxEPD2 + ; https://github.com/meshtastic/GxEPD2/ + https://github.com/todd-herbert/meshtastic-GxEPD2#async ; Revert to meshtastic/firmware before submitting PR before final merge adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 upload_speed = 115200 \ No newline at end of file diff --git a/variants/heltec_wireless_paper_v1/platformio.ini b/variants/heltec_wireless_paper_v1/platformio.ini index 4e5e291e0..8cd870353 100644 --- a/variants/heltec_wireless_paper_v1/platformio.ini +++ b/variants/heltec_wireless_paper_v1/platformio.ini @@ -16,7 +16,8 @@ build_flags = ;-D EINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. lib_deps = ${esp32s3_base.lib_deps} - https://github.com/meshtastic/GxEPD2/ + ; https://github.com/meshtastic/GxEPD2/ + https://github.com/todd-herbert/meshtastic-GxEPD2#async ; Revert to meshtastic/firmware before submitting PR before final merge adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 upload_speed = 115200 \ No newline at end of file From ac89bb33871a37005a50ef2b7410b8102186c1d9 Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Fri, 8 Mar 2024 13:16:06 +1300 Subject: [PATCH 264/472] initial config for T-Echo --- variants/t-echo/platformio.ini | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/variants/t-echo/platformio.ini b/variants/t-echo/platformio.ini index 49ba3bb34..f894b1203 100644 --- a/variants/t-echo/platformio.ini +++ b/variants/t-echo/platformio.ini @@ -11,6 +11,12 @@ build_flags = ${nrf52840_base.build_flags} -Ivariants/t-echo -DEINK_DISPLAY_MODEL=GxEPD2_154_D67 -DEINK_WIDTH=200 -DEINK_HEIGHT=200 + -D USE_EINK_DYNAMICDISPLAY ; Enable Dynamic EInk + -D EINK_LIMIT_FASTREFRESH=10 ; How many consecutive fast-refreshes are permitted + -D EINK_LIMIT_RATE_BACKGROUND_SEC=30 ; Minimum interval between BACKGROUND updates + -D EINK_LIMIT_RATE_RESPONSIVE_SEC=1 ; Minimum interval between RESPONSIVE updates + -D EINK_LIMIT_GHOSTING_PX=2000 ; (Optional) How much image ghosting is tolerated + -D EINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. build_src_filter = ${nrf52_base.build_src_filter} +<../variants/t-echo> lib_deps = ${nrf52840_base.lib_deps} From 7275c21f6b054e57a9c2c1b8a418cb1aa047bab5 Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Sat, 9 Mar 2024 09:34:53 +1300 Subject: [PATCH 265/472] formatting responds to https://github.com/meshtastic/firmware/pull/3339#discussion_r1518175434 --- variants/t-echo/platformio.ini | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/variants/t-echo/platformio.ini b/variants/t-echo/platformio.ini index f894b1203..076f1a747 100644 --- a/variants/t-echo/platformio.ini +++ b/variants/t-echo/platformio.ini @@ -11,12 +11,12 @@ build_flags = ${nrf52840_base.build_flags} -Ivariants/t-echo -DEINK_DISPLAY_MODEL=GxEPD2_154_D67 -DEINK_WIDTH=200 -DEINK_HEIGHT=200 - -D USE_EINK_DYNAMICDISPLAY ; Enable Dynamic EInk - -D EINK_LIMIT_FASTREFRESH=10 ; How many consecutive fast-refreshes are permitted - -D EINK_LIMIT_RATE_BACKGROUND_SEC=30 ; Minimum interval between BACKGROUND updates - -D EINK_LIMIT_RATE_RESPONSIVE_SEC=1 ; Minimum interval between RESPONSIVE updates - -D EINK_LIMIT_GHOSTING_PX=2000 ; (Optional) How much image ghosting is tolerated - -D EINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. + -DUSE_EINK_DYNAMICDISPLAY ; Enable Dynamic EInk + -DEINK_LIMIT_FASTREFRESH=10 ; How many consecutive fast-refreshes are permitted + -DEINK_LIMIT_RATE_BACKGROUND_SEC=30 ; Minimum interval between BACKGROUND updates + -DEINK_LIMIT_RATE_RESPONSIVE_SEC=1 ; Minimum interval between RESPONSIVE updates + -DEINK_LIMIT_GHOSTING_PX=2000 ; (Optional) How much image ghosting is tolerated + -DEINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. build_src_filter = ${nrf52_base.build_src_filter} +<../variants/t-echo> lib_deps = ${nrf52840_base.lib_deps} From 23926210d1bcd841b27e15a5119941621be94c72 Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Sat, 9 Mar 2024 09:57:30 +1300 Subject: [PATCH 266/472] increase fast-refresh limit for T-Echo https://github.com/meshtastic/firmware/pull/3339#issuecomment-1986245727 --- variants/t-echo/platformio.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/variants/t-echo/platformio.ini b/variants/t-echo/platformio.ini index 076f1a747..94b6ee087 100644 --- a/variants/t-echo/platformio.ini +++ b/variants/t-echo/platformio.ini @@ -12,7 +12,7 @@ build_flags = ${nrf52840_base.build_flags} -Ivariants/t-echo -DEINK_WIDTH=200 -DEINK_HEIGHT=200 -DUSE_EINK_DYNAMICDISPLAY ; Enable Dynamic EInk - -DEINK_LIMIT_FASTREFRESH=10 ; How many consecutive fast-refreshes are permitted + -DEINK_LIMIT_FASTREFRESH=20 ; How many consecutive fast-refreshes are permitted -DEINK_LIMIT_RATE_BACKGROUND_SEC=30 ; Minimum interval between BACKGROUND updates -DEINK_LIMIT_RATE_RESPONSIVE_SEC=1 ; Minimum interval between RESPONSIVE updates -DEINK_LIMIT_GHOSTING_PX=2000 ; (Optional) How much image ghosting is tolerated From 0f1bc98305c3c6fd56b6d394aaf3d0e1ba1b66b9 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 8 Mar 2024 20:15:00 -0600 Subject: [PATCH 267/472] Update MQTT topic to match (#3353) --- src/mqtt/MQTT.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/mqtt/MQTT.h b/src/mqtt/MQTT.h index 2b803e3fc..e67958b25 100644 --- a/src/mqtt/MQTT.h +++ b/src/mqtt/MQTT.h @@ -80,10 +80,10 @@ class MQTT : private concurrency::OSThread private: std::string statusTopic = "/2/stat/"; - std::string cryptTopic = "/2/c/"; // msh/2/c/CHANNELID/NODEID + std::string cryptTopic = "/2/e/"; // msh/2/e/CHANNELID/NODEID std::string jsonTopic = "/2/json/"; // msh/2/json/CHANNELID/NODEID - /** return true if we have a channel that wants uplink/downlink - */ + /** return true if we have a channel that wants uplink/downlink + */ bool wantsLink() const; /** Tell the server what subscriptions we want (based on channels.downlink_enabled) From 51df4fc7750b5affda52b82f901173195f201293 Mon Sep 17 00:00:00 2001 From: Andre K Date: Fri, 8 Mar 2024 23:15:37 -0300 Subject: [PATCH 268/472] fix: turn off T-Echo peripherals on deep sleep (#3162) Co-authored-by: Ben Meadors --- src/Power.cpp | 5 ----- src/graphics/EInkDisplay2.cpp | 5 ----- src/graphics/Screen.cpp | 3 +++ src/main.cpp | 9 +++++---- src/sleep.cpp | 7 +++++++ variants/rak10701/variant.h | 4 ---- variants/rak4631/variant.h | 4 ---- variants/rak4631_epaper/variant.h | 4 ---- variants/rak4631_epaper_onrxtx/variant.h | 4 ---- variants/t-echo/variant.h | 6 +++--- 10 files changed, 18 insertions(+), 33 deletions(-) diff --git a/src/Power.cpp b/src/Power.cpp index 8e44ddb98..3d1a1b9b2 100644 --- a/src/Power.cpp +++ b/src/Power.cpp @@ -473,11 +473,6 @@ bool Power::setup() void Power::shutdown() { - screen->setOn(false); -#if defined(USE_EINK) && defined(PIN_EINK_EN) - digitalWrite(PIN_EINK_EN, LOW); // power off backlight first -#endif - LOG_INFO("Shutting down\n"); #ifdef HAS_PMU diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index aee30c7f8..6ee4245b3 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -122,11 +122,6 @@ bool EInkDisplay::connect() { LOG_INFO("Doing EInk init\n"); -#ifdef PIN_EINK_PWR_ON - pinMode(PIN_EINK_PWR_ON, OUTPUT); - digitalWrite(PIN_EINK_PWR_ON, HIGH); // If we need to assert a pin to power external peripherals -#endif - #ifdef PIN_EINK_EN // backlight power, HIGH is backlight on, LOW is off pinMode(PIN_EINK_EN, OUTPUT); diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 33df78462..3ffea4a60 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -938,6 +938,9 @@ void Screen::doDeepSleep() static const int sleepFrameCount = sizeof(sleepFrames) / sizeof(sleepFrames[0]); ui->setFrames(sleepFrames, sleepFrameCount); ui->update(); +#ifdef PIN_EINK_EN + digitalWrite(PIN_EINK_EN, LOW); // power off backlight +#endif #endif setOn(false); } diff --git a/src/main.cpp b/src/main.cpp index b62ccf986..ef1cd53c3 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -219,10 +219,11 @@ void setup() initDeepSleep(); - // Testing this fix für erratic T-Echo boot behaviour -#if defined(TTGO_T_ECHO) && defined(PIN_EINK_PWR_ON) - pinMode(PIN_EINK_PWR_ON, OUTPUT); - digitalWrite(PIN_EINK_PWR_ON, HIGH); + // power on peripherals +#if defined(TTGO_T_ECHO) && defined(PIN_POWER_EN) + pinMode(PIN_POWER_EN, OUTPUT); + digitalWrite(PIN_POWER_EN, HIGH); + digitalWrite(PIN_POWER_EN1, INPUT); #endif #if defined(VEXT_ENABLE_V03) diff --git a/src/sleep.cpp b/src/sleep.cpp index 1afba1173..bfacffeb9 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -200,6 +200,13 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) nodeDB.saveToDisk(); +#ifdef TTGO_T_ECHO +#ifdef PIN_POWER_EN + pinMode(PIN_POWER_EN, INPUT); // power off peripherals + pinMode(PIN_POWER_EN1, INPUT_PULLDOWN); +#endif +#endif + // Kill GPS power completely (even if previously we just had it in sleep mode) if (gps) gps->setGPSPower(false, false, 0); diff --git a/variants/rak10701/variant.h b/variants/rak10701/variant.h index 837d081ff..d6eeb71dc 100644 --- a/variants/rak10701/variant.h +++ b/variants/rak10701/variant.h @@ -133,10 +133,6 @@ static const uint8_t SCK = PIN_SPI_SCK; #define PIN_EINK_SCLK (0 + 3) #define PIN_EINK_MOSI (0 + 30) // also called SDI -// Controls power for the eink display - Board power is enabled either by VBUS from USB or the CPU asserting PWR_ON -// FIXME - I think this is actually just the board power enable - it enables power to the CPU also -// #define PIN_EINK_PWR_ON (-1) - // #define USE_EINK // RAKRGB diff --git a/variants/rak4631/variant.h b/variants/rak4631/variant.h index 4ad99df44..0ccf3b1d7 100644 --- a/variants/rak4631/variant.h +++ b/variants/rak4631/variant.h @@ -133,10 +133,6 @@ static const uint8_t SCK = PIN_SPI_SCK; #define PIN_EINK_SCLK (0 + 3) #define PIN_EINK_MOSI (0 + 30) // also called SDI -// Controls power for the eink display - Board power is enabled either by VBUS from USB or the CPU asserting PWR_ON -// FIXME - I think this is actually just the board power enable - it enables power to the CPU also -// #define PIN_EINK_PWR_ON (-1) - // #define USE_EINK // RAKRGB diff --git a/variants/rak4631_epaper/variant.h b/variants/rak4631_epaper/variant.h index d8a5e5597..b1bd84d21 100644 --- a/variants/rak4631_epaper/variant.h +++ b/variants/rak4631_epaper/variant.h @@ -133,10 +133,6 @@ static const uint8_t SCK = PIN_SPI_SCK; #define PIN_EINK_SCLK (0 + 3) #define PIN_EINK_MOSI (0 + 30) // also called SDI -// Controls power for the eink display - Board power is enabled either by VBUS from USB or the CPU asserting PWR_ON -// FIXME - I think this is actually just the board power enable - it enables power to the CPU also -// #define PIN_EINK_PWR_ON (-1) - #define USE_EINK // RAKRGB diff --git a/variants/rak4631_epaper_onrxtx/variant.h b/variants/rak4631_epaper_onrxtx/variant.h index 411e3eb17..ec53ebd33 100644 --- a/variants/rak4631_epaper_onrxtx/variant.h +++ b/variants/rak4631_epaper_onrxtx/variant.h @@ -119,10 +119,6 @@ static const uint8_t SCK = PIN_SPI_SCK; #define PIN_EINK_SCLK (0 + 14) // SCL #define PIN_EINK_MOSI (0 + 13) // SDA -// Controls power for the eink display - Board power is enabled either by VBUS from USB or the CPU asserting PWR_ON -// FIXME - I think this is actually just the board power enable - it enables power to the CPU also -// #define PIN_EINK_PWR_ON (-1) - // RAKRGB #define HAS_NCP5623 diff --git a/variants/t-echo/variant.h b/variants/t-echo/variant.h index 1af68863e..19a66719f 100644 --- a/variants/t-echo/variant.h +++ b/variants/t-echo/variant.h @@ -156,9 +156,9 @@ External serial flash WP25R1635FZUIL0 #define PIN_EINK_SCLK (0 + 31) #define PIN_EINK_MOSI (0 + 29) // also called SDI -// Controls power for the eink display - Board power is enabled either by VBUS from USB or the CPU asserting PWR_ON -// FIXME - I think this is actually just the board power enable - it enables power to the CPU also -#define PIN_EINK_PWR_ON (0 + 12) +// Controls power for all peripherals (eink + GPS + LoRa + Sensor) +#define PIN_POWER_EN (0 + 12) +#define PIN_POWER_EN1 (0 + 13) #define USE_EINK From 29335a18f58d10ca7f86a234c921f5b3b8e1e469 Mon Sep 17 00:00:00 2001 From: Mark Trevor Birss Date: Sat, 9 Mar 2024 14:55:02 +0200 Subject: [PATCH 269/472] Update variant.h (#3354) --- variants/heltec_esp32c3/variant.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/variants/heltec_esp32c3/variant.h b/variants/heltec_esp32c3/variant.h index de6462a38..6641f9d21 100644 --- a/variants/heltec_esp32c3/variant.h +++ b/variants/heltec_esp32c3/variant.h @@ -9,7 +9,7 @@ #define LED_PIN 18 // LED #define LED_INVERTED 1 -#define HAS_SCREEN 0 +#define HAS_SCREEN 1 #define HAS_GPS 0 #undef GPS_RX_PIN #undef GPS_TX_PIN From 3efd606ea7fcc7cda763eff3d5cbab0aa80c2447 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sat, 9 Mar 2024 07:01:46 -0600 Subject: [PATCH 270/472] Bump to 2.3.0 --- version.properties | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/version.properties b/version.properties index 14d1884fb..8927d1781 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 -minor = 2 -build = 25 +minor = 3 +build = 0 From d5c11d18922301864617ff160468bb39751916e0 Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Sun, 10 Mar 2024 02:11:49 +1300 Subject: [PATCH 271/472] change dependency from private repo to meshtastic/GxEPD2 --- variants/heltec_wireless_paper/platformio.ini | 3 +-- variants/heltec_wireless_paper_v1/platformio.ini | 3 +-- variants/t-echo/platformio.ini | 2 +- 3 files changed, 3 insertions(+), 5 deletions(-) diff --git a/variants/heltec_wireless_paper/platformio.ini b/variants/heltec_wireless_paper/platformio.ini index 7aebef014..14275830a 100644 --- a/variants/heltec_wireless_paper/platformio.ini +++ b/variants/heltec_wireless_paper/platformio.ini @@ -16,8 +16,7 @@ build_flags = -D EINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. lib_deps = ${esp32s3_base.lib_deps} - ; https://github.com/meshtastic/GxEPD2/ - https://github.com/todd-herbert/meshtastic-GxEPD2#async ; Revert to meshtastic/firmware before submitting PR before final merge + https://github.com/meshtastic/GxEPD2/ adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 upload_speed = 115200 \ No newline at end of file diff --git a/variants/heltec_wireless_paper_v1/platformio.ini b/variants/heltec_wireless_paper_v1/platformio.ini index 8cd870353..4e5e291e0 100644 --- a/variants/heltec_wireless_paper_v1/platformio.ini +++ b/variants/heltec_wireless_paper_v1/platformio.ini @@ -16,8 +16,7 @@ build_flags = ;-D EINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. lib_deps = ${esp32s3_base.lib_deps} - ; https://github.com/meshtastic/GxEPD2/ - https://github.com/todd-herbert/meshtastic-GxEPD2#async ; Revert to meshtastic/firmware before submitting PR before final merge + https://github.com/meshtastic/GxEPD2/ adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 upload_speed = 115200 \ No newline at end of file diff --git a/variants/t-echo/platformio.ini b/variants/t-echo/platformio.ini index 94b6ee087..c97341a3b 100644 --- a/variants/t-echo/platformio.ini +++ b/variants/t-echo/platformio.ini @@ -20,7 +20,7 @@ build_flags = ${nrf52840_base.build_flags} -Ivariants/t-echo build_src_filter = ${nrf52_base.build_src_filter} +<../variants/t-echo> lib_deps = ${nrf52840_base.lib_deps} - https://github.com/meshtastic/GxEPD2#afce87a97dda1ac31d8a28dc8fa7c6f55dc96a61 + https://github.com/meshtastic/GxEPD2 adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 ;upload_protocol = fs From 576f582cd9a41ac877f11129a834cac9d18e4b81 Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Sun, 10 Mar 2024 02:30:16 +1300 Subject: [PATCH 272/472] rename setFrameFlag() method --- src/graphics/EInkDynamicDisplay.cpp | 12 ++++++------ src/graphics/EInkDynamicDisplay.h | 2 +- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/graphics/EInkDynamicDisplay.cpp b/src/graphics/EInkDynamicDisplay.cpp index 75db0e33f..c9bd5b22b 100644 --- a/src/graphics/EInkDynamicDisplay.cpp +++ b/src/graphics/EInkDynamicDisplay.cpp @@ -25,19 +25,19 @@ EInkDynamicDisplay::~EInkDynamicDisplay() // Screen requests a BACKGROUND frame void EInkDynamicDisplay::display() { - setFrameFlag(BACKGROUND); + addFrameFlag(BACKGROUND); update(); } // Screen requests a RESPONSIVE frame bool EInkDynamicDisplay::forceDisplay(uint32_t msecLimit) { - setFrameFlag(RESPONSIVE); + addFrameFlag(RESPONSIVE); return update(); // (Unutilized) Base class promises to return true if update ran } // Add flag for the next frame -void EInkDynamicDisplay::setFrameFlag(frameFlagTypes flag) +void EInkDynamicDisplay::addFrameFlag(frameFlagTypes flag) { // OR the new flag into the existing flags this->frameFlags = (frameFlagTypes)(this->frameFlags | flag); @@ -169,14 +169,14 @@ void EInkDynamicDisplay::checkForPromotion() switch (previousReason) { case ASYNC_REFRESH_BLOCKED_DEMANDFAST: - setFrameFlag(DEMAND_FAST); + addFrameFlag(DEMAND_FAST); break; case ASYNC_REFRESH_BLOCKED_COSMETIC: - setFrameFlag(COSMETIC); + addFrameFlag(COSMETIC); break; case ASYNC_REFRESH_BLOCKED_RESPONSIVE: case EXCEEDED_RATELIMIT_FAST: - setFrameFlag(RESPONSIVE); + addFrameFlag(RESPONSIVE); break; default: break; diff --git a/src/graphics/EInkDynamicDisplay.h b/src/graphics/EInkDynamicDisplay.h index 3dc00ba7c..1eeb28f81 100644 --- a/src/graphics/EInkDynamicDisplay.h +++ b/src/graphics/EInkDynamicDisplay.h @@ -29,7 +29,7 @@ class EInkDynamicDisplay : public EInkDisplay COSMETIC = (1 << 2), // For splashes DEMAND_FAST = (1 << 3), // Special case only }; - void setFrameFlag(frameFlagTypes flag); + void addFrameFlag(frameFlagTypes flag); // Set the correct frame flag, then call universal "update()" method void display() override; From efd818fe903dc042aa92ae78ea940466689e67ae Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Sun, 10 Mar 2024 03:07:13 +1300 Subject: [PATCH 273/472] move storeAndReset() to end of update() --- src/graphics/EInkDynamicDisplay.cpp | 14 +++++++------- src/graphics/EInkDynamicDisplay.h | 7 ++++--- 2 files changed, 11 insertions(+), 10 deletions(-) diff --git a/src/graphics/EInkDynamicDisplay.cpp b/src/graphics/EInkDynamicDisplay.cpp index c9bd5b22b..0a4d9691d 100644 --- a/src/graphics/EInkDynamicDisplay.cpp +++ b/src/graphics/EInkDynamicDisplay.cpp @@ -104,6 +104,7 @@ bool EInkDynamicDisplay::update() endOrDetach(); // Either endUpdate() right now (fast refresh), or set the async flag (full refresh) #endif + storeAndReset(); // Store the result of this loop for next time return refreshApproved; // (Unutilized) Base class promises to return true if update ran } @@ -117,10 +118,8 @@ bool EInkDynamicDisplay::determineMode() checkRateLimiting(); // If too soon for a new frame, or display busy, abort early - if (refresh == SKIPPED) { - storeAndReset(); + if (refresh == SKIPPED) return false; // No refresh - } // -- New frame is due -- @@ -152,12 +151,12 @@ bool EInkDynamicDisplay::determineMode() #endif // Return - call a refresh or not? - if (refresh == SKIPPED) { - storeAndReset(); + if (refresh == SKIPPED) return false; // Don't trigger a refresh - } else { - storeAndReset(); + else return true; // Do trigger a refresh +} + } } @@ -335,6 +334,7 @@ void EInkDynamicDisplay::hashImage() // Store the results of determineMode() for future use, and reset for next call void EInkDynamicDisplay::storeAndReset() { + previousFrameFlags = frameFlags; previousRefresh = refresh; previousReason = reason; diff --git a/src/graphics/EInkDynamicDisplay.h b/src/graphics/EInkDynamicDisplay.h index 1eeb28f81..ad4d9bfd9 100644 --- a/src/graphics/EInkDynamicDisplay.h +++ b/src/graphics/EInkDynamicDisplay.h @@ -82,13 +82,14 @@ class EInkDynamicDisplay : public EInkDisplay void storeAndReset(); // Keep results of determineMode() for later, tidy-up for next call // What we are determining for this frame - frameFlagTypes frameFlags = BACKGROUND; // Frame type(s) - determineMode() input + frameFlagTypes frameFlags = BACKGROUND; // Frame characteristics - determineMode() input refreshTypes refresh = UNSPECIFIED; // Refresh type - determineMode() output reasonTypes reason = NO_OBJECTIONS; // Reason - why was refresh type used // What happened last time determineMode() ran - refreshTypes previousRefresh = UNSPECIFIED; // (Previous) Outcome - reasonTypes previousReason = NO_OBJECTIONS; // (Previous) Reason + frameFlagTypes previousFrameFlags = BACKGROUND; // (Previous) Frame flags + refreshTypes previousRefresh = UNSPECIFIED; // (Previous) Outcome + reasonTypes previousReason = NO_OBJECTIONS; // (Previous) Reason uint32_t previousRunMs = -1; // When did determineMode() last run (rather than rejecting for rate-limiting) uint32_t imageHash = 0; // Hash of the current frame. Don't bother updating if nothing has changed! From 95b6f27d2a9dcd436070b81524fbe583e342aa6a Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Sun, 10 Mar 2024 03:38:39 +1300 Subject: [PATCH 274/472] change order of determineMode() checks --- src/graphics/EInkDynamicDisplay.cpp | 34 ++++++++++++++--------------- src/graphics/EInkDynamicDisplay.h | 2 +- 2 files changed, 18 insertions(+), 18 deletions(-) diff --git a/src/graphics/EInkDynamicDisplay.cpp b/src/graphics/EInkDynamicDisplay.cpp index 0a4d9691d..7666820bd 100644 --- a/src/graphics/EInkDynamicDisplay.cpp +++ b/src/graphics/EInkDynamicDisplay.cpp @@ -130,11 +130,11 @@ bool EInkDynamicDisplay::determineMode() // Once mode determined, any remaining checks will bypass checkCosmetic(); checkDemandingFast(); - checkConsecutiveFastRefreshes(); #ifdef EINK_LIMIT_GHOSTING_PX checkExcessiveGhosting(); #endif checkFrameMatchesPrevious(); + checkConsecutiveFastRefreshes(); checkFastRequested(); if (refresh == UNSPECIFIED) @@ -244,21 +244,6 @@ void EInkDynamicDisplay::checkDemandingFast() } } -// Have too many fast-refreshes occured consecutively, since last full refresh? -void EInkDynamicDisplay::checkConsecutiveFastRefreshes() -{ - // If a decision was already reached, don't run the check - if (refresh != UNSPECIFIED) - return; - - // If too many FAST refreshes consecutively - force a FULL refresh - if (fastRefreshCount >= EINK_LIMIT_FASTREFRESH) { - refresh = FULL; - reason = EXCEEDED_LIMIT_FASTREFRESH; - LOG_DEBUG("refresh=FULL, reason=EXCEEDED_LIMIT_FASTREFRESH\n"); - } -} - // Does the new frame match the currently displayed image? void EInkDynamicDisplay::checkFrameMatchesPrevious() { @@ -283,7 +268,22 @@ void EInkDynamicDisplay::checkFrameMatchesPrevious() // Not redrawn, not COSMETIC, not DEMAND_FAST refresh = SKIPPED; reason = FRAME_MATCHED_PREVIOUS; - LOG_DEBUG("refresh=SKIPPED, reason=FRAME_MATCHED_PREVIOUS\n"); + LOG_DEBUG("refresh=SKIPPED, reason=FRAME_MATCHED_PREVIOUS, frameFlags=0x%x\n", frameFlags); +} + +// Have too many fast-refreshes occured consecutively, since last full refresh? +void EInkDynamicDisplay::checkConsecutiveFastRefreshes() +{ + // If a decision was already reached, don't run the check + if (refresh != UNSPECIFIED) + return; + + // If too many FAST refreshes consecutively - force a FULL refresh + if (fastRefreshCount >= EINK_LIMIT_FASTREFRESH) { + refresh = FULL; + reason = EXCEEDED_LIMIT_FASTREFRESH; + LOG_DEBUG("refresh=FULL, reason=EXCEEDED_LIMIT_FASTREFRESH\n"); + } } // No objections, we can perform fast-refresh, if desired diff --git a/src/graphics/EInkDynamicDisplay.h b/src/graphics/EInkDynamicDisplay.h index ad4d9bfd9..b3e091fb2 100644 --- a/src/graphics/EInkDynamicDisplay.h +++ b/src/graphics/EInkDynamicDisplay.h @@ -73,8 +73,8 @@ class EInkDynamicDisplay : public EInkDisplay void checkRateLimiting(); // Is this frame too soon? void checkCosmetic(); // Was the COSMETIC flag set? void checkDemandingFast(); // Was the DEMAND_FAST flag set? - void checkConsecutiveFastRefreshes(); // Too many fast-refreshes consecutively? void checkFrameMatchesPrevious(); // Does the new frame match the existing display image? + void checkConsecutiveFastRefreshes(); // Too many fast-refreshes consecutively? void checkFastRequested(); // Was the flag set for RESPONSIVE, or only BACKGROUND? void resetRateLimiting(); // Set previousRunMs - this now counts as an update, for rate-limiting From 94794edd43392836ddbd88471f6575bc859ac676 Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Sun, 10 Mar 2024 03:43:07 +1300 Subject: [PATCH 275/472] add init code as a determineMode() check --- src/graphics/EInkDisplay2.cpp | 1 - src/graphics/EInkDynamicDisplay.cpp | 16 ++++++++++++++++ src/graphics/EInkDynamicDisplay.h | 2 ++ 3 files changed, 18 insertions(+), 1 deletion(-) diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index 6f7885b45..0c5fab4fb 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -184,7 +184,6 @@ bool EInkDisplay::connect() // Init GxEPD2 adafruitDisplay->init(); adafruitDisplay->setRotation(3); - adafruitDisplay->clearScreen(); // Clearing now, so the boot logo will draw nice and smoothe (fast refresh) } #elif defined(PCA10059) { diff --git a/src/graphics/EInkDynamicDisplay.cpp b/src/graphics/EInkDynamicDisplay.cpp index 7666820bd..8ff8dc4af 100644 --- a/src/graphics/EInkDynamicDisplay.cpp +++ b/src/graphics/EInkDynamicDisplay.cpp @@ -111,6 +111,7 @@ bool EInkDynamicDisplay::update() // Assess situation, pick a refresh type bool EInkDynamicDisplay::determineMode() { + checkInitialized(); checkForPromotion(); #if defined(HAS_EINK_ASYNCFULL) checkAsyncFullRefresh(); @@ -157,6 +158,21 @@ bool EInkDynamicDisplay::determineMode() return true; // Do trigger a refresh } +// Is this the very first frame? +void EInkDynamicDisplay::checkInitialized() +{ + if (!initialized) { + // Undo GxEPD2_BW::partialWindow(), if set by developer in EInkDisplay::connect() + configForFullRefresh(); + + // Clear any existing image, so we can draw logo with fast-refresh, but also to set GxEPD2_EPD::_initial_write + adafruitDisplay->clearScreen(); + + LOG_DEBUG("initialized, "); + initialized = true; + + // Use a fast-refresh for the next frame; no skipping or else blank screen when waking from deep sleep + addFrameFlag(DEMAND_FAST); } } diff --git a/src/graphics/EInkDynamicDisplay.h b/src/graphics/EInkDynamicDisplay.h index b3e091fb2..48540a132 100644 --- a/src/graphics/EInkDynamicDisplay.h +++ b/src/graphics/EInkDynamicDisplay.h @@ -69,6 +69,7 @@ class EInkDynamicDisplay : public EInkDisplay bool update(); // Trigger the display update - determine mode, then call base class // Checks as part of determineMode() + void checkInitialized(); // Is this the very first frame? void checkForPromotion(); // Was a frame skipped (rate, display busy) that should have been a FAST refresh? void checkRateLimiting(); // Is this frame too soon? void checkCosmetic(); // Was the COSMETIC flag set? @@ -91,6 +92,7 @@ class EInkDynamicDisplay : public EInkDisplay refreshTypes previousRefresh = UNSPECIFIED; // (Previous) Outcome reasonTypes previousReason = NO_OBJECTIONS; // (Previous) Reason + bool initialized = false; // Have we drawn at least one frame yet? uint32_t previousRunMs = -1; // When did determineMode() last run (rather than rejecting for rate-limiting) uint32_t imageHash = 0; // Hash of the current frame. Don't bother updating if nothing has changed! uint32_t previousImageHash = 0; // Hash of the previous update's frame From e232e3462c58bd67711a1706351f3d5a4adb61d6 Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Sun, 10 Mar 2024 03:48:59 +1300 Subject: [PATCH 276/472] add BLOCKING modifier to frameFlagTypes --- src/graphics/EInkDynamicDisplay.cpp | 21 +++++++++++++++++++-- src/graphics/EInkDynamicDisplay.h | 2 ++ 2 files changed, 21 insertions(+), 2 deletions(-) diff --git a/src/graphics/EInkDynamicDisplay.cpp b/src/graphics/EInkDynamicDisplay.cpp index 8ff8dc4af..2b3659099 100644 --- a/src/graphics/EInkDynamicDisplay.cpp +++ b/src/graphics/EInkDynamicDisplay.cpp @@ -458,15 +458,32 @@ void EInkDynamicDisplay::checkAsyncFullRefresh() // Figure out who runs the post-update code void EInkDynamicDisplay::endOrDetach() { - if (previousRefresh == FULL) { // Note: previousRefresh is the refresh from this loop. + if (refresh == FULL) { asyncRefreshRunning = true; // Set the flag - picked up at start of determineMode(), next loop. - LOG_DEBUG("Async full-refresh begins\n"); + + if (frameFlags & BLOCKING) + awaitRefresh(); + else + LOG_DEBUG("Async full-refresh begins\n"); } // Fast Refresh else EInkDisplay::endUpdate(); // Still block while updating, but EInkDisplay needs us to call endUpdate() ourselves. } + +// Hold control while an async refresh runs +void EInkDynamicDisplay::awaitRefresh() +{ + // Continually poll the BUSY pin + while (adafruitDisplay->epd2.isBusy()) + yield(); + + // End the full-refresh process + adafruitDisplay->endAsyncFull(); // Run the end of nextPage() code + EInkDisplay::endUpdate(); // Run base-class code to finish off update (NOT our derived class override) + asyncRefreshRunning = false; // Unset the flag +} #endif // HAS_EINK_ASYNCFULL #endif // USE_EINK_DYNAMICDISPLAY \ No newline at end of file diff --git a/src/graphics/EInkDynamicDisplay.h b/src/graphics/EInkDynamicDisplay.h index 48540a132..ed5be70cd 100644 --- a/src/graphics/EInkDynamicDisplay.h +++ b/src/graphics/EInkDynamicDisplay.h @@ -28,6 +28,7 @@ class EInkDynamicDisplay : public EInkDisplay RESPONSIVE = (1 << 1), // For frames via forceDisplay() COSMETIC = (1 << 2), // For splashes DEMAND_FAST = (1 << 3), // Special case only + BLOCKING = (1 << 4), // Modifier - block while refresh runs }; void addFrameFlag(frameFlagTypes flag); @@ -112,6 +113,7 @@ class EInkDynamicDisplay : public EInkDisplay #if defined(HAS_EINK_ASYNCFULL) void checkAsyncFullRefresh(); // Check the status of "async full-refresh"; run the post-update code if the hardware is ready void endOrDetach(); // Run the post-update code, or delegate it off to checkAsyncFullRefresh() + void awaitRefresh(); // Hold control while an async refresh runs void endUpdate() override {} // Disable base-class behavior of running post-update immediately after forceDisplay() bool asyncRefreshRunning = false; // Flag, checked by checkAsyncFullRefresh() #endif From a9c07a4c016f330cf6a50c3dd8ed61ab0e535453 Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Sun, 10 Mar 2024 04:07:51 +1300 Subject: [PATCH 277/472] add frameFlags to LOG_DEBUG() messages --- src/graphics/EInkDynamicDisplay.cpp | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/src/graphics/EInkDynamicDisplay.cpp b/src/graphics/EInkDynamicDisplay.cpp index 2b3659099..d53969540 100644 --- a/src/graphics/EInkDynamicDisplay.cpp +++ b/src/graphics/EInkDynamicDisplay.cpp @@ -241,7 +241,7 @@ void EInkDynamicDisplay::checkCosmetic() if (frameFlags & COSMETIC) { refresh = FULL; reason = FLAGGED_COSMETIC; - LOG_DEBUG("refresh=FULL, reason=FLAGGED_COSMETIC\n"); + LOG_DEBUG("refresh=FULL, reason=FLAGGED_COSMETIC, frameFlags=0x%x\n", frameFlags); } } @@ -256,7 +256,7 @@ void EInkDynamicDisplay::checkDemandingFast() if (frameFlags & DEMAND_FAST) { refresh = FAST; reason = FLAGGED_DEMAND_FAST; - LOG_DEBUG("refresh=FAST, reason=FLAGGED_DEMAND_FAST\n"); + LOG_DEBUG("refresh=FAST, reason=FLAGGED_DEMAND_FAST, frameFlags=0x%x\n", frameFlags); } } @@ -276,7 +276,7 @@ void EInkDynamicDisplay::checkFrameMatchesPrevious() if (frameFlags == BACKGROUND && fastRefreshCount > 0) { refresh = FULL; reason = REDRAW_WITH_FULL; - LOG_DEBUG("refresh=FULL, reason=REDRAW_WITH_FULL\n"); + LOG_DEBUG("refresh=FULL, reason=REDRAW_WITH_FULL, frameFlags=0x%x\n", frameFlags); return; } #endif @@ -298,7 +298,7 @@ void EInkDynamicDisplay::checkConsecutiveFastRefreshes() if (fastRefreshCount >= EINK_LIMIT_FASTREFRESH) { refresh = FULL; reason = EXCEEDED_LIMIT_FASTREFRESH; - LOG_DEBUG("refresh=FULL, reason=EXCEEDED_LIMIT_FASTREFRESH\n"); + LOG_DEBUG("refresh=FULL, reason=EXCEEDED_LIMIT_FASTREFRESH, frameFlags=0x%x\n", frameFlags); } } @@ -313,7 +313,8 @@ void EInkDynamicDisplay::checkFastRequested() // If we want BACKGROUND to use fast. (FULL only when a limit is hit) refresh = FAST; reason = BACKGROUND_USES_FAST; - LOG_DEBUG("refresh=FAST, reason=BACKGROUND_USES_FAST, fastRefreshCount=%lu\n", fastRefreshCount); + LOG_DEBUG("refresh=FAST, reason=BACKGROUND_USES_FAST, fastRefreshCount=%lu, frameFlags=0x%x\n", fastRefreshCount, + frameFlags); #else // If we do want to use FULL for BACKGROUND updates refresh = FULL; @@ -326,7 +327,7 @@ void EInkDynamicDisplay::checkFastRequested() if (frameFlags & RESPONSIVE) { refresh = FAST; reason = NO_OBJECTIONS; - LOG_DEBUG("refresh=FAST, reason=NO_OBJECTIONS, fastRefreshCount=%lu\n", fastRefreshCount); + LOG_DEBUG("refresh=FAST, reason=NO_OBJECTIONS, fastRefreshCount=%lu, frameFlags=0x%x\n", fastRefreshCount, frameFlags); } } @@ -407,7 +408,7 @@ void EInkDynamicDisplay::checkExcessiveGhosting() if (ghostPixelCount > EINK_LIMIT_GHOSTING_PX) { refresh = FULL; reason = EXCEEDED_GHOSTINGLIMIT; - LOG_DEBUG("refresh=FULL, reason=EXCEEDED_GHOSTINGLIMIT\n"); + LOG_DEBUG("refresh=FULL, reason=EXCEEDED_GHOSTINGLIMIT, frameFlags=0x%x\n", frameFlags); } } From 94eb837ee8c506ef4838d720f343a51914cd0a94 Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Sun, 10 Mar 2024 04:14:45 +1300 Subject: [PATCH 278/472] function macro for tidier addFramFlag() calls --- src/graphics/EInkDynamicDisplay.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/graphics/EInkDynamicDisplay.h b/src/graphics/EInkDynamicDisplay.h index ed5be70cd..495d20e7b 100644 --- a/src/graphics/EInkDynamicDisplay.h +++ b/src/graphics/EInkDynamicDisplay.h @@ -119,4 +119,10 @@ class EInkDynamicDisplay : public EInkDisplay #endif }; +// Tidier calls to addFrameFlag() from outside class +#define EINK_ADD_FRAMEFLAG(display, flag) static_cast(display)->addFrameFlag(EInkDynamicDisplay::flag) + +#else // !USE_EINK_DYNAMICDISPLAY +// Dummy-macro, removes the need for include guards +#define EINK_ADD_FRAMEFLAG(display, flag) #endif \ No newline at end of file From 7b703244351eb5bbee8542a638a04e12e965db28 Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Sun, 10 Mar 2024 05:00:51 +1300 Subject: [PATCH 279/472] handle special frames in Screen.cpp --- src/graphics/Screen.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 3ffea4a60..7f20b5666 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -260,6 +260,10 @@ static void drawWelcomeScreen(OLEDDisplay *display, OLEDDisplayUiState *state, i /// Used on eink displays while in deep sleep static void drawSleepScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) { + // Next frame should use full-refresh, and block while running, else device will sleep before async callback + EINK_ADD_FRAMEFLAG(display, COSMETIC); + EINK_ADD_FRAMEFLAG(display, BLOCKING); + drawIconScreen("Sleeping...", display, state, x, y); } #endif @@ -1170,6 +1174,7 @@ int32_t Screen::runOnce() break; case Cmd::STOP_BLUETOOTH_PIN_SCREEN: case Cmd::STOP_BOOT_SCREEN: + EINK_ADD_FRAMEFLAG(dispdev, COSMETIC); // E-Ink: Explicitly use full-refresh for next frame setFrames(); break; case Cmd::PRINT: @@ -1350,6 +1355,7 @@ void Screen::handleStartBluetoothPinScreen(uint32_t pin) { LOG_DEBUG("showing bluetooth screen\n"); showingNormalScreen = false; + EINK_ADD_FRAMEFLAG(dispdev, DEMAND_FAST); // E-Ink: Explicitly use fast-refresh for next frame static FrameCallback frames[] = {drawFrameBluetooth}; snprintf(btPIN, sizeof(btPIN), "%06u", pin); @@ -1367,6 +1373,7 @@ void Screen::handleShutdownScreen() { LOG_DEBUG("showing shutdown screen\n"); showingNormalScreen = false; + EINK_ADD_FRAMEFLAG(dispdev, DEMAND_FAST); // E-Ink: Explicitly use fast-refresh for next frame auto frame = [](OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) -> void { drawFrameText(display, state, x, y, "Shutting down..."); @@ -1380,6 +1387,7 @@ void Screen::handleRebootScreen() { LOG_DEBUG("showing reboot screen\n"); showingNormalScreen = false; + EINK_ADD_FRAMEFLAG(dispdev, DEMAND_FAST); // E-Ink: Explicitly use fast-refresh for next frame auto frame = [](OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) -> void { drawFrameText(display, state, x, y, "Rebooting..."); @@ -1392,6 +1400,7 @@ void Screen::handleStartFirmwareUpdateScreen() { LOG_DEBUG("showing firmware screen\n"); showingNormalScreen = false; + EINK_ADD_FRAMEFLAG(dispdev, DEMAND_FAST); // E-Ink: Explicitly use fast-refresh for next frame static FrameCallback frames[] = {drawFrameFirmware}; setFrameImmediateDraw(frames); From 3da7c0dba709c8b38a80371d59f1f693430cc65c Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Sat, 9 Mar 2024 18:32:49 +0100 Subject: [PATCH 280/472] Add hops_away to JSON output (#3357) --- src/mqtt/MQTT.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 898607eca..b25075177 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -808,6 +808,8 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp) jsonObj["rssi"] = new JSONValue((int)mp->rx_rssi); if (mp->rx_snr != 0) jsonObj["snr"] = new JSONValue((float)mp->rx_snr); + if (mp->hop_start != 0 && mp->hop_limit <= mp->hop_start) + jsonObj["hops_away"] = new JSONValue((uint)(mp->hop_start - mp->hop_limit)); // serialize and write it to the stream JSONValue *value = new JSONValue(jsonObj); From 7167f1e04f3a7f76b4dc476bf36df581d6afeb9c Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sat, 9 Mar 2024 15:25:16 -0600 Subject: [PATCH 281/472] Add parens to macro (#3361) --- src/gps/GeoCoord.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/gps/GeoCoord.h b/src/gps/GeoCoord.h index 9f911ed93..e811035db 100644 --- a/src/gps/GeoCoord.h +++ b/src/gps/GeoCoord.h @@ -11,7 +11,7 @@ #define PI 3.1415926535897932384626433832795 #define OLC_CODE_LEN 11 -#define DEG_CONVERT 180 / PI +#define DEG_CONVERT (180 / PI) // Helper functions // Raises a number to an exponent, handling negative exponents. From dced888492a915e84d74cbd3fc2afa5d07ff54d8 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sat, 9 Mar 2024 13:40:03 -0600 Subject: [PATCH 282/472] Add precision_bit sto json --- src/mqtt/MQTT.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index b25075177..619815e85 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -655,6 +655,9 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp) if ((int)decoded->VDOP) { msgPayload["VDOP"] = new JSONValue((int)decoded->VDOP); } + if ((int)decoded->precision_bits) { + msgPayload["precision_bits"] = new JSONValue((int)decoded->precision_bits); + } jsonObj["payload"] = new JSONValue(msgPayload); } else { LOG_ERROR("Error decoding protobuf for position message!\n"); From 3daae24d29d2962d38fa33f2b4577c09698b04db Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Sun, 10 Mar 2024 13:43:57 +1300 Subject: [PATCH 283/472] fix fallback behavior for unmodified GxEPD2 Issues exposed by https://github.com/meshtastic/firmware/pull/3356#issuecomment-1986950317 --- src/graphics/EInkDynamicDisplay.cpp | 58 +++++++++++++++++------------ src/graphics/EInkDynamicDisplay.h | 2 +- 2 files changed, 35 insertions(+), 25 deletions(-) diff --git a/src/graphics/EInkDynamicDisplay.cpp b/src/graphics/EInkDynamicDisplay.cpp index d53969540..2f3c2fd0e 100644 --- a/src/graphics/EInkDynamicDisplay.cpp +++ b/src/graphics/EInkDynamicDisplay.cpp @@ -96,18 +96,45 @@ bool EInkDynamicDisplay::update() { // Detemine the refresh mode to use, and start the update bool refreshApproved = determineMode(); - if (refreshApproved) + if (refreshApproved) { EInkDisplay::forceDisplay(0); // Bypass base class' own rate-limiting system + storeAndReset(); // Store the result of this loop for next time. Note: call *before* endOrDetach() + endOrDetach(); // endUpdate() right now, or set the async refresh flag (if FULL and HAS_EINK_ASYNC) + } else + storeAndReset(); // No update, no post-update code, just store the results -#if defined(HAS_EINK_ASYNCFULL) - if (refreshApproved) - endOrDetach(); // Either endUpdate() right now (fast refresh), or set the async flag (full refresh) -#endif - - storeAndReset(); // Store the result of this loop for next time return refreshApproved; // (Unutilized) Base class promises to return true if update ran } +// Figure out who runs the post-update code +void EInkDynamicDisplay::endOrDetach() +{ + // If the GxEPD2 version reports that it has the async modifications +#ifdef HAS_EINK_ASYNCFULL + if (previousRefresh == FULL) { + asyncRefreshRunning = true; // Set the flag - picked up at start of determineMode(), next loop. + + if (previousFrameFlags & BLOCKING) + awaitRefresh(); + else + LOG_DEBUG("Async full-refresh begins\n"); + } + + // Fast Refresh + else if (previousRefresh == FAST) + EInkDisplay::endUpdate(); // Still block while updating, but EInkDisplay needs us to call endUpdate() ourselves. + + // Fallback - If using an unmodified version of GxEPD2 for some reason +#else + if (previousRefresh == FULL || previousRefresh == FAST) { // If refresh wasn't skipped (on unspecified..) + LOG_WARN( + "GxEPD2 version has not been modified to support async refresh; using fallback behavior. Please update lib_deps in " + "variant's platformio.ini file\n"); + EInkDisplay::endUpdate(); + } +#endif +} + // Assess situation, pick a refresh type bool EInkDynamicDisplay::determineMode() { @@ -456,23 +483,6 @@ void EInkDynamicDisplay::checkAsyncFullRefresh() // It is only equipped to intercept calls to nextPage() } -// Figure out who runs the post-update code -void EInkDynamicDisplay::endOrDetach() -{ - if (refresh == FULL) { - asyncRefreshRunning = true; // Set the flag - picked up at start of determineMode(), next loop. - - if (frameFlags & BLOCKING) - awaitRefresh(); - else - LOG_DEBUG("Async full-refresh begins\n"); - } - - // Fast Refresh - else - EInkDisplay::endUpdate(); // Still block while updating, but EInkDisplay needs us to call endUpdate() ourselves. -} - // Hold control while an async refresh runs void EInkDynamicDisplay::awaitRefresh() { diff --git a/src/graphics/EInkDynamicDisplay.h b/src/graphics/EInkDynamicDisplay.h index 495d20e7b..dcae056c6 100644 --- a/src/graphics/EInkDynamicDisplay.h +++ b/src/graphics/EInkDynamicDisplay.h @@ -68,6 +68,7 @@ class EInkDynamicDisplay : public EInkDisplay void applyRefreshMode(); // Run any relevant GxEPD2 code, so next update will use correct refresh type void adjustRefreshCounters(); // Update fastRefreshCount bool update(); // Trigger the display update - determine mode, then call base class + void endOrDetach(); // Run the post-update code, or delegate it off to checkAsyncFullRefresh() // Checks as part of determineMode() void checkInitialized(); // Is this the very first frame? @@ -112,7 +113,6 @@ class EInkDynamicDisplay : public EInkDisplay // Conditional - async full refresh - only with modified meshtastic/GxEPD2 #if defined(HAS_EINK_ASYNCFULL) void checkAsyncFullRefresh(); // Check the status of "async full-refresh"; run the post-update code if the hardware is ready - void endOrDetach(); // Run the post-update code, or delegate it off to checkAsyncFullRefresh() void awaitRefresh(); // Hold control while an async refresh runs void endUpdate() override {} // Disable base-class behavior of running post-update immediately after forceDisplay() bool asyncRefreshRunning = false; // Flag, checked by checkAsyncFullRefresh() From c0a3b20aa3eec657300b9c83b97dc1b3e8d8d00c Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Sun, 10 Mar 2024 13:45:35 +1300 Subject: [PATCH 284/472] while drafting, build from todd-herbert/meshtastic-GxEPD2#async --- variants/heltec_wireless_paper/platformio.ini | 2 +- variants/heltec_wireless_paper_v1/platformio.ini | 2 +- variants/t-echo/platformio.ini | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/variants/heltec_wireless_paper/platformio.ini b/variants/heltec_wireless_paper/platformio.ini index 14275830a..8ff475d06 100644 --- a/variants/heltec_wireless_paper/platformio.ini +++ b/variants/heltec_wireless_paper/platformio.ini @@ -16,7 +16,7 @@ build_flags = -D EINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. lib_deps = ${esp32s3_base.lib_deps} - https://github.com/meshtastic/GxEPD2/ + https://github.com/todd-herbert/meshtastic-GxEPD2#async adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 upload_speed = 115200 \ No newline at end of file diff --git a/variants/heltec_wireless_paper_v1/platformio.ini b/variants/heltec_wireless_paper_v1/platformio.ini index 4e5e291e0..9327ed256 100644 --- a/variants/heltec_wireless_paper_v1/platformio.ini +++ b/variants/heltec_wireless_paper_v1/platformio.ini @@ -16,7 +16,7 @@ build_flags = ;-D EINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. lib_deps = ${esp32s3_base.lib_deps} - https://github.com/meshtastic/GxEPD2/ + https://github.com/todd-herbert/meshtastic-GxEPD2#async adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 upload_speed = 115200 \ No newline at end of file diff --git a/variants/t-echo/platformio.ini b/variants/t-echo/platformio.ini index c97341a3b..1a35f2f28 100644 --- a/variants/t-echo/platformio.ini +++ b/variants/t-echo/platformio.ini @@ -20,7 +20,7 @@ build_flags = ${nrf52840_base.build_flags} -Ivariants/t-echo build_src_filter = ${nrf52_base.build_src_filter} +<../variants/t-echo> lib_deps = ${nrf52840_base.lib_deps} - https://github.com/meshtastic/GxEPD2 + https://github.com/todd-herbert/meshtastic-GxEPD2#async adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 ;upload_protocol = fs From 3da1b74a103df8cdead31f671eb46ac2ac0acf2a Mon Sep 17 00:00:00 2001 From: Andre K Date: Sun, 10 Mar 2024 05:39:37 -0300 Subject: [PATCH 285/472] refactor: always send range tests with zero hops --- src/modules/RangeTestModule.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/RangeTestModule.cpp b/src/modules/RangeTestModule.cpp index ecf4b70c7..b45068b45 100644 --- a/src/modules/RangeTestModule.cpp +++ b/src/modules/RangeTestModule.cpp @@ -113,7 +113,7 @@ void RangeTestModuleRadio::sendPayload(NodeNum dest, bool wantReplies) meshtastic_MeshPacket *p = allocDataPacket(); p->to = dest; p->decoded.want_response = wantReplies; - + p->hop_limit = 0; p->want_ack = true; packetSequence++; @@ -295,4 +295,4 @@ bool RangeTestModuleRadio::appendFile(const meshtastic_MeshPacket &mp) #endif return 1; -} \ No newline at end of file +} From 1032e16ea44d824fdfe49ffc0c4bf5c146bf712c Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Mon, 11 Mar 2024 01:02:03 +1300 Subject: [PATCH 286/472] reorder determineMode() checks --- src/graphics/EInkDynamicDisplay.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/graphics/EInkDynamicDisplay.cpp b/src/graphics/EInkDynamicDisplay.cpp index 2f3c2fd0e..732f6d3fb 100644 --- a/src/graphics/EInkDynamicDisplay.cpp +++ b/src/graphics/EInkDynamicDisplay.cpp @@ -99,7 +99,7 @@ bool EInkDynamicDisplay::update() if (refreshApproved) { EInkDisplay::forceDisplay(0); // Bypass base class' own rate-limiting system storeAndReset(); // Store the result of this loop for next time. Note: call *before* endOrDetach() - endOrDetach(); // endUpdate() right now, or set the async refresh flag (if FULL and HAS_EINK_ASYNC) + endOrDetach(); // endUpdate() right now, or set the async refresh flag (if FULL and HAS_EINK_ASYNCFULL) } else storeAndReset(); // No update, no post-update code, just store the results @@ -158,11 +158,11 @@ bool EInkDynamicDisplay::determineMode() // Once mode determined, any remaining checks will bypass checkCosmetic(); checkDemandingFast(); + checkFrameMatchesPrevious(); + checkConsecutiveFastRefreshes(); #ifdef EINK_LIMIT_GHOSTING_PX checkExcessiveGhosting(); #endif - checkFrameMatchesPrevious(); - checkConsecutiveFastRefreshes(); checkFastRequested(); if (refresh == UNSPECIFIED) From af9d14c370699c8a8cc618763052ecf12eccb461 Mon Sep 17 00:00:00 2001 From: GUVWAF Date: Sun, 10 Mar 2024 14:52:37 +0100 Subject: [PATCH 287/472] Periodic reporting of device information to a map via MQTT --- src/mesh/Channels.cpp | 20 +++++++ src/mesh/Channels.h | 3 + src/mesh/NodeDB.cpp | 7 ++- src/mesh/NodeDB.h | 8 ++- src/mesh/RadioInterface.cpp | 6 ++ src/mesh/RadioInterface.h | 3 + src/mqtt/MQTT.cpp | 107 +++++++++++++++++++++++++++++++----- src/mqtt/MQTT.h | 17 ++++-- 8 files changed, 149 insertions(+), 22 deletions(-) diff --git a/src/mesh/Channels.cpp b/src/mesh/Channels.cpp index 2d27c737d..b50ecf6ca 100644 --- a/src/mesh/Channels.cpp +++ b/src/mesh/Channels.cpp @@ -2,6 +2,7 @@ #include "CryptoEngine.h" #include "DisplayFormatters.h" #include "NodeDB.h" +#include "RadioInterface.h" #include "configuration.h" #include @@ -254,6 +255,25 @@ const char *Channels::getName(size_t chIndex) return channelName; } +bool Channels::hasDefaultChannel() +{ + // If we don't use a preset or we override the frequency, we don't have a default channel + if (!config.lora.use_preset || config.lora.override_frequency) + return false; + // Check if any of the channels are using the default name and PSK + for (size_t i = 0; i < getNumChannels(); i++) { + const auto &ch = getByIndex(i); + if (ch.settings.psk.size == 1 && ch.settings.psk.bytes[0] == 1) { + const char *name = getName(i); + const char *presetName = DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false); + // Check if the name is the default derived from the modem preset and we use the default frequency slot + if (strcmp(name, presetName) == 0 && RadioInterface::uses_default_frequency_slot) + return true; + } + } + return false; +} + /** * Generate a short suffix used to disambiguate channels that might have the same "name" entered by the human but different PSKs. * The ideas is that the PSK changing should be visible to the user so that they see they probably messed up and that's why they diff --git a/src/mesh/Channels.h b/src/mesh/Channels.h index 87a72e07b..0e11605c4 100644 --- a/src/mesh/Channels.h +++ b/src/mesh/Channels.h @@ -102,6 +102,9 @@ class Channels */ int16_t setActiveByIndex(ChannelIndex channelIndex); + // Returns true if we can be reached via a channel with the default settings given a region and modem preset + bool hasDefaultChannel(); + private: /** Given a channel index, change to use the crypto key specified by that index * diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 787c16a79..9d7647138 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -744,14 +744,17 @@ uint32_t sinceReceived(const meshtastic_MeshPacket *p) #define NUM_ONLINE_SECS (60 * 60 * 2) // 2 hrs to consider someone offline -size_t NodeDB::getNumOnlineMeshNodes() +size_t NodeDB::getNumOnlineMeshNodes(bool localOnly) { size_t numseen = 0; // FIXME this implementation is kinda expensive - for (int i = 0; i < *numMeshNodes; i++) + for (int i = 0; i < *numMeshNodes; i++) { + if (localOnly && meshNodes[i].via_mqtt) + continue; if (sinceLastSeen(&meshNodes[i]) < NUM_ONLINE_SECS) numseen++; + } return numseen; } diff --git a/src/mesh/NodeDB.h b/src/mesh/NodeDB.h index e24a971c1..8545b08d6 100644 --- a/src/mesh/NodeDB.h +++ b/src/mesh/NodeDB.h @@ -108,8 +108,10 @@ class NodeDB // get channel channel index we heard a nodeNum on, defaults to 0 if not found uint8_t getMeshNodeChannel(NodeNum n); - /// Return the number of nodes we've heard from recently (within the last 2 hrs?) - size_t getNumOnlineMeshNodes(); + /* Return the number of nodes we've heard from recently (within the last 2 hrs?) + * @param localOnly if true, ignore nodes heard via MQTT + */ + size_t getNumOnlineMeshNodes(bool localOnly = false); void initConfigIntervals(), initModuleConfigIntervals(), resetNodes(), removeNodeByNum(uint nodeNum); @@ -246,4 +248,4 @@ extern uint32_t error_address; #define Module_Config_size \ (ModuleConfig_CannedMessageConfig_size + ModuleConfig_ExternalNotificationConfig_size + ModuleConfig_MQTTConfig_size + \ ModuleConfig_RangeTestConfig_size + ModuleConfig_SerialConfig_size + ModuleConfig_StoreForwardConfig_size + \ - ModuleConfig_TelemetryConfig_size + ModuleConfig_size) + ModuleConfig_TelemetryConfig_size + ModuleConfig_size) \ No newline at end of file diff --git a/src/mesh/RadioInterface.cpp b/src/mesh/RadioInterface.cpp index c10eb26f6..7a2711251 100644 --- a/src/mesh/RadioInterface.cpp +++ b/src/mesh/RadioInterface.cpp @@ -1,5 +1,6 @@ #include "RadioInterface.h" #include "Channels.h" +#include "DisplayFormatters.h" #include "MeshRadio.h" #include "MeshService.h" #include "NodeDB.h" @@ -143,6 +144,7 @@ const RegionInfo regions[] = { }; const RegionInfo *myRegion; +bool RadioInterface::uses_default_frequency_slot = true; static uint8_t bytes[MAX_RHPACKETLEN]; @@ -486,6 +488,10 @@ void RadioInterface::applyModemConfig() // channel_num is actually (channel_num - 1), since modulus (%) returns values from 0 to (numChannels - 1) int channel_num = (loraConfig.channel_num ? loraConfig.channel_num - 1 : hash(channelName)) % numChannels; + // Check if we use the default frequency slot + RadioInterface::uses_default_frequency_slot = + channel_num == hash(DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false)) % numChannels; + // Old frequency selection formula // float freq = myRegion->freqStart + ((((myRegion->freqEnd - myRegion->freqStart) / numChannels) / 2) * channel_num); diff --git a/src/mesh/RadioInterface.h b/src/mesh/RadioInterface.h index f85b3bfa5..ee4726d74 100644 --- a/src/mesh/RadioInterface.h +++ b/src/mesh/RadioInterface.h @@ -175,6 +175,9 @@ class RadioInterface /// Some boards (1st gen Pinetab Lora module) have broken IRQ wires, so we need to poll via i2c registers virtual bool isIRQPending() { return false; } + // Whether we use the default frequency slot given our LoRa config (region and modem preset) + static bool uses_default_frequency_slot; + protected: int8_t power = 17; // Set by applyModemConfig() diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 898607eca..426934be8 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -77,8 +77,7 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length) if (jsonPayloadStr.length() <= sizeof(p->decoded.payload.bytes)) { memcpy(p->decoded.payload.bytes, jsonPayloadStr.c_str(), jsonPayloadStr.length()); p->decoded.payload.size = jsonPayloadStr.length(); - meshtastic_MeshPacket *packet = packetPool.allocCopy(*p); - service.sendToMesh(packet, RX_SRC_LOCAL); + service.sendToMesh(p, RX_SRC_LOCAL); } else { LOG_WARN("Received MQTT json payload too long, dropping\n"); } @@ -192,6 +191,11 @@ MQTT::MQTT() : concurrency::OSThread("mqtt"), mqttQueue(MAX_MQTT_QUEUE) jsonTopic = "msh" + jsonTopic; } + if (moduleConfig.mqtt.map_reporting_enabled && moduleConfig.mqtt.has_map_report_settings) { + map_position_precision = moduleConfig.mqtt.map_report_settings.position_precision; + map_publish_interval_secs = moduleConfig.mqtt.map_report_settings.publish_interval_secs; + } + #ifdef HAS_NETWORKING if (!moduleConfig.mqtt.proxy_to_client_enabled) pubSub.setCallback(mqttCallback); @@ -365,27 +369,30 @@ void MQTT::sendSubscriptions() bool MQTT::wantsLink() const { - bool hasChannel = false; + bool hasChannelorMapReport = false; if (moduleConfig.mqtt.enabled) { - // No need for link if no channel needed it - size_t numChan = channels.getNumChannels(); - for (size_t i = 0; i < numChan; i++) { - const auto &ch = channels.getByIndex(i); - if (ch.settings.uplink_enabled || ch.settings.downlink_enabled) { - hasChannel = true; - break; + hasChannelorMapReport = moduleConfig.mqtt.map_reporting_enabled; + if (!hasChannelorMapReport) { + // No need for link if no channel needed it + size_t numChan = channels.getNumChannels(); + for (size_t i = 0; i < numChan; i++) { + const auto &ch = channels.getByIndex(i); + if (ch.settings.uplink_enabled || ch.settings.downlink_enabled) { + hasChannelorMapReport = true; + break; + } } } } - if (hasChannel && moduleConfig.mqtt.proxy_to_client_enabled) + if (hasChannelorMapReport && moduleConfig.mqtt.proxy_to_client_enabled) return true; #if HAS_WIFI - return hasChannel && WiFi.isConnected(); + return hasChannelorMapReport && WiFi.isConnected(); #endif #if HAS_ETHERNET - return hasChannel && Ethernet.linkStatus() == LinkON; + return hasChannelorMapReport && Ethernet.linkStatus() == LinkON; #endif return false; } @@ -397,6 +404,8 @@ int32_t MQTT::runOnce() bool wantConnection = wantsLink(); + perhapsReportToMap(); + // If connected poll rapidly, otherwise only occasionally check for a wifi connection change and ability to contact server if (moduleConfig.mqtt.proxy_to_client_enabled) { publishQueuedMessages(); @@ -536,6 +545,78 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket & } } +void MQTT::perhapsReportToMap() +{ + if (!moduleConfig.mqtt.map_reporting_enabled || !(moduleConfig.mqtt.proxy_to_client_enabled || isConnectedDirectly())) + return; + + if (map_position_precision == 0 || (localPosition.latitude_i == 0 && localPosition.longitude_i == 0)) { + LOG_WARN("MQTT Map reporting is enabled, but precision is 0 or no position available.\n"); + return; + } + + if (millis() - last_report_to_map < map_publish_interval_secs * 1000) { + return; + } else { + // Allocate ServiceEnvelope and fill it + meshtastic_ServiceEnvelope *se = mqttPool.allocZeroed(); + se->channel_id = (char *)channels.getGlobalId(channels.getPrimaryIndex()); // Use primary channel as the channel_id + se->gateway_id = owner.id; + + // Allocate MeshPacket and fill it + meshtastic_MeshPacket *mp = packetPool.allocZeroed(); + mp->which_payload_variant = meshtastic_MeshPacket_decoded_tag; + mp->from = nodeDB.getNodeNum(); + mp->to = NODENUM_BROADCAST; + mp->decoded.portnum = meshtastic_PortNum_MAP_REPORT_APP; + + // Fill MapReport message + meshtastic_MapReport mapReport = meshtastic_MapReport_init_default; + memcpy(mapReport.long_name, owner.long_name, sizeof(owner.long_name)); + memcpy(mapReport.short_name, owner.short_name, sizeof(owner.short_name)); + mapReport.role = config.device.role; + mapReport.hw_model = owner.hw_model; + strncpy(mapReport.firmware_version, optstr(APP_VERSION), sizeof(mapReport.firmware_version)); + mapReport.region = config.lora.region; + mapReport.modem_preset = config.lora.modem_preset; + mapReport.has_default_channel = channels.hasDefaultChannel(); + + // Set position with precision (same as in PositionModule) + if (map_position_precision < 32 && map_position_precision > 0) { + mapReport.latitude_i = localPosition.latitude_i & (UINT32_MAX << (32 - map_position_precision)); + mapReport.longitude_i = localPosition.longitude_i & (UINT32_MAX << (32 - map_position_precision)); + mapReport.latitude_i += (1 << (31 - map_position_precision)); + mapReport.longitude_i += (1 << (31 - map_position_precision)); + } else { + mapReport.latitude_i = localPosition.latitude_i; + mapReport.longitude_i = localPosition.longitude_i; + } + mapReport.altitude = localPosition.altitude; + mapReport.position_precision = map_position_precision; + + mapReport.num_online_local_nodes = nodeDB.getNumOnlineMeshNodes(true); + + // Encode MapReport message and set it to MeshPacket in ServiceEnvelope + mp->decoded.payload.size = pb_encode_to_bytes(mp->decoded.payload.bytes, sizeof(mp->decoded.payload.bytes), + &meshtastic_MapReport_msg, &mapReport); + se->packet = mp; + + // FIXME - this size calculation is super sloppy, but it will go away once we dynamically alloc meshpackets + static uint8_t bytes[meshtastic_MeshPacket_size + 64]; + size_t numBytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_ServiceEnvelope_msg, se); + + LOG_INFO("MQTT Publish map report to %s\n", statusTopic.c_str()); + publish(statusTopic.c_str(), bytes, numBytes, false); + + // Release the allocated memory for ServiceEnvelope and MeshPacket + mqttPool.release(se); + packetPool.release(mp); + + // Update the last report time + last_report_to_map = millis(); + } +} + // converts a downstream packet into a json message std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp) { diff --git a/src/mqtt/MQTT.h b/src/mqtt/MQTT.h index 2b803e3fc..1599c7ae8 100644 --- a/src/mqtt/MQTT.h +++ b/src/mqtt/MQTT.h @@ -79,10 +79,16 @@ class MQTT : private concurrency::OSThread virtual int32_t runOnce() override; private: - std::string statusTopic = "/2/stat/"; - std::string cryptTopic = "/2/c/"; // msh/2/c/CHANNELID/NODEID - std::string jsonTopic = "/2/json/"; // msh/2/json/CHANNELID/NODEID - /** return true if we have a channel that wants uplink/downlink + std::string statusTopic = "/2/stat/"; // For "online"/"offline" message and MapReport + std::string cryptTopic = "/2/c/"; // msh/2/c/CHANNELID/NODEID + std::string jsonTopic = "/2/json/"; // msh/2/json/CHANNELID/NODEID + + // For map reporting (only applies when enabled) + uint32_t last_report_to_map = 0; + uint32_t map_position_precision = 32; // default to full precision + uint32_t map_publish_interval_secs = 60 * 15; // default to 15 minutes + + /** return true if we have a channel that wants uplink/downlink or map reporting is enabled */ bool wantsLink() const; @@ -102,6 +108,9 @@ class MQTT : private concurrency::OSThread void publishStatus(); void publishQueuedMessages(); + // Check if we should report unencrypted information about our node for consumption by a map + void perhapsReportToMap(); + // returns true if this is a valid JSON envelope which we accept on downlink bool isValidJsonEnvelope(JSONObject &json); From 69dcc948b9631e798f232c3669e114a8da0ab9a7 Mon Sep 17 00:00:00 2001 From: caveman99 Date: Sun, 10 Mar 2024 14:39:40 +0000 Subject: [PATCH 288/472] [create-pull-request] automated change --- protobufs | 2 +- src/mesh/generated/meshtastic/deviceonly.pb.h | 2 +- src/mesh/generated/meshtastic/localonly.pb.h | 2 +- .../generated/meshtastic/module_config.pb.c | 5 +- .../generated/meshtastic/module_config.pb.h | 42 ++++++++++-- src/mesh/generated/meshtastic/mqtt.pb.c | 3 + src/mesh/generated/meshtastic/mqtt.pb.h | 68 +++++++++++++++++++ src/mesh/generated/meshtastic/portnums.pb.h | 2 + 8 files changed, 117 insertions(+), 9 deletions(-) diff --git a/protobufs b/protobufs index 5a97acb17..00332412b 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 5a97acb17543a10e114675a205e3274a83e721af +Subproject commit 00332412b238fe559175a6e83fdf8d31fa5e209a diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index ca4b2176b..556821e1c 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -324,7 +324,7 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg; #define meshtastic_DeviceState_size 17571 #define meshtastic_NodeInfoLite_size 158 #define meshtastic_NodeRemoteHardwarePin_size 29 -#define meshtastic_OEMStore_size 3246 +#define meshtastic_OEMStore_size 3262 #define meshtastic_PositionLite_size 28 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/localonly.pb.h b/src/mesh/generated/meshtastic/localonly.pb.h index 7d39da01f..2e22cb1e4 100644 --- a/src/mesh/generated/meshtastic/localonly.pb.h +++ b/src/mesh/generated/meshtastic/localonly.pb.h @@ -181,7 +181,7 @@ extern const pb_msgdesc_t meshtastic_LocalModuleConfig_msg; /* Maximum encoded size of messages (where known) */ #define meshtastic_LocalConfig_size 469 -#define meshtastic_LocalModuleConfig_size 631 +#define meshtastic_LocalModuleConfig_size 647 #ifdef __cplusplus } /* extern "C" */ diff --git a/src/mesh/generated/meshtastic/module_config.pb.c b/src/mesh/generated/meshtastic/module_config.pb.c index 38965f3e2..a75c3fb59 100644 --- a/src/mesh/generated/meshtastic/module_config.pb.c +++ b/src/mesh/generated/meshtastic/module_config.pb.c @@ -6,12 +6,15 @@ #error Regenerate this file with the current version of nanopb generator. #endif -PB_BIND(meshtastic_ModuleConfig, meshtastic_ModuleConfig, AUTO) +PB_BIND(meshtastic_ModuleConfig, meshtastic_ModuleConfig, 2) PB_BIND(meshtastic_ModuleConfig_MQTTConfig, meshtastic_ModuleConfig_MQTTConfig, AUTO) +PB_BIND(meshtastic_ModuleConfig_MapReportSettings, meshtastic_ModuleConfig_MapReportSettings, AUTO) + + PB_BIND(meshtastic_ModuleConfig_RemoteHardwareConfig, meshtastic_ModuleConfig_RemoteHardwareConfig, AUTO) diff --git a/src/mesh/generated/meshtastic/module_config.pb.h b/src/mesh/generated/meshtastic/module_config.pb.h index edfd56e4c..2e1c25c7f 100644 --- a/src/mesh/generated/meshtastic/module_config.pb.h +++ b/src/mesh/generated/meshtastic/module_config.pb.h @@ -84,6 +84,14 @@ typedef enum _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar { } meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar; /* Struct definitions */ +/* Settings for reporting unencrypted information about our node to a map via MQTT */ +typedef struct _meshtastic_ModuleConfig_MapReportSettings { + /* How often we should report our info to the map (in seconds) */ + uint32_t publish_interval_secs; + /* Bits of precision for the location sent (default of 32 is full precision). */ + uint32_t position_precision; +} meshtastic_ModuleConfig_MapReportSettings; + /* MQTT Client Config */ typedef struct _meshtastic_ModuleConfig_MQTTConfig { /* If a meshtastic node is able to reach the internet it will normally attempt to gateway any channels that are marked as @@ -114,6 +122,11 @@ typedef struct _meshtastic_ModuleConfig_MQTTConfig { char root[16]; /* If true, we can use the connected phone / client to proxy messages to MQTT instead of a direct connection */ bool proxy_to_client_enabled; + /* If true, we will periodically report unencrypted information about our node to a map via MQTT */ + bool map_reporting_enabled; + /* Settings for reporting information about our node to a map via MQTT */ + bool has_map_report_settings; + meshtastic_ModuleConfig_MapReportSettings map_report_settings; } meshtastic_ModuleConfig_MQTTConfig; /* NeighborInfoModule Config */ @@ -427,6 +440,7 @@ extern "C" { + #define meshtastic_ModuleConfig_AudioConfig_bitrate_ENUMTYPE meshtastic_ModuleConfig_AudioConfig_Audio_Baud @@ -447,7 +461,8 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_ModuleConfig_init_default {0, {meshtastic_ModuleConfig_MQTTConfig_init_default}} -#define meshtastic_ModuleConfig_MQTTConfig_init_default {0, "", "", "", 0, 0, 0, "", 0} +#define meshtastic_ModuleConfig_MQTTConfig_init_default {0, "", "", "", 0, 0, 0, "", 0, 0, false, meshtastic_ModuleConfig_MapReportSettings_init_default} +#define meshtastic_ModuleConfig_MapReportSettings_init_default {0, 0} #define meshtastic_ModuleConfig_RemoteHardwareConfig_init_default {0, 0, 0, {meshtastic_RemoteHardwarePin_init_default, meshtastic_RemoteHardwarePin_init_default, meshtastic_RemoteHardwarePin_init_default, meshtastic_RemoteHardwarePin_init_default}} #define meshtastic_ModuleConfig_NeighborInfoConfig_init_default {0, 0} #define meshtastic_ModuleConfig_DetectionSensorConfig_init_default {0, 0, 0, 0, "", 0, 0, 0} @@ -462,7 +477,8 @@ extern "C" { #define meshtastic_ModuleConfig_AmbientLightingConfig_init_default {0, 0, 0, 0, 0} #define meshtastic_RemoteHardwarePin_init_default {0, "", _meshtastic_RemoteHardwarePinType_MIN} #define meshtastic_ModuleConfig_init_zero {0, {meshtastic_ModuleConfig_MQTTConfig_init_zero}} -#define meshtastic_ModuleConfig_MQTTConfig_init_zero {0, "", "", "", 0, 0, 0, "", 0} +#define meshtastic_ModuleConfig_MQTTConfig_init_zero {0, "", "", "", 0, 0, 0, "", 0, 0, false, meshtastic_ModuleConfig_MapReportSettings_init_zero} +#define meshtastic_ModuleConfig_MapReportSettings_init_zero {0, 0} #define meshtastic_ModuleConfig_RemoteHardwareConfig_init_zero {0, 0, 0, {meshtastic_RemoteHardwarePin_init_zero, meshtastic_RemoteHardwarePin_init_zero, meshtastic_RemoteHardwarePin_init_zero, meshtastic_RemoteHardwarePin_init_zero}} #define meshtastic_ModuleConfig_NeighborInfoConfig_init_zero {0, 0} #define meshtastic_ModuleConfig_DetectionSensorConfig_init_zero {0, 0, 0, 0, "", 0, 0, 0} @@ -478,6 +494,8 @@ extern "C" { #define meshtastic_RemoteHardwarePin_init_zero {0, "", _meshtastic_RemoteHardwarePinType_MIN} /* Field tags (for use in manual encoding/decoding) */ +#define meshtastic_ModuleConfig_MapReportSettings_publish_interval_secs_tag 1 +#define meshtastic_ModuleConfig_MapReportSettings_position_precision_tag 2 #define meshtastic_ModuleConfig_MQTTConfig_enabled_tag 1 #define meshtastic_ModuleConfig_MQTTConfig_address_tag 2 #define meshtastic_ModuleConfig_MQTTConfig_username_tag 3 @@ -487,6 +505,8 @@ extern "C" { #define meshtastic_ModuleConfig_MQTTConfig_tls_enabled_tag 7 #define meshtastic_ModuleConfig_MQTTConfig_root_tag 8 #define meshtastic_ModuleConfig_MQTTConfig_proxy_to_client_enabled_tag 9 +#define meshtastic_ModuleConfig_MQTTConfig_map_reporting_enabled_tag 10 +#define meshtastic_ModuleConfig_MQTTConfig_map_report_settings_tag 11 #define meshtastic_ModuleConfig_NeighborInfoConfig_enabled_tag 1 #define meshtastic_ModuleConfig_NeighborInfoConfig_update_interval_tag 2 #define meshtastic_ModuleConfig_DetectionSensorConfig_enabled_tag 1 @@ -623,9 +643,18 @@ X(a, STATIC, SINGULAR, BOOL, encryption_enabled, 5) \ X(a, STATIC, SINGULAR, BOOL, json_enabled, 6) \ X(a, STATIC, SINGULAR, BOOL, tls_enabled, 7) \ X(a, STATIC, SINGULAR, STRING, root, 8) \ -X(a, STATIC, SINGULAR, BOOL, proxy_to_client_enabled, 9) +X(a, STATIC, SINGULAR, BOOL, proxy_to_client_enabled, 9) \ +X(a, STATIC, SINGULAR, BOOL, map_reporting_enabled, 10) \ +X(a, STATIC, OPTIONAL, MESSAGE, map_report_settings, 11) #define meshtastic_ModuleConfig_MQTTConfig_CALLBACK NULL #define meshtastic_ModuleConfig_MQTTConfig_DEFAULT NULL +#define meshtastic_ModuleConfig_MQTTConfig_map_report_settings_MSGTYPE meshtastic_ModuleConfig_MapReportSettings + +#define meshtastic_ModuleConfig_MapReportSettings_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, UINT32, publish_interval_secs, 1) \ +X(a, STATIC, SINGULAR, UINT32, position_precision, 2) +#define meshtastic_ModuleConfig_MapReportSettings_CALLBACK NULL +#define meshtastic_ModuleConfig_MapReportSettings_DEFAULT NULL #define meshtastic_ModuleConfig_RemoteHardwareConfig_FIELDLIST(X, a) \ X(a, STATIC, SINGULAR, BOOL, enabled, 1) \ @@ -764,6 +793,7 @@ X(a, STATIC, SINGULAR, UENUM, type, 3) extern const pb_msgdesc_t meshtastic_ModuleConfig_msg; extern const pb_msgdesc_t meshtastic_ModuleConfig_MQTTConfig_msg; +extern const pb_msgdesc_t meshtastic_ModuleConfig_MapReportSettings_msg; extern const pb_msgdesc_t meshtastic_ModuleConfig_RemoteHardwareConfig_msg; extern const pb_msgdesc_t meshtastic_ModuleConfig_NeighborInfoConfig_msg; extern const pb_msgdesc_t meshtastic_ModuleConfig_DetectionSensorConfig_msg; @@ -781,6 +811,7 @@ extern const pb_msgdesc_t meshtastic_RemoteHardwarePin_msg; /* Defines for backwards compatibility with code written before nanopb-0.4.0 */ #define meshtastic_ModuleConfig_fields &meshtastic_ModuleConfig_msg #define meshtastic_ModuleConfig_MQTTConfig_fields &meshtastic_ModuleConfig_MQTTConfig_msg +#define meshtastic_ModuleConfig_MapReportSettings_fields &meshtastic_ModuleConfig_MapReportSettings_msg #define meshtastic_ModuleConfig_RemoteHardwareConfig_fields &meshtastic_ModuleConfig_RemoteHardwareConfig_msg #define meshtastic_ModuleConfig_NeighborInfoConfig_fields &meshtastic_ModuleConfig_NeighborInfoConfig_msg #define meshtastic_ModuleConfig_DetectionSensorConfig_fields &meshtastic_ModuleConfig_DetectionSensorConfig_msg @@ -801,7 +832,8 @@ extern const pb_msgdesc_t meshtastic_RemoteHardwarePin_msg; #define meshtastic_ModuleConfig_CannedMessageConfig_size 49 #define meshtastic_ModuleConfig_DetectionSensorConfig_size 44 #define meshtastic_ModuleConfig_ExternalNotificationConfig_size 42 -#define meshtastic_ModuleConfig_MQTTConfig_size 222 +#define meshtastic_ModuleConfig_MQTTConfig_size 238 +#define meshtastic_ModuleConfig_MapReportSettings_size 12 #define meshtastic_ModuleConfig_NeighborInfoConfig_size 8 #define meshtastic_ModuleConfig_PaxcounterConfig_size 8 #define meshtastic_ModuleConfig_RangeTestConfig_size 10 @@ -809,7 +841,7 @@ extern const pb_msgdesc_t meshtastic_RemoteHardwarePin_msg; #define meshtastic_ModuleConfig_SerialConfig_size 28 #define meshtastic_ModuleConfig_StoreForwardConfig_size 22 #define meshtastic_ModuleConfig_TelemetryConfig_size 36 -#define meshtastic_ModuleConfig_size 225 +#define meshtastic_ModuleConfig_size 241 #define meshtastic_RemoteHardwarePin_size 21 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/mqtt.pb.c b/src/mesh/generated/meshtastic/mqtt.pb.c index 3046e6109..a43f364e1 100644 --- a/src/mesh/generated/meshtastic/mqtt.pb.c +++ b/src/mesh/generated/meshtastic/mqtt.pb.c @@ -9,4 +9,7 @@ PB_BIND(meshtastic_ServiceEnvelope, meshtastic_ServiceEnvelope, AUTO) +PB_BIND(meshtastic_MapReport, meshtastic_MapReport, AUTO) + + diff --git a/src/mesh/generated/meshtastic/mqtt.pb.h b/src/mesh/generated/meshtastic/mqtt.pb.h index 12e83c724..8ca570d78 100644 --- a/src/mesh/generated/meshtastic/mqtt.pb.h +++ b/src/mesh/generated/meshtastic/mqtt.pb.h @@ -5,6 +5,7 @@ #define PB_MESHTASTIC_MESHTASTIC_MQTT_PB_H_INCLUDED #include #include "meshtastic/mesh.pb.h" +#include "meshtastic/config.pb.h" #if PB_PROTO_HEADER_VERSION != 40 #error Regenerate this file with the current version of nanopb generator. @@ -23,6 +24,38 @@ typedef struct _meshtastic_ServiceEnvelope { char *gateway_id; } meshtastic_ServiceEnvelope; +/* Information about a node intended to be reported unencrypted to a map using MQTT. */ +typedef struct _meshtastic_MapReport { + /* A full name for this user, i.e. "Kevin Hester" */ + char long_name[40]; + /* A VERY short name, ideally two characters. + Suitable for a tiny OLED screen */ + char short_name[5]; + /* Role of the node that applies specific settings for a particular use-case */ + meshtastic_Config_DeviceConfig_Role role; + /* Hardware model of the node, i.e. T-Beam, Heltec V3, etc... */ + meshtastic_HardwareModel hw_model; + /* Device firmware version string */ + char firmware_version[18]; + /* The region code for the radio (US, CN, EU433, etc...) */ + meshtastic_Config_LoRaConfig_RegionCode region; + /* Modem preset used by the radio (LongFast, MediumSlow, etc...) */ + meshtastic_Config_LoRaConfig_ModemPreset modem_preset; + /* Whether the node has a channel with default PSK and name (LongFast, MediumSlow, etc...) + and it uses the default frequency slot given the region and modem preset. */ + bool has_default_channel; + /* Latitude: multiply by 1e-7 to get degrees in floating point */ + int32_t latitude_i; + /* Longitude: multiply by 1e-7 to get degrees in floating point */ + int32_t longitude_i; + /* Altitude in meters above MSL */ + int32_t altitude; + /* Indicates the bits of precision for latitude and longitude set by the sending node */ + uint32_t position_precision; + /* Number of online nodes (heard in the last 2 hours) this node has in its list that were received locally (not via MQTT) */ + uint16_t num_online_local_nodes; +} meshtastic_MapReport; + #ifdef __cplusplus extern "C" { @@ -30,12 +63,27 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_ServiceEnvelope_init_default {NULL, NULL, NULL} +#define meshtastic_MapReport_init_default {"", "", _meshtastic_Config_DeviceConfig_Role_MIN, _meshtastic_HardwareModel_MIN, "", _meshtastic_Config_LoRaConfig_RegionCode_MIN, _meshtastic_Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, 0, 0} #define meshtastic_ServiceEnvelope_init_zero {NULL, NULL, NULL} +#define meshtastic_MapReport_init_zero {"", "", _meshtastic_Config_DeviceConfig_Role_MIN, _meshtastic_HardwareModel_MIN, "", _meshtastic_Config_LoRaConfig_RegionCode_MIN, _meshtastic_Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, 0, 0} /* Field tags (for use in manual encoding/decoding) */ #define meshtastic_ServiceEnvelope_packet_tag 1 #define meshtastic_ServiceEnvelope_channel_id_tag 2 #define meshtastic_ServiceEnvelope_gateway_id_tag 3 +#define meshtastic_MapReport_long_name_tag 1 +#define meshtastic_MapReport_short_name_tag 2 +#define meshtastic_MapReport_role_tag 3 +#define meshtastic_MapReport_hw_model_tag 4 +#define meshtastic_MapReport_firmware_version_tag 5 +#define meshtastic_MapReport_region_tag 6 +#define meshtastic_MapReport_modem_preset_tag 7 +#define meshtastic_MapReport_has_default_channel_tag 8 +#define meshtastic_MapReport_latitude_i_tag 9 +#define meshtastic_MapReport_longitude_i_tag 10 +#define meshtastic_MapReport_altitude_tag 11 +#define meshtastic_MapReport_position_precision_tag 12 +#define meshtastic_MapReport_num_online_local_nodes_tag 13 /* Struct field encoding specification for nanopb */ #define meshtastic_ServiceEnvelope_FIELDLIST(X, a) \ @@ -46,13 +94,33 @@ X(a, POINTER, SINGULAR, STRING, gateway_id, 3) #define meshtastic_ServiceEnvelope_DEFAULT NULL #define meshtastic_ServiceEnvelope_packet_MSGTYPE meshtastic_MeshPacket +#define meshtastic_MapReport_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, STRING, long_name, 1) \ +X(a, STATIC, SINGULAR, STRING, short_name, 2) \ +X(a, STATIC, SINGULAR, UENUM, role, 3) \ +X(a, STATIC, SINGULAR, UENUM, hw_model, 4) \ +X(a, STATIC, SINGULAR, STRING, firmware_version, 5) \ +X(a, STATIC, SINGULAR, UENUM, region, 6) \ +X(a, STATIC, SINGULAR, UENUM, modem_preset, 7) \ +X(a, STATIC, SINGULAR, BOOL, has_default_channel, 8) \ +X(a, STATIC, SINGULAR, SFIXED32, latitude_i, 9) \ +X(a, STATIC, SINGULAR, SFIXED32, longitude_i, 10) \ +X(a, STATIC, SINGULAR, INT32, altitude, 11) \ +X(a, STATIC, SINGULAR, UINT32, position_precision, 12) \ +X(a, STATIC, SINGULAR, UINT32, num_online_local_nodes, 13) +#define meshtastic_MapReport_CALLBACK NULL +#define meshtastic_MapReport_DEFAULT NULL + extern const pb_msgdesc_t meshtastic_ServiceEnvelope_msg; +extern const pb_msgdesc_t meshtastic_MapReport_msg; /* Defines for backwards compatibility with code written before nanopb-0.4.0 */ #define meshtastic_ServiceEnvelope_fields &meshtastic_ServiceEnvelope_msg +#define meshtastic_MapReport_fields &meshtastic_MapReport_msg /* Maximum encoded size of messages (where known) */ /* meshtastic_ServiceEnvelope_size depends on runtime parameters */ +#define meshtastic_MapReport_size 108 #ifdef __cplusplus } /* extern "C" */ diff --git a/src/mesh/generated/meshtastic/portnums.pb.h b/src/mesh/generated/meshtastic/portnums.pb.h index 3f3e9aaee..f576c7893 100644 --- a/src/mesh/generated/meshtastic/portnums.pb.h +++ b/src/mesh/generated/meshtastic/portnums.pb.h @@ -122,6 +122,8 @@ typedef enum _meshtastic_PortNum { /* ATAK Plugin Portnum for payloads from the official Meshtastic ATAK plugin */ meshtastic_PortNum_ATAK_PLUGIN = 72, + /* Provides unencrypted information about a node for consumption by a map via MQTT */ + meshtastic_PortNum_MAP_REPORT_APP = 73, /* Private applications should use portnums >= 256. To simplify initial development and testing you can use "PRIVATE_APP" in your code without needing to rebuild protobuf files (via [regen-protos.sh](https://github.com/meshtastic/firmware/blob/master/bin/regen-protos.sh)) */ From b45a912409c067b9ea6c0c41799a1128800cab4b Mon Sep 17 00:00:00 2001 From: GUVWAF Date: Sun, 10 Mar 2024 15:56:00 +0100 Subject: [PATCH 289/472] Use dedicated `map` topic --- src/mqtt/MQTT.cpp | 6 ++++-- src/mqtt/MQTT.h | 3 ++- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index b33132aa4..2de35971a 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -185,10 +185,12 @@ MQTT::MQTT() : concurrency::OSThread("mqtt"), mqttQueue(MAX_MQTT_QUEUE) statusTopic = moduleConfig.mqtt.root + statusTopic; cryptTopic = moduleConfig.mqtt.root + cryptTopic; jsonTopic = moduleConfig.mqtt.root + jsonTopic; + mapTopic = moduleConfig.mqtt.root + jsonTopic; } else { statusTopic = "msh" + statusTopic; cryptTopic = "msh" + cryptTopic; jsonTopic = "msh" + jsonTopic; + mapTopic = "msh" + mapTopic; } if (moduleConfig.mqtt.map_reporting_enabled && moduleConfig.mqtt.has_map_report_settings) { @@ -605,8 +607,8 @@ void MQTT::perhapsReportToMap() static uint8_t bytes[meshtastic_MeshPacket_size + 64]; size_t numBytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_ServiceEnvelope_msg, se); - LOG_INFO("MQTT Publish map report to %s\n", statusTopic.c_str()); - publish(statusTopic.c_str(), bytes, numBytes, false); + LOG_INFO("MQTT Publish map report to %s\n", mapTopic.c_str()); + publish(mapTopic.c_str(), bytes, numBytes, false); // Release the allocated memory for ServiceEnvelope and MeshPacket mqttPool.release(se); diff --git a/src/mqtt/MQTT.h b/src/mqtt/MQTT.h index b665a6efc..eeeb00d92 100644 --- a/src/mqtt/MQTT.h +++ b/src/mqtt/MQTT.h @@ -79,9 +79,10 @@ class MQTT : private concurrency::OSThread virtual int32_t runOnce() override; private: - std::string statusTopic = "/2/stat/"; // For "online"/"offline" message and MapReport + std::string statusTopic = "/2/stat/"; // For "online"/"offline" message std::string cryptTopic = "/2/e/"; // msh/2/e/CHANNELID/NODEID std::string jsonTopic = "/2/json/"; // msh/2/json/CHANNELID/NODEID + std::string mapTopic = "/2/map/"; // For protobuf-encoded MapReport messages // For map reporting (only applies when enabled) uint32_t last_report_to_map = 0; From cb7407e06ba88f8c9d1aec45e0ccae2101cc5d99 Mon Sep 17 00:00:00 2001 From: GUVWAF Date: Sun, 10 Mar 2024 16:04:59 +0100 Subject: [PATCH 290/472] Don't need to check all channels if not using default frequency slot --- src/mesh/Channels.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/mesh/Channels.cpp b/src/mesh/Channels.cpp index b50ecf6ca..3e9c78241 100644 --- a/src/mesh/Channels.cpp +++ b/src/mesh/Channels.cpp @@ -257,8 +257,8 @@ const char *Channels::getName(size_t chIndex) bool Channels::hasDefaultChannel() { - // If we don't use a preset or we override the frequency, we don't have a default channel - if (!config.lora.use_preset || config.lora.override_frequency) + // If we don't use a preset or the default frequency slot, or we override the frequency, we don't have a default channel + if (!config.lora.use_preset || !RadioInterface::uses_default_frequency_slot || config.lora.override_frequency) return false; // Check if any of the channels are using the default name and PSK for (size_t i = 0; i < getNumChannels(); i++) { @@ -266,8 +266,8 @@ bool Channels::hasDefaultChannel() if (ch.settings.psk.size == 1 && ch.settings.psk.bytes[0] == 1) { const char *name = getName(i); const char *presetName = DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false); - // Check if the name is the default derived from the modem preset and we use the default frequency slot - if (strcmp(name, presetName) == 0 && RadioInterface::uses_default_frequency_slot) + // Check if the name is the default derived from the modem preset + if (strcmp(name, presetName) == 0) return true; } } From fb4faf790ba28fd09344c61a713728e647f6c711 Mon Sep 17 00:00:00 2001 From: Thomas Herrmann Date: Tue, 5 Mar 2024 23:39:43 +0100 Subject: [PATCH 291/472] split query of paxcounter data from sending funcionality; don't cummulate (count mode != 1); use flag to signal changed count data --- src/modules/esp32/PaxcounterModule.cpp | 24 ++++++++++++++++++------ src/modules/esp32/PaxcounterModule.h | 3 +++ 2 files changed, 21 insertions(+), 6 deletions(-) diff --git a/src/modules/esp32/PaxcounterModule.cpp b/src/modules/esp32/PaxcounterModule.cpp index 2182ed124..29edb069d 100644 --- a/src/modules/esp32/PaxcounterModule.cpp +++ b/src/modules/esp32/PaxcounterModule.cpp @@ -7,8 +7,6 @@ PaxcounterModule *paxcounterModule; -void NullFunc(){}; - // paxcounterModule->sendInfo(NODENUM_BROADCAST); PaxcounterModule::PaxcounterModule() @@ -19,10 +17,14 @@ PaxcounterModule::PaxcounterModule() bool PaxcounterModule::sendInfo(NodeNum dest) { - libpax_counter_count(&count_from_libpax); - LOG_INFO("(Sending): pax: wifi=%d; ble=%d; uptime=%d\n", count_from_libpax.wifi_count, count_from_libpax.ble_count, + if (paxcounterModule->reportedDataSent) + return false; + + LOG_INFO("(Sending): pax: wifi=%d; ble=%d; uptime=%lu\n", count_from_libpax.wifi_count, count_from_libpax.ble_count, millis() / 1000); + paxcounterModule->reportedDataSent = true; + meshtastic_Paxcount pl = meshtastic_Paxcount_init_default; pl.wifi = count_from_libpax.wifi_count; pl.ble = count_from_libpax.ble_count; @@ -55,6 +57,14 @@ meshtastic_MeshPacket *PaxcounterModule::allocReply() return allocDataProtobuf(pl); } +void PaxcounterModule::handlePaxCounterReportRequest() +{ + // libpax_counter_count(&paxcounterModule->count_from_libpax); + LOG_INFO("(Reading): libPax reported new data: wifi=%d; ble=%d; uptime=%lu\n", paxcounterModule->count_from_libpax.wifi_count, + paxcounterModule->count_from_libpax.ble_count, millis() / 1000); + paxcounterModule->reportedDataSent = false; +} + int32_t PaxcounterModule::runOnce() { if (isActive()) { @@ -76,12 +86,14 @@ int32_t PaxcounterModule::runOnce() libpax_update_config(&configuration); // internal processing initialization - libpax_counter_init(NullFunc, &count_from_libpax, UINT16_MAX, 1); + libpax_counter_init(handlePaxCounterReportRequest, &count_from_libpax, + moduleConfig.paxcounter.paxcounter_update_interval, 0); libpax_counter_start(); } else { sendInfo(NODENUM_BROADCAST); } - return getConfiguredOrDefaultMs(moduleConfig.paxcounter.paxcounter_update_interval, default_broadcast_interval_secs); + // we check every second if the counter had new data to send + return 1000; } else { return disable(); } diff --git a/src/modules/esp32/PaxcounterModule.h b/src/modules/esp32/PaxcounterModule.h index e72f87450..67d47be56 100644 --- a/src/modules/esp32/PaxcounterModule.h +++ b/src/modules/esp32/PaxcounterModule.h @@ -13,10 +13,13 @@ class PaxcounterModule : private concurrency::OSThread, public ProtobufModule { bool firstTime = true; + bool reportedDataSent = true; public: PaxcounterModule(); + static void handlePaxCounterReportRequest(); + protected: struct count_payload_t count_from_libpax = {0, 0, 0}; virtual int32_t runOnce() override; From 73c77b663c0bff89aa28817d27faf667201088f6 Mon Sep 17 00:00:00 2001 From: Thomas Herrmann Date: Tue, 5 Mar 2024 23:48:52 +0100 Subject: [PATCH 292/472] fix typo --- src/modules/esp32/PaxcounterModule.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/esp32/PaxcounterModule.cpp b/src/modules/esp32/PaxcounterModule.cpp index 29edb069d..94fcca36f 100644 --- a/src/modules/esp32/PaxcounterModule.cpp +++ b/src/modules/esp32/PaxcounterModule.cpp @@ -77,7 +77,7 @@ int32_t PaxcounterModule::runOnce() libpax_default_config(&configuration); configuration.blecounter = 1; - configuration.blescantime = 0; // infinit + configuration.blescantime = 0; // infinite configuration.wificounter = 1; configuration.wifi_channel_map = WIFI_CHANNEL_ALL; configuration.wifi_channel_switch_interval = 50; From 09e08e0091dc2c4ef2dfc2debdf7bda7b4f6f5b2 Mon Sep 17 00:00:00 2001 From: Thomas Herrmann Date: Wed, 6 Mar 2024 19:15:04 +0100 Subject: [PATCH 293/472] add some documentation, cleanup --- src/modules/esp32/PaxcounterModule.cpp | 39 +++++++++++++++++--------- src/modules/esp32/PaxcounterModule.h | 7 +++-- 2 files changed, 29 insertions(+), 17 deletions(-) diff --git a/src/modules/esp32/PaxcounterModule.cpp b/src/modules/esp32/PaxcounterModule.cpp index 94fcca36f..e718d6261 100644 --- a/src/modules/esp32/PaxcounterModule.cpp +++ b/src/modules/esp32/PaxcounterModule.cpp @@ -7,7 +7,18 @@ PaxcounterModule *paxcounterModule; -// paxcounterModule->sendInfo(NODENUM_BROADCAST); +/** + * Callback function for libpax. + * We only clear our sent flag here, since this function is called from another thread, so we + * cannot send to the mesh directly. + */ +void PaxcounterModule::handlePaxCounterReportRequest() +{ + // The libpax library already updated our data structure, just before invoking this callback. + LOG_INFO("PaxcounterModule: libpax reported new data: wifi=%d; ble=%d; uptime=%lu\n", + paxcounterModule->count_from_libpax.wifi_count, paxcounterModule->count_from_libpax.ble_count, millis() / 1000); + paxcounterModule->reportedDataSent = false; +} PaxcounterModule::PaxcounterModule() : concurrency::OSThread("PaxcounterModule"), @@ -15,15 +26,20 @@ PaxcounterModule::PaxcounterModule() { } +/** + * Send the Pax information to the mesh if we got new data from libpax. + * This is called periodically from our runOnce() method and will actually send the data to the mesh + * if libpax updated it since the last transmission through the callback. + * @param dest - destination node (usually NODENUM_BROADCAST) + * @return false if sending is unnecessary, true if information was sent + */ bool PaxcounterModule::sendInfo(NodeNum dest) { if (paxcounterModule->reportedDataSent) return false; - LOG_INFO("(Sending): pax: wifi=%d; ble=%d; uptime=%lu\n", count_from_libpax.wifi_count, count_from_libpax.ble_count, - millis() / 1000); - - paxcounterModule->reportedDataSent = true; + LOG_INFO("PaxcounterModule: sending pax info wifi=%d; ble=%d; uptime=%lu\n", count_from_libpax.wifi_count, + count_from_libpax.ble_count, millis() / 1000); meshtastic_Paxcount pl = meshtastic_Paxcount_init_default; pl.wifi = count_from_libpax.wifi_count; @@ -33,9 +49,12 @@ bool PaxcounterModule::sendInfo(NodeNum dest) meshtastic_MeshPacket *p = allocDataProtobuf(pl); p->to = dest; p->decoded.want_response = false; - p->priority = meshtastic_MeshPacket_Priority_MIN; + p->priority = meshtastic_MeshPacket_Priority_DEFAULT; service.sendToMesh(p, RX_SRC_LOCAL, true); + + paxcounterModule->reportedDataSent = true; + return true; } @@ -57,14 +76,6 @@ meshtastic_MeshPacket *PaxcounterModule::allocReply() return allocDataProtobuf(pl); } -void PaxcounterModule::handlePaxCounterReportRequest() -{ - // libpax_counter_count(&paxcounterModule->count_from_libpax); - LOG_INFO("(Reading): libPax reported new data: wifi=%d; ble=%d; uptime=%lu\n", paxcounterModule->count_from_libpax.wifi_count, - paxcounterModule->count_from_libpax.ble_count, millis() / 1000); - paxcounterModule->reportedDataSent = false; -} - int32_t PaxcounterModule::runOnce() { if (isActive()) { diff --git a/src/modules/esp32/PaxcounterModule.h b/src/modules/esp32/PaxcounterModule.h index 67d47be56..ebd6e7191 100644 --- a/src/modules/esp32/PaxcounterModule.h +++ b/src/modules/esp32/PaxcounterModule.h @@ -8,18 +8,19 @@ #include /** - * A simple example module that just replies with "Message received" to any message it receives. + * Wrapper module for the estimate passenger (PAX) count library (https://github.com/dbinfrago/libpax) which + * implements the core functionality of the ESP32 Paxcounter project (https://github.com/cyberman54/ESP32-Paxcounter) */ class PaxcounterModule : private concurrency::OSThread, public ProtobufModule { bool firstTime = true; bool reportedDataSent = true; + static void handlePaxCounterReportRequest(); + public: PaxcounterModule(); - static void handlePaxCounterReportRequest(); - protected: struct count_payload_t count_from_libpax = {0, 0, 0}; virtual int32_t runOnce() override; From 26691c0be7145b726eafad236def154cad3122d5 Mon Sep 17 00:00:00 2001 From: Thomas Herrmann Date: Fri, 8 Mar 2024 23:48:56 +0100 Subject: [PATCH 294/472] include requested change and suggestions on PR from @caveman99 --- src/modules/esp32/PaxcounterModule.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/esp32/PaxcounterModule.cpp b/src/modules/esp32/PaxcounterModule.cpp index e718d6261..580fc46e1 100644 --- a/src/modules/esp32/PaxcounterModule.cpp +++ b/src/modules/esp32/PaxcounterModule.cpp @@ -18,6 +18,7 @@ void PaxcounterModule::handlePaxCounterReportRequest() LOG_INFO("PaxcounterModule: libpax reported new data: wifi=%d; ble=%d; uptime=%lu\n", paxcounterModule->count_from_libpax.wifi_count, paxcounterModule->count_from_libpax.ble_count, millis() / 1000); paxcounterModule->reportedDataSent = false; + paxcounterModule->setIntervalFromNow(0); } PaxcounterModule::PaxcounterModule() @@ -49,7 +50,7 @@ bool PaxcounterModule::sendInfo(NodeNum dest) meshtastic_MeshPacket *p = allocDataProtobuf(pl); p->to = dest; p->decoded.want_response = false; - p->priority = meshtastic_MeshPacket_Priority_DEFAULT; + p->priority = meshtastic_MeshPacket_Priority_MIN; service.sendToMesh(p, RX_SRC_LOCAL, true); @@ -103,8 +104,7 @@ int32_t PaxcounterModule::runOnce() } else { sendInfo(NODENUM_BROADCAST); } - // we check every second if the counter had new data to send - return 1000; + return getConfiguredOrDefaultMs(moduleConfig.paxcounter.paxcounter_update_interval, default_broadcast_interval_secs); } else { return disable(); } From 766beefbc5796f700e5d6d94f7f9d7682cc0a4c8 Mon Sep 17 00:00:00 2001 From: Kevin Cai Date: Sun, 10 Mar 2024 18:24:32 -0400 Subject: [PATCH 295/472] Update AccelerometerThread.h to work with T-Watch S3 --- src/AccelerometerThread.h | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/src/AccelerometerThread.h b/src/AccelerometerThread.h index 744f0ad64..9898f4d49 100644 --- a/src/AccelerometerThread.h +++ b/src/AccelerometerThread.h @@ -103,12 +103,21 @@ class AccelerometerThread : public concurrency::OSThread #endif struct bma423_axes_remap remap_data; +#ifdef T_WATCH_S3 + remap_data.x_axis = 1; + remap_data.x_axis_sign = 0; + remap_data.y_axis = 0; + remap_data.y_axis_sign = 0; + remap_data.z_axis = 2; + remap_data.z_axis_sign = 1; +#else remap_data.x_axis = 0; remap_data.x_axis_sign = 1; remap_data.y_axis = 1; remap_data.y_axis_sign = 0; remap_data.z_axis = 2; remap_data.z_axis_sign = 1; +#endif // Need to raise the wrist function, need to set the correct axis bmaSensor.setRemapAxes(&remap_data); // sensor.enableFeature(BMA423_STEP_CNTR, true); @@ -171,4 +180,4 @@ class AccelerometerThread : public concurrency::OSThread Adafruit_LIS3DH lis; }; -} // namespace concurrency \ No newline at end of file +} // namespace concurrency From b65b9e5d659b6bd8f4eb3314d8cf24f4892e47f4 Mon Sep 17 00:00:00 2001 From: David Ellefsen Date: Thu, 7 Mar 2024 16:03:01 +0200 Subject: [PATCH 296/472] Include esp32c3 build step --- .github/workflows/build_esp32.yml | 1 + .github/workflows/build_esp32_c3.yml | 60 ++++++++++++++++++++++++++++ .github/workflows/build_esp32_s3.yml | 1 + .github/workflows/main_matrix.yml | 14 ++++++- 4 files changed, 74 insertions(+), 2 deletions(-) create mode 100644 .github/workflows/build_esp32_c3.yml diff --git a/.github/workflows/build_esp32.yml b/.github/workflows/build_esp32.yml index c9664152e..31f0dd5a0 100644 --- a/.github/workflows/build_esp32.yml +++ b/.github/workflows/build_esp32.yml @@ -35,6 +35,7 @@ jobs: sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32.ini sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32s2.ini sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32s3.ini + sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32c3.ini - name: Build ESP32 run: bin/build-esp32.sh ${{ inputs.board }} diff --git a/.github/workflows/build_esp32_c3.yml b/.github/workflows/build_esp32_c3.yml new file mode 100644 index 000000000..f9164b96a --- /dev/null +++ b/.github/workflows/build_esp32_c3.yml @@ -0,0 +1,60 @@ +name: Build ESP32-C3 + +on: + workflow_call: + inputs: + board: + required: true + type: string + +jobs: + build-esp32-c3: + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v3 + - name: Build base + id: base + uses: ./.github/actions/setup-base + + - name: Pull web ui + uses: dsaltares/fetch-gh-release-asset@a40c8b4a0471f9ab81bdf73a010f74cc51476ad4 + with: + repo: meshtastic/web + file: build.tar + target: build.tar + token: ${{ secrets.GITHUB_TOKEN }} + + - name: Unpack web ui + run: | + tar -xf build.tar -C data/static + rm build.tar + - name: Remove debug flags for release + if: ${{ github.event_name == 'workflow_dispatch' }} + run: | + sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32.ini + sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32s2.ini + sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32s3.ini + sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32c3.ini + - name: Build ESP32 + run: bin/build-esp32.sh ${{ inputs.board }} + + - name: Pull OTA Firmware + uses: dsaltares/fetch-gh-release-asset@a40c8b4a0471f9ab81bdf73a010f74cc51476ad4 + with: + repo: meshtastic/firmware-ota + file: firmware-c3.bin + target: release/bleota-c3.bin + token: ${{ secrets.GITHUB_TOKEN }} + + - name: Get release version string + shell: bash + run: echo "version=$(./bin/buildinfo.py long)" >> $GITHUB_OUTPUT + id: version + + - name: Store binaries as an artifact + uses: actions/upload-artifact@v3 + with: + name: firmware-${{ inputs.board }}-${{ steps.version.outputs.version }}.zip + path: | + release/*.bin + release/*.elf diff --git a/.github/workflows/build_esp32_s3.yml b/.github/workflows/build_esp32_s3.yml index 9611dd5b8..f603a6a31 100644 --- a/.github/workflows/build_esp32_s3.yml +++ b/.github/workflows/build_esp32_s3.yml @@ -34,6 +34,7 @@ jobs: sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32.ini sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32s2.ini sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32s3.ini + sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32c3.ini - name: Build ESP32 run: bin/build-esp32.sh ${{ inputs.board }} diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index e77b4a261..03d47f18e 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -67,7 +67,6 @@ jobs: - board: tlora-v2-1-1_6-tcxo - board: tlora-v2-1-1_8 - board: tbeam - - board: heltec-ht62-esp32c3-sx1262 - board: heltec-v2_0 - board: heltec-v2_1 - board: tbeam0_7 @@ -105,6 +104,16 @@ jobs: with: board: ${{ matrix.board }} + build-esp32-c3: + strategy: + fail-fast: false + matrix: + include: + - board: heltec-ht62-esp32c3-sx1262 + uses: ./.github/workflows/build_esp32_c3.yml + with: + board: ${{ matrix.board }} + build-nrf52: strategy: fail-fast: false @@ -226,6 +235,7 @@ jobs: [ build-esp32, build-esp32-s3, + build-esp32-c3, build-nrf52, build-raspbian, build-native, @@ -251,7 +261,7 @@ jobs: id: version - name: Move files up - run: mv -b -t ./ ./*tbeam-2*/littlefs*.bin ./*tbeam-2*/bleota.bin ./*tbeam-s3*/bleota-s3.bin ./**/firmware*.bin ./*t-echo*/Meshtastic_nRF52_factory_erase_v2.uf2 ./**/firmware-*.uf2 ./**/firmware-*-ota.zip ./**/*.elf ./*native*/*device-*.sh ./*native*/*device-*.bat ./firmware-raspbian-*/release/meshtasticd_linux_aarch64 ./firmware-raspbian-*/bin/config-dist.yaml + run: mv -b -t ./ ./*tbeam-2*/littlefs*.bin ./*tbeam-2*/bleota.bin ./*tbeam-s3*/bleota-s3.bin ./*esp32c3*/bleota-c3.bin ./**/firmware*.bin ./*t-echo*/Meshtastic_nRF52_factory_erase_v2.uf2 ./**/firmware-*.uf2 ./**/firmware-*-ota.zip ./**/*.elf ./*native*/*device-*.sh ./*native*/*device-*.bat ./firmware-raspbian-*/release/meshtasticd_linux_aarch64 ./firmware-raspbian-*/bin/config-dist.yaml - name: Repackage in single firmware zip uses: actions/upload-artifact@v3 From b3ec3c20fbd80081328e44e7d4ce084afd42fa58 Mon Sep 17 00:00:00 2001 From: David Ellefsen Date: Thu, 7 Mar 2024 16:31:20 +0200 Subject: [PATCH 297/472] Update device-install.sh files to account for bleota-c3.bin file --- bin/device-install.bat | 8 ++++++-- bin/device-install.sh | 6 +++++- 2 files changed, 11 insertions(+), 3 deletions(-) diff --git a/bin/device-install.bat b/bin/device-install.bat index c7d8a10cf..cb652346f 100755 --- a/bin/device-install.bat +++ b/bin/device-install.bat @@ -31,9 +31,13 @@ IF EXIST %FILENAME% IF x%FILENAME:update=%==x%FILENAME% ( %PYTHON% -m esptool --baud 115200 erase_flash %PYTHON% -m esptool --baud 115200 write_flash 0x00 %FILENAME% - @REM Account for S3 board's different OTA partition + @REM Account for S3 and C3 board's different OTA partition IF x%FILENAME:s3=%==x%FILENAME% IF x%FILENAME:v3=%==x%FILENAME% IF x%FILENAME:t-deck=%==x%FILENAME% IF x%FILENAME:wireless-paper=%==x%FILENAME% IF x%FILENAME:wireless-tracker=%==x%FILENAME% ( - %PYTHON% -m esptool --baud 115200 write_flash 0x260000 bleota.bin + IF x%FILENAME:esp32c3=%==x%FILENAME% ( + %PYTHON% -m esptool --baud 115200 write_flash 0x260000 bleota.bin + ) else ( + %PYTHON% -m esptool --baud 115200 write_flash 0x260000 bleota-c3.bin + ) ) else ( %PYTHON% -m esptool --baud 115200 write_flash 0x260000 bleota-s3.bin ) diff --git a/bin/device-install.sh b/bin/device-install.sh index 35d99286d..52a27309a 100755 --- a/bin/device-install.sh +++ b/bin/device-install.sh @@ -51,7 +51,11 @@ if [ -f "${FILENAME}" ] && [ ! -z "${FILENAME##*"update"*}" ]; then "$PYTHON" -m esptool write_flash 0x00 ${FILENAME} # Account for S3 board's different OTA partition if [ ! -z "${FILENAME##*"s3"*}" ] && [ ! -z "${FILENAME##*"-v3"*}" ] && [ ! -z "${FILENAME##*"t-deck"*}" ] && [ ! -z "${FILENAME##*"wireless-paper"*}" ] && [ ! -z "${FILENAME##*"wireless-tracker"*}" ]; then - "$PYTHON" -m esptool write_flash 0x260000 bleota.bin + if [ ! -z "${FILENAME##*"esp32c3"*}" ]; then + "$PYTHON" -m esptool write_flash 0x260000 bleota.bin + else + "$PYTHON" -m esptool write_flash 0x260000 bleota-c3.bin + fi else "$PYTHON" -m esptool write_flash 0x260000 bleota-s3.bin fi From a493ab526f82979890d97e9354a2753eec8c06a7 Mon Sep 17 00:00:00 2001 From: David Ellefsen Date: Fri, 8 Mar 2024 10:50:03 +0200 Subject: [PATCH 298/472] Trunk fmt to correct failing PR check for device-install.sh --- bin/device-install.sh | 56 ++++++++++++++++++++++--------------------- 1 file changed, 29 insertions(+), 27 deletions(-) diff --git a/bin/device-install.sh b/bin/device-install.sh index 52a27309a..a4ee20c9c 100755 --- a/bin/device-install.sh +++ b/bin/device-install.sh @@ -1,12 +1,12 @@ #!/bin/sh -PYTHON=${PYTHON:-$(which python3 python|head -n 1)} +PYTHON=${PYTHON:-$(which python3 python | head -n 1)} set -e # Usage info show_help() { -cat << EOF + cat <&2 - exit 1 - ;; - esac + case "${opt}" in + h) + show_help + exit 0 + ;; + p) + export ESPTOOL_PORT=${OPTARG} + ;; + P) + PYTHON=${OPTARG} + ;; + f) + FILENAME=${OPTARG} + ;; + *) + echo "Invalid flag." + show_help >&2 + exit 1 + ;; + esac done -shift "$((OPTIND-1))" +shift "$((OPTIND - 1))" [ -z "$FILENAME" -a -n "$1" ] && { - FILENAME=$1 - shift + FILENAME=$1 + shift } if [ -f "${FILENAME}" ] && [ ! -z "${FILENAME##*"update"*}" ]; then echo "Trying to flash ${FILENAME}, but first erasing and writing system information" - "$PYTHON" -m esptool erase_flash - "$PYTHON" -m esptool write_flash 0x00 ${FILENAME} + "$PYTHON" -m esptool erase_flash + "$PYTHON" -m esptool write_flash 0x00 ${FILENAME} # Account for S3 board's different OTA partition if [ ! -z "${FILENAME##*"s3"*}" ] && [ ! -z "${FILENAME##*"-v3"*}" ] && [ ! -z "${FILENAME##*"t-deck"*}" ] && [ ! -z "${FILENAME##*"wireless-paper"*}" ] && [ ! -z "${FILENAME##*"wireless-tracker"*}" ]; then if [ ! -z "${FILENAME##*"esp32c3"*}" ]; then @@ -57,9 +59,9 @@ if [ -f "${FILENAME}" ] && [ ! -z "${FILENAME##*"update"*}" ]; then "$PYTHON" -m esptool write_flash 0x260000 bleota-c3.bin fi else - "$PYTHON" -m esptool write_flash 0x260000 bleota-s3.bin + "$PYTHON" -m esptool write_flash 0x260000 bleota-s3.bin fi - "$PYTHON" -m esptool write_flash 0x300000 littlefs-*.bin + "$PYTHON" -m esptool write_flash 0x300000 littlefs-*.bin else show_help From f09e5c96fcad715a7e3b3fe4bb285f1348d6c29d Mon Sep 17 00:00:00 2001 From: David Ellefsen Date: Fri, 8 Mar 2024 11:03:03 +0200 Subject: [PATCH 299/472] Add permission: read-all to silence CKV_GHA_1 check --- .github/workflows/build_esp32_c3.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/build_esp32_c3.yml b/.github/workflows/build_esp32_c3.yml index f9164b96a..a30cf33f1 100644 --- a/.github/workflows/build_esp32_c3.yml +++ b/.github/workflows/build_esp32_c3.yml @@ -7,6 +7,8 @@ on: required: true type: string +permissions: read-all + jobs: build-esp32-c3: runs-on: ubuntu-latest From 3a8f623f8adfc73e0c3b36453d8392394377713a Mon Sep 17 00:00:00 2001 From: David Ellefsen Date: Fri, 8 Mar 2024 11:27:31 +0200 Subject: [PATCH 300/472] Change '! -z' to '-n' to addresss shellcheck/SC2236 --- bin/device-install.sh | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/bin/device-install.sh b/bin/device-install.sh index a4ee20c9c..0e7bd8ada 100755 --- a/bin/device-install.sh +++ b/bin/device-install.sh @@ -47,13 +47,13 @@ shift "$((OPTIND - 1))" shift } -if [ -f "${FILENAME}" ] && [ ! -z "${FILENAME##*"update"*}" ]; then +if [ -f "${FILENAME}" ] && [ -n "${FILENAME##*"update"*}" ]; then echo "Trying to flash ${FILENAME}, but first erasing and writing system information" "$PYTHON" -m esptool erase_flash "$PYTHON" -m esptool write_flash 0x00 ${FILENAME} # Account for S3 board's different OTA partition - if [ ! -z "${FILENAME##*"s3"*}" ] && [ ! -z "${FILENAME##*"-v3"*}" ] && [ ! -z "${FILENAME##*"t-deck"*}" ] && [ ! -z "${FILENAME##*"wireless-paper"*}" ] && [ ! -z "${FILENAME##*"wireless-tracker"*}" ]; then - if [ ! -z "${FILENAME##*"esp32c3"*}" ]; then + if [ -n "${FILENAME##*"s3"*}" ] && [ -n "${FILENAME##*"-v3"*}" ] && [ -n "${FILENAME##*"t-deck"*}" ] && [ -n "${FILENAME##*"wireless-paper"*}" ] && [ -n "${FILENAME##*"wireless-tracker"*}" ]; then + if [ -n "${FILENAME##*"esp32c3"*}" ]; then "$PYTHON" -m esptool write_flash 0x260000 bleota.bin else "$PYTHON" -m esptool write_flash 0x260000 bleota-c3.bin From 658ed6fd2874f8e7e73007a492ff81e40af1093b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Mon, 11 Mar 2024 13:51:26 +0100 Subject: [PATCH 301/472] tryfix SHT31 sensor on secondary bus --- src/mesh/NodeDB.h | 2 +- src/modules/Telemetry/Sensor/SHT31Sensor.cpp | 2 +- src/modules/Telemetry/Sensor/SHT31Sensor.h | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/mesh/NodeDB.h b/src/mesh/NodeDB.h index 8545b08d6..e472f7151 100644 --- a/src/mesh/NodeDB.h +++ b/src/mesh/NodeDB.h @@ -248,4 +248,4 @@ extern uint32_t error_address; #define Module_Config_size \ (ModuleConfig_CannedMessageConfig_size + ModuleConfig_ExternalNotificationConfig_size + ModuleConfig_MQTTConfig_size + \ ModuleConfig_RangeTestConfig_size + ModuleConfig_SerialConfig_size + ModuleConfig_StoreForwardConfig_size + \ - ModuleConfig_TelemetryConfig_size + ModuleConfig_size) \ No newline at end of file + ModuleConfig_TelemetryConfig_size + ModuleConfig_size) diff --git a/src/modules/Telemetry/Sensor/SHT31Sensor.cpp b/src/modules/Telemetry/Sensor/SHT31Sensor.cpp index 7ffb68254..7f2b7691e 100644 --- a/src/modules/Telemetry/Sensor/SHT31Sensor.cpp +++ b/src/modules/Telemetry/Sensor/SHT31Sensor.cpp @@ -12,7 +12,7 @@ int32_t SHT31Sensor::runOnce() if (!hasSensor()) { return DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS; } - status = sht31.begin(); + status = sht31.begin(nodeTelemetrySensorsMap[sensorType].first); return initI2CSensor(); } diff --git a/src/modules/Telemetry/Sensor/SHT31Sensor.h b/src/modules/Telemetry/Sensor/SHT31Sensor.h index 940361325..9700bdf2c 100644 --- a/src/modules/Telemetry/Sensor/SHT31Sensor.h +++ b/src/modules/Telemetry/Sensor/SHT31Sensor.h @@ -5,7 +5,7 @@ class SHT31Sensor : public TelemetrySensor { private: - Adafruit_SHT31 sht31 = Adafruit_SHT31(); + Adafruit_SHT31 sht31 = Adafruit_SHT31(nodeTelemetrySensorsMap[sensorType].second); protected: virtual void setup() override; From 892223a297c23b788ae879b3a6dab92a10e391ad Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Mon, 11 Mar 2024 13:52:46 +0100 Subject: [PATCH 302/472] fix typos and add 2 missing modules to the equasion (#3370) --- src/configuration.h | 2 ++ src/modules/Modules.cpp | 8 ++++---- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/src/configuration.h b/src/configuration.h index 03170c1c7..ac8f9435a 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -239,4 +239,6 @@ along with this program. If not, see . #define MESHTASTIC_EXCLUDE_NEIGHBORINFO 1 #define MESHTASTIC_EXCLUDE_TRACEROUTE 1 #define MESHTASTIC_EXCLUDE_WAYPOINT 1 +#define MESHTASTIC_EXCLUDE_INPUTBROKER 1 +#define MESHTASTIC_EXCLUDE_SERIAL 1 #endif diff --git a/src/modules/Modules.cpp b/src/modules/Modules.cpp index 4f0b8f2b0..97ed90cf1 100644 --- a/src/modules/Modules.cpp +++ b/src/modules/Modules.cpp @@ -39,11 +39,11 @@ #if HAS_TELEMETRY #include "modules/Telemetry/DeviceTelemetry.h" #endif -#if HAS_SENSOR && !EXCLUDE_ENVIRONMENTAL_SENSOR +#if HAS_SENSOR && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR #include "modules/Telemetry/AirQualityTelemetry.h" #include "modules/Telemetry/EnvironmentTelemetry.h" #endif -#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) && !EXCLUDE_POWER_TELEMETRY +#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) && !MESHTASTIC_EXCLUDE_POWER_TELEMETRY #include "modules/Telemetry/PowerTelemetry.h" #endif #ifdef ARCH_ESP32 @@ -138,13 +138,13 @@ void setupModules() #if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) new DeviceTelemetryModule(); #endif -#if HAS_SENSOR && !EXCLUDE_ENVIRONMENTAL_SENSOR +#if HAS_SENSOR && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR new EnvironmentTelemetryModule(); if (nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_PMSA003I].first > 0) { new AirQualityTelemetryModule(); } #endif -#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) && !EXCLUDE_POWER_TELEMETRY +#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) && !MESHTASTIC_EXCLUDE_POWER_TELEMETRY new PowerTelemetryModule(); #endif #if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)) && !defined(CONFIG_IDF_TARGET_ESP32S2) && \ From cf4753f7fd32ce43e6f11b5760f1e0366f7c07a5 Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Tue, 12 Mar 2024 01:56:55 +1300 Subject: [PATCH 303/472] Async full-refresh for EInkDynamicDisplay (#3339) * Move Wireless Paper V1.1 custom hibernate behavior to GxEPD2 * Async full-refresh for EInkDynamicDisplay * initial config for T-Echo * formatting responds to https://github.com/meshtastic/firmware/pull/3339#discussion_r1518175434 * increase fast-refresh limit for T-Echo https://github.com/meshtastic/firmware/pull/3339#issuecomment-1986245727 * change dependency from private repo to meshtastic/GxEPD2 --------- Co-authored-by: Ben Meadors --- src/graphics/EInkDisplay2.cpp | 25 +++--- src/graphics/EInkDisplay2.h | 7 ++ src/graphics/EInkDynamicDisplay.cpp | 90 +++++++++++++++++-- src/graphics/EInkDynamicDisplay.h | 15 +++- variants/heltec_wireless_paper/platformio.ini | 2 +- variants/heltec_wireless_paper/variant.h | 1 - variants/t-echo/platformio.ini | 8 +- 7 files changed, 121 insertions(+), 27 deletions(-) diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index 6ee4245b3..6f7885b45 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -71,28 +71,24 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit) } } + // Trigger the refresh in GxEPD2 LOG_DEBUG("Updating E-Paper... "); - -#if false - // Currently unused; rescued from commented-out line during a refactor - // Use a meaningful macro here if variant doesn't want fast refresh - - // Full update mode (slow) - adafruitDisplay->display(false) -#else - // Fast update mode adafruitDisplay->nextPage(); -#endif -#ifndef EINK_NO_HIBERNATE // Only hibernate if controller IC will preserve image memory - // Put screen to sleep to save power (possibly not necessary because we already did poweroff inside of display) - adafruitDisplay->hibernate(); -#endif + // End the update process + endUpdate(); LOG_DEBUG("done\n"); return true; } +// End the update process - virtual method, overriden in derived class +void EInkDisplay::endUpdate() +{ + // Power off display hardware, then deep-sleep (Except Wireless Paper V1.1, no deep-sleep) + adafruitDisplay->hibernate(); +} + // Write the buffer to the display memory void EInkDisplay::display(void) { @@ -188,6 +184,7 @@ bool EInkDisplay::connect() // Init GxEPD2 adafruitDisplay->init(); adafruitDisplay->setRotation(3); + adafruitDisplay->clearScreen(); // Clearing now, so the boot logo will draw nice and smoothe (fast refresh) } #elif defined(PCA10059) { diff --git a/src/graphics/EInkDisplay2.h b/src/graphics/EInkDisplay2.h index 75770a3bc..f74416494 100644 --- a/src/graphics/EInkDisplay2.h +++ b/src/graphics/EInkDisplay2.h @@ -45,6 +45,13 @@ class EInkDisplay : public OLEDDisplay */ virtual bool forceDisplay(uint32_t msecLimit = 1000); + /** + * Run any code needed to complete an update, after the physical refresh has completed. + * Split from forceDisplay(), to enable async refresh in derived EInkDynamicDisplay class. + * + */ + virtual void endUpdate(); + /** * shim to make the abstraction happy * diff --git a/src/graphics/EInkDynamicDisplay.cpp b/src/graphics/EInkDynamicDisplay.cpp index ae1e30fe1..75db0e33f 100644 --- a/src/graphics/EInkDynamicDisplay.cpp +++ b/src/graphics/EInkDynamicDisplay.cpp @@ -94,19 +94,29 @@ void EInkDynamicDisplay::adjustRefreshCounters() // Trigger the display update by calling base class bool EInkDynamicDisplay::update() { + // Detemine the refresh mode to use, and start the update bool refreshApproved = determineMode(); if (refreshApproved) EInkDisplay::forceDisplay(0); // Bypass base class' own rate-limiting system - return refreshApproved; // (Unutilized) Base class promises to return true if update ran + +#if defined(HAS_EINK_ASYNCFULL) + if (refreshApproved) + endOrDetach(); // Either endUpdate() right now (fast refresh), or set the async flag (full refresh) +#endif + + return refreshApproved; // (Unutilized) Base class promises to return true if update ran } // Assess situation, pick a refresh type bool EInkDynamicDisplay::determineMode() { - checkWasFlooded(); + checkForPromotion(); +#if defined(HAS_EINK_ASYNCFULL) + checkAsyncFullRefresh(); +#endif checkRateLimiting(); - // If too soon for a new time, abort here + // If too soon for a new frame, or display busy, abort early if (refresh == SKIPPED) { storeAndReset(); return false; // No refresh @@ -116,7 +126,7 @@ bool EInkDynamicDisplay::determineMode() resetRateLimiting(); // Once determineMode() ends, will have to wait again hashImage(); // Generate here, so we can still copy it to previousImageHash, even if we skip the comparison check - LOG_DEBUG("EInkDynamicDisplay: "); // Begin log entry + LOG_DEBUG("determineMode(): "); // Begin log entry // Once mode determined, any remaining checks will bypass checkCosmetic(); @@ -151,13 +161,25 @@ bool EInkDynamicDisplay::determineMode() } } -// Did RESPONSIVE frames previously exceed the rate-limit for fast refresh? -void EInkDynamicDisplay::checkWasFlooded() +// Was a frame skipped (rate, display busy) that should have been a FAST refresh? +void EInkDynamicDisplay::checkForPromotion() { - if (previousReason == EXCEEDED_RATELIMIT_FAST) { - // If so, allow a BACKGROUND frame to draw as RESPONSIVE - // Because we DID want a RESPONSIVE frame last time, we just didn't get it + // If a frame was skipped (rate, display busy), then promote a BACKGROUND frame + // Because we DID want a RESPONSIVE/COSMETIC/DEMAND_FULL frame last time, we just didn't get it + + switch (previousReason) { + case ASYNC_REFRESH_BLOCKED_DEMANDFAST: + setFrameFlag(DEMAND_FAST); + break; + case ASYNC_REFRESH_BLOCKED_COSMETIC: + setFrameFlag(COSMETIC); + break; + case ASYNC_REFRESH_BLOCKED_RESPONSIVE: + case EXCEEDED_RATELIMIT_FAST: setFrameFlag(RESPONSIVE); + break; + default: + break; } } @@ -381,4 +403,54 @@ void EInkDynamicDisplay::resetGhostPixelTracking() } #endif // EINK_LIMIT_GHOSTING_PX +#ifdef HAS_EINK_ASYNCFULL +// Check the status of an "async full-refresh", and run the finish-up code if the hardware is ready +void EInkDynamicDisplay::checkAsyncFullRefresh() +{ + // No refresh taking place, continue with determineMode() + if (!asyncRefreshRunning) + return; + + // Full refresh still running + if (adafruitDisplay->epd2.isBusy()) { + // No refresh + refresh = SKIPPED; + + // Set the reason, marking what type of frame we're skipping + if (frameFlags & DEMAND_FAST) + reason = ASYNC_REFRESH_BLOCKED_DEMANDFAST; + else if (frameFlags & COSMETIC) + reason = ASYNC_REFRESH_BLOCKED_COSMETIC; + else if (frameFlags & RESPONSIVE) + reason = ASYNC_REFRESH_BLOCKED_RESPONSIVE; + else + reason = ASYNC_REFRESH_BLOCKED_BACKGROUND; + + return; + } + + // If we asyncRefreshRunning flag is still set, but display's BUSY pin reports the refresh is done + adafruitDisplay->endAsyncFull(); // Run the end of nextPage() code + EInkDisplay::endUpdate(); // Run base-class code to finish off update (NOT our derived class override) + asyncRefreshRunning = false; // Unset the flag + LOG_DEBUG("Async full-refresh complete\n"); + + // Note: this code only works because of a modification to meshtastic/GxEPD2. + // It is only equipped to intercept calls to nextPage() +} + +// Figure out who runs the post-update code +void EInkDynamicDisplay::endOrDetach() +{ + if (previousRefresh == FULL) { // Note: previousRefresh is the refresh from this loop. + asyncRefreshRunning = true; // Set the flag - picked up at start of determineMode(), next loop. + LOG_DEBUG("Async full-refresh begins\n"); + } + + // Fast Refresh + else + EInkDisplay::endUpdate(); // Still block while updating, but EInkDisplay needs us to call endUpdate() ourselves. +} +#endif // HAS_EINK_ASYNCFULL + #endif // USE_EINK_DYNAMICDISPLAY \ No newline at end of file diff --git a/src/graphics/EInkDynamicDisplay.h b/src/graphics/EInkDynamicDisplay.h index 2880c716b..3dc00ba7c 100644 --- a/src/graphics/EInkDynamicDisplay.h +++ b/src/graphics/EInkDynamicDisplay.h @@ -44,6 +44,11 @@ class EInkDynamicDisplay : public EInkDisplay }; enum reasonTypes : uint8_t { // How was the decision reached NO_OBJECTIONS, + ASYNC_REFRESH_BLOCKED_DEMANDFAST, + ASYNC_REFRESH_BLOCKED_COSMETIC, + ASYNC_REFRESH_BLOCKED_RESPONSIVE, + ASYNC_REFRESH_BLOCKED_BACKGROUND, + DISPLAY_NOT_READY_FOR_FULL, EXCEEDED_RATELIMIT_FAST, EXCEEDED_RATELIMIT_FULL, FLAGGED_COSMETIC, @@ -64,7 +69,7 @@ class EInkDynamicDisplay : public EInkDisplay bool update(); // Trigger the display update - determine mode, then call base class // Checks as part of determineMode() - void checkWasFlooded(); // Was the previous frame skipped for exceeding EINK_LIMIT_RATE_RESPONSIVE_SEC? + void checkForPromotion(); // Was a frame skipped (rate, display busy) that should have been a FAST refresh? void checkRateLimiting(); // Is this frame too soon? void checkCosmetic(); // Was the COSMETIC flag set? void checkDemandingFast(); // Was the DEMAND_FAST flag set? @@ -99,6 +104,14 @@ class EInkDynamicDisplay : public EInkDisplay uint8_t *dirtyPixels; // Any pixels that have been black since last full-refresh (dynamically allocated mem) uint32_t ghostPixelCount = 0; // Number of pixels with problematic ghosting. Retained here for LOG_DEBUG use #endif + + // Conditional - async full refresh - only with modified meshtastic/GxEPD2 +#if defined(HAS_EINK_ASYNCFULL) + void checkAsyncFullRefresh(); // Check the status of "async full-refresh"; run the post-update code if the hardware is ready + void endOrDetach(); // Run the post-update code, or delegate it off to checkAsyncFullRefresh() + void endUpdate() override {} // Disable base-class behavior of running post-update immediately after forceDisplay() + bool asyncRefreshRunning = false; // Flag, checked by checkAsyncFullRefresh() +#endif }; #endif \ No newline at end of file diff --git a/variants/heltec_wireless_paper/platformio.ini b/variants/heltec_wireless_paper/platformio.ini index 0abbe085e..14275830a 100644 --- a/variants/heltec_wireless_paper/platformio.ini +++ b/variants/heltec_wireless_paper/platformio.ini @@ -16,7 +16,7 @@ build_flags = -D EINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. lib_deps = ${esp32s3_base.lib_deps} - https://github.com/meshtastic/GxEPD2 + https://github.com/meshtastic/GxEPD2/ adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 upload_speed = 115200 \ No newline at end of file diff --git a/variants/heltec_wireless_paper/variant.h b/variants/heltec_wireless_paper/variant.h index 28bc8628a..29b8bbbd1 100644 --- a/variants/heltec_wireless_paper/variant.h +++ b/variants/heltec_wireless_paper/variant.h @@ -5,7 +5,6 @@ #define I2C_SCL SCL #define USE_EINK -#define EINK_NO_HIBERNATE /* * eink display pins diff --git a/variants/t-echo/platformio.ini b/variants/t-echo/platformio.ini index 49ba3bb34..c97341a3b 100644 --- a/variants/t-echo/platformio.ini +++ b/variants/t-echo/platformio.ini @@ -11,10 +11,16 @@ build_flags = ${nrf52840_base.build_flags} -Ivariants/t-echo -DEINK_DISPLAY_MODEL=GxEPD2_154_D67 -DEINK_WIDTH=200 -DEINK_HEIGHT=200 + -DUSE_EINK_DYNAMICDISPLAY ; Enable Dynamic EInk + -DEINK_LIMIT_FASTREFRESH=20 ; How many consecutive fast-refreshes are permitted + -DEINK_LIMIT_RATE_BACKGROUND_SEC=30 ; Minimum interval between BACKGROUND updates + -DEINK_LIMIT_RATE_RESPONSIVE_SEC=1 ; Minimum interval between RESPONSIVE updates + -DEINK_LIMIT_GHOSTING_PX=2000 ; (Optional) How much image ghosting is tolerated + -DEINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. build_src_filter = ${nrf52_base.build_src_filter} +<../variants/t-echo> lib_deps = ${nrf52840_base.lib_deps} - https://github.com/meshtastic/GxEPD2#afce87a97dda1ac31d8a28dc8fa7c6f55dc96a61 + https://github.com/meshtastic/GxEPD2 adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 ;upload_protocol = fs From 1d31be939ff36dd2ad675a72893d502aa91808e2 Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Tue, 12 Mar 2024 03:06:01 +1300 Subject: [PATCH 304/472] Swap Wireless Paper V1.0 dependency to meshtastic/GxEPD2 --- variants/heltec_wireless_paper_v1/platformio.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/variants/heltec_wireless_paper_v1/platformio.ini b/variants/heltec_wireless_paper_v1/platformio.ini index 9327ed256..de832d6d7 100644 --- a/variants/heltec_wireless_paper_v1/platformio.ini +++ b/variants/heltec_wireless_paper_v1/platformio.ini @@ -16,7 +16,7 @@ build_flags = ;-D EINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. lib_deps = ${esp32s3_base.lib_deps} - https://github.com/todd-herbert/meshtastic-GxEPD2#async + https://github.com/meshtastic/GxEPD2#55f618961db45a23eff0233546430f1e5a80f63a adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 upload_speed = 115200 \ No newline at end of file From 1f766a04aa036c83094eb34c6048f8ab6774f0f4 Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Tue, 12 Mar 2024 04:04:28 +1300 Subject: [PATCH 305/472] purge unused enum val --- src/graphics/EInkDynamicDisplay.h | 1 - 1 file changed, 1 deletion(-) diff --git a/src/graphics/EInkDynamicDisplay.h b/src/graphics/EInkDynamicDisplay.h index dcae056c6..81963df58 100644 --- a/src/graphics/EInkDynamicDisplay.h +++ b/src/graphics/EInkDynamicDisplay.h @@ -49,7 +49,6 @@ class EInkDynamicDisplay : public EInkDisplay ASYNC_REFRESH_BLOCKED_COSMETIC, ASYNC_REFRESH_BLOCKED_RESPONSIVE, ASYNC_REFRESH_BLOCKED_BACKGROUND, - DISPLAY_NOT_READY_FOR_FULL, EXCEEDED_RATELIMIT_FAST, EXCEEDED_RATELIMIT_FULL, FLAGGED_COSMETIC, From c80098f517b9f69071227f96f96834e57282e9d8 Mon Sep 17 00:00:00 2001 From: Andre K Date: Mon, 11 Mar 2024 13:49:46 -0300 Subject: [PATCH 306/472] refactor: remove ACKs in range tests so zero hops is honored (#3374) --- src/modules/RangeTestModule.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/RangeTestModule.cpp b/src/modules/RangeTestModule.cpp index b45068b45..904fb25db 100644 --- a/src/modules/RangeTestModule.cpp +++ b/src/modules/RangeTestModule.cpp @@ -114,7 +114,7 @@ void RangeTestModuleRadio::sendPayload(NodeNum dest, bool wantReplies) p->to = dest; p->decoded.want_response = wantReplies; p->hop_limit = 0; - p->want_ack = true; + p->want_ack = false; packetSequence++; From e16689a0d6b3192c12fe5b7090992b61d540aeb8 Mon Sep 17 00:00:00 2001 From: Manuel <71137295+mverch67@users.noreply.github.com> Date: Mon, 11 Mar 2024 18:45:59 +0100 Subject: [PATCH 307/472] fix heap use after delete (#3373) --- src/mesh/ReliableRouter.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/mesh/ReliableRouter.cpp b/src/mesh/ReliableRouter.cpp index 167a248ab..2327cbfb7 100644 --- a/src/mesh/ReliableRouter.cpp +++ b/src/mesh/ReliableRouter.cpp @@ -167,8 +167,6 @@ bool ReliableRouter::stopRetransmission(GlobalPacketId key) auto old = findPendingPacket(key); if (old) { auto p = old->packet; - auto numErased = pending.erase(key); - assert(numErased == 1); /* Only when we already transmitted a packet via LoRa, we will cancel the packet in the Tx queue to avoid canceling a transmission if it was ACKed super fast via MQTT */ if (old->numRetransmissions < NUM_RETRANSMISSIONS - 1) { @@ -177,6 +175,8 @@ bool ReliableRouter::stopRetransmission(GlobalPacketId key) // now free the pooled copy for retransmission too packetPool.release(p); } + auto numErased = pending.erase(key); + assert(numErased == 1); return true; } else return false; From c7839b469b5a3dee6711c4d892bb9a002d7d96d2 Mon Sep 17 00:00:00 2001 From: Manuel <71137295+mverch67@users.noreply.github.com> Date: Mon, 11 Mar 2024 18:51:14 +0100 Subject: [PATCH 308/472] fix of tryfix SHT31 sensor (#3377) --- src/modules/Telemetry/Sensor/SHT31Sensor.cpp | 1 + src/modules/Telemetry/Sensor/SHT31Sensor.h | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/src/modules/Telemetry/Sensor/SHT31Sensor.cpp b/src/modules/Telemetry/Sensor/SHT31Sensor.cpp index 7f2b7691e..35978d970 100644 --- a/src/modules/Telemetry/Sensor/SHT31Sensor.cpp +++ b/src/modules/Telemetry/Sensor/SHT31Sensor.cpp @@ -12,6 +12,7 @@ int32_t SHT31Sensor::runOnce() if (!hasSensor()) { return DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS; } + sht31 = Adafruit_SHT31(nodeTelemetrySensorsMap[sensorType].second); status = sht31.begin(nodeTelemetrySensorsMap[sensorType].first); return initI2CSensor(); } diff --git a/src/modules/Telemetry/Sensor/SHT31Sensor.h b/src/modules/Telemetry/Sensor/SHT31Sensor.h index 9700bdf2c..c6f8f1596 100644 --- a/src/modules/Telemetry/Sensor/SHT31Sensor.h +++ b/src/modules/Telemetry/Sensor/SHT31Sensor.h @@ -5,7 +5,7 @@ class SHT31Sensor : public TelemetrySensor { private: - Adafruit_SHT31 sht31 = Adafruit_SHT31(nodeTelemetrySensorsMap[sensorType].second); + Adafruit_SHT31 sht31; protected: virtual void setup() override; From 5f47ca1f32dd283739c4d78a4e08f20a9bd60fa1 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Mon, 11 Mar 2024 21:58:45 +0100 Subject: [PATCH 309/472] Don't spam logs if no position with map reporting (#3378) --- src/mqtt/MQTT.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 2de35971a..760aa7210 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -552,14 +552,14 @@ void MQTT::perhapsReportToMap() if (!moduleConfig.mqtt.map_reporting_enabled || !(moduleConfig.mqtt.proxy_to_client_enabled || isConnectedDirectly())) return; - if (map_position_precision == 0 || (localPosition.latitude_i == 0 && localPosition.longitude_i == 0)) { - LOG_WARN("MQTT Map reporting is enabled, but precision is 0 or no position available.\n"); - return; - } - if (millis() - last_report_to_map < map_publish_interval_secs * 1000) { return; } else { + if (map_position_precision == 0 || (localPosition.latitude_i == 0 && localPosition.longitude_i == 0)) { + LOG_WARN("MQTT Map reporting is enabled, but precision is 0 or no position available.\n"); + return; + } + // Allocate ServiceEnvelope and fill it meshtastic_ServiceEnvelope *se = mqttPool.allocZeroed(); se->channel_id = (char *)channels.getGlobalId(channels.getPrimaryIndex()); // Use primary channel as the channel_id From f9bf9e2dcc3e9ea11c4ae3fbe8916f54aa2df171 Mon Sep 17 00:00:00 2001 From: thebentern Date: Mon, 11 Mar 2024 21:43:46 +0000 Subject: [PATCH 310/472] [create-pull-request] automated change --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 8927d1781..07fadd0d8 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 3 -build = 0 +build = 1 From affbd7f2b91ffb397066df70e22e34d3e6ac3aeb Mon Sep 17 00:00:00 2001 From: AeroXuk Date: Tue, 12 Mar 2024 02:13:52 +0000 Subject: [PATCH 311/472] Update MQTT.cpp Bug fix for #3382 --- src/mqtt/MQTT.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 760aa7210..4250ad5cd 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -185,7 +185,7 @@ MQTT::MQTT() : concurrency::OSThread("mqtt"), mqttQueue(MAX_MQTT_QUEUE) statusTopic = moduleConfig.mqtt.root + statusTopic; cryptTopic = moduleConfig.mqtt.root + cryptTopic; jsonTopic = moduleConfig.mqtt.root + jsonTopic; - mapTopic = moduleConfig.mqtt.root + jsonTopic; + mapTopic = moduleConfig.mqtt.root + mapTopic; } else { statusTopic = "msh" + statusTopic; cryptTopic = "msh" + cryptTopic; @@ -915,4 +915,4 @@ bool MQTT::isValidJsonEnvelope(JSONObject &json) (json["from"]->AsNumber() == nodeDB.getNodeNum()) && // only accept message if the "from" is us (json.find("type") != json.end()) && json["type"]->IsString() && // should specify a type (json.find("payload") != json.end()); // should have a payload -} \ No newline at end of file +} From 7f063fbf811faf0c722cd377f5b7bde572872fbd Mon Sep 17 00:00:00 2001 From: Wolfgang Nagele Date: Tue, 12 Mar 2024 17:55:31 +0100 Subject: [PATCH 312/472] Support external charge detection (#3386) * Support external charge detection * trunk fmt --- src/Power.cpp | 25 ++++++++++++++++++++++++- 1 file changed, 24 insertions(+), 1 deletion(-) diff --git a/src/Power.cpp b/src/Power.cpp index 3d1a1b9b2..71554daa3 100644 --- a/src/Power.cpp +++ b/src/Power.cpp @@ -54,6 +54,19 @@ static const adc_atten_t atten = ADC_ATTENUATION; #endif #endif // BATTERY_PIN && ARCH_ESP32 +#ifdef EXT_CHRG_DETECT +#ifndef EXT_CHRG_DETECT_MODE +static const uint8_t ext_chrg_detect_mode = INPUT; +#else +static const uint8_t ext_chrg_detect_mode = EXT_CHRG_DETECT_MODE; +#endif +#ifndef EXT_CHRG_DETECT_VALUE +static const uint8_t ext_chrg_detect_value = HIGH; +#else +static const uint8_t ext_chrg_detect_value = EXT_CHRG_DETECT_VALUE; +#endif +#endif + #if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) INA260Sensor ina260Sensor; INA219Sensor ina219Sensor; @@ -322,7 +335,14 @@ class AnalogBatteryLevel : public HasBatteryLevel /// Assume charging if we have a battery and external power is connected. /// we can't be smart enough to say 'full'? - virtual bool isCharging() override { return isBatteryConnect() && isVbusIn(); } + virtual bool isCharging() override + { +#ifdef EXT_CHRG_DETECT + return digitalRead(EXT_CHRG_DETECT) == ext_chrg_detect_value; +#else + return isBatteryConnect() && isVbusIn(); +#endif + } private: /// If we see a battery voltage higher than physics allows - assume charger is pumping @@ -389,6 +409,9 @@ bool Power::analogInit() #ifdef EXT_PWR_DETECT pinMode(EXT_PWR_DETECT, INPUT); #endif +#ifdef EXT_CHRG_DETECT + pinMode(EXT_CHRG_DETECT, ext_chrg_detect_mode); +#endif #ifdef BATTERY_PIN LOG_DEBUG("Using analog input %d for battery level\n", BATTERY_PIN); From cf11807f9711eb4575ada4dce1fbb32c18f9e89a Mon Sep 17 00:00:00 2001 From: Thomas Herrmann Date: Tue, 12 Mar 2024 18:21:09 +0100 Subject: [PATCH 313/472] use priority background for low priority messages (#3381) --- src/modules/Telemetry/AirQualityTelemetry.cpp | 2 +- src/modules/Telemetry/DeviceTelemetry.cpp | 2 +- src/modules/Telemetry/EnvironmentTelemetry.cpp | 2 +- src/modules/Telemetry/PowerTelemetry.cpp | 2 +- src/modules/esp32/PaxcounterModule.cpp | 2 +- src/modules/esp32/StoreForwardModule.cpp | 4 ++-- 6 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/modules/Telemetry/AirQualityTelemetry.cpp b/src/modules/Telemetry/AirQualityTelemetry.cpp index f87ea504b..ada1fdef8 100644 --- a/src/modules/Telemetry/AirQualityTelemetry.cpp +++ b/src/modules/Telemetry/AirQualityTelemetry.cpp @@ -112,7 +112,7 @@ bool AirQualityTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly) if (config.device.role == meshtastic_Config_DeviceConfig_Role_SENSOR) p->priority = meshtastic_MeshPacket_Priority_RELIABLE; else - p->priority = meshtastic_MeshPacket_Priority_MIN; + p->priority = meshtastic_MeshPacket_Priority_BACKGROUND; // release previous packet before occupying a new spot if (lastMeasurementPacket != nullptr) diff --git a/src/modules/Telemetry/DeviceTelemetry.cpp b/src/modules/Telemetry/DeviceTelemetry.cpp index a6eecda80..55000e4c6 100644 --- a/src/modules/Telemetry/DeviceTelemetry.cpp +++ b/src/modules/Telemetry/DeviceTelemetry.cpp @@ -91,7 +91,7 @@ bool DeviceTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly) meshtastic_MeshPacket *p = allocDataProtobuf(telemetry); p->to = dest; p->decoded.want_response = false; - p->priority = meshtastic_MeshPacket_Priority_MIN; + p->priority = meshtastic_MeshPacket_Priority_BACKGROUND; nodeDB.updateTelemetry(nodeDB.getNodeNum(), telemetry, RX_SRC_LOCAL); if (phoneOnly) { diff --git a/src/modules/Telemetry/EnvironmentTelemetry.cpp b/src/modules/Telemetry/EnvironmentTelemetry.cpp index d4f423e54..7b59c28a6 100644 --- a/src/modules/Telemetry/EnvironmentTelemetry.cpp +++ b/src/modules/Telemetry/EnvironmentTelemetry.cpp @@ -253,7 +253,7 @@ bool EnvironmentTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly) if (config.device.role == meshtastic_Config_DeviceConfig_Role_SENSOR) p->priority = meshtastic_MeshPacket_Priority_RELIABLE; else - p->priority = meshtastic_MeshPacket_Priority_MIN; + p->priority = meshtastic_MeshPacket_Priority_BACKGROUND; // release previous packet before occupying a new spot if (lastMeasurementPacket != nullptr) packetPool.release(lastMeasurementPacket); diff --git a/src/modules/Telemetry/PowerTelemetry.cpp b/src/modules/Telemetry/PowerTelemetry.cpp index 30628bfd7..300ab1f62 100644 --- a/src/modules/Telemetry/PowerTelemetry.cpp +++ b/src/modules/Telemetry/PowerTelemetry.cpp @@ -195,7 +195,7 @@ bool PowerTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly) if (config.device.role == meshtastic_Config_DeviceConfig_Role_SENSOR) p->priority = meshtastic_MeshPacket_Priority_RELIABLE; else - p->priority = meshtastic_MeshPacket_Priority_MIN; + p->priority = meshtastic_MeshPacket_Priority_BACKGROUND; // release previous packet before occupying a new spot if (lastMeasurementPacket != nullptr) packetPool.release(lastMeasurementPacket); diff --git a/src/modules/esp32/PaxcounterModule.cpp b/src/modules/esp32/PaxcounterModule.cpp index 580fc46e1..54c67fad7 100644 --- a/src/modules/esp32/PaxcounterModule.cpp +++ b/src/modules/esp32/PaxcounterModule.cpp @@ -50,7 +50,7 @@ bool PaxcounterModule::sendInfo(NodeNum dest) meshtastic_MeshPacket *p = allocDataProtobuf(pl); p->to = dest; p->decoded.want_response = false; - p->priority = meshtastic_MeshPacket_Priority_MIN; + p->priority = meshtastic_MeshPacket_Priority_BACKGROUND; service.sendToMesh(p, RX_SRC_LOCAL, true); diff --git a/src/modules/esp32/StoreForwardModule.cpp b/src/modules/esp32/StoreForwardModule.cpp index 70d13afca..71d75750a 100644 --- a/src/modules/esp32/StoreForwardModule.cpp +++ b/src/modules/esp32/StoreForwardModule.cpp @@ -255,7 +255,7 @@ void StoreForwardModule::sendMessage(NodeNum dest, const meshtastic_StoreAndForw p->to = dest; - p->priority = meshtastic_MeshPacket_Priority_MIN; + p->priority = meshtastic_MeshPacket_Priority_BACKGROUND; // FIXME - Determine if the delayed packet is broadcast or delayed. For now, assume // everything is broadcast. @@ -334,7 +334,7 @@ ProcessMessage StoreForwardModule::handleReceived(const meshtastic_MeshPacket &m LOG_INFO("*** S&F - Busy. Try again shortly.\n"); meshtastic_MeshPacket *pr = allocReply(); pr->to = getFrom(&mp); - pr->priority = meshtastic_MeshPacket_Priority_MIN; + pr->priority = meshtastic_MeshPacket_Priority_BACKGROUND; pr->want_ack = false; pr->decoded.want_response = false; pr->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_APP; From ee685b4ed78edad0f06b5816b913f39af8e25fb4 Mon Sep 17 00:00:00 2001 From: Wolfgang Nagele Date: Tue, 12 Mar 2024 19:03:04 +0100 Subject: [PATCH 314/472] Check AQ_SET_PIN instead of EINK dependency (#3387) --- src/main.cpp | 2 +- src/platform/nrf52/main-nrf52.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main.cpp b/src/main.cpp index ef1cd53c3..535051811 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -342,7 +342,7 @@ void setup() pinMode(PIN_3V3_EN, OUTPUT); digitalWrite(PIN_3V3_EN, HIGH); #endif -#ifndef USE_EINK +#ifdef AQ_SET_PIN // RAK-12039 set pin for Air quality sensor pinMode(AQ_SET_PIN, OUTPUT); digitalWrite(AQ_SET_PIN, HIGH); diff --git a/src/platform/nrf52/main-nrf52.cpp b/src/platform/nrf52/main-nrf52.cpp index 9e8798e37..2f670dee3 100644 --- a/src/platform/nrf52/main-nrf52.cpp +++ b/src/platform/nrf52/main-nrf52.cpp @@ -177,7 +177,7 @@ void cpuDeepSleep(uint32_t msecToWake) #ifdef PIN_3V3_EN digitalWrite(PIN_3V3_EN, LOW); #endif -#ifndef USE_EINK +#ifdef AQ_SET_PIN // RAK-12039 set pin for Air quality sensor digitalWrite(AQ_SET_PIN, LOW); #endif From 38ea6814331c26cdb72af024e401151a6f466de5 Mon Sep 17 00:00:00 2001 From: Wolfgang Nagele Date: Tue, 12 Mar 2024 22:42:21 +0100 Subject: [PATCH 315/472] Fix LTO discharge curve (#3385) * Fix LTO discharge curve * Remove duplicate info --- src/power.h | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/src/power.h b/src/power.h index 4dd35e710..b94ce8f98 100644 --- a/src/power.h +++ b/src/power.h @@ -10,13 +10,6 @@ #define NUM_OCV_POINTS 11 #endif -// 3400,3350,3320,3290,3270,3260,3250,3230,3200,3120,3000 //3.4 to 3.0 LiFePO4 -// 2120,2090,2070,2050,2030,2010,1990,1980,1970,1960,1950 //2.12 to 1.95 Lead Acid -// 4200,4050,3990,3890,3790,3700,3650,3550,3450,3300,3200 //4.2 to 3.2 LiIon/LiPo -// 4200,4050,3990,3890,3790,3700,3650,3550,3400,3300,3000 //4.2 to 3.0 LiIon/LiPo -// 4150,4050,3990,3890,3790,3690,3620,3520,3420,3300,3100 //4.15 to 3.1 LiIon/LiPo -// 2770,2650,2540,2420,2300,2180,2060,1940,1800,1680,1550 //2.8 to 1.5 Lithium Titanate - #ifndef OCV_ARRAY #ifdef CELL_TYPE_LIFEPO4 #define OCV_ARRAY 3400, 3350, 3320, 3290, 3270, 3260, 3250, 3230, 3200, 3120, 3000 @@ -27,7 +20,7 @@ #elif defined(CELL_TYPE_NIMH) #define OCV_ARRAY 1400, 1300, 1280, 1270, 1260, 1250, 1240, 1230, 1210, 1150, 1000 #elif defined(CELL_TYPE_LTO) -#define OCV_ARRAY 2770, 2650, 2540, 2420, 2300, 2180, 2060, 1940, 1800, 1680, 1550 +#define OCV_ARRAY 2700, 2560, 2540, 2520, 2500, 2460, 2420, 2400, 2380, 2320, 1500 #else // LiIon #define OCV_ARRAY 4190, 4050, 3990, 3890, 3800, 3720, 3630, 3530, 3420, 3300, 3100 #endif From 724fa38a552ddd952ceeca336e65ae187962bb59 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Tue, 12 Mar 2024 22:42:34 +0100 Subject: [PATCH 316/472] Fix T-LoRa V2.1-6 with TCXO init (#3392) --- src/main.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/main.cpp b/src/main.cpp index 535051811..bb9b68631 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -226,6 +226,11 @@ void setup() digitalWrite(PIN_POWER_EN1, INPUT); #endif +#if defined(LORA_TCXO_GPIO) + pinMode(LORA_TCXO_GPIO, OUTPUT); + digitalWrite(LORA_TCXO_GPIO, HIGH); +#endif + #if defined(VEXT_ENABLE_V03) pinMode(VEXT_ENABLE_V03, OUTPUT); pinMode(ST7735_BL_V03, OUTPUT); From 333c3c1c9ebf71910c78e90d171db5a921b4d733 Mon Sep 17 00:00:00 2001 From: Tavis Date: Tue, 12 Mar 2024 21:42:08 -1000 Subject: [PATCH 317/472] fix off by one error buzzer is index 2, but loop was 0-1 so buzzer never got turned off. --- src/modules/ExternalNotificationModule.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/ExternalNotificationModule.cpp b/src/modules/ExternalNotificationModule.cpp index 9af1f9e00..652965f6d 100644 --- a/src/modules/ExternalNotificationModule.cpp +++ b/src/modules/ExternalNotificationModule.cpp @@ -81,7 +81,7 @@ int32_t ExternalNotificationModule::runOnce() // let the song finish if we reach timeout nagCycleCutoff = UINT32_MAX; LOG_INFO("Turning off external notification: "); - for (int i = 0; i < 2; i++) { + for (int i = 0; i < 3; i++) { setExternalOff(i); externalTurnedOn[i] = 0; LOG_INFO("%d ", i); From 2efe436102d097d535bf2d20b90f399e58f4a0ef Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 13 Mar 2024 07:20:51 -0500 Subject: [PATCH 318/472] Update nrf52 platform and consolidate Adafruit Bus IO (#3393) --- arch/nrf52/nrf52.ini | 2 +- platformio.ini | 2 +- variants/canaryone/platformio.ini | 1 - variants/heltec_wireless_paper/platformio.ini | 1 - variants/heltec_wireless_paper_v1/platformio.ini | 1 - variants/nano-g2-ultra/platformio.ini | 1 - variants/t-echo/platformio.ini | 1 - 7 files changed, 2 insertions(+), 7 deletions(-) diff --git a/arch/nrf52/nrf52.ini b/arch/nrf52/nrf52.ini index 5155eaadc..2505fe315 100644 --- a/arch/nrf52/nrf52.ini +++ b/arch/nrf52/nrf52.ini @@ -1,6 +1,6 @@ [nrf52_base] ; Instead of the standard nordicnrf52 platform, we use our fork which has our added variant files -platform = platformio/nordicnrf52@^10.1.0 +platform = platformio/nordicnrf52@^10.4.0 extends = arduino_base build_type = debug ; I'm debugging with ICE a lot now diff --git a/platformio.ini b/platformio.ini index b67ddc50a..392b38fd7 100644 --- a/platformio.ini +++ b/platformio.ini @@ -113,7 +113,7 @@ lib_deps = ; (not included in native / portduino) [environmental_base] lib_deps = - adafruit/Adafruit BusIO@^1.11.4 + adafruit/Adafruit BusIO@^1.15.0 adafruit/Adafruit Unified Sensor@^1.1.11 adafruit/Adafruit BMP280 Library@^2.6.8 adafruit/Adafruit BMP085 Library@^1.2.4 diff --git a/variants/canaryone/platformio.ini b/variants/canaryone/platformio.ini index d52bbb24a..4917f52c7 100644 --- a/variants/canaryone/platformio.ini +++ b/variants/canaryone/platformio.ini @@ -10,6 +10,5 @@ build_flags = ${nrf52840_base.build_flags} -Ivariants/canaryone build_src_filter = ${nrf52_base.build_src_filter} +<../variants/canaryone> lib_deps = ${nrf52840_base.lib_deps} - adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 ;upload_protocol = fs diff --git a/variants/heltec_wireless_paper/platformio.ini b/variants/heltec_wireless_paper/platformio.ini index 94ed15ed1..1e1bb9376 100644 --- a/variants/heltec_wireless_paper/platformio.ini +++ b/variants/heltec_wireless_paper/platformio.ini @@ -17,6 +17,5 @@ build_flags = lib_deps = ${esp32s3_base.lib_deps} https://github.com/meshtastic/GxEPD2#55f618961db45a23eff0233546430f1e5a80f63a - adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 upload_speed = 115200 \ No newline at end of file diff --git a/variants/heltec_wireless_paper_v1/platformio.ini b/variants/heltec_wireless_paper_v1/platformio.ini index de832d6d7..cae1940b3 100644 --- a/variants/heltec_wireless_paper_v1/platformio.ini +++ b/variants/heltec_wireless_paper_v1/platformio.ini @@ -17,6 +17,5 @@ build_flags = lib_deps = ${esp32s3_base.lib_deps} https://github.com/meshtastic/GxEPD2#55f618961db45a23eff0233546430f1e5a80f63a - adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 upload_speed = 115200 \ No newline at end of file diff --git a/variants/nano-g2-ultra/platformio.ini b/variants/nano-g2-ultra/platformio.ini index d5e5a6137..2b011e032 100644 --- a/variants/nano-g2-ultra/platformio.ini +++ b/variants/nano-g2-ultra/platformio.ini @@ -9,6 +9,5 @@ build_flags = ${nrf52840_base.build_flags} -Ivariants/nano-g2-ultra -D NANO_G2_U build_src_filter = ${nrf52_base.build_src_filter} +<../variants/nano-g2-ultra> lib_deps = ${nrf52840_base.lib_deps} - adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 ;upload_protocol = fs diff --git a/variants/t-echo/platformio.ini b/variants/t-echo/platformio.ini index be8900e0f..9ff60be3f 100644 --- a/variants/t-echo/platformio.ini +++ b/variants/t-echo/platformio.ini @@ -21,6 +21,5 @@ build_src_filter = ${nrf52_base.build_src_filter} +<../variants/t-echo> lib_deps = ${nrf52840_base.lib_deps} https://github.com/meshtastic/GxEPD2#55f618961db45a23eff0233546430f1e5a80f63a - adafruit/Adafruit BusIO@^1.13.2 lewisxhe/PCF8563_Library@^1.0.1 ;upload_protocol = fs From 216f85ff221990a86b4ffd4548c90220b59fd255 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Wed, 13 Mar 2024 09:02:48 -0500 Subject: [PATCH 319/472] [create-pull-request] automated change (#3397) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/clientonly.pb.c | 3 +++ src/mesh/generated/meshtastic/clientonly.pb.h | 16 ++++++++++++++++ src/mesh/generated/meshtastic/deviceonly.pb.h | 2 +- src/mesh/generated/meshtastic/localonly.pb.h | 2 +- src/mesh/generated/meshtastic/module_config.pb.c | 2 +- src/mesh/generated/meshtastic/module_config.pb.h | 6 +++--- 7 files changed, 26 insertions(+), 7 deletions(-) diff --git a/protobufs b/protobufs index 00332412b..7e3ee8cd9 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 00332412b238fe559175a6e83fdf8d31fa5e209a +Subproject commit 7e3ee8cd96740910d0611433cb9a05a7a692568c diff --git a/src/mesh/generated/meshtastic/clientonly.pb.c b/src/mesh/generated/meshtastic/clientonly.pb.c index ebc2ffabc..90e8e2d8a 100644 --- a/src/mesh/generated/meshtastic/clientonly.pb.c +++ b/src/mesh/generated/meshtastic/clientonly.pb.c @@ -9,4 +9,7 @@ PB_BIND(meshtastic_DeviceProfile, meshtastic_DeviceProfile, 2) +PB_BIND(meshtastic_Heartbeat, meshtastic_Heartbeat, AUTO) + + diff --git a/src/mesh/generated/meshtastic/clientonly.pb.h b/src/mesh/generated/meshtastic/clientonly.pb.h index 0f70e09c6..19b0a0e5f 100644 --- a/src/mesh/generated/meshtastic/clientonly.pb.h +++ b/src/mesh/generated/meshtastic/clientonly.pb.h @@ -30,6 +30,12 @@ typedef struct _meshtastic_DeviceProfile { meshtastic_LocalModuleConfig module_config; } meshtastic_DeviceProfile; +/* A heartbeat message is sent by a node to indicate that it is still alive. + This is currently only needed to keep serial connections alive. */ +typedef struct _meshtastic_Heartbeat { + char dummy_field; +} meshtastic_Heartbeat; + #ifdef __cplusplus extern "C" { @@ -37,7 +43,9 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_DeviceProfile_init_default {false, "", false, "", {{NULL}, NULL}, false, meshtastic_LocalConfig_init_default, false, meshtastic_LocalModuleConfig_init_default} +#define meshtastic_Heartbeat_init_default {0} #define meshtastic_DeviceProfile_init_zero {false, "", false, "", {{NULL}, NULL}, false, meshtastic_LocalConfig_init_zero, false, meshtastic_LocalModuleConfig_init_zero} +#define meshtastic_Heartbeat_init_zero {0} /* Field tags (for use in manual encoding/decoding) */ #define meshtastic_DeviceProfile_long_name_tag 1 @@ -58,13 +66,21 @@ X(a, STATIC, OPTIONAL, MESSAGE, module_config, 5) #define meshtastic_DeviceProfile_config_MSGTYPE meshtastic_LocalConfig #define meshtastic_DeviceProfile_module_config_MSGTYPE meshtastic_LocalModuleConfig +#define meshtastic_Heartbeat_FIELDLIST(X, a) \ + +#define meshtastic_Heartbeat_CALLBACK NULL +#define meshtastic_Heartbeat_DEFAULT NULL + extern const pb_msgdesc_t meshtastic_DeviceProfile_msg; +extern const pb_msgdesc_t meshtastic_Heartbeat_msg; /* Defines for backwards compatibility with code written before nanopb-0.4.0 */ #define meshtastic_DeviceProfile_fields &meshtastic_DeviceProfile_msg +#define meshtastic_Heartbeat_fields &meshtastic_Heartbeat_msg /* Maximum encoded size of messages (where known) */ /* meshtastic_DeviceProfile_size depends on runtime parameters */ +#define meshtastic_Heartbeat_size 0 #ifdef __cplusplus } /* extern "C" */ diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index 556821e1c..79800d4b4 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -324,7 +324,7 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg; #define meshtastic_DeviceState_size 17571 #define meshtastic_NodeInfoLite_size 158 #define meshtastic_NodeRemoteHardwarePin_size 29 -#define meshtastic_OEMStore_size 3262 +#define meshtastic_OEMStore_size 3278 #define meshtastic_PositionLite_size 28 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/localonly.pb.h b/src/mesh/generated/meshtastic/localonly.pb.h index 2e22cb1e4..f27c119bd 100644 --- a/src/mesh/generated/meshtastic/localonly.pb.h +++ b/src/mesh/generated/meshtastic/localonly.pb.h @@ -181,7 +181,7 @@ extern const pb_msgdesc_t meshtastic_LocalModuleConfig_msg; /* Maximum encoded size of messages (where known) */ #define meshtastic_LocalConfig_size 469 -#define meshtastic_LocalModuleConfig_size 647 +#define meshtastic_LocalModuleConfig_size 663 #ifdef __cplusplus } /* extern "C" */ diff --git a/src/mesh/generated/meshtastic/module_config.pb.c b/src/mesh/generated/meshtastic/module_config.pb.c index a75c3fb59..594cf9628 100644 --- a/src/mesh/generated/meshtastic/module_config.pb.c +++ b/src/mesh/generated/meshtastic/module_config.pb.c @@ -9,7 +9,7 @@ PB_BIND(meshtastic_ModuleConfig, meshtastic_ModuleConfig, 2) -PB_BIND(meshtastic_ModuleConfig_MQTTConfig, meshtastic_ModuleConfig_MQTTConfig, AUTO) +PB_BIND(meshtastic_ModuleConfig_MQTTConfig, meshtastic_ModuleConfig_MQTTConfig, 2) PB_BIND(meshtastic_ModuleConfig_MapReportSettings, meshtastic_ModuleConfig_MapReportSettings, AUTO) diff --git a/src/mesh/generated/meshtastic/module_config.pb.h b/src/mesh/generated/meshtastic/module_config.pb.h index 2e1c25c7f..a2adbc1b9 100644 --- a/src/mesh/generated/meshtastic/module_config.pb.h +++ b/src/mesh/generated/meshtastic/module_config.pb.h @@ -119,7 +119,7 @@ typedef struct _meshtastic_ModuleConfig_MQTTConfig { bool tls_enabled; /* The root topic to use for MQTT messages. Default is "msh". This is useful if you want to use a single MQTT server for multiple meshtastic networks and separate them via ACLs */ - char root[16]; + char root[32]; /* If true, we can use the connected phone / client to proxy messages to MQTT instead of a direct connection */ bool proxy_to_client_enabled; /* If true, we will periodically report unencrypted information about our node to a map via MQTT */ @@ -832,7 +832,7 @@ extern const pb_msgdesc_t meshtastic_RemoteHardwarePin_msg; #define meshtastic_ModuleConfig_CannedMessageConfig_size 49 #define meshtastic_ModuleConfig_DetectionSensorConfig_size 44 #define meshtastic_ModuleConfig_ExternalNotificationConfig_size 42 -#define meshtastic_ModuleConfig_MQTTConfig_size 238 +#define meshtastic_ModuleConfig_MQTTConfig_size 254 #define meshtastic_ModuleConfig_MapReportSettings_size 12 #define meshtastic_ModuleConfig_NeighborInfoConfig_size 8 #define meshtastic_ModuleConfig_PaxcounterConfig_size 8 @@ -841,7 +841,7 @@ extern const pb_msgdesc_t meshtastic_RemoteHardwarePin_msg; #define meshtastic_ModuleConfig_SerialConfig_size 28 #define meshtastic_ModuleConfig_StoreForwardConfig_size 22 #define meshtastic_ModuleConfig_TelemetryConfig_size 36 -#define meshtastic_ModuleConfig_size 241 +#define meshtastic_ModuleConfig_size 257 #define meshtastic_RemoteHardwarePin_size 21 #ifdef __cplusplus From 3995e2f7084b5776b655a7027af4620ee7c21e02 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 13 Mar 2024 15:06:52 -0500 Subject: [PATCH 320/472] Remove bunk code --- src/platform/nrf52/NRF52Bluetooth.cpp | 13 ++++--------- 1 file changed, 4 insertions(+), 9 deletions(-) diff --git a/src/platform/nrf52/NRF52Bluetooth.cpp b/src/platform/nrf52/NRF52Bluetooth.cpp index 9a93f5cc6..e1914a184 100644 --- a/src/platform/nrf52/NRF52Bluetooth.cpp +++ b/src/platform/nrf52/NRF52Bluetooth.cpp @@ -202,8 +202,6 @@ void setupMeshService(void) toRadio.begin(); } -// FIXME, turn off soft device access for debugging -static bool isSoftDeviceAllowed = true; static uint32_t configuredPasskey; void NRF52Bluetooth::shutdown() @@ -281,14 +279,11 @@ void NRF52Bluetooth::setup() LOG_INFO("Configuring the Mesh bluetooth service\n"); setupMeshService(); - // Supposedly debugging works with soft device if you disable advertising - if (isSoftDeviceAllowed) { - // Setup the advertising packet(s) - LOG_INFO("Setting up the advertising payload(s)\n"); - startAdv(); + // Setup the advertising packet(s) + LOG_INFO("Setting up the advertising payload(s)\n"); + startAdv(); - LOG_INFO("Advertising\n"); - } + LOG_INFO("Advertising\n"); } void NRF52Bluetooth::resumeAdverising() From 9d2fcbe1e108d221824fc5a1ead1c4cfa08e909b Mon Sep 17 00:00:00 2001 From: Andre K Date: Wed, 13 Mar 2024 20:24:49 -0300 Subject: [PATCH 321/472] use decoded packets in public MQTT range test/detection sensor filter (#3404) Co-authored-by: Ben Meadors --- src/mqtt/MQTT.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 4250ad5cd..c518bc4b5 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -486,9 +486,9 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket & auto &ch = channels.getByIndex(chIndex); - if (&mp.decoded && strcmp(moduleConfig.mqtt.address, default_mqtt_address) == 0 && - (mp.decoded.portnum == meshtastic_PortNum_RANGE_TEST_APP || - mp.decoded.portnum == meshtastic_PortNum_DETECTION_SENSOR_APP)) { + if (&mp_decoded.decoded && strcmp(moduleConfig.mqtt.address, default_mqtt_address) == 0 && + (mp_decoded.decoded.portnum == meshtastic_PortNum_RANGE_TEST_APP || + mp_decoded.decoded.portnum == meshtastic_PortNum_DETECTION_SENSOR_APP)) { LOG_DEBUG("MQTT onSend - Ignoring range test or detection sensor message on public mqtt\n"); return; } From 9c37e57e750a72324ea58f6acda53168c4efae50 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 13 Mar 2024 20:27:26 -0500 Subject: [PATCH 322/472] Only allow phone to set time for fixed positions (#3403) --- src/mesh/NodeDB.h | 9 +++++++-- src/modules/PositionModule.cpp | 10 ++++++++-- 2 files changed, 15 insertions(+), 4 deletions(-) diff --git a/src/mesh/NodeDB.h b/src/mesh/NodeDB.h index e472f7151..20cc5c25b 100644 --- a/src/mesh/NodeDB.h +++ b/src/mesh/NodeDB.h @@ -133,8 +133,13 @@ class NodeDB meshtastic_NodeInfoLite *getMeshNode(NodeNum n); size_t getNumMeshNodes() { return *numMeshNodes; } - void setLocalPosition(meshtastic_Position position) + void setLocalPosition(meshtastic_Position position, bool timeOnly = false) { + if (timeOnly) { + LOG_DEBUG("Setting local position time only: time=%i\n", position.time); + localPosition.time = position.time; + return; + } LOG_DEBUG("Setting local position: latitude=%i, longitude=%i, time=%i\n", position.latitude_i, position.longitude_i, position.time); localPosition = position; @@ -248,4 +253,4 @@ extern uint32_t error_address; #define Module_Config_size \ (ModuleConfig_CannedMessageConfig_size + ModuleConfig_ExternalNotificationConfig_size + ModuleConfig_MQTTConfig_size + \ ModuleConfig_RangeTestConfig_size + ModuleConfig_SerialConfig_size + ModuleConfig_StoreForwardConfig_size + \ - ModuleConfig_TelemetryConfig_size + ModuleConfig_size) + ModuleConfig_TelemetryConfig_size + ModuleConfig_size) \ No newline at end of file diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index 4634f8fef..59f62bd5c 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -59,9 +59,15 @@ bool PositionModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes // to set fixed location, EUD-GPS location or just the time (see also issue #900) bool isLocal = false; if (nodeDB.getNodeNum() == getFrom(&mp)) { - LOG_DEBUG("Incoming update from MYSELF\n"); isLocal = true; - nodeDB.setLocalPosition(p); + if (config.position.fixed_position) { + LOG_DEBUG("Ignore incoming position update from myself except for time, because position.fixed_position is true\n"); + nodeDB.setLocalPosition(p, true); + return false; + } else { + LOG_DEBUG("Incoming update from MYSELF\n"); + nodeDB.setLocalPosition(p); + } } // Log packet size and data fields From 58cdf360f862d7027f77148fc4f78d16d237365e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Thu, 14 Mar 2024 16:18:33 +0100 Subject: [PATCH 323/472] (1/3) Support L76B GNSS chip found on pico waveshare shield. Original work by @Mictronics --- platformio.ini | 4 ++-- src/gps/GPS.cpp | 50 +++++++++++++++++++++++++++++++++++++++++++++++-- src/gps/GPS.h | 12 +++++------- 3 files changed, 55 insertions(+), 11 deletions(-) diff --git a/platformio.ini b/platformio.ini index 392b38fd7..7680f2f20 100644 --- a/platformio.ini +++ b/platformio.ini @@ -77,7 +77,7 @@ lib_deps = https://github.com/meshtastic/esp8266-oled-ssd1306.git#ee628ee6c9588d4c56c9e3da35f0fc9448ad54a8 ; ESP8266_SSD1306 mathertel/OneButton@^2.5.0 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 - https://github.com/meshtastic/TinyGPSPlus.git#2044b2c51e91ab4cd8cc93b15e40658cd808dd06 + https://github.com/meshtastic/TinyGPSPlus.git#f9f4fef2183514aa52be91d714c1455dd6f26e45 https://github.com/meshtastic/ArduinoThread.git#72921ac222eed6f526ba1682023cee290d9aa1b3 nanopb/Nanopb@^0.4.7 erriez/ErriezCRC32@^1.0.1 @@ -130,4 +130,4 @@ lib_deps = adafruit/Adafruit PM25 AQI Sensor@^1.0.6 adafruit/Adafruit MPU6050@^2.2.4 adafruit/Adafruit LIS3DH@^1.2.4 - https://github.com/lewisxhe/BMA423_Library@^0.0.1 + https://github.com/lewisxhe/BMA423_Library@^0.0.1 \ No newline at end of file diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 849c38794..5b7d18bab 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -290,6 +290,26 @@ bool GPS::setup() // Switch to Vehicle Mode, since SoftRF enables Aviation < 2g _serial_gps->write("$PCAS11,3*1E\r\n"); delay(250); + } else if (gnssModel == GNSS_MODEL_MTK_L76B) { + // Waveshare Pico-GPS hat uses the L76B with 9600 baud + // Initialize the L76B Chip, use GPS + GLONASS + // See note in L76_Series_GNSS_Protocol_Specification, chapter 3.29 + _serial_gps->write("$PMTK353,1,1,0,0,0*2B\r\n"); + // Above command will reset the GPS and takes longer before it will accept new commands + delay(1000); + // only ask for RMC and GGA (GNRMC and GNGGA) + // See note in L76_Series_GNSS_Protocol_Specification, chapter 2.1 + _serial_gps->write("$PMTK314,0,1,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*28\r\n"); + delay(250); + // Enable SBAS + _serial_gps->write("$PMTK301,2*2E\r\n"); + delay(250); + // Enable PPS for 2D/3D fix only + _serial_gps->write("$PMTK285,3,100*3F\r\n"); + delay(250); + // Switch to Fitness Mode, for running and walking purpose with low speed (<5 m/s) + _serial_gps->write("$PMTK886,1*29\r\n"); + delay(250); } else if (gnssModel == GNSS_MODEL_UC6580) { // The Unicore UC6580 can use a lot of sat systems, enable it to // use GPS L1 & L5 + BDS B1I & B2a + GLONASS L1 + GALILEO E1 & E5a + SBAS @@ -625,17 +645,27 @@ void GPS::setGPSPower(bool on, bool standbyOnly, uint32_t sleepTime) return; } #endif -#ifdef PIN_GPS_STANDBY // Specifically the standby pin for L76K and clones +#ifdef PIN_GPS_STANDBY // Specifically the standby pin for L76B, L76K and clones if (on) { LOG_INFO("Waking GPS\n"); pinMode(PIN_GPS_STANDBY, OUTPUT); + // Some PCB's use an inverse logic due to a transistor driver + // Example for this is the Pico-Waveshare Lora+GPS HAT +#ifdef PIN_GPS_STANDBY_INVERTED + digitalWrite(PIN_GPS_STANDBY, 0); +#else digitalWrite(PIN_GPS_STANDBY, 1); +#endif return; } else { LOG_INFO("GPS entering sleep\n"); // notifyGPSSleep.notifyObservers(NULL); pinMode(PIN_GPS_STANDBY, OUTPUT); +#ifdef PIN_GPS_STANDBY_INVERTED + digitalWrite(PIN_GPS_STANDBY, 1); +#else digitalWrite(PIN_GPS_STANDBY, 0); +#endif return; } #endif @@ -916,7 +946,7 @@ GnssModel_t GPS::probe(int serialSpeed) uint8_t buffer[768] = {0}; delay(100); - // Close all NMEA sentences , Only valid for MTK platform + // Close all NMEA sentences , Only valid for L76K MTK platform _serial_gps->write("$PCAS03,0,0,0,0,0,0,0,0,0,0,,,0,0*02\r\n"); delay(20); @@ -928,6 +958,18 @@ GnssModel_t GPS::probe(int serialSpeed) return GNSS_MODEL_MTK; } + // Close all NMEA sentences, valid for L76B MTK platform (Waveshare Pico GPS) + _serial_gps->write("$PMTK514,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*2E\r\n"); + delay(20); + + // Get version information + clearBuffer(); + _serial_gps->write("$PMTK605*31\r\n"); + if (getACK("Quectel-L76B", 500) == GNSS_RESPONSE_OK) { + LOG_INFO("L76B GNSS init succeeded, using L76B GNSS Module\n"); + return GNSS_MODEL_MTK_L76B; + } + uint8_t cfg_rate[] = {0xB5, 0x62, 0x06, 0x08, 0x00, 0x00, 0x00, 0x00}; UBXChecksum(cfg_rate, sizeof(cfg_rate)); clearBuffer(); @@ -1111,6 +1153,7 @@ GPS *GPS::createGps() _serial_gps->begin(GPS_BAUDRATE, SERIAL_8N1, new_gps->rx_gpio, new_gps->tx_gpio); #else + _serial_gps->setFIFOSize(256); _serial_gps->begin(GPS_BAUDRATE); #endif @@ -1168,6 +1211,9 @@ bool GPS::factoryReset() // byte _message_CFG_RST_COLDSTART[] = {0xB5, 0x62, 0x06, 0x04, 0x04, 0x00, 0xFF, 0xB9, 0x00, 0x00, 0xC6, 0x8B}; // _serial_gps->write(_message_CFG_RST_COLDSTART, sizeof(_message_CFG_RST_COLDSTART)); // delay(1000); + } else if (HW_VENDOR == meshtastic_HardwareModel_RPI_PICO) { + _serial_gps->write("$PMTK104*37\r\n"); + // No PMTK_ACK for this command. } else { // send the UBLOX Factory Reset Command regardless of detect state, something is very wrong, just assume it's UBLOX. // Factory Reset diff --git a/src/gps/GPS.h b/src/gps/GPS.h index 77e1d8042..502763bb6 100644 --- a/src/gps/GPS.h +++ b/src/gps/GPS.h @@ -20,12 +20,7 @@ struct uBloxGnssModelInfo { char extension[10][30]; }; -typedef enum { - GNSS_MODEL_MTK, - GNSS_MODEL_UBLOX, - GNSS_MODEL_UC6580, - GNSS_MODEL_UNKNOWN, -} GnssModel_t; +typedef enum { GNSS_MODEL_MTK, GNSS_MODEL_UBLOX, GNSS_MODEL_UC6580, GNSS_MODEL_UNKNOWN, GNSS_MODEL_MTK_L76B } GnssModel_t; typedef enum { GNSS_RESPONSE_NONE, @@ -92,8 +87,11 @@ class GPS : private concurrency::OSThread public: /** If !NULL we will use this serial port to construct our GPS */ +#if defined(RPI_PICO_WAVESHARE) + static SerialUART *_serial_gps; +#else static HardwareSerial *_serial_gps; - +#endif static uint8_t _message_PMREQ[]; static uint8_t _message_PMREQ_10[]; static const uint8_t _message_CFG_RXM_PSM[]; From a085c3ddb334fb4977f68980ebd2ef79e625c861 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 14 Mar 2024 17:00:57 -0500 Subject: [PATCH 324/472] Try-fix router missed messages (#3405) --- src/PowerFSM.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/PowerFSM.cpp b/src/PowerFSM.cpp index c359e4c12..f98b03077 100644 --- a/src/PowerFSM.cpp +++ b/src/PowerFSM.cpp @@ -358,10 +358,10 @@ void PowerFSM_setup() // Don't add power saving transitions if we are a power saving tracker or sensor. Sleep will be initiatiated through the // modules if ((isRouter || config.power.is_power_saving) && !isTrackerOrSensor) { - powerFSM.add_timed_transition(&stateNB, isInfrastructureRole ? &stateSDS : &stateLS, + powerFSM.add_timed_transition(&stateNB, &stateLS, getConfiguredOrDefaultMs(config.power.min_wake_secs, default_min_wake_secs), NULL, "Min wake timeout"); - powerFSM.add_timed_transition(&stateDARK, isInfrastructureRole ? &stateSDS : &stateLS, + powerFSM.add_timed_transition(&stateDARK, &stateLS, getConfiguredOrDefaultMs(config.power.wait_bluetooth_secs, default_wait_bluetooth_secs), NULL, "Bluetooth timeout"); } From ec6bdeed8115be3904d413c1cd0ad79928d4f55e Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 15 Mar 2024 07:12:03 -0500 Subject: [PATCH 325/472] NodeInfo broadcast ensure default on 0 and enforce 1 hour minimum (#3415) * NodeInfo broadcasts ensure defaults on 0 and enforce 1 hour minumum * Doh! * Hey that's not on config! --- src/mesh/NodeDB.cpp | 13 ++----------- src/mesh/NodeDB.h | 2 ++ src/modules/AdminModule.cpp | 4 ++++ src/modules/NodeInfoModule.cpp | 3 +-- 4 files changed, 9 insertions(+), 13 deletions(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 9d7647138..6898f7702 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -101,16 +101,7 @@ bool NodeDB::resetRadioConfig(bool factory_reset) // devicestate.no_save = true; if (devicestate.no_save) { LOG_DEBUG("***** DEVELOPMENT MODE - DO NOT RELEASE *****\n"); - - // Sleep quite frequently to stress test the BLE comms, broadcast position every 6 mins - config.display.screen_on_secs = 10; - config.power.wait_bluetooth_secs = 10; - config.position.position_broadcast_secs = 6 * 60; - config.power.ls_secs = 60; - config.lora.region = meshtastic_Config_LoRaConfig_RegionCode_TW; - - // Enter super deep sleep soon and stay there not very long - // radioConfig.preferences.sds_secs = 60; + // Put your development config changes here } // Update the global myRegion @@ -199,7 +190,7 @@ void NodeDB::installDefaultConfig() config.position.broadcast_smart_minimum_distance = 100; config.position.broadcast_smart_minimum_interval_secs = 30; if (config.device.role != meshtastic_Config_DeviceConfig_Role_ROUTER) - config.device.node_info_broadcast_secs = 3 * 60 * 60; + config.device.node_info_broadcast_secs = default_node_info_broadcast_secs; config.device.serial_enabled = true; resetRadioConfig(); strncpy(config.network.ntp_server, "0.pool.ntp.org", 32); diff --git a/src/mesh/NodeDB.h b/src/mesh/NodeDB.h index 20cc5c25b..b34059fb9 100644 --- a/src/mesh/NodeDB.h +++ b/src/mesh/NodeDB.h @@ -203,6 +203,8 @@ extern NodeDB nodeDB; #define default_ls_secs IF_ROUTER(ONE_DAY, 5 * 60) #define default_min_wake_secs 10 #define default_screen_on_secs IF_ROUTER(1, 60 * 10) +#define default_node_info_broadcast_secs 3 * 60 * 60 +#define min_node_info_broadcast_secs 60 * 60 // No regular broadcasts of more than once an hour #define default_mqtt_address "mqtt.meshtastic.org" #define default_mqtt_username "meshdev" diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index abd7c2e54..06818dc88 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -302,6 +302,10 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c) // If we're setting router role for the first time, install its intervals if (existingRole != c.payload_variant.device.role) nodeDB.installRoleDefaults(c.payload_variant.device.role); + if (config.device.node_info_broadcast_secs < min_node_info_broadcast_secs) { + LOG_DEBUG("Tried to set node_info_broadcast_secs too low, setting to %d\n", min_node_info_broadcast_secs); + config.device.node_info_broadcast_secs = min_node_info_broadcast_secs; + } break; case meshtastic_Config_position_tag: LOG_INFO("Setting config: Position\n"); diff --git a/src/modules/NodeInfoModule.cpp b/src/modules/NodeInfoModule.cpp index b0b4bbdcd..5177af33a 100644 --- a/src/modules/NodeInfoModule.cpp +++ b/src/modules/NodeInfoModule.cpp @@ -91,6 +91,5 @@ int32_t NodeInfoModule::runOnce() LOG_INFO("Sending our nodeinfo to mesh (wantReplies=%d)\n", requestReplies); sendOurNodeInfo(NODENUM_BROADCAST, requestReplies); // Send our info (don't request replies) } - - return getConfiguredOrDefaultMs(config.device.node_info_broadcast_secs, default_broadcast_interval_secs); + return getConfiguredOrDefaultMs(config.device.node_info_broadcast_secs, default_node_info_broadcast_secs); } From 50cc4cfcf15a65997f72960c7f1ab762d796dba1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Fri, 15 Mar 2024 14:07:54 +0100 Subject: [PATCH 326/472] We don't use Lorawan (#3417) #warning "Persistent storage not supported!" [-Wcpp] --- platformio.ini | 1 + 1 file changed, 1 insertion(+) diff --git a/platformio.ini b/platformio.ini index 392b38fd7..68cfa1753 100644 --- a/platformio.ini +++ b/platformio.ini @@ -69,6 +69,7 @@ build_flags = -Wno-missing-field-initializers -DRADIOLIB_EXCLUDE_PAGER -DRADIOLIB_EXCLUDE_FSK4 -DRADIOLIB_EXCLUDE_APRS + -DRADIOLIB_EXCLUDE_LORAWAN monitor_speed = 115200 From 876a0520a99787f371d36e42db6475b4e80dcc34 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Fri, 15 Mar 2024 08:09:48 -0500 Subject: [PATCH 327/472] [create-pull-request] automated change (#3418) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/clientonly.pb.c | 3 - src/mesh/generated/meshtastic/clientonly.pb.h | 16 ---- src/mesh/generated/meshtastic/mesh.pb.c | 3 + src/mesh/generated/meshtastic/mesh.pb.h | 86 ++++++++++++------- 5 files changed, 58 insertions(+), 52 deletions(-) diff --git a/protobufs b/protobufs index 7e3ee8cd9..cf25b390d 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 7e3ee8cd96740910d0611433cb9a05a7a692568c +Subproject commit cf25b390d65113980b1a239e16faa79c7730a736 diff --git a/src/mesh/generated/meshtastic/clientonly.pb.c b/src/mesh/generated/meshtastic/clientonly.pb.c index 90e8e2d8a..ebc2ffabc 100644 --- a/src/mesh/generated/meshtastic/clientonly.pb.c +++ b/src/mesh/generated/meshtastic/clientonly.pb.c @@ -9,7 +9,4 @@ PB_BIND(meshtastic_DeviceProfile, meshtastic_DeviceProfile, 2) -PB_BIND(meshtastic_Heartbeat, meshtastic_Heartbeat, AUTO) - - diff --git a/src/mesh/generated/meshtastic/clientonly.pb.h b/src/mesh/generated/meshtastic/clientonly.pb.h index 19b0a0e5f..0f70e09c6 100644 --- a/src/mesh/generated/meshtastic/clientonly.pb.h +++ b/src/mesh/generated/meshtastic/clientonly.pb.h @@ -30,12 +30,6 @@ typedef struct _meshtastic_DeviceProfile { meshtastic_LocalModuleConfig module_config; } meshtastic_DeviceProfile; -/* A heartbeat message is sent by a node to indicate that it is still alive. - This is currently only needed to keep serial connections alive. */ -typedef struct _meshtastic_Heartbeat { - char dummy_field; -} meshtastic_Heartbeat; - #ifdef __cplusplus extern "C" { @@ -43,9 +37,7 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_DeviceProfile_init_default {false, "", false, "", {{NULL}, NULL}, false, meshtastic_LocalConfig_init_default, false, meshtastic_LocalModuleConfig_init_default} -#define meshtastic_Heartbeat_init_default {0} #define meshtastic_DeviceProfile_init_zero {false, "", false, "", {{NULL}, NULL}, false, meshtastic_LocalConfig_init_zero, false, meshtastic_LocalModuleConfig_init_zero} -#define meshtastic_Heartbeat_init_zero {0} /* Field tags (for use in manual encoding/decoding) */ #define meshtastic_DeviceProfile_long_name_tag 1 @@ -66,21 +58,13 @@ X(a, STATIC, OPTIONAL, MESSAGE, module_config, 5) #define meshtastic_DeviceProfile_config_MSGTYPE meshtastic_LocalConfig #define meshtastic_DeviceProfile_module_config_MSGTYPE meshtastic_LocalModuleConfig -#define meshtastic_Heartbeat_FIELDLIST(X, a) \ - -#define meshtastic_Heartbeat_CALLBACK NULL -#define meshtastic_Heartbeat_DEFAULT NULL - extern const pb_msgdesc_t meshtastic_DeviceProfile_msg; -extern const pb_msgdesc_t meshtastic_Heartbeat_msg; /* Defines for backwards compatibility with code written before nanopb-0.4.0 */ #define meshtastic_DeviceProfile_fields &meshtastic_DeviceProfile_msg -#define meshtastic_Heartbeat_fields &meshtastic_Heartbeat_msg /* Maximum encoded size of messages (where known) */ /* meshtastic_DeviceProfile_size depends on runtime parameters */ -#define meshtastic_Heartbeat_size 0 #ifdef __cplusplus } /* extern "C" */ diff --git a/src/mesh/generated/meshtastic/mesh.pb.c b/src/mesh/generated/meshtastic/mesh.pb.c index 790f8be2d..97bb7e53b 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.c +++ b/src/mesh/generated/meshtastic/mesh.pb.c @@ -60,6 +60,9 @@ PB_BIND(meshtastic_Neighbor, meshtastic_Neighbor, AUTO) PB_BIND(meshtastic_DeviceMetadata, meshtastic_DeviceMetadata, AUTO) +PB_BIND(meshtastic_Heartbeat, meshtastic_Heartbeat, AUTO) + + diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index 04590210e..8f260589c 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -682,32 +682,6 @@ typedef struct _meshtastic_QueueStatus { uint32_t mesh_packet_id; } meshtastic_QueueStatus; -/* Packets/commands to the radio will be written (reliably) to the toRadio characteristic. - Once the write completes the phone can assume it is handled. */ -typedef struct _meshtastic_ToRadio { - pb_size_t which_payload_variant; - union { - /* Send this packet on the mesh */ - meshtastic_MeshPacket packet; - /* Phone wants radio to send full node db to the phone, This is - typically the first packet sent to the radio when the phone gets a - bluetooth connection. The radio will respond by sending back a - MyNodeInfo, a owner, a radio config and a series of - FromRadio.node_infos, and config_complete - the integer you write into this field will be reported back in the - config_complete_id response this allows clients to never be confused by - a stale old partially sent config. */ - uint32_t want_config_id; - /* Tell API server we are disconnecting now. - This is useful for serial links where there is no hardware/protocol based notification that the client has dropped the link. - (Sending this message is optional for clients) */ - bool disconnect; - meshtastic_XModem xmodemPacket; - /* MQTT Client Proxy Message (for client / phone subscribed to MQTT sending to device) */ - meshtastic_MqttClientProxyMessage mqttClientProxyMessage; - }; -} meshtastic_ToRadio; - typedef PB_BYTES_ARRAY_T(237) meshtastic_Compressed_data_t; /* Compressed message payload */ typedef struct _meshtastic_Compressed { @@ -815,6 +789,40 @@ typedef struct _meshtastic_FromRadio { }; } meshtastic_FromRadio; +/* A heartbeat message is sent to the node from the client to keep the connection alive. + This is currently only needed to keep serial connections alive, but can be used by any PhoneAPI. */ +typedef struct _meshtastic_Heartbeat { + char dummy_field; +} meshtastic_Heartbeat; + +/* Packets/commands to the radio will be written (reliably) to the toRadio characteristic. + Once the write completes the phone can assume it is handled. */ +typedef struct _meshtastic_ToRadio { + pb_size_t which_payload_variant; + union { + /* Send this packet on the mesh */ + meshtastic_MeshPacket packet; + /* Phone wants radio to send full node db to the phone, This is + typically the first packet sent to the radio when the phone gets a + bluetooth connection. The radio will respond by sending back a + MyNodeInfo, a owner, a radio config and a series of + FromRadio.node_infos, and config_complete + the integer you write into this field will be reported back in the + config_complete_id response this allows clients to never be confused by + a stale old partially sent config. */ + uint32_t want_config_id; + /* Tell API server we are disconnecting now. + This is useful for serial links where there is no hardware/protocol based notification that the client has dropped the link. + (Sending this message is optional for clients) */ + bool disconnect; + meshtastic_XModem xmodemPacket; + /* MQTT Client Proxy Message (for client / phone subscribed to MQTT sending to device) */ + meshtastic_MqttClientProxyMessage mqttClientProxyMessage; + /* Heartbeat message (used to keep the device connection awake on serial) */ + meshtastic_Heartbeat hearbeat; + }; +} meshtastic_ToRadio; + #ifdef __cplusplus extern "C" { @@ -888,6 +896,7 @@ extern "C" { #define meshtastic_DeviceMetadata_hw_model_ENUMTYPE meshtastic_HardwareModel + /* Initializer values for message structs */ #define meshtastic_Position_init_default {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN, _meshtastic_Position_AltSource_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_User_init_default {"", "", "", {0}, _meshtastic_HardwareModel_MIN, 0, _meshtastic_Config_DeviceConfig_Role_MIN} @@ -907,6 +916,7 @@ extern "C" { #define meshtastic_NeighborInfo_init_default {0, 0, 0, 0, {meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default}} #define meshtastic_Neighbor_init_default {0, 0, 0, 0} #define meshtastic_DeviceMetadata_init_default {"", 0, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_Role_MIN, 0, _meshtastic_HardwareModel_MIN, 0} +#define meshtastic_Heartbeat_init_default {0} #define meshtastic_Position_init_zero {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN, _meshtastic_Position_AltSource_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_User_init_zero {"", "", "", {0}, _meshtastic_HardwareModel_MIN, 0, _meshtastic_Config_DeviceConfig_Role_MIN} #define meshtastic_RouteDiscovery_init_zero {0, {0, 0, 0, 0, 0, 0, 0, 0}} @@ -925,6 +935,7 @@ extern "C" { #define meshtastic_NeighborInfo_init_zero {0, 0, 0, 0, {meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero}} #define meshtastic_Neighbor_init_zero {0, 0, 0, 0} #define meshtastic_DeviceMetadata_init_zero {"", 0, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_Role_MIN, 0, _meshtastic_HardwareModel_MIN, 0} +#define meshtastic_Heartbeat_init_zero {0} /* Field tags (for use in manual encoding/decoding) */ #define meshtastic_Position_latitude_i_tag 1 @@ -1016,11 +1027,6 @@ extern "C" { #define meshtastic_QueueStatus_free_tag 2 #define meshtastic_QueueStatus_maxlen_tag 3 #define meshtastic_QueueStatus_mesh_packet_id_tag 4 -#define meshtastic_ToRadio_packet_tag 1 -#define meshtastic_ToRadio_want_config_id_tag 3 -#define meshtastic_ToRadio_disconnect_tag 4 -#define meshtastic_ToRadio_xmodemPacket_tag 5 -#define meshtastic_ToRadio_mqttClientProxyMessage_tag 6 #define meshtastic_Compressed_portnum_tag 1 #define meshtastic_Compressed_data_tag 2 #define meshtastic_Neighbor_node_id_tag 1 @@ -1055,6 +1061,12 @@ extern "C" { #define meshtastic_FromRadio_xmodemPacket_tag 12 #define meshtastic_FromRadio_metadata_tag 13 #define meshtastic_FromRadio_mqttClientProxyMessage_tag 14 +#define meshtastic_ToRadio_packet_tag 1 +#define meshtastic_ToRadio_want_config_id_tag 3 +#define meshtastic_ToRadio_disconnect_tag 4 +#define meshtastic_ToRadio_xmodemPacket_tag 5 +#define meshtastic_ToRadio_mqttClientProxyMessage_tag 6 +#define meshtastic_ToRadio_hearbeat_tag 7 /* Struct field encoding specification for nanopb */ #define meshtastic_Position_FIELDLIST(X, a) \ @@ -1234,12 +1246,14 @@ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,packet,packet), 1) \ X(a, STATIC, ONEOF, UINT32, (payload_variant,want_config_id,want_config_id), 3) \ X(a, STATIC, ONEOF, BOOL, (payload_variant,disconnect,disconnect), 4) \ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,xmodemPacket,xmodemPacket), 5) \ -X(a, STATIC, ONEOF, MESSAGE, (payload_variant,mqttClientProxyMessage,mqttClientProxyMessage), 6) +X(a, STATIC, ONEOF, MESSAGE, (payload_variant,mqttClientProxyMessage,mqttClientProxyMessage), 6) \ +X(a, STATIC, ONEOF, MESSAGE, (payload_variant,hearbeat,hearbeat), 7) #define meshtastic_ToRadio_CALLBACK NULL #define meshtastic_ToRadio_DEFAULT NULL #define meshtastic_ToRadio_payload_variant_packet_MSGTYPE meshtastic_MeshPacket #define meshtastic_ToRadio_payload_variant_xmodemPacket_MSGTYPE meshtastic_XModem #define meshtastic_ToRadio_payload_variant_mqttClientProxyMessage_MSGTYPE meshtastic_MqttClientProxyMessage +#define meshtastic_ToRadio_payload_variant_hearbeat_MSGTYPE meshtastic_Heartbeat #define meshtastic_Compressed_FIELDLIST(X, a) \ X(a, STATIC, SINGULAR, UENUM, portnum, 1) \ @@ -1278,6 +1292,11 @@ X(a, STATIC, SINGULAR, BOOL, hasRemoteHardware, 10) #define meshtastic_DeviceMetadata_CALLBACK NULL #define meshtastic_DeviceMetadata_DEFAULT NULL +#define meshtastic_Heartbeat_FIELDLIST(X, a) \ + +#define meshtastic_Heartbeat_CALLBACK NULL +#define meshtastic_Heartbeat_DEFAULT NULL + extern const pb_msgdesc_t meshtastic_Position_msg; extern const pb_msgdesc_t meshtastic_User_msg; extern const pb_msgdesc_t meshtastic_RouteDiscovery_msg; @@ -1296,6 +1315,7 @@ extern const pb_msgdesc_t meshtastic_Compressed_msg; extern const pb_msgdesc_t meshtastic_NeighborInfo_msg; extern const pb_msgdesc_t meshtastic_Neighbor_msg; extern const pb_msgdesc_t meshtastic_DeviceMetadata_msg; +extern const pb_msgdesc_t meshtastic_Heartbeat_msg; /* Defines for backwards compatibility with code written before nanopb-0.4.0 */ #define meshtastic_Position_fields &meshtastic_Position_msg @@ -1316,12 +1336,14 @@ extern const pb_msgdesc_t meshtastic_DeviceMetadata_msg; #define meshtastic_NeighborInfo_fields &meshtastic_NeighborInfo_msg #define meshtastic_Neighbor_fields &meshtastic_Neighbor_msg #define meshtastic_DeviceMetadata_fields &meshtastic_DeviceMetadata_msg +#define meshtastic_Heartbeat_fields &meshtastic_Heartbeat_msg /* Maximum encoded size of messages (where known) */ #define meshtastic_Compressed_size 243 #define meshtastic_Data_size 270 #define meshtastic_DeviceMetadata_size 46 #define meshtastic_FromRadio_size 510 +#define meshtastic_Heartbeat_size 0 #define meshtastic_LogRecord_size 81 #define meshtastic_MeshPacket_size 326 #define meshtastic_MqttClientProxyMessage_size 501 From cbc0aa16c5851f4a822a37d24f2d1798a153ad80 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Fri, 15 Mar 2024 16:37:47 +0100 Subject: [PATCH 328/472] fix compilation --- src/gps/GPS.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 5b7d18bab..7073e4eb0 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -1151,10 +1151,11 @@ GPS *GPS::createGps() LOG_DEBUG("Using GPIO%d for GPS RX\n", new_gps->rx_gpio); LOG_DEBUG("Using GPIO%d for GPS TX\n", new_gps->tx_gpio); _serial_gps->begin(GPS_BAUDRATE, SERIAL_8N1, new_gps->rx_gpio, new_gps->tx_gpio); - -#else +#elif defined(ARCH_RP2040) _serial_gps->setFIFOSize(256); _serial_gps->begin(GPS_BAUDRATE); +#else + _serial_gps->begin(GPS_BAUDRATE); #endif /* From b06c77d46fa2867a629dbc0c3d14e9400076005f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Fri, 15 Mar 2024 16:43:39 +0100 Subject: [PATCH 329/472] don't fix this to a hardware model. --- src/gps/GPS.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 7073e4eb0..4812786cb 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -1212,10 +1212,11 @@ bool GPS::factoryReset() // byte _message_CFG_RST_COLDSTART[] = {0xB5, 0x62, 0x06, 0x04, 0x04, 0x00, 0xFF, 0xB9, 0x00, 0x00, 0xC6, 0x8B}; // _serial_gps->write(_message_CFG_RST_COLDSTART, sizeof(_message_CFG_RST_COLDSTART)); // delay(1000); - } else if (HW_VENDOR == meshtastic_HardwareModel_RPI_PICO) { + } else { + // fire this for good measure, if we have an L76B - won't harm other devices. _serial_gps->write("$PMTK104*37\r\n"); // No PMTK_ACK for this command. - } else { + delay(100); // send the UBLOX Factory Reset Command regardless of detect state, something is very wrong, just assume it's UBLOX. // Factory Reset byte _message_reset[] = {0xB5, 0x62, 0x06, 0x09, 0x0D, 0x00, 0xFF, 0xFB, 0x00, 0x00, 0x00, From da7cd5fc7fbe460969246e83bad981f68460a0d7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Fri, 15 Mar 2024 16:45:14 +0100 Subject: [PATCH 330/472] new Accelerometer lib (#3413) * new Accelerometer lib * Use our fork till upstreasm merges changes. * that PR escalated quickly * resurrect display flip --- platformio.ini | 2 +- src/AccelerometerThread.h | 70 ++++++++++++++------------------------- 2 files changed, 25 insertions(+), 47 deletions(-) diff --git a/platformio.ini b/platformio.ini index 68cfa1753..dbd15645f 100644 --- a/platformio.ini +++ b/platformio.ini @@ -131,4 +131,4 @@ lib_deps = adafruit/Adafruit PM25 AQI Sensor@^1.0.6 adafruit/Adafruit MPU6050@^2.2.4 adafruit/Adafruit LIS3DH@^1.2.4 - https://github.com/lewisxhe/BMA423_Library@^0.0.1 + https://github.com/lewisxhe/SensorLib#27fd0f721e20cd09e1f81383f0ba58a54fe84a17 diff --git a/src/AccelerometerThread.h b/src/AccelerometerThread.h index 9898f4d49..6827908b7 100644 --- a/src/AccelerometerThread.h +++ b/src/AccelerometerThread.h @@ -7,16 +7,16 @@ #include #include #include +#include #include -#include -BMA423 bmaSensor; +SensorBMA423 bmaSensor; bool BMA_IRQ = false; #define ACCELEROMETER_CHECK_INTERVAL_MS 100 #define ACCELEROMETER_CLICK_THRESHOLD 40 -uint16_t readRegister(uint8_t address, uint8_t reg, uint8_t *data, uint16_t len) +int readRegister(uint8_t address, uint8_t reg, uint8_t *data, uint8_t len) { Wire.beginTransmission(address); Wire.write(reg); @@ -29,7 +29,7 @@ uint16_t readRegister(uint8_t address, uint8_t reg, uint8_t *data, uint16_t len) return 0; // Pass } -uint16_t writeRegister(uint8_t address, uint8_t reg, uint8_t *data, uint16_t len) +int writeRegister(uint8_t address, uint8_t reg, uint8_t *data, uint8_t len) { Wire.beginTransmission(address); Wire.write(reg); @@ -72,24 +72,14 @@ class AccelerometerThread : public concurrency::OSThread lis.setRange(LIS3DH_RANGE_2_G); // Adjust threshold, higher numbers are less sensitive lis.setClick(config.device.double_tap_as_button_press ? 2 : 1, ACCELEROMETER_CLICK_THRESHOLD); - } else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 && bmaSensor.begin(readRegister, writeRegister, delay)) { + } else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 && + bmaSensor.begin(accelerometer_found.address, &readRegister, &writeRegister)) { LOG_DEBUG("BMA423 initializing\n"); - Acfg cfg; - cfg.odr = BMA4_OUTPUT_DATA_RATE_100HZ; - cfg.range = BMA4_ACCEL_RANGE_2G; - cfg.bandwidth = BMA4_ACCEL_NORMAL_AVG4; - cfg.perf_mode = BMA4_CONTINUOUS_MODE; - bmaSensor.setAccelConfig(cfg); - bmaSensor.enableAccel(); - - struct bma4_int_pin_config pin_config; - pin_config.edge_ctrl = BMA4_LEVEL_TRIGGER; - pin_config.lvl = BMA4_ACTIVE_HIGH; - pin_config.od = BMA4_PUSH_PULL; - pin_config.output_en = BMA4_OUTPUT_ENABLE; - pin_config.input_en = BMA4_INPUT_DISABLE; - // The correct trigger interrupt needs to be configured as needed - bmaSensor.setINTPinConfig(pin_config, BMA4_INTR1_MAP); + bmaSensor.configAccelerometer(bmaSensor.RANGE_2G, bmaSensor.ODR_100HZ, bmaSensor.BW_NORMAL_AVG4, + bmaSensor.PERF_CONTINUOUS_MODE); + bmaSensor.enableAccelerometer(); + bmaSensor.configInterrupt(BMA4_LEVEL_TRIGGER, BMA4_ACTIVE_HIGH, BMA4_PUSH_PULL, BMA4_OUTPUT_ENABLE, + BMA4_INPUT_DISABLE); #ifdef BMA423_INT pinMode(BMA4XX_INT, INPUT); @@ -102,34 +92,22 @@ class AccelerometerThread : public concurrency::OSThread RISING); // Select the interrupt mode according to the actual circuit #endif - struct bma423_axes_remap remap_data; #ifdef T_WATCH_S3 - remap_data.x_axis = 1; - remap_data.x_axis_sign = 0; - remap_data.y_axis = 0; - remap_data.y_axis_sign = 0; - remap_data.z_axis = 2; - remap_data.z_axis_sign = 1; -#else - remap_data.x_axis = 0; - remap_data.x_axis_sign = 1; - remap_data.y_axis = 1; - remap_data.y_axis_sign = 0; - remap_data.z_axis = 2; - remap_data.z_axis_sign = 1; -#endif // Need to raise the wrist function, need to set the correct axis - bmaSensor.setRemapAxes(&remap_data); - // sensor.enableFeature(BMA423_STEP_CNTR, true); - bmaSensor.enableFeature(BMA423_TILT, true); - bmaSensor.enableFeature(BMA423_WAKEUP, true); - // sensor.resetStepCounter(); + bmaSensor.setReampAxes(bmaSensor.REMAP_TOP_LAYER_RIGHT_CORNER); +#else + bmaSensor.setReampAxes(bmaSensor.REMAP_BOTTOM_LAYER_BOTTOM_LEFT_CORNER); +#endif + // bmaSensor.enableFeature(bmaSensor.FEATURE_STEP_CNTR, true); + bmaSensor.enableFeature(bmaSensor.FEATURE_TILT, true); + bmaSensor.enableFeature(bmaSensor.FEATURE_WAKEUP, true); + // bmaSensor.resetPedometer(); // Turn on feature interrupt - bmaSensor.enableStepCountInterrupt(); - bmaSensor.enableTiltInterrupt(); + bmaSensor.enablePedometerIRQ(); + bmaSensor.enableTiltIRQ(); // It corresponds to isDoubleClick interrupt - bmaSensor.enableWakeupInterrupt(); + bmaSensor.enableWakeupIRQ(); } } @@ -150,8 +128,8 @@ class AccelerometerThread : public concurrency::OSThread buttonPress(); return 500; } - } else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 && bmaSensor.getINT()) { - if (bmaSensor.isTilt() || bmaSensor.isDoubleClick()) { + } else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 && bmaSensor.readIrqStatus() != DEV_WIRE_NONE) { + if (bmaSensor.isTilt() || bmaSensor.isDoubleTap()) { wakeScreen(); return 500; } From b9004152189933d9e0de7184ec7687166d9415c2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Fri, 15 Mar 2024 19:47:47 +0100 Subject: [PATCH 331/472] that should work now --- src/gps/GPS.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 4812786cb..2321ee246 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -1151,9 +1151,6 @@ GPS *GPS::createGps() LOG_DEBUG("Using GPIO%d for GPS RX\n", new_gps->rx_gpio); LOG_DEBUG("Using GPIO%d for GPS TX\n", new_gps->tx_gpio); _serial_gps->begin(GPS_BAUDRATE, SERIAL_8N1, new_gps->rx_gpio, new_gps->tx_gpio); -#elif defined(ARCH_RP2040) - _serial_gps->setFIFOSize(256); - _serial_gps->begin(GPS_BAUDRATE); #else _serial_gps->begin(GPS_BAUDRATE); #endif From 34bc22f94db27fb59d609b969c285644f30937a0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Thu, 14 Mar 2024 16:29:28 +0100 Subject: [PATCH 332/472] (2/3) Add Slow Clock Support for RP2040 platform. This will disable USB Softserial. --- arch/rp2040/rp2040.ini | 4 +-- src/SerialConsole.cpp | 8 +++++ src/modules/SerialModule.cpp | 10 ++++++ src/platform/rp2040/main-rp2040.cpp | 52 ++++++++++++++++++++++++++++- 4 files changed, 71 insertions(+), 3 deletions(-) diff --git a/arch/rp2040/rp2040.ini b/arch/rp2040/rp2040.ini index edc4373ad..dd3a4d7ff 100644 --- a/arch/rp2040/rp2040.ini +++ b/arch/rp2040/rp2040.ini @@ -1,8 +1,8 @@ ; Common settings for rp2040 Processor based targets [rp2040_base] -platform = https://github.com/maxgerhardt/platform-raspberrypi.git#612de5399d68b359053f1307ed223d400aea975c +platform = https://github.com/maxgerhardt/platform-raspberrypi.git#60d6ae81fcc73c34b1493ca9e261695e471bc0c2 extends = arduino_base -platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#3.6.2 +platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#3.7.2 board_build.core = earlephilhower board_build.filesystem_size = 0.5m diff --git a/src/SerialConsole.cpp b/src/SerialConsole.cpp index ed217c3ed..485329ddc 100644 --- a/src/SerialConsole.cpp +++ b/src/SerialConsole.cpp @@ -3,7 +3,11 @@ #include "PowerFSM.h" #include "configuration.h" +#ifdef RP2040_SLOW_CLOCK +#define Port Serial2 +#else #define Port Serial +#endif // Defaulting to the formerly removed phone_timeout_secs value of 15 minutes #define SERIAL_CONNECTION_TIMEOUT (15 * 60) * 1000UL @@ -31,6 +35,10 @@ SerialConsole::SerialConsole() : StreamAPI(&Port), RedirectablePrint(&Port), con canWrite = false; // We don't send packets to our port until it has talked to us first // setDestination(&noopPrint); for testing, try turning off 'all' debug output and see what leaks +#ifdef RP2040_SLOW_CLOCK + Port.setTX(SERIAL2_TX); + Port.setRX(SERIAL2_RX); +#endif Port.begin(SERIAL_BAUD); #if defined(ARCH_NRF52) || defined(CONFIG_IDF_TARGET_ESP32S2) || defined(CONFIG_IDF_TARGET_ESP32S3) || defined(ARCH_RP2040) time_t timeout = millis(); diff --git a/src/modules/SerialModule.cpp b/src/modules/SerialModule.cpp index 820e1fb62..1dee42a8d 100644 --- a/src/modules/SerialModule.cpp +++ b/src/modules/SerialModule.cpp @@ -126,8 +126,13 @@ int32_t SerialModule::runOnce() uint32_t baud = getBaudRate(); if (moduleConfig.serial.override_console_serial_port) { +#ifdef RP2040_SLOW_CLOCK + Serial2.flush(); + serialPrint = &Serial2; +#else Serial.flush(); serialPrint = &Serial; +#endif // Give it a chance to flush out 💩 delay(10); } @@ -151,8 +156,13 @@ int32_t SerialModule::runOnce() Serial2.begin(baud, SERIAL_8N1); Serial2.setTimeout(moduleConfig.serial.timeout > 0 ? moduleConfig.serial.timeout : TIMEOUT); } else { +#ifdef RP2040_SLOW_CLOCK + Serial2.begin(baud, SERIAL_8N1); + Serial2.setTimeout(moduleConfig.serial.timeout > 0 ? moduleConfig.serial.timeout : TIMEOUT); +#else Serial.begin(baud, SERIAL_8N1); Serial.setTimeout(moduleConfig.serial.timeout > 0 ? moduleConfig.serial.timeout : TIMEOUT); +#endif } #else Serial.begin(baud, SERIAL_8N1); diff --git a/src/platform/rp2040/main-rp2040.cpp b/src/platform/rp2040/main-rp2040.cpp index 283b801f1..af3aeadc3 100644 --- a/src/platform/rp2040/main-rp2040.cpp +++ b/src/platform/rp2040/main-rp2040.cpp @@ -1,4 +1,7 @@ #include "configuration.h" +#include +#include +#include #include #include @@ -35,9 +38,56 @@ void rp2040Setup() Taken from CPU cycle counter and ROSC oscillator, so should be pretty random. */ randomSeed(rp2040.hwrand32()); + +#ifdef RP2040_SLOW_CLOCK + uint f_pll_sys = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_PLL_SYS_CLKSRC_PRIMARY); + uint f_pll_usb = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_PLL_USB_CLKSRC_PRIMARY); + uint f_rosc = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_ROSC_CLKSRC); + uint f_clk_sys = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_CLK_SYS); + uint f_clk_peri = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_CLK_PERI); + uint f_clk_usb = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_CLK_USB); + uint f_clk_adc = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_CLK_ADC); + uint f_clk_rtc = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_CLK_RTC); + + LOG_INFO("Clock speed:\n"); + LOG_INFO("pll_sys = %dkHz\n", f_pll_sys); + LOG_INFO("pll_usb = %dkHz\n", f_pll_usb); + LOG_INFO("rosc = %dkHz\n", f_rosc); + LOG_INFO("clk_sys = %dkHz\n", f_clk_sys); + LOG_INFO("clk_peri = %dkHz\n", f_clk_peri); + LOG_INFO("clk_usb = %dkHz\n", f_clk_usb); + LOG_INFO("clk_adc = %dkHz\n", f_clk_adc); + LOG_INFO("clk_rtc = %dkHz\n", f_clk_rtc); +#endif } void enterDfuMode() { reset_usb_boot(0, 0); -} \ No newline at end of file +} + +/* Init in early boot state. */ +#ifdef RP2040_SLOW_CLOCK +void initVariant() +{ + /* Set the system frequency to 18 MHz. */ + set_sys_clock_khz(18 * KHZ, false); + /* The previous line automatically detached clk_peri from clk_sys, and + attached it to pll_usb. We need to attach clk_peri back to system PLL to keep SPI + working at this low speed. + For details see https://github.com/jgromes/RadioLib/discussions/938 + */ + clock_configure(clk_peri, + 0, // No glitchless mux + CLOCKS_CLK_PERI_CTRL_AUXSRC_VALUE_CLKSRC_PLL_SYS, // System PLL on AUX mux + 18 * MHZ, // Input frequency + 18 * MHZ // Output (must be same as no divider) + ); + /* Run also ADC on lower clk_sys. */ + clock_configure(clk_adc, 0, CLOCKS_CLK_ADC_CTRL_AUXSRC_VALUE_CLKSRC_PLL_SYS, 18 * MHZ, 18 * MHZ); + /* Run RTC from XOSC since USB clock is off */ + clock_configure(clk_rtc, 0, CLOCKS_CLK_RTC_CTRL_AUXSRC_VALUE_XOSC_CLKSRC, 12 * MHZ, 47 * KHZ); + /* Turn off USB PLL */ + pll_deinit(pll_usb); +} +#endif \ No newline at end of file From 52cfec29fcf595aa3f069993a6b0dec293110647 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 15 Mar 2024 16:17:47 -0500 Subject: [PATCH 333/472] More comprehensive client proxy queue guards (#3414) * More comprehensive MQTT thread and queue guards * Consolidate logic * Remove channel check * Check for map_reporting_enabled as well * Update message * Remove channel check from here as well * One liner * Start the mqtt thread back up when channels change and we want mqtt --- src/mesh/Channels.cpp | 16 ++++++++++++++++ src/mesh/Channels.h | 3 +++ src/mesh/PhoneAPI.cpp | 6 +++++- src/mqtt/MQTT.cpp | 21 ++++----------------- src/mqtt/MQTT.h | 4 ++++ 5 files changed, 32 insertions(+), 18 deletions(-) diff --git a/src/mesh/Channels.cpp b/src/mesh/Channels.cpp index 3e9c78241..93dec7e7d 100644 --- a/src/mesh/Channels.cpp +++ b/src/mesh/Channels.cpp @@ -7,6 +7,8 @@ #include +#include "mqtt/MQTT.h" + /// 16 bytes of random PSK for our _public_ default channel that all devices power up on (AES128) static const uint8_t defaultpsk[] = {0xd4, 0xf1, 0xbb, 0x3a, 0x20, 0x29, 0x07, 0x59, 0xf0, 0xbc, 0xff, 0xab, 0xcf, 0x4e, 0x69, 0x01}; @@ -193,6 +195,10 @@ void Channels::onConfigChanged() if (ch.role == meshtastic_Channel_Role_PRIMARY) primaryIndex = i; } + if (channels.anyMqttEnabled() && mqtt && !mqtt->isEnabled()) { + LOG_DEBUG("MQTT is enabled on at least one channel, so set MQTT thread to run immediately\n"); + mqtt->start(); + } } meshtastic_Channel &Channels::getByIndex(ChannelIndex chIndex) @@ -237,6 +243,16 @@ void Channels::setChannel(const meshtastic_Channel &c) old = c; // slam in the new settings/role } +bool Channels::anyMqttEnabled() +{ + for (int i = 0; i < getNumChannels(); i++) + if (channelFile.channels[i].role != meshtastic_Channel_Role_DISABLED && channelFile.channels[i].has_settings && + (channelFile.channels[i].settings.downlink_enabled || channelFile.channels[i].settings.uplink_enabled)) + return true; + + return false; +} + const char *Channels::getName(size_t chIndex) { // Convert the short "" representation for Default into a usable string diff --git a/src/mesh/Channels.h b/src/mesh/Channels.h index 0e11605c4..a1c4ba171 100644 --- a/src/mesh/Channels.h +++ b/src/mesh/Channels.h @@ -105,6 +105,9 @@ class Channels // Returns true if we can be reached via a channel with the default settings given a region and modem preset bool hasDefaultChannel(); + // Returns true if any of our channels have enabled MQTT uplink or downlink + bool anyMqttEnabled(); + private: /** Given a channel index, change to use the crypto key specified by that index * diff --git a/src/mesh/PhoneAPI.cpp b/src/mesh/PhoneAPI.cpp index 270bf613f..8e8d69156 100644 --- a/src/mesh/PhoneAPI.cpp +++ b/src/mesh/PhoneAPI.cpp @@ -105,8 +105,12 @@ bool PhoneAPI::handleToRadio(const uint8_t *buf, size_t bufLength) break; case meshtastic_ToRadio_mqttClientProxyMessage_tag: LOG_INFO("Got MqttClientProxy message\n"); - if (mqtt && moduleConfig.mqtt.proxy_to_client_enabled) { + if (mqtt && moduleConfig.mqtt.proxy_to_client_enabled && moduleConfig.mqtt.enabled && + (channels.anyMqttEnabled() || moduleConfig.mqtt.map_reporting_enabled)) { mqtt->onClientProxyReceive(toRadioScratch.mqttClientProxyMessage); + } else { + LOG_WARN("MqttClientProxy received but proxy is not enabled, no channels have up/downlink, or map reporting " + "not enabled\n"); } break; default: diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index c518bc4b5..0d99a3cfd 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -371,22 +371,9 @@ void MQTT::sendSubscriptions() bool MQTT::wantsLink() const { - bool hasChannelorMapReport = false; + bool hasChannelorMapReport = + moduleConfig.mqtt.enabled && (moduleConfig.mqtt.map_reporting_enabled || channels.anyMqttEnabled()); - if (moduleConfig.mqtt.enabled) { - hasChannelorMapReport = moduleConfig.mqtt.map_reporting_enabled; - if (!hasChannelorMapReport) { - // No need for link if no channel needed it - size_t numChan = channels.getNumChannels(); - for (size_t i = 0; i < numChan; i++) { - const auto &ch = channels.getByIndex(i); - if (ch.settings.uplink_enabled || ch.settings.downlink_enabled) { - hasChannelorMapReport = true; - break; - } - } - } - } if (hasChannelorMapReport && moduleConfig.mqtt.proxy_to_client_enabled) return true; @@ -401,7 +388,7 @@ bool MQTT::wantsLink() const int32_t MQTT::runOnce() { - if (!moduleConfig.mqtt.enabled) + if (!moduleConfig.mqtt.enabled || !(moduleConfig.mqtt.map_reporting_enabled || channels.anyMqttEnabled())) return disable(); bool wantConnection = wantsLink(); @@ -915,4 +902,4 @@ bool MQTT::isValidJsonEnvelope(JSONObject &json) (json["from"]->AsNumber() == nodeDB.getNodeNum()) && // only accept message if the "from" is us (json.find("type") != json.end()) && json["type"]->IsString() && // should specify a type (json.find("payload") != json.end()); // should have a payload -} +} \ No newline at end of file diff --git a/src/mqtt/MQTT.h b/src/mqtt/MQTT.h index eeeb00d92..dbc0c77b3 100644 --- a/src/mqtt/MQTT.h +++ b/src/mqtt/MQTT.h @@ -71,6 +71,10 @@ class MQTT : private concurrency::OSThread void onClientProxyReceive(meshtastic_MqttClientProxyMessage msg); + bool isEnabled() { return this->enabled; }; + + void start() { setIntervalFromNow(0); }; + protected: PointerQueue mqttQueue; From 0dda20bc353343d8e8a8edcfab7fed80d33b047a Mon Sep 17 00:00:00 2001 From: Andre K Date: Fri, 15 Mar 2024 19:12:30 -0300 Subject: [PATCH 334/472] fix for I2C scan getting stuck (#3375) * refactor: add delay for T-Echo peripherals setup * comment out `PIN_POWER_EN1` --- src/main.cpp | 4 ++-- src/sleep.cpp | 2 +- variants/t-echo/variant.h | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main.cpp b/src/main.cpp index bb9b68631..fe5d455f8 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -223,7 +223,7 @@ void setup() #if defined(TTGO_T_ECHO) && defined(PIN_POWER_EN) pinMode(PIN_POWER_EN, OUTPUT); digitalWrite(PIN_POWER_EN, HIGH); - digitalWrite(PIN_POWER_EN1, INPUT); + // digitalWrite(PIN_POWER_EN1, INPUT); #endif #if defined(LORA_TCXO_GPIO) @@ -965,4 +965,4 @@ void loop() mainDelay.delay(delayMsec); } // if (didWake) LOG_DEBUG("wake!\n"); -} \ No newline at end of file +} diff --git a/src/sleep.cpp b/src/sleep.cpp index bfacffeb9..6d8e4f3cc 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -203,7 +203,7 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) #ifdef TTGO_T_ECHO #ifdef PIN_POWER_EN pinMode(PIN_POWER_EN, INPUT); // power off peripherals - pinMode(PIN_POWER_EN1, INPUT_PULLDOWN); + // pinMode(PIN_POWER_EN1, INPUT_PULLDOWN); #endif #endif diff --git a/variants/t-echo/variant.h b/variants/t-echo/variant.h index 19a66719f..13f74d303 100644 --- a/variants/t-echo/variant.h +++ b/variants/t-echo/variant.h @@ -158,7 +158,7 @@ External serial flash WP25R1635FZUIL0 // Controls power for all peripherals (eink + GPS + LoRa + Sensor) #define PIN_POWER_EN (0 + 12) -#define PIN_POWER_EN1 (0 + 13) +// #define PIN_POWER_EN1 (0 + 13) #define USE_EINK From 0de36fbfb0bd5a6cd773726de03b084ab96d7960 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Fri, 15 Mar 2024 17:12:45 -0500 Subject: [PATCH 335/472] [create-pull-request] automated change (#3419) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/mesh.pb.h | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/protobufs b/protobufs index cf25b390d..b2b145e33 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit cf25b390d65113980b1a239e16faa79c7730a736 +Subproject commit b2b145e3321beab1441fa59290137ab42eb38dc8 diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index 8f260589c..2f57f1ae2 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -819,7 +819,7 @@ typedef struct _meshtastic_ToRadio { /* MQTT Client Proxy Message (for client / phone subscribed to MQTT sending to device) */ meshtastic_MqttClientProxyMessage mqttClientProxyMessage; /* Heartbeat message (used to keep the device connection awake on serial) */ - meshtastic_Heartbeat hearbeat; + meshtastic_Heartbeat heartbeat; }; } meshtastic_ToRadio; @@ -1066,7 +1066,7 @@ extern "C" { #define meshtastic_ToRadio_disconnect_tag 4 #define meshtastic_ToRadio_xmodemPacket_tag 5 #define meshtastic_ToRadio_mqttClientProxyMessage_tag 6 -#define meshtastic_ToRadio_hearbeat_tag 7 +#define meshtastic_ToRadio_heartbeat_tag 7 /* Struct field encoding specification for nanopb */ #define meshtastic_Position_FIELDLIST(X, a) \ @@ -1247,13 +1247,13 @@ X(a, STATIC, ONEOF, UINT32, (payload_variant,want_config_id,want_config_i X(a, STATIC, ONEOF, BOOL, (payload_variant,disconnect,disconnect), 4) \ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,xmodemPacket,xmodemPacket), 5) \ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,mqttClientProxyMessage,mqttClientProxyMessage), 6) \ -X(a, STATIC, ONEOF, MESSAGE, (payload_variant,hearbeat,hearbeat), 7) +X(a, STATIC, ONEOF, MESSAGE, (payload_variant,heartbeat,heartbeat), 7) #define meshtastic_ToRadio_CALLBACK NULL #define meshtastic_ToRadio_DEFAULT NULL #define meshtastic_ToRadio_payload_variant_packet_MSGTYPE meshtastic_MeshPacket #define meshtastic_ToRadio_payload_variant_xmodemPacket_MSGTYPE meshtastic_XModem #define meshtastic_ToRadio_payload_variant_mqttClientProxyMessage_MSGTYPE meshtastic_MqttClientProxyMessage -#define meshtastic_ToRadio_payload_variant_hearbeat_MSGTYPE meshtastic_Heartbeat +#define meshtastic_ToRadio_payload_variant_heartbeat_MSGTYPE meshtastic_Heartbeat #define meshtastic_Compressed_FIELDLIST(X, a) \ X(a, STATIC, SINGULAR, UENUM, portnum, 1) \ From 9586606229f59883938b263c9abc451ce6967b3a Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 15 Mar 2024 18:40:48 -0500 Subject: [PATCH 336/472] Handle for heartbeat toradio packets (#3420) --- src/SerialConsole.cpp | 2 +- src/mesh/PhoneAPI.cpp | 3 +++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/src/SerialConsole.cpp b/src/SerialConsole.cpp index 485329ddc..e17c8f99e 100644 --- a/src/SerialConsole.cpp +++ b/src/SerialConsole.cpp @@ -72,7 +72,7 @@ bool SerialConsole::checkIsConnected() /** * we override this to notice when we've received a protobuf over the serial - * stream. Then we shunt off debug serial output. + * stream. Then we shut off debug serial output. */ bool SerialConsole::handleToRadio(const uint8_t *buf, size_t len) { diff --git a/src/mesh/PhoneAPI.cpp b/src/mesh/PhoneAPI.cpp index 8e8d69156..e6b336d41 100644 --- a/src/mesh/PhoneAPI.cpp +++ b/src/mesh/PhoneAPI.cpp @@ -113,6 +113,9 @@ bool PhoneAPI::handleToRadio(const uint8_t *buf, size_t bufLength) "not enabled\n"); } break; + case meshtastic_ToRadio_heartbeat_tag: + LOG_DEBUG("Got client heartbeat\n"); + break; default: // Ignore nop messages // LOG_DEBUG("Error: unexpected ToRadio variant\n"); From 611f291d4d5e26e6d19c9f54ff0188b836209a4b Mon Sep 17 00:00:00 2001 From: David Ellefsen <93522+titan098@users.noreply.github.com> Date: Sat, 16 Mar 2024 02:19:50 +0200 Subject: [PATCH 337/472] Factory reset GNSS_MODEL_MTK GPS modules with PCAS10,3 (#3388) Co-authored-by: Ben Meadors --- src/gps/GPS.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 2321ee246..18932e066 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -1209,6 +1209,11 @@ bool GPS::factoryReset() // byte _message_CFG_RST_COLDSTART[] = {0xB5, 0x62, 0x06, 0x04, 0x04, 0x00, 0xFF, 0xB9, 0x00, 0x00, 0xC6, 0x8B}; // _serial_gps->write(_message_CFG_RST_COLDSTART, sizeof(_message_CFG_RST_COLDSTART)); // delay(1000); + } else if (gnssModel == GNSS_MODEL_MTK) { + // send the CAS10 to perform a factory restart of the device (and other device that support PCAS statements) + LOG_INFO("GNSS Factory Reset via PCAS10,3\n"); + _serial_gps->write("$PCAS10,3*1F\r\n"); + delay(100); } else { // fire this for good measure, if we have an L76B - won't harm other devices. _serial_gps->write("$PMTK104*37\r\n"); From 54a2a4bcc67793fc8e72621d487153d4eb801c3d Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sat, 16 Mar 2024 07:39:28 -0500 Subject: [PATCH 338/472] [create-pull-request] automated change (#3422) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/deviceonly.pb.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/protobufs b/protobufs index b2b145e33..556e49ba6 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit b2b145e3321beab1441fa59290137ab42eb38dc8 +Subproject commit 556e49ba619e2f4d8fa3c2dee2a94129a43d5f08 diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index 79800d4b4..d6a2a0272 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -141,7 +141,8 @@ typedef struct _meshtastic_DeviceState { NodeDB.cpp in the device code. */ uint32_t version; /* Used only during development. - Indicates developer is testing and changes should never be saved to flash. */ + Indicates developer is testing and changes should never be saved to flash. + Deprecated in 2.3.1 */ bool no_save; /* Some GPS receivers seem to have bogus settings from the factory, so we always do one factory reset. */ bool did_gps_reset; From 13cc1b0252b5fdae9a195412039ea46b0288d634 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sat, 16 Mar 2024 16:01:43 +0100 Subject: [PATCH 339/472] (3/3) Add variant for pico with waveshare and GPS hat (#3412) * (3/3) Add variant for pico with waveshare and GPS hat, utilizing slow clock. * Not everybody has Serial2 * Trunk * Push it real gud * No init --------- Co-authored-by: Ben Meadors --- src/configuration.h | 1 + src/detect/ScanI2CTwoWire.cpp | 10 ++- src/modules/Telemetry/Sensor/INA219Sensor.cpp | 6 +- variants/rpipico-slowclock/platformio.ini | 28 ++++++ variants/rpipico-slowclock/variant.h | 87 +++++++++++++++++++ 5 files changed, 129 insertions(+), 3 deletions(-) create mode 100644 variants/rpipico-slowclock/platformio.ini create mode 100644 variants/rpipico-slowclock/variant.h diff --git a/src/configuration.h b/src/configuration.h index ac8f9435a..ec32c72d1 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -111,6 +111,7 @@ along with this program. If not, see . #define MCP9808_ADDR 0x18 #define INA_ADDR 0x40 #define INA_ADDR_ALTERNATE 0x41 +#define INA_ADDR_WAVESHARE_UPS 0x43 #define INA3221_ADDR 0x42 #define QMC6310_ADDR 0x1C #define QMI8658_ADDR 0x6B diff --git a/src/detect/ScanI2CTwoWire.cpp b/src/detect/ScanI2CTwoWire.cpp index b6eca5fa4..146daa3dc 100644 --- a/src/detect/ScanI2CTwoWire.cpp +++ b/src/detect/ScanI2CTwoWire.cpp @@ -183,8 +183,13 @@ void ScanI2CTwoWire::scanPort(I2CPort port) #if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) case ATECC608B_ADDR: - type = ATECC608B; - if (atecc.begin(addr.address) == true) { +#ifdef RP2040_SLOW_CLOCK + if (atecc.begin(addr.address, Wire, Serial2) == true) +#else + if (atecc.begin(addr.address) == true) +#endif + + { LOG_INFO("ATECC608B initialized\n"); } else { LOG_WARN("ATECC608B initialization failed\n"); @@ -254,6 +259,7 @@ void ScanI2CTwoWire::scanPort(I2CPort port) case INA_ADDR: case INA_ADDR_ALTERNATE: + case INA_ADDR_WAVESHARE_UPS: registerValue = getRegisterValue(ScanI2CTwoWire::RegisterLocation(addr, 0xFE), 2); LOG_DEBUG("Register MFG_UID: 0x%x\n", registerValue); if (registerValue == 0x5449) { diff --git a/src/modules/Telemetry/Sensor/INA219Sensor.cpp b/src/modules/Telemetry/Sensor/INA219Sensor.cpp index 5a1faa99f..ecb564368 100644 --- a/src/modules/Telemetry/Sensor/INA219Sensor.cpp +++ b/src/modules/Telemetry/Sensor/INA219Sensor.cpp @@ -4,6 +4,10 @@ #include "configuration.h" #include +#ifndef INA219_MULTIPLIER +#define INA219_MULTIPLIER 1.0f +#endif + INA219Sensor::INA219Sensor() : TelemetrySensor(meshtastic_TelemetrySensorType_INA219, "INA219") {} int32_t INA219Sensor::runOnce() @@ -26,7 +30,7 @@ void INA219Sensor::setup() {} bool INA219Sensor::getMetrics(meshtastic_Telemetry *measurement) { measurement->variant.environment_metrics.voltage = ina219.getBusVoltage_V(); - measurement->variant.environment_metrics.current = ina219.getCurrent_mA(); + measurement->variant.environment_metrics.current = ina219.getCurrent_mA() * INA219_MULTIPLIER; return true; } diff --git a/variants/rpipico-slowclock/platformio.ini b/variants/rpipico-slowclock/platformio.ini new file mode 100644 index 000000000..e583c4b0d --- /dev/null +++ b/variants/rpipico-slowclock/platformio.ini @@ -0,0 +1,28 @@ +[env:pico_slowclock] +extends = rp2040_base +board = rpipico +upload_protocol = jlink +# debug settings for external openocd with RP2040 support (custom build) +debug_tool = custom +debug_init_cmds = + target extended-remote localhost:3333 + $INIT_BREAK + monitor reset halt + $LOAD_CMDS + monitor init + monitor reset halt + +# add our variants files to the include and src paths +build_flags = ${rp2040_base.build_flags} + -DRPI_PICO + -Ivariants/rpipico_slowclock + -DDEBUG_RP2040_PORT=Serial2 + -DHW_SPI1_DEVICE + -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m0plus" + -g + -DNO_USB +lib_deps = + ${rp2040_base.lib_deps} +debug_build_flags = ${rp2040_base.build_flags} + -g + -DNO_USB \ No newline at end of file diff --git a/variants/rpipico-slowclock/variant.h b/variants/rpipico-slowclock/variant.h new file mode 100644 index 000000000..fb97ec0fb --- /dev/null +++ b/variants/rpipico-slowclock/variant.h @@ -0,0 +1,87 @@ +#define ARDUINO_ARCH_AVR + +// Build with slow system clock enabled to reduce power consumption. +#define RP2040_SLOW_CLOCK + +#ifdef RP2040_SLOW_CLOCK +// Redefine UART1 serial log output to avoid collision with UART0 for GPS. +#define SERIAL2_TX 4 +#define SERIAL2_RX 5 +// Reroute log output in SensorLib when USB is not available +#define log_e(...) Serial2.printf(__VA_ARGS__) +#define log_i(...) Serial2.printf(__VA_ARGS__) +#define log_d(...) Serial2.printf(__VA_ARGS__) +#endif + +// Expecting the Waveshare Pico GPS hat +#define HAS_GPS 1 + +// Enable OLED Screen +#define HAS_SCREEN 1 +#define USE_SH1106 1 +#define RESET_OLED 13 + +// Redefine I2C0 pins to avoid collision with UART1/Serial2. +#define I2C_SDA 8 +#define I2C_SCL 9 + +// Redefine Waveshare UPS-A/B I2C_1 pins: +#define I2C_SDA1 6 +#define I2C_SCL1 7 +// Waveshare UPS-A/B uses a 0.01 Ohm shunt for the INA219 sensor +#define INA219_MULTIPLIER 10.0f + +// Waveshare Pico GPS L76B pins: +#define GPS_RX_PIN 1 +#define GPS_TX_PIN 0 + +// Wakeup from backup mode +// #define PIN_GPS_FORCE_ON 14 +// No GPS reset available +#undef PIN_GPS_RESET +/* + * For PPS output the resistor R20 needs to be populated with 0 Ohm + * on the Waveshare Pico GPS board. + */ +#define PIN_GPS_PPS 16 +/* + * For standby mode switching the resistor R18 needs to be populated + * with 0 Ohm on the Waveshare Pico GPS board. + */ +#define PIN_GPS_STANDBY 17 + +#define BUTTON_PIN 18 +#define EXT_NOTIFY_OUT 22 +#define LED_PIN PIN_LED + +#define BATTERY_PIN 26 +// ratio of voltage divider = 3.0 (R17=200k, R18=100k) +#define ADC_MULTIPLIER 3.1 // 3.0 + a bit for being optimistic +#define BATTERY_SENSE_RESOLUTION_BITS ADC_RESOLUTION + +#define USE_SX1262 + +#undef LORA_SCK +#undef LORA_MISO +#undef LORA_MOSI +#undef LORA_CS + +#define LORA_SCK 10 +#define LORA_MISO 12 +#define LORA_MOSI 11 +#define LORA_CS 3 + +#define LORA_DIO0 RADIOLIB_NC +#define LORA_RESET 15 +#define LORA_DIO1 20 +#define LORA_DIO2 2 +#define LORA_DIO3 RADIOLIB_NC + +#ifdef USE_SX1262 +#define SX126X_CS LORA_CS +#define SX126X_DIO1 LORA_DIO1 +#define SX126X_BUSY LORA_DIO2 +#define SX126X_RESET LORA_RESET +#define SX126X_DIO2_AS_RF_SWITCH +#define SX126X_DIO3_TCXO_VOLTAGE 1.8 +#endif \ No newline at end of file From e27f029d09424698f6e8b00ac64efe73ee85749a Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sat, 16 Mar 2024 19:56:42 -0500 Subject: [PATCH 340/472] Bump minimum NodeInfo send to 5 minutes (#3423) * Bump minimum NodeInfo send to 3 minutes * 5 --- src/modules/NodeInfoModule.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/NodeInfoModule.cpp b/src/modules/NodeInfoModule.cpp index 5177af33a..6b4289970 100644 --- a/src/modules/NodeInfoModule.cpp +++ b/src/modules/NodeInfoModule.cpp @@ -58,8 +58,8 @@ void NodeInfoModule::sendOurNodeInfo(NodeNum dest, bool wantReplies, uint8_t cha meshtastic_MeshPacket *NodeInfoModule::allocReply() { uint32_t now = millis(); - // If we sent our NodeInfo less than 1 min. ago, don't send it again as it may be still underway. - if (lastSentToMesh && (now - lastSentToMesh) < 60 * 1000) { + // If we sent our NodeInfo less than 5 min. ago, don't send it again as it may be still underway. + if (lastSentToMesh && (now - lastSentToMesh) < (5 * 60 * 1000)) { LOG_DEBUG("Sending NodeInfo will be ignored since we just sent it.\n"); ignoreRequest = true; // Mark it as ignored for MeshModule return NULL; From bb57ccfc9eccc9520950c125debcf7bfe73b87ab Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 17 Mar 2024 08:16:22 -0500 Subject: [PATCH 341/472] Remove devicestate no_save (#3424) --- src/mesh/NodeDB.cpp | 74 ++++++++++++++++++--------------------------- 1 file changed, 29 insertions(+), 45 deletions(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 6898f7702..a9fffc335 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -97,13 +97,6 @@ bool NodeDB::resetRadioConfig(bool factory_reset) channels.onConfigChanged(); - // temp hack for quicker testing - // devicestate.no_save = true; - if (devicestate.no_save) { - LOG_DEBUG("***** DEVELOPMENT MODE - DO NOT RELEASE *****\n"); - // Put your development config changes here - } - // Update the global myRegion initRegion(); @@ -644,61 +637,52 @@ bool NodeDB::saveProto(const char *filename, size_t protoSize, const pb_msgdesc_ void NodeDB::saveChannelsToDisk() { - if (!devicestate.no_save) { #ifdef FSCom - FSCom.mkdir("/prefs"); + FSCom.mkdir("/prefs"); #endif - saveProto(channelFileName, meshtastic_ChannelFile_size, &meshtastic_ChannelFile_msg, &channelFile); - } + saveProto(channelFileName, meshtastic_ChannelFile_size, &meshtastic_ChannelFile_msg, &channelFile); } void NodeDB::saveDeviceStateToDisk() { - if (!devicestate.no_save) { #ifdef FSCom - FSCom.mkdir("/prefs"); + FSCom.mkdir("/prefs"); #endif - saveProto(prefFileName, meshtastic_DeviceState_size, &meshtastic_DeviceState_msg, &devicestate); - } } void NodeDB::saveToDisk(int saveWhat) { - if (!devicestate.no_save) { #ifdef FSCom - FSCom.mkdir("/prefs"); + FSCom.mkdir("/prefs"); #endif - if (saveWhat & SEGMENT_DEVICESTATE) { - saveDeviceStateToDisk(); - } + if (saveWhat & SEGMENT_DEVICESTATE) { + saveDeviceStateToDisk(); + } - if (saveWhat & SEGMENT_CONFIG) { - config.has_device = true; - config.has_display = true; - config.has_lora = true; - config.has_position = true; - config.has_power = true; - config.has_network = true; - config.has_bluetooth = true; - saveProto(configFileName, meshtastic_LocalConfig_size, &meshtastic_LocalConfig_msg, &config); - } + if (saveWhat & SEGMENT_CONFIG) { + config.has_device = true; + config.has_display = true; + config.has_lora = true; + config.has_position = true; + config.has_power = true; + config.has_network = true; + config.has_bluetooth = true; + saveProto(configFileName, meshtastic_LocalConfig_size, &meshtastic_LocalConfig_msg, &config); + } - if (saveWhat & SEGMENT_MODULECONFIG) { - moduleConfig.has_canned_message = true; - moduleConfig.has_external_notification = true; - moduleConfig.has_mqtt = true; - moduleConfig.has_range_test = true; - moduleConfig.has_serial = true; - moduleConfig.has_store_forward = true; - moduleConfig.has_telemetry = true; - saveProto(moduleConfigFileName, meshtastic_LocalModuleConfig_size, &meshtastic_LocalModuleConfig_msg, &moduleConfig); - } + if (saveWhat & SEGMENT_MODULECONFIG) { + moduleConfig.has_canned_message = true; + moduleConfig.has_external_notification = true; + moduleConfig.has_mqtt = true; + moduleConfig.has_range_test = true; + moduleConfig.has_serial = true; + moduleConfig.has_store_forward = true; + moduleConfig.has_telemetry = true; + saveProto(moduleConfigFileName, meshtastic_LocalModuleConfig_size, &meshtastic_LocalModuleConfig_msg, &moduleConfig); + } - if (saveWhat & SEGMENT_CHANNELS) { - saveChannelsToDisk(); - } - } else { - LOG_DEBUG("***** DEVELOPMENT MODE - DO NOT RELEASE - not saving to flash *****\n"); + if (saveWhat & SEGMENT_CHANNELS) { + saveChannelsToDisk(); } } From 0d1d79b6d15f5e7c4bcde12a1f59af3c204117c3 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 17 Mar 2024 08:18:30 -0500 Subject: [PATCH 342/472] Extract default intervals and coalesce methods into their own file / static class methods (#3425) * Extract default intervals and coalesce methods into their own file / static class methods * Missed pax * Still managed to miss one --- src/PowerFSM.cpp | 18 ++++---- src/PowerFSMThread.h | 3 +- src/gps/GPS.cpp | 4 +- src/mesh/Default.cpp | 23 ++++++++++ src/mesh/Default.h | 30 +++++++++++++ src/mesh/NodeDB.cpp | 1 + src/mesh/NodeDB.h | 42 ------------------- src/mesh/PhoneAPI.cpp | 1 + src/modules/AdminModule.cpp | 1 + src/modules/AtakPluginModule.cpp | 1 + src/modules/DetectionSensorModule.cpp | 7 ++-- src/modules/NeighborInfoModule.cpp | 3 +- src/modules/NodeInfoModule.cpp | 3 +- src/modules/PositionModule.cpp | 11 +++-- src/modules/Telemetry/AirQualityTelemetry.cpp | 3 +- src/modules/Telemetry/DeviceTelemetry.cpp | 3 +- .../Telemetry/EnvironmentTelemetry.cpp | 5 ++- src/modules/Telemetry/PowerTelemetry.cpp | 5 ++- src/modules/esp32/PaxcounterModule.cpp | 11 ++--- src/mqtt/MQTT.cpp | 1 + 20 files changed, 103 insertions(+), 73 deletions(-) create mode 100644 src/mesh/Default.cpp create mode 100644 src/mesh/Default.h diff --git a/src/PowerFSM.cpp b/src/PowerFSM.cpp index f98b03077..5d86987df 100644 --- a/src/PowerFSM.cpp +++ b/src/PowerFSM.cpp @@ -8,6 +8,7 @@ * actions to be taken upon entering or exiting each state. */ #include "PowerFSM.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "configuration.h" @@ -45,7 +46,7 @@ static void sdsEnter() { LOG_DEBUG("Enter state: SDS\n"); // FIXME - make sure GPS and LORA radio are off first - because we want close to zero current draw - doDeepSleep(getConfiguredOrDefaultMs(config.power.sds_secs), false); + doDeepSleep(Default::getConfiguredOrDefaultMs(config.power.sds_secs), false); } extern Power *power; @@ -343,13 +344,13 @@ void PowerFSM_setup() powerFSM.add_transition(&stateDARK, &stateDARK, EVENT_CONTACT_FROM_PHONE, NULL, "Contact from phone"); powerFSM.add_timed_transition(&stateON, &stateDARK, - getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, + Default::getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, "Screen-on timeout"); powerFSM.add_timed_transition(&statePOWER, &stateDARK, - getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, + Default::getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, "Screen-on timeout"); powerFSM.add_timed_transition(&stateDARK, &stateDARK, - getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, + Default::getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, "Screen-on timeout"); // We never enter light-sleep or NB states on NRF52 (because the CPU uses so little power normally) @@ -359,11 +360,12 @@ void PowerFSM_setup() // modules if ((isRouter || config.power.is_power_saving) && !isTrackerOrSensor) { powerFSM.add_timed_transition(&stateNB, &stateLS, - getConfiguredOrDefaultMs(config.power.min_wake_secs, default_min_wake_secs), NULL, + Default::getConfiguredOrDefaultMs(config.power.min_wake_secs, default_min_wake_secs), NULL, "Min wake timeout"); - powerFSM.add_timed_transition(&stateDARK, &stateLS, - getConfiguredOrDefaultMs(config.power.wait_bluetooth_secs, default_wait_bluetooth_secs), - NULL, "Bluetooth timeout"); + powerFSM.add_timed_transition( + &stateDARK, &stateLS, + Default::getConfiguredOrDefaultMs(config.power.wait_bluetooth_secs, default_wait_bluetooth_secs), NULL, + "Bluetooth timeout"); } #endif diff --git a/src/PowerFSMThread.h b/src/PowerFSMThread.h index 584c955aa..fb640dd8b 100644 --- a/src/PowerFSMThread.h +++ b/src/PowerFSMThread.h @@ -1,3 +1,4 @@ +#include "Default.h" #include "NodeDB.h" #include "PowerFSM.h" #include "concurrency/OSThread.h" @@ -28,7 +29,7 @@ class PowerFSMThread : public OSThread timeLastPowered = millis(); } else if (config.power.on_battery_shutdown_after_secs > 0 && config.power.on_battery_shutdown_after_secs != UINT32_MAX && millis() > (timeLastPowered + - getConfiguredOrDefaultMs( + Default::getConfiguredOrDefaultMs( config.power.on_battery_shutdown_after_secs))) { // shutdown after 30 minutes unpowered powerFSM.trigger(EVENT_SHUTDOWN); } diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 18932e066..5595172dd 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -1,4 +1,5 @@ #include "GPS.h" +#include "Default.h" #include "NodeDB.h" #include "RTC.h" #include "configuration.h" @@ -495,7 +496,6 @@ bool GPS::setup() } } } - } else { // LOG_INFO("u-blox M10 hardware found.\n"); delay(1000); @@ -759,7 +759,7 @@ uint32_t GPS::getWakeTime() const if (t == UINT32_MAX) return t; // already maxint - return getConfiguredOrDefaultMs(t, default_broadcast_interval_secs); + return Default::Default::getConfiguredOrDefaultMs(t, default_broadcast_interval_secs); } /** Get how long we should sleep between aqusition attempts in msecs diff --git a/src/mesh/Default.cpp b/src/mesh/Default.cpp new file mode 100644 index 000000000..db058c5b0 --- /dev/null +++ b/src/mesh/Default.cpp @@ -0,0 +1,23 @@ +#include "Default.h" + +uint32_t Default::getConfiguredOrDefaultMs(uint32_t configuredInterval) +{ + if (configuredInterval > 0) + return configuredInterval * 1000; + return default_broadcast_interval_secs * 1000; +} + +uint32_t Default::getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t defaultInterval) +{ + if (configuredInterval > 0) + return configuredInterval * 1000; + return defaultInterval * 1000; +} + +uint32_t Default::getConfiguredOrDefault(uint32_t configured, uint32_t defaultValue) +{ + if (configured > 0) + return configured; + + return defaultValue; +} \ No newline at end of file diff --git a/src/mesh/Default.h b/src/mesh/Default.h new file mode 100644 index 000000000..734cdf519 --- /dev/null +++ b/src/mesh/Default.h @@ -0,0 +1,30 @@ +#pragma once +#include +#include +#define ONE_DAY 24 * 60 * 60 + +#define default_gps_update_interval IF_ROUTER(ONE_DAY, 2 * 60) +#define default_broadcast_interval_secs IF_ROUTER(ONE_DAY / 2, 15 * 60) +#define default_wait_bluetooth_secs IF_ROUTER(1, 60) +#define default_sds_secs IF_ROUTER(ONE_DAY, UINT32_MAX) // Default to forever super deep sleep +#define default_ls_secs IF_ROUTER(ONE_DAY, 5 * 60) +#define default_min_wake_secs 10 +#define default_screen_on_secs IF_ROUTER(1, 60 * 10) +#define default_node_info_broadcast_secs 3 * 60 * 60 +#define min_node_info_broadcast_secs 60 * 60 // No regular broadcasts of more than once an hour + +#define default_mqtt_address "mqtt.meshtastic.org" +#define default_mqtt_username "meshdev" +#define default_mqtt_password "large4cats" +#define default_mqtt_root "msh" + +#define IF_ROUTER(routerVal, normalVal) \ + ((config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER) ? (routerVal) : (normalVal)) + +class Default +{ + public: + static uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval); + static uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t defaultInterval); + static uint32_t getConfiguredOrDefault(uint32_t configured, uint32_t defaultValue); +}; diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index a9fffc335..04b6fe89d 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -3,6 +3,7 @@ #include "../detect/ScanI2C.h" #include "Channels.h" #include "CryptoEngine.h" +#include "Default.h" #include "FSCommon.h" #include "GPS.h" #include "MeshRadio.h" diff --git a/src/mesh/NodeDB.h b/src/mesh/NodeDB.h index b34059fb9..930b3483e 100644 --- a/src/mesh/NodeDB.h +++ b/src/mesh/NodeDB.h @@ -191,48 +191,6 @@ extern NodeDB nodeDB; // Our delay functions check for this for times that should never expire #define NODE_DELAY_FOREVER 0xffffffff -#define IF_ROUTER(routerVal, normalVal) \ - ((config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER) ? (routerVal) : (normalVal)) - -#define ONE_DAY 24 * 60 * 60 - -#define default_gps_update_interval IF_ROUTER(ONE_DAY, 2 * 60) -#define default_broadcast_interval_secs IF_ROUTER(ONE_DAY / 2, 15 * 60) -#define default_wait_bluetooth_secs IF_ROUTER(1, 60) -#define default_sds_secs IF_ROUTER(ONE_DAY, UINT32_MAX) // Default to forever super deep sleep -#define default_ls_secs IF_ROUTER(ONE_DAY, 5 * 60) -#define default_min_wake_secs 10 -#define default_screen_on_secs IF_ROUTER(1, 60 * 10) -#define default_node_info_broadcast_secs 3 * 60 * 60 -#define min_node_info_broadcast_secs 60 * 60 // No regular broadcasts of more than once an hour - -#define default_mqtt_address "mqtt.meshtastic.org" -#define default_mqtt_username "meshdev" -#define default_mqtt_password "large4cats" -#define default_mqtt_root "msh" - -inline uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval) -{ - if (configuredInterval > 0) - return configuredInterval * 1000; - return default_broadcast_interval_secs * 1000; -} - -inline uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t defaultInterval) -{ - if (configuredInterval > 0) - return configuredInterval * 1000; - return defaultInterval * 1000; -} - -inline uint32_t getConfiguredOrDefault(uint32_t configured, uint32_t defaultValue) -{ - if (configured > 0) - return configured; - - return defaultValue; -} - /// Sometimes we will have Position objects that only have a time, so check for /// valid lat/lon static inline bool hasValidPosition(const meshtastic_NodeInfoLite *n) diff --git a/src/mesh/PhoneAPI.cpp b/src/mesh/PhoneAPI.cpp index e6b336d41..d8e842149 100644 --- a/src/mesh/PhoneAPI.cpp +++ b/src/mesh/PhoneAPI.cpp @@ -1,5 +1,6 @@ #include "PhoneAPI.h" #include "Channels.h" +#include "Default.h" #include "GPS.h" #include "MeshService.h" #include "NodeDB.h" diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index 06818dc88..6c4c80dbb 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -16,6 +16,7 @@ #ifdef ARCH_PORTDUINO #include "unistd.h" #endif +#include "Default.h" #include "mqtt/MQTT.h" diff --git a/src/modules/AtakPluginModule.cpp b/src/modules/AtakPluginModule.cpp index ffc4fe68a..64a85e2bf 100644 --- a/src/modules/AtakPluginModule.cpp +++ b/src/modules/AtakPluginModule.cpp @@ -1,4 +1,5 @@ #include "AtakPluginModule.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "PowerFSM.h" diff --git a/src/modules/DetectionSensorModule.cpp b/src/modules/DetectionSensorModule.cpp index 6c35e94ae..fd26749c1 100644 --- a/src/modules/DetectionSensorModule.cpp +++ b/src/modules/DetectionSensorModule.cpp @@ -1,10 +1,10 @@ #include "DetectionSensorModule.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "PowerFSM.h" #include "configuration.h" #include "main.h" - DetectionSensorModule *detectionSensorModule; #define GPIO_POLLING_INTERVAL 100 @@ -49,7 +49,7 @@ int32_t DetectionSensorModule::runOnce() // LOG_DEBUG("Detection Sensor Module: Current pin state: %i\n", digitalRead(moduleConfig.detection_sensor.monitor_pin)); - if ((millis() - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.detection_sensor.minimum_broadcast_secs) && + if ((millis() - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.detection_sensor.minimum_broadcast_secs) && hasDetectionEvent()) { sendDetectionMessage(); return DELAYED_INTERVAL; @@ -58,7 +58,8 @@ int32_t DetectionSensorModule::runOnce() // of heartbeat. We only do this if the minimum broadcast interval is greater than zero, otherwise we'll only broadcast state // change detections. else if (moduleConfig.detection_sensor.state_broadcast_secs > 0 && - (millis() - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.detection_sensor.state_broadcast_secs)) { + (millis() - lastSentToMesh) >= + Default::getConfiguredOrDefaultMs(moduleConfig.detection_sensor.state_broadcast_secs)) { sendCurrentStateMessage(); return DELAYED_INTERVAL; } diff --git a/src/modules/NeighborInfoModule.cpp b/src/modules/NeighborInfoModule.cpp index 2e0b04afa..024f321e6 100644 --- a/src/modules/NeighborInfoModule.cpp +++ b/src/modules/NeighborInfoModule.cpp @@ -1,4 +1,5 @@ #include "NeighborInfoModule.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "RTC.h" @@ -194,7 +195,7 @@ int32_t NeighborInfoModule::runOnce() { bool requestReplies = false; sendNeighborInfo(NODENUM_BROADCAST, requestReplies); - return getConfiguredOrDefaultMs(moduleConfig.neighbor_info.update_interval, default_broadcast_interval_secs); + return Default::getConfiguredOrDefaultMs(moduleConfig.neighbor_info.update_interval, default_broadcast_interval_secs); } /* diff --git a/src/modules/NodeInfoModule.cpp b/src/modules/NodeInfoModule.cpp index 6b4289970..370847b94 100644 --- a/src/modules/NodeInfoModule.cpp +++ b/src/modules/NodeInfoModule.cpp @@ -1,4 +1,5 @@ #include "NodeInfoModule.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "RTC.h" @@ -91,5 +92,5 @@ int32_t NodeInfoModule::runOnce() LOG_INFO("Sending our nodeinfo to mesh (wantReplies=%d)\n", requestReplies); sendOurNodeInfo(NODENUM_BROADCAST, requestReplies); // Send our info (don't request replies) } - return getConfiguredOrDefaultMs(config.device.node_info_broadcast_secs, default_node_info_broadcast_secs); + return Default::getConfiguredOrDefaultMs(config.device.node_info_broadcast_secs, default_node_info_broadcast_secs); } diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index 59f62bd5c..853808f44 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -1,4 +1,5 @@ #include "PositionModule.h" +#include "Default.h" #include "GPS.h" #include "MeshService.h" #include "NodeDB.h" @@ -280,7 +281,7 @@ int32_t PositionModule::runOnce() { if (sleepOnNextExecution == true) { sleepOnNextExecution = false; - uint32_t nightyNightMs = getConfiguredOrDefaultMs(config.position.position_broadcast_secs); + uint32_t nightyNightMs = Default::getConfiguredOrDefaultMs(config.position.position_broadcast_secs); LOG_DEBUG("Sleeping for %ims, then awaking to send position again.\n", nightyNightMs); doDeepSleep(nightyNightMs, false); } @@ -291,7 +292,8 @@ int32_t PositionModule::runOnce() // We limit our GPS broadcasts to a max rate uint32_t now = millis(); - uint32_t intervalMs = getConfiguredOrDefaultMs(config.position.position_broadcast_secs, default_broadcast_interval_secs); + uint32_t intervalMs = + Default::getConfiguredOrDefaultMs(config.position.position_broadcast_secs, default_broadcast_interval_secs); uint32_t msSinceLastSend = now - lastGpsSend; // Only send packets if the channel util. is less than 25% utilized or we're a tracker with less than 40% utilized. if (!airTime->isTxAllowedChannelUtil(config.device.role != meshtastic_Config_DeviceConfig_Role_TRACKER && @@ -322,7 +324,7 @@ int32_t PositionModule::runOnce() if (hasValidPosition(node2)) { // The minimum time (in seconds) that would pass before we are able to send a new position packet. const uint32_t minimumTimeThreshold = - getConfiguredOrDefaultMs(config.position.broadcast_smart_minimum_interval_secs, 30); + Default::getConfiguredOrDefaultMs(config.position.broadcast_smart_minimum_interval_secs, 30); auto smartPosition = getDistanceTraveledSinceLastSend(node->position); @@ -369,7 +371,8 @@ void PositionModule::sendLostAndFoundText() struct SmartPosition PositionModule::getDistanceTraveledSinceLastSend(meshtastic_PositionLite currentPosition) { // The minimum distance to travel before we are able to send a new position packet. - const uint32_t distanceTravelThreshold = getConfiguredOrDefault(config.position.broadcast_smart_minimum_distance, 100); + const uint32_t distanceTravelThreshold = + Default::getConfiguredOrDefault(config.position.broadcast_smart_minimum_distance, 100); // Determine the distance in meters between two points on the globe float distanceTraveledSinceLastSend = GeoCoord::latLongToMeter( diff --git a/src/modules/Telemetry/AirQualityTelemetry.cpp b/src/modules/Telemetry/AirQualityTelemetry.cpp index ada1fdef8..3e9b069c4 100644 --- a/src/modules/Telemetry/AirQualityTelemetry.cpp +++ b/src/modules/Telemetry/AirQualityTelemetry.cpp @@ -1,5 +1,6 @@ #include "AirQualityTelemetry.h" #include "../mesh/generated/meshtastic/telemetry.pb.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "PowerFSM.h" @@ -43,7 +44,7 @@ int32_t AirQualityTelemetryModule::runOnce() uint32_t now = millis(); if (((lastSentToMesh == 0) || - ((now - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.telemetry.air_quality_interval))) && + ((now - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.air_quality_interval))) && airTime->isTxAllowedAirUtil()) { sendTelemetry(); lastSentToMesh = now; diff --git a/src/modules/Telemetry/DeviceTelemetry.cpp b/src/modules/Telemetry/DeviceTelemetry.cpp index 55000e4c6..3ed106d1c 100644 --- a/src/modules/Telemetry/DeviceTelemetry.cpp +++ b/src/modules/Telemetry/DeviceTelemetry.cpp @@ -1,5 +1,6 @@ #include "DeviceTelemetry.h" #include "../mesh/generated/meshtastic/telemetry.pb.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "PowerFSM.h" @@ -16,7 +17,7 @@ int32_t DeviceTelemetryModule::runOnce() { uint32_t now = millis(); if (((lastSentToMesh == 0) || - ((now - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.telemetry.device_update_interval))) && + ((now - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.device_update_interval))) && airTime->isTxAllowedChannelUtil() && airTime->isTxAllowedAirUtil() && config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER && config.device.role != meshtastic_Config_DeviceConfig_Role_CLIENT_HIDDEN) { diff --git a/src/modules/Telemetry/EnvironmentTelemetry.cpp b/src/modules/Telemetry/EnvironmentTelemetry.cpp index 7b59c28a6..203b632a7 100644 --- a/src/modules/Telemetry/EnvironmentTelemetry.cpp +++ b/src/modules/Telemetry/EnvironmentTelemetry.cpp @@ -1,5 +1,6 @@ #include "EnvironmentTelemetry.h" #include "../mesh/generated/meshtastic/telemetry.pb.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "PowerFSM.h" @@ -41,7 +42,7 @@ int32_t EnvironmentTelemetryModule::runOnce() { if (sleepOnNextExecution == true) { sleepOnNextExecution = false; - uint32_t nightyNightMs = getConfiguredOrDefaultMs(moduleConfig.telemetry.environment_update_interval); + uint32_t nightyNightMs = Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.environment_update_interval); LOG_DEBUG("Sleeping for %ims, then awaking to send metrics again.\n", nightyNightMs); doDeepSleep(nightyNightMs, true); } @@ -102,7 +103,7 @@ int32_t EnvironmentTelemetryModule::runOnce() uint32_t now = millis(); if (((lastSentToMesh == 0) || - ((now - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.telemetry.environment_update_interval))) && + ((now - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.environment_update_interval))) && airTime->isTxAllowedAirUtil()) { sendTelemetry(); lastSentToMesh = now; diff --git a/src/modules/Telemetry/PowerTelemetry.cpp b/src/modules/Telemetry/PowerTelemetry.cpp index 300ab1f62..713f6aacb 100644 --- a/src/modules/Telemetry/PowerTelemetry.cpp +++ b/src/modules/Telemetry/PowerTelemetry.cpp @@ -1,5 +1,6 @@ #include "PowerTelemetry.h" #include "../mesh/generated/meshtastic/telemetry.pb.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "PowerFSM.h" @@ -20,7 +21,7 @@ int32_t PowerTelemetryModule::runOnce() { if (sleepOnNextExecution == true) { sleepOnNextExecution = false; - uint32_t nightyNightMs = getConfiguredOrDefaultMs(moduleConfig.telemetry.power_update_interval); + uint32_t nightyNightMs = Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.power_update_interval); LOG_DEBUG("Sleeping for %ims, then awaking to send metrics again.\n", nightyNightMs); doDeepSleep(nightyNightMs, true); } @@ -66,7 +67,7 @@ int32_t PowerTelemetryModule::runOnce() uint32_t now = millis(); if (((lastSentToMesh == 0) || - ((now - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.telemetry.power_update_interval))) && + ((now - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.power_update_interval))) && airTime->isTxAllowedAirUtil()) { sendTelemetry(); lastSentToMesh = now; diff --git a/src/modules/esp32/PaxcounterModule.cpp b/src/modules/esp32/PaxcounterModule.cpp index 54c67fad7..aad7b5d63 100644 --- a/src/modules/esp32/PaxcounterModule.cpp +++ b/src/modules/esp32/PaxcounterModule.cpp @@ -1,8 +1,8 @@ #include "configuration.h" #if defined(ARCH_ESP32) +#include "Default.h" #include "MeshService.h" #include "PaxcounterModule.h" - #include PaxcounterModule *paxcounterModule; @@ -82,9 +82,9 @@ int32_t PaxcounterModule::runOnce() if (isActive()) { if (firstTime) { firstTime = false; - LOG_DEBUG( - "Paxcounter starting up with interval of %d seconds\n", - getConfiguredOrDefault(moduleConfig.paxcounter.paxcounter_update_interval, default_broadcast_interval_secs)); + LOG_DEBUG("Paxcounter starting up with interval of %d seconds\n", + Default::getConfiguredOrDefault(moduleConfig.paxcounter.paxcounter_update_interval, + default_broadcast_interval_secs)); struct libpax_config_t configuration; libpax_default_config(&configuration); @@ -104,7 +104,8 @@ int32_t PaxcounterModule::runOnce() } else { sendInfo(NODENUM_BROADCAST); } - return getConfiguredOrDefaultMs(moduleConfig.paxcounter.paxcounter_update_interval, default_broadcast_interval_secs); + return Default::getConfiguredOrDefaultMs(moduleConfig.paxcounter.paxcounter_update_interval, + default_broadcast_interval_secs); } else { return disable(); } diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 0d99a3cfd..7e341a18c 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -17,6 +17,7 @@ #include "mesh/wifi/WiFiAPClient.h" #include #endif +#include "Default.h" #include const int reconnectMax = 5; From aae49f5ecf06fb216a59b8ac4bad2e5cc008d641 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 17 Mar 2024 08:38:49 -0500 Subject: [PATCH 343/472] Remove confusing channel suffix (#3432) * Remove confusing channel suffix * Missed it --- src/graphics/Screen.cpp | 3 +-- src/mesh/Channels.cpp | 34 ---------------------------------- src/mesh/Channels.h | 19 ------------------- 3 files changed, 1 insertion(+), 55 deletions(-) diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 7f20b5666..cfd8494d2 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -1513,8 +1513,7 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16 char channelStr[20]; { concurrency::LockGuard guard(&lock); - auto chName = channels.getPrimaryName(); - snprintf(channelStr, sizeof(channelStr), "%s", chName); + snprintf(channelStr, sizeof(channelStr), "#%s", channels.getName(channels.getPrimaryIndex())); } // Display power status diff --git a/src/mesh/Channels.cpp b/src/mesh/Channels.cpp index 93dec7e7d..840e65bca 100644 --- a/src/mesh/Channels.cpp +++ b/src/mesh/Channels.cpp @@ -290,40 +290,6 @@ bool Channels::hasDefaultChannel() return false; } -/** -* Generate a short suffix used to disambiguate channels that might have the same "name" entered by the human but different PSKs. -* The ideas is that the PSK changing should be visible to the user so that they see they probably messed up and that's why they -their nodes -* aren't talking to each other. -* -* This string is of the form "#name-X". -* -* Where X is either: -* (for custom PSKS) a letter from A to Z (base26), and formed by xoring all the bytes of the PSK together, -* -* This function will also need to be implemented in GUI apps that talk to the radio. -* -* https://github.com/meshtastic/firmware/issues/269 -*/ -const char *Channels::getPrimaryName() -{ - static char buf[32]; - - char suffix; - // auto channelSettings = getPrimary(); - // if (channelSettings.psk.size != 1) { - // We have a standard PSK, so generate a letter based hash. - uint8_t code = getHash(primaryIndex); - - suffix = 'A' + (code % 26); - /* } else { - suffix = '0' + channelSettings.psk.bytes[0]; - } */ - - snprintf(buf, sizeof(buf), "#%s-%c", getName(primaryIndex), suffix); - return buf; -} - /** Given a channel hash setup crypto for decoding that channel (or the primary channel if that channel is unsecured) * * This method is called before decoding inbound packets diff --git a/src/mesh/Channels.h b/src/mesh/Channels.h index a1c4ba171..952445a1d 100644 --- a/src/mesh/Channels.h +++ b/src/mesh/Channels.h @@ -61,25 +61,6 @@ class Channels ChannelIndex getNumChannels() { return channelFile.channels_count; } - /** - * Generate a short suffix used to disambiguate channels that might have the same "name" entered by the human but different - PSKs. - * The ideas is that the PSK changing should be visible to the user so that they see they probably messed up and that's why - they their nodes - * aren't talking to each other. - * - * This string is of the form "#name-X". - * - * Where X is either: - * (for custom PSKS) a letter from A to Z (base26), and formed by xoring all the bytes of the PSK together, - * OR (for the standard minimially secure PSKs) a number from 0 to 9. - * - * This function will also need to be implemented in GUI apps that talk to the radio. - * - * https://github.com/meshtastic/firmware/issues/269 - */ - const char *getPrimaryName(); - /// Called by NodeDB on initial boot when the radio config settings are unset. Set a default single channel config. void initDefaults(); From b98176e73ee2eed034d435cf586f2c188120e129 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Mon, 18 Mar 2024 07:33:01 -0500 Subject: [PATCH 344/472] [create-pull-request] automated change (#3434) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 07fadd0d8..12603eda7 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 3 -build = 1 +build = 2 From 711b85cfe80c10ac79b16864c59956552ca8321e Mon Sep 17 00:00:00 2001 From: Manuel <71137295+mverch67@users.noreply.github.com> Date: Mon, 18 Mar 2024 21:42:44 +0100 Subject: [PATCH 345/472] fix WLAN crash (#3435) * fix WLAN crash * link to commit in arduinothread * revert usb mode --- platformio.ini | 2 +- variants/t-deck/platformio.ini | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/platformio.ini b/platformio.ini index c511587a6..2c373ab00 100644 --- a/platformio.ini +++ b/platformio.ini @@ -79,7 +79,7 @@ lib_deps = mathertel/OneButton@^2.5.0 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 https://github.com/meshtastic/TinyGPSPlus.git#f9f4fef2183514aa52be91d714c1455dd6f26e45 - https://github.com/meshtastic/ArduinoThread.git#72921ac222eed6f526ba1682023cee290d9aa1b3 + https://github.com/meshtastic/ArduinoThread.git#1ae8778c85d0a2a729f989e0b1e7d7c4dc84eef0 nanopb/Nanopb@^0.4.7 erriez/ErriezCRC32@^1.0.1 diff --git a/variants/t-deck/platformio.ini b/variants/t-deck/platformio.ini index cb6033300..593fdae5e 100644 --- a/variants/t-deck/platformio.ini +++ b/variants/t-deck/platformio.ini @@ -8,6 +8,7 @@ upload_protocol = esptool build_flags = ${esp32_base.build_flags} -DT_DECK -DBOARD_HAS_PSRAM + -DMAX_THREADS=40 -DGPS_POWER_TOGGLE -Ivariants/t-deck From a6625998f5936e4503e75b31ac5a03054c933e73 Mon Sep 17 00:00:00 2001 From: Manuel <71137295+mverch67@users.noreply.github.com> Date: Tue, 19 Mar 2024 12:22:45 +0100 Subject: [PATCH 346/472] fix compiler warnings in NodeDB.h (#3439) * fix warnings on arm * make trunk+compiler happy --- src/mesh/NodeDB.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/mesh/NodeDB.h b/src/mesh/NodeDB.h index 930b3483e..1d2086adb 100644 --- a/src/mesh/NodeDB.h +++ b/src/mesh/NodeDB.h @@ -213,4 +213,6 @@ extern uint32_t error_address; #define Module_Config_size \ (ModuleConfig_CannedMessageConfig_size + ModuleConfig_ExternalNotificationConfig_size + ModuleConfig_MQTTConfig_size + \ ModuleConfig_RangeTestConfig_size + ModuleConfig_SerialConfig_size + ModuleConfig_StoreForwardConfig_size + \ - ModuleConfig_TelemetryConfig_size + ModuleConfig_size) \ No newline at end of file + ModuleConfig_TelemetryConfig_size + ModuleConfig_size) + +// Please do not remove this comment, it makes trunk and compiler happy at the same time. From 4fa7f5a748b833cdf20536153725af3ff4b4b912 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Tue, 19 Mar 2024 10:31:31 -0500 Subject: [PATCH 347/472] Fix devicestate persistence bug --- src/mesh/NodeDB.cpp | 1 + version.properties | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 04b6fe89d..25d010f16 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -649,6 +649,7 @@ void NodeDB::saveDeviceStateToDisk() #ifdef FSCom FSCom.mkdir("/prefs"); #endif + saveProto(prefFileName, meshtastic_DeviceState_size, &meshtastic_DeviceState_msg, &devicestate); } void NodeDB::saveToDisk(int saveWhat) diff --git a/version.properties b/version.properties index 12603eda7..3cb488c16 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 3 -build = 2 +build = 1 \ No newline at end of file From 5e832e2fc6671a5eadbedd17f5f262c05498cf2e Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Tue, 19 Mar 2024 12:02:29 -0500 Subject: [PATCH 348/472] [create-pull-request] automated change (#3444) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 3cb488c16..12603eda7 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 3 -build = 1 \ No newline at end of file +build = 2 From 7aa21f6e3fc550e8ed41958ef7bc5c308c18eba7 Mon Sep 17 00:00:00 2001 From: Mictronics Date: Wed, 20 Mar 2024 16:58:48 +0100 Subject: [PATCH 349/472] Fixed double and missing Default class. (#3448) * Fix LED pinout for T-Echo board marked v1.0, date 2021-6-28 * Merge PR #420 * Fixed double and missing Default class. --------- Co-authored-by: Ben Meadors --- src/gps/GPS.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 5595172dd..506f6d89c 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -759,7 +759,7 @@ uint32_t GPS::getWakeTime() const if (t == UINT32_MAX) return t; // already maxint - return Default::Default::getConfiguredOrDefaultMs(t, default_broadcast_interval_secs); + return Default::getConfiguredOrDefaultMs(t, default_broadcast_interval_secs); } /** Get how long we should sleep between aqusition attempts in msecs @@ -775,7 +775,7 @@ uint32_t GPS::getSleepTime() const if (t == UINT32_MAX) return t; // already maxint - return t * 1000; + return Default::getConfiguredOrDefaultMs(t, default_gps_update_interval); } void GPS::publishUpdate() From f4095ce00d7b26fcd94b8f3987e3fbdfa499067f Mon Sep 17 00:00:00 2001 From: Jim Whitelaw Date: Thu, 21 Mar 2024 05:34:34 -0600 Subject: [PATCH 350/472] Adds configuration option to exclude the webserver on esp32. (#3369) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Adds configuration option to not build/include the webserver. * Adds configuration option to not build/include the webserver. * Keep initApiServer when excluding webserver * fixes for failed formatting check * Once more with feeling! Fix for regression. * Fix includes for ARCH_ESP32 * Format changes from trunk * Merge updates from origin * Revert "Format changes from trunk" This reverts commit 436e6317744576ca6b00559937ca76235b7cd66b. * jeez! * tryfix proto conflict --------- Co-authored-by: Thomas Göttgens --- src/main.cpp | 4 +++- src/mesh/http/ContentHandler.cpp | 2 ++ src/mesh/http/WebServer.cpp | 6 +++--- src/mesh/wifi/WiFiAPClient.cpp | 12 +++++++----- 4 files changed, 15 insertions(+), 9 deletions(-) diff --git a/src/main.cpp b/src/main.cpp index fe5d455f8..4fc713b1c 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -33,7 +33,9 @@ // #include #ifdef ARCH_ESP32 +#if !MESHTASTIC_EXCLUDE_WEBSERVER #include "mesh/http/WebServer.h" +#endif #include "nimble/NimbleBluetooth.h" NimbleBluetooth *nimbleBluetooth; #endif @@ -864,7 +866,7 @@ void setup() #endif #endif -#ifdef ARCH_ESP32 +#if defined(ARCH_ESP32) && !MESHTASTIC_EXCLUDE_WEBSERVER // Start web server thread. webServerThread = new WebServerThread(); #endif diff --git a/src/mesh/http/ContentHandler.cpp b/src/mesh/http/ContentHandler.cpp index 7640e879c..1557948d8 100644 --- a/src/mesh/http/ContentHandler.cpp +++ b/src/mesh/http/ContentHandler.cpp @@ -1,3 +1,4 @@ +#if !MESHTASTIC_EXCLUDE_WEBSERVER #include "NodeDB.h" #include "PowerFSM.h" #include "RadioLibInterface.h" @@ -855,3 +856,4 @@ void handleScanNetworks(HTTPRequest *req, HTTPResponse *res) res->print(value->Stringify().c_str()); delete value; } +#endif \ No newline at end of file diff --git a/src/mesh/http/WebServer.cpp b/src/mesh/http/WebServer.cpp index 7814f2c29..83fe20dd8 100644 --- a/src/mesh/http/WebServer.cpp +++ b/src/mesh/http/WebServer.cpp @@ -1,3 +1,4 @@ +#if !MESHTASTIC_EXCLUDE_WEBSERVER #include "mesh/http/WebServer.h" #include "NodeDB.h" #include "graphics/Screen.h" @@ -92,7 +93,6 @@ static void taskCreateCert(void *parameter) LOG_DEBUG("Retrieved Private Key: %d Bytes\n", cert->getPKLength()); LOG_DEBUG("Retrieved Certificate: %d Bytes\n", cert->getCertLength()); - } else { LOG_INFO("Creating the certificate. This may take a while. Please wait...\n"); @@ -105,7 +105,6 @@ static void taskCreateCert(void *parameter) if (createCertResult != 0) { LOG_ERROR("Creating the certificate failed\n"); - } else { LOG_INFO("Creating the certificate was successful\n"); @@ -210,4 +209,5 @@ void initWebServer() } else { LOG_ERROR("Web Servers Failed! ;-( \n"); } -} \ No newline at end of file +} +#endif \ No newline at end of file diff --git a/src/mesh/wifi/WiFiAPClient.cpp b/src/mesh/wifi/WiFiAPClient.cpp index b0b033ba0..88764d2be 100644 --- a/src/mesh/wifi/WiFiAPClient.cpp +++ b/src/mesh/wifi/WiFiAPClient.cpp @@ -10,7 +10,9 @@ #include #include #ifdef ARCH_ESP32 +#if !MESHTASTIC_EXCLUDE_WEBSERVER #include "mesh/http/WebServer.h" +#endif #include #include static void WiFiEvent(WiFiEvent_t event); @@ -92,11 +94,10 @@ static void onNetworkConnected() syslog.enable(); } -#ifdef ARCH_ESP32 +#if defined(ARCH_ESP32) && !MESHTASTIC_EXCLUDE_WEBSERVER initWebServer(); #endif initApiServer(); - APStartupComplete = true; } @@ -146,7 +147,6 @@ static int32_t reconnectWiFi() perhapsSetRTC(RTCQualityNTP, &tv); lastrun_ntp = millis(); - } else { LOG_DEBUG("NTP Update failed\n"); } @@ -204,7 +204,9 @@ bool initWifi() const char *wifiPsw = config.network.wifi_psk; #ifndef ARCH_RP2040 - createSSLCert(); // For WebServer +#if !MESHTASTIC_EXCLUDE_WEBSERVER + createSSLCert(); // For WebServer +#endif esp_wifi_set_storage(WIFI_STORAGE_RAM); // Disable flash storage for WiFi credentials #endif if (!*wifiPsw) // Treat empty password as no password @@ -405,4 +407,4 @@ static void WiFiEvent(WiFiEvent_t event) uint8_t getWifiDisconnectReason() { return wifiDisconnectReason; -} \ No newline at end of file +} From dfcd0d14f610a6510622e903d19cc08122da9407 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 21 Mar 2024 09:06:37 -0500 Subject: [PATCH 351/472] Add MaxNodes to Native config (#3427) * Add MaxNodes to Native * It compiles... * Convert nodedb to use new * Closer but still broken. * Finally working * Remove unintended lines * Don't include a pointer * Capitalization matters. * avoid rename in protocol regen * When trimming the nodeDB, start with a cleanup * Remove extra cleanupMeshDB() call for now --------- Co-authored-by: Ben Meadors --- bin/config-dist.yaml | 3 + bin/regen-protos.bat | 2 +- bin/regen-protos.sh | 3 +- src/GPSStatus.h | 25 +--- src/gps/GPS.cpp | 4 +- src/graphics/Screen.cpp | 30 +++-- src/graphics/Screen.h | 2 + src/main.cpp | 8 +- src/mesh/MeshModule.cpp | 4 +- src/mesh/MeshService.cpp | 24 ++-- src/mesh/NodeDB.cpp | 125 +++++++++++------- src/mesh/NodeDB.h | 15 ++- src/mesh/PacketHistory.cpp | 4 + src/mesh/PhoneAPI.cpp | 2 +- src/mesh/ProtobufModule.h | 2 +- src/mesh/RadioInterface.cpp | 4 +- src/mesh/ReliableRouter.cpp | 2 +- src/mesh/Router.cpp | 20 +-- src/mesh/SX128xInterface.cpp | 10 +- .../meshtastic/{admin.pb.c => admin.pb.cpp} | 0 .../{apponly.pb.c => apponly.pb.cpp} | 0 .../meshtastic/{atak.pb.c => atak.pb.cpp} | 0 ...nedmessages.pb.c => cannedmessages.pb.cpp} | 0 .../{channel.pb.c => channel.pb.cpp} | 0 .../{clientonly.pb.c => clientonly.pb.cpp} | 0 .../meshtastic/{config.pb.c => config.pb.cpp} | 0 ...n_status.pb.c => connection_status.pb.cpp} | 0 .../{deviceonly.pb.c => deviceonly.pb.cpp} | 2 +- src/mesh/generated/meshtastic/deviceonly.pb.h | 15 ++- .../{localonly.pb.c => localonly.pb.cpp} | 0 .../meshtastic/{mesh.pb.c => mesh.pb.cpp} | 0 ...odule_config.pb.c => module_config.pb.cpp} | 0 .../meshtastic/{mqtt.pb.c => mqtt.pb.cpp} | 0 .../{paxcount.pb.c => paxcount.pb.cpp} | 0 .../{portnums.pb.c => portnums.pb.cpp} | 0 ...e_hardware.pb.c => remote_hardware.pb.cpp} | 0 .../meshtastic/{rtttl.pb.c => rtttl.pb.cpp} | 0 ...{storeforward.pb.c => storeforward.pb.cpp} | 0 .../{telemetry.pb.c => telemetry.pb.cpp} | 0 .../meshtastic/{xmodem.pb.c => xmodem.pb.cpp} | 0 src/mesh/mesh-pb-constants.h | 7 +- src/modules/AdminModule.cpp | 12 +- src/modules/CannedMessageModule.cpp | 32 ++--- src/modules/ExternalNotificationModule.cpp | 8 +- src/modules/NeighborInfoModule.cpp | 26 ++-- src/modules/NodeInfoModule.cpp | 4 +- src/modules/PositionModule.cpp | 18 +-- src/modules/RangeTestModule.cpp | 8 +- src/modules/RoutingModule.cpp | 4 +- src/modules/SerialModule.cpp | 12 +- src/modules/Telemetry/DeviceTelemetry.cpp | 4 +- src/modules/esp32/AudioModule.cpp | 3 +- src/modules/esp32/StoreForwardModule.cpp | 4 +- src/mqtt/MQTT.cpp | 10 +- src/platform/portduino/PortduinoGlue.cpp | 2 + src/platform/portduino/PortduinoGlue.h | 3 +- src/shutdown.h | 2 + src/sleep.cpp | 2 +- 58 files changed, 258 insertions(+), 209 deletions(-) rename src/mesh/generated/meshtastic/{admin.pb.c => admin.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{apponly.pb.c => apponly.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{atak.pb.c => atak.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{cannedmessages.pb.c => cannedmessages.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{channel.pb.c => channel.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{clientonly.pb.c => clientonly.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{config.pb.c => config.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{connection_status.pb.c => connection_status.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{deviceonly.pb.c => deviceonly.pb.cpp} (90%) rename src/mesh/generated/meshtastic/{localonly.pb.c => localonly.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{mesh.pb.c => mesh.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{module_config.pb.c => module_config.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{mqtt.pb.c => mqtt.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{paxcount.pb.c => paxcount.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{portnums.pb.c => portnums.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{remote_hardware.pb.c => remote_hardware.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{rtttl.pb.c => rtttl.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{storeforward.pb.c => storeforward.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{telemetry.pb.c => telemetry.pb.cpp} (100%) rename src/mesh/generated/meshtastic/{xmodem.pb.c => xmodem.pb.cpp} (100%) diff --git a/bin/config-dist.yaml b/bin/config-dist.yaml index a241a929a..22ca3e7db 100644 --- a/bin/config-dist.yaml +++ b/bin/config-dist.yaml @@ -121,3 +121,6 @@ Logging: Webserver: # Port: 443 # Port for Webserver & Webservices # RootPath: /usr/share/doc/meshtasticd/web # Root Dir of WebServer + +General: + MaxNodes: 200 diff --git a/bin/regen-protos.bat b/bin/regen-protos.bat index 1422f7914..1d55c2506 100644 --- a/bin/regen-protos.bat +++ b/bin/regen-protos.bat @@ -1 +1 @@ -cd protobufs && ..\nanopb-0.4.7\generator-bin\protoc.exe --experimental_allow_proto3_optional --nanopb_out=-v:..\src\mesh\generated -I=..\protobufs ..\protobufs\meshtastic\*.proto +cd protobufs && ..\nanopb-0.4.7\generator-bin\protoc.exe --experimental_allow_proto3_optional "--nanopb_out=-S.cpp -v:..\src\mesh\generated\" -I=..\protobufs ..\protobufs\meshtastic\*.proto diff --git a/bin/regen-protos.sh b/bin/regen-protos.sh index ad771ab45..7c751208a 100755 --- a/bin/regen-protos.sh +++ b/bin/regen-protos.sh @@ -8,9 +8,8 @@ echo "prebuilt binaries for your computer into nanopb-0.4.7" # the nanopb tool seems to require that the .options file be in the current directory! cd protobufs -../nanopb-0.4.7/generator-bin/protoc --nanopb_out=-v:../src/mesh/generated/ -I=../protobufs meshtastic/*.proto --experimental_allow_proto3_optional +../nanopb-0.4.7/generator-bin/protoc "--nanopb_out=-S.cpp -v:../src/mesh/generated/" -I=../protobufs meshtastic/*.proto --experimental_allow_proto3_optional -# cd ../src/mesh/generated/meshtastic # sed -i 's/#include "meshtastic/#include "./g' -- * # sed -i 's/meshtastic_//g' -- * diff --git a/src/GPSStatus.h b/src/GPSStatus.h index bcfb5f2eb..1245d5e5d 100644 --- a/src/GPSStatus.h +++ b/src/GPSStatus.h @@ -4,8 +4,6 @@ #include "configuration.h" #include -extern NodeDB nodeDB; - namespace meshtastic { @@ -55,7 +53,7 @@ class GPSStatus : public Status #ifdef GPS_EXTRAVERBOSE LOG_WARN("Using fixed latitude\n"); #endif - meshtastic_NodeInfoLite *node = nodeDB.getMeshNode(nodeDB.getNodeNum()); + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(nodeDB->getNodeNum()); return node->position.latitude_i; } else { return p.latitude_i; @@ -68,7 +66,7 @@ class GPSStatus : public Status #ifdef GPS_EXTRAVERBOSE LOG_WARN("Using fixed longitude\n"); #endif - meshtastic_NodeInfoLite *node = nodeDB.getMeshNode(nodeDB.getNodeNum()); + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(nodeDB->getNodeNum()); return node->position.longitude_i; } else { return p.longitude_i; @@ -81,27 +79,18 @@ class GPSStatus : public Status #ifdef GPS_EXTRAVERBOSE LOG_WARN("Using fixed altitude\n"); #endif - meshtastic_NodeInfoLite *node = nodeDB.getMeshNode(nodeDB.getNodeNum()); + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(nodeDB->getNodeNum()); return node->position.altitude; } else { return p.altitude; } } - uint32_t getDOP() const - { - return p.PDOP; - } + uint32_t getDOP() const { return p.PDOP; } - uint32_t getHeading() const - { - return p.ground_track; - } + uint32_t getHeading() const { return p.ground_track; } - uint32_t getNumSatellites() const - { - return p.sats_in_view; - } + uint32_t getNumSatellites() const { return p.sats_in_view; } bool matches(const GPSStatus *newStatus) const { @@ -149,4 +138,4 @@ class GPSStatus : public Status } // namespace meshtastic -extern meshtastic::GPSStatus *gpsStatus; \ No newline at end of file +extern meshtastic::GPSStatus *gpsStatus; diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 506f6d89c..7d4f41a55 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -815,7 +815,7 @@ int32_t GPS::runOnce() LOG_WARN("GPS FactoryReset requested\n"); if (gps->factoryReset()) { // If we don't succeed try again next time devicestate.did_gps_reset = true; - nodeDB.saveToDisk(SEGMENT_DEVICESTATE); + nodeDB->saveToDisk(SEGMENT_DEVICESTATE); } } GPSInitFinished = true; @@ -835,7 +835,7 @@ int32_t GPS::runOnce() if (devicestate.did_gps_reset && (millis() - lastWakeStartMsec > 60000) && !hasFlow()) { LOG_DEBUG("GPS is not communicating, trying factory reset on next bootup.\n"); devicestate.did_gps_reset = false; - nodeDB.saveDeviceStateToDisk(); + nodeDB->saveDeviceStateToDisk(); return disable(); // Stop the GPS thread as it can do nothing useful until next reboot. } } diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index cfd8494d2..3c3777496 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -71,7 +71,7 @@ namespace graphics // #define SHOW_REDRAWS // A text message frame + debug frame + all the node infos -static FrameCallback normalFrames[MAX_NUM_NODES + NUM_EXTRA_FRAMES]; +FrameCallback *normalFrames; static uint32_t targetFramerate = IDLE_FRAMERATE; static char btPIN[16] = "888888"; @@ -354,7 +354,7 @@ static void drawTextMessageFrame(OLEDDisplay *display, OLEDDisplayUiState *state static char tempBuf[237]; const meshtastic_MeshPacket &mp = devicestate.rx_text_message; - meshtastic_NodeInfoLite *node = nodeDB.getMeshNode(getFrom(&mp)); + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(getFrom(&mp)); // LOG_DEBUG("drawing text message from 0x%x: %s\n", mp.from, // mp.decoded.variant.data.decoded.bytes); @@ -392,7 +392,7 @@ static void drawWaypointFrame(OLEDDisplay *display, OLEDDisplayUiState *state, i static char tempBuf[237]; meshtastic_MeshPacket &mp = devicestate.rx_waypoint; - meshtastic_NodeInfoLite *node = nodeDB.getMeshNode(getFrom(&mp)); + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(getFrom(&mp)); display->setTextAlignment(TEXT_ALIGN_LEFT); display->setFont(FONT_SMALL); @@ -780,16 +780,16 @@ static void drawNodeInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_ if (state->currentFrame != prevFrame) { prevFrame = state->currentFrame; - nodeIndex = (nodeIndex + 1) % nodeDB.getNumMeshNodes(); - meshtastic_NodeInfoLite *n = nodeDB.getMeshNodeByIndex(nodeIndex); - if (n->num == nodeDB.getNodeNum()) { + nodeIndex = (nodeIndex + 1) % nodeDB->getNumMeshNodes(); + meshtastic_NodeInfoLite *n = nodeDB->getMeshNodeByIndex(nodeIndex); + if (n->num == nodeDB->getNodeNum()) { // Don't show our node, just skip to next - nodeIndex = (nodeIndex + 1) % nodeDB.getNumMeshNodes(); - n = nodeDB.getMeshNodeByIndex(nodeIndex); + nodeIndex = (nodeIndex + 1) % nodeDB->getNumMeshNodes(); + n = nodeDB->getMeshNodeByIndex(nodeIndex); } } - meshtastic_NodeInfoLite *node = nodeDB.getMeshNodeByIndex(nodeIndex); + meshtastic_NodeInfoLite *node = nodeDB->getMeshNodeByIndex(nodeIndex); display->setFont(FONT_SMALL); @@ -827,7 +827,7 @@ static void drawNodeInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_ } else { strncpy(distStr, "? km", sizeof(distStr)); } - meshtastic_NodeInfoLite *ourNode = nodeDB.getMeshNode(nodeDB.getNodeNum()); + meshtastic_NodeInfoLite *ourNode = nodeDB->getMeshNode(nodeDB->getNodeNum()); const char *fields[] = {username, distStr, signalStr, lastStr, NULL}; int16_t compassX = 0, compassY = 0; @@ -893,6 +893,7 @@ static void drawNodeInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_ Screen::Screen(ScanI2C::DeviceAddress address, meshtastic_Config_DisplayConfig_OledType screenType, OLEDDISPLAY_GEOMETRY geometry) : concurrency::OSThread("Screen"), address_found(address), model(screenType), geometry(geometry), cmdQueue(32) { + graphics::normalFrames = new FrameCallback[MAX_NUM_NODES + NUM_EXTRA_FRAMES]; #if defined(USE_SH1106) || defined(USE_SH1107) || defined(USE_SH1107_128_64) dispdev = new SH1106Wire(address.address, -1, -1, geometry, (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); @@ -931,6 +932,11 @@ Screen::Screen(ScanI2C::DeviceAddress address, meshtastic_Config_DisplayConfig_O cmdQueue.setReader(this); } +Screen::~Screen() +{ + delete[] graphics::normalFrames; +} + /** * Prepare the display for the unit going to the lowest power mode possible. Most screens will just * poweroff, but eink screens will show a "I'm sleeping" graphic, possibly with a QR code @@ -1287,7 +1293,7 @@ void Screen::setFrames() #endif // We don't show the node info our our node (if we have it yet - we should) - size_t numMeshNodes = nodeDB.getNumMeshNodes(); + size_t numMeshNodes = nodeDB->getNumMeshNodes(); if (numMeshNodes > 0) numMeshNodes--; @@ -1792,7 +1798,7 @@ int Screen::handleStatusUpdate(const meshtastic::Status *arg) if (showingNormalScreen && nodeStatus->getLastNumTotal() != nodeStatus->getNumTotal()) { setFrames(); // Regen the list of screens } - nodeDB.updateGUI = false; + nodeDB->updateGUI = false; break; } diff --git a/src/graphics/Screen.h b/src/graphics/Screen.h index 69e858dd2..a66cc44ec 100644 --- a/src/graphics/Screen.h +++ b/src/graphics/Screen.h @@ -125,6 +125,8 @@ class Screen : public concurrency::OSThread public: explicit Screen(ScanI2C::DeviceAddress, meshtastic_Config_DisplayConfig_OledType, OLEDDISPLAY_GEOMETRY); + ~Screen(); + Screen(const Screen &) = delete; Screen &operator=(const Screen &) = delete; diff --git a/src/main.cpp b/src/main.cpp index 4fc713b1c..e09af0c9a 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -556,7 +556,7 @@ void setup() // We do this as early as possible because this loads preferences from flash // but we need to do this after main cpu init (esp32setup), because we need the random seed set - nodeDB.init(); + nodeDB = NodeDB::init(); // If we're taking on the repeater role, use flood router and turn off 3V3_S rail because peripherals are not needed if (config.device.role == meshtastic_Config_DeviceConfig_Role_REPEATER) { @@ -650,7 +650,7 @@ void setup() } else { LOG_DEBUG("Running without GPS.\n"); } - nodeStatus->observe(&nodeDB.newStatus); + nodeStatus->observe(&nodeDB->newStatus); #ifdef HAS_I2S LOG_DEBUG("Starting audio thread\n"); @@ -844,7 +844,7 @@ void setup() if ((config.lora.region == meshtastic_Config_LoRaConfig_RegionCode_LORA_24) && (!rIf->wideLora())) { LOG_WARN("Radio chip does not support 2.4GHz LoRa. Reverting to unset.\n"); config.lora.region = meshtastic_Config_LoRaConfig_RegionCode_UNSET; - nodeDB.saveToDisk(SEGMENT_CONFIG); + nodeDB->saveToDisk(SEGMENT_CONFIG); if (!rIf->reconfigure()) { LOG_WARN("Reconfigure failed, rebooting\n"); screen->startRebootScreen(); @@ -967,4 +967,4 @@ void loop() mainDelay.delay(delayMsec); } // if (didWake) LOG_DEBUG("wake!\n"); -} +} \ No newline at end of file diff --git a/src/mesh/MeshModule.cpp b/src/mesh/MeshModule.cpp index ad0c78108..c8dd7f3d1 100644 --- a/src/mesh/MeshModule.cpp +++ b/src/mesh/MeshModule.cpp @@ -81,7 +81,7 @@ void MeshModule::callPlugins(meshtastic_MeshPacket &mp, RxSource src) bool ignoreRequest = false; // No module asked to ignore the request yet // Was this message directed to us specifically? Will be false if we are sniffing someone elses packets - auto ourNodeNum = nodeDB.getNodeNum(); + auto ourNodeNum = nodeDB->getNodeNum(); bool toUs = mp.to == NODENUM_BROADCAST || mp.to == ourNodeNum; for (auto i = modules->begin(); i != modules->end(); ++i) { @@ -279,4 +279,4 @@ AdminMessageHandleResult MeshModule::handleAdminMessageForAllPlugins(const mesht } } return handled; -} +} \ No newline at end of file diff --git a/src/mesh/MeshService.cpp b/src/mesh/MeshService.cpp index db0dd88ec..31eb082ec 100644 --- a/src/mesh/MeshService.cpp +++ b/src/mesh/MeshService.cpp @@ -71,7 +71,7 @@ MeshService::MeshService() void MeshService::init() { // moved much earlier in boot (called from setup()) - // nodeDB.init(); + // nodeDB->init(); if (gps) gpsObserver.observe(&gps->newStatus); @@ -81,13 +81,13 @@ int MeshService::handleFromRadio(const meshtastic_MeshPacket *mp) { powerFSM.trigger(EVENT_PACKET_FOR_PHONE); // Possibly keep the node from sleeping - nodeDB.updateFrom(*mp); // update our DB state based off sniffing every RX packet from the radio + nodeDB->updateFrom(*mp); // update our DB state based off sniffing every RX packet from the radio if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag && mp->decoded.portnum == meshtastic_PortNum_TELEMETRY_APP && mp->decoded.request_id > 0) { LOG_DEBUG( "Received telemetry response. Skip sending our NodeInfo because this potentially a Repeater which will ignore our " "request for its NodeInfo.\n"); - } else if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag && !nodeDB.getMeshNode(mp->from)->has_user && + } else if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag && !nodeDB->getMeshNode(mp->from)->has_user && nodeInfoModule) { LOG_INFO("Heard a node on channel %d we don't know, sending NodeInfo and asking for a response.\n", mp->channel); nodeInfoModule->sendOurNodeInfo(mp->from, true, mp->channel); @@ -120,10 +120,10 @@ bool MeshService::reloadConfig(int saveWhat) // If we can successfully set this radio to these settings, save them to disk // This will also update the region as needed - bool didReset = nodeDB.resetRadioConfig(); // Don't let the phone send us fatally bad settings + bool didReset = nodeDB->resetRadioConfig(); // Don't let the phone send us fatally bad settings configChanged.notifyObservers(NULL); // This will cause radio hardware to change freqs etc - nodeDB.saveToDisk(saveWhat); + nodeDB->saveToDisk(saveWhat); return didReset; } @@ -133,7 +133,7 @@ void MeshService::reloadOwner(bool shouldSave) { // LOG_DEBUG("reloadOwner()\n"); // update our local data directly - nodeDB.updateUser(nodeDB.getNodeNum(), owner); + nodeDB->updateUser(nodeDB->getNodeNum(), owner); assert(nodeInfoModule); // update everyone else and save to disk if (nodeInfoModule && shouldSave) { @@ -192,7 +192,7 @@ void MeshService::handleToRadio(meshtastic_MeshPacket &p) LOG_WARN("phone tried to pick a nodenum, we don't allow that.\n"); p.from = 0; } else { - // p.from = nodeDB.getNodeNum(); + // p.from = nodeDB->getNodeNum(); } if (p.id == 0) @@ -217,7 +217,7 @@ void MeshService::handleToRadio(meshtastic_MeshPacket &p) /** Attempt to cancel a previously sent packet from this _local_ node. Returns true if a packet was found we could cancel */ bool MeshService::cancelSending(PacketId id) { - return router->cancelSending(nodeDB.getNodeNum(), id); + return router->cancelSending(nodeDB->getNodeNum(), id); } ErrorCode MeshService::sendQueueStatusToPhone(const meshtastic_QueueStatus &qs, ErrorCode res, uint32_t mesh_packet_id) @@ -245,7 +245,7 @@ ErrorCode MeshService::sendQueueStatusToPhone(const meshtastic_QueueStatus &qs, void MeshService::sendToMesh(meshtastic_MeshPacket *p, RxSource src, bool ccToPhone) { uint32_t mesh_packet_id = p->id; - nodeDB.updateFrom(*p); // update our local DB for this packet (because phone might have sent position packets etc...) + nodeDB->updateFrom(*p); // update our local DB for this packet (because phone might have sent position packets etc...) // Note: We might return !OK if our fifo was full, at that point the only option we have is to drop it ErrorCode res = router->sendLocal(p, src); @@ -265,7 +265,7 @@ void MeshService::sendToMesh(meshtastic_MeshPacket *p, RxSource src, bool ccToPh void MeshService::sendNetworkPing(NodeNum dest, bool wantReplies) { - meshtastic_NodeInfoLite *node = nodeDB.getMeshNode(nodeDB.getNodeNum()); + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(nodeDB->getNodeNum()); assert(node); @@ -320,7 +320,7 @@ void MeshService::sendMqttMessageToClientProxy(meshtastic_MqttClientProxyMessage meshtastic_NodeInfoLite *MeshService::refreshLocalMeshNode() { - meshtastic_NodeInfoLite *node = nodeDB.getMeshNode(nodeDB.getNodeNum()); + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(nodeDB->getNodeNum()); assert(node); // We might not have a position yet for our local node, in that case, at least try to send the time @@ -373,7 +373,7 @@ int MeshService::onGPSChanged(const meshtastic::GPSStatus *newStatus) pos.longitude_i, pos.altitude); // Update our current position in the local DB - nodeDB.updatePosition(nodeDB.getNodeNum(), pos, RX_SRC_LOCAL); + nodeDB->updatePosition(nodeDB->getNodeNum(), pos, RX_SRC_LOCAL); return 0; } diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 25d010f16..37232e6ed 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -18,8 +18,11 @@ #include "mesh-pb-constants.h" #include "modules/NeighborInfoModule.h" #include +#include +#include #include #include +#include #ifdef ARCH_ESP32 #include "mesh/wifi/WiFiAPClient.h" @@ -37,7 +40,7 @@ #include #endif -NodeDB nodeDB; +NodeDB *nodeDB = nullptr; // we have plenty of ram so statically alloc this tempbuf (for now) EXT_RAM_ATTR meshtastic_DeviceState devicestate; @@ -47,6 +50,26 @@ meshtastic_LocalModuleConfig moduleConfig; meshtastic_ChannelFile channelFile; meshtastic_OEMStore oemStore; +bool meshtastic_DeviceState_callback(pb_istream_t *istream, pb_ostream_t *ostream, const pb_field_iter_t *field) +{ + if (ostream) { + std::vector *vec = (std::vector *)field->pData; + for (auto item : *vec) { + if (!pb_encode_tag_for_field(ostream, field)) + return false; + pb_encode_submessage(ostream, meshtastic_NodeInfoLite_fields, &item); + } + } + if (istream) { + meshtastic_NodeInfoLite node; // this gets good data + std::vector *vec = (std::vector *)field->pData; + + if (istream->bytes_left && pb_decode(istream, meshtastic_NodeInfoLite_fields, &node)) + vec->push_back(node); + } + return true; +} + /** The current change # for radio settings. Starts at 0 on boot and any time the radio settings * might have changed is incremented. Allows others to detect they might now be on a new channel. */ @@ -69,7 +92,7 @@ uint32_t error_address = 0; static uint8_t ourMacAddr[6]; -NodeDB::NodeDB() : meshNodes(devicestate.node_db_lite), numMeshNodes(&devicestate.node_db_lite_count) {} +NodeDB::NodeDB() {} /** * Most (but not always) of the time we want to treat packets 'from' the local phone (where from == 0), as if they originated on @@ -77,7 +100,7 @@ NodeDB::NodeDB() : meshNodes(devicestate.node_db_lite), numMeshNodes(&devicestat */ NodeNum getFrom(const meshtastic_MeshPacket *p) { - return (p->from == 0) ? nodeDB.getNodeNum() : p->from; + return (p->from == 0) ? nodeDB->getNodeNum() : p->from; } bool NodeDB::resetRadioConfig(bool factory_reset) @@ -353,8 +376,8 @@ void NodeDB::installDefaultChannels() void NodeDB::resetNodes() { - devicestate.node_db_lite_count = 1; - std::fill(&devicestate.node_db_lite[1], &devicestate.node_db_lite[MAX_NUM_NODES - 1], meshtastic_NodeInfoLite()); + numMeshNodes = 1; + std::fill(devicestate.node_db_lite.begin() + 1, devicestate.node_db_lite.end(), meshtastic_NodeInfoLite()); saveDeviceStateToDisk(); if (neighborInfoModule && moduleConfig.neighbor_info.enabled) neighborInfoModule->resetNeighbors(); @@ -363,13 +386,15 @@ void NodeDB::resetNodes() void NodeDB::removeNodeByNum(uint nodeNum) { int newPos = 0, removed = 0; - for (int i = 0; i < *numMeshNodes; i++) { - if (meshNodes[i].num != nodeNum) - meshNodes[newPos++] = meshNodes[i]; + for (int i = 0; i < numMeshNodes; i++) { + if (meshNodes->at(i).num != nodeNum) + meshNodes->at(newPos++) = meshNodes->at(i); else removed++; } - *numMeshNodes -= removed; + numMeshNodes -= removed; + std::fill(devicestate.node_db_lite.begin() + numMeshNodes, devicestate.node_db_lite.begin() + numMeshNodes + 1, + meshtastic_NodeInfoLite()); LOG_DEBUG("NodeDB::removeNodeByNum purged %d entries. Saving changes...\n", removed); saveDeviceStateToDisk(); } @@ -377,27 +402,30 @@ void NodeDB::removeNodeByNum(uint nodeNum) void NodeDB::cleanupMeshDB() { int newPos = 0, removed = 0; - for (int i = 0; i < *numMeshNodes; i++) { - if (meshNodes[i].has_user) - meshNodes[newPos++] = meshNodes[i]; + for (int i = 0; i < numMeshNodes; i++) { + if (meshNodes->at(i).has_user) + meshNodes->at(newPos++) = meshNodes->at(i); else removed++; } - *numMeshNodes -= removed; + numMeshNodes -= removed; + std::fill(devicestate.node_db_lite.begin() + numMeshNodes, devicestate.node_db_lite.begin() + numMeshNodes + removed, + meshtastic_NodeInfoLite()); LOG_DEBUG("cleanupMeshDB purged %d entries\n", removed); } void NodeDB::installDefaultDeviceState() { LOG_INFO("Installing default DeviceState\n"); - memset(&devicestate, 0, sizeof(meshtastic_DeviceState)); + // memset(&devicestate, 0, sizeof(meshtastic_DeviceState)); - *numMeshNodes = 0; + numMeshNodes = 0; + meshNodes = &devicestate.node_db_lite; // init our devicestate with valid flags so protobuf writing/reading will work devicestate.has_my_node = true; devicestate.has_owner = true; - devicestate.node_db_lite_count = 0; + // devicestate.node_db_lite_count = 0; devicestate.version = DEVICESTATE_CUR_VER; devicestate.receive_queue_count = 0; // Not yet implemented FIXME @@ -411,11 +439,12 @@ void NodeDB::installDefaultDeviceState() memcpy(owner.macaddr, ourMacAddr, sizeof(owner.macaddr)); } -void NodeDB::init() +NodeDB *NodeDB::init() { LOG_INFO("Initializing NodeDB\n"); - loadFromDisk(); - cleanupMeshDB(); + NodeDB *newnodeDB = new NodeDB; + newnodeDB->loadFromDisk(); + newnodeDB->cleanupMeshDB(); uint32_t devicestateCRC = crc32Buffer(&devicestate, sizeof(devicestate)); uint32_t configCRC = crc32Buffer(&config, sizeof(config)); @@ -427,7 +456,7 @@ void NodeDB::init() myNodeInfo.min_app_version = 30200; // format is Mmmss (where M is 1+the numeric major number. i.e. 30200 means 2.2.00 // Note! We do this after loading saved settings, so that if somehow an invalid nodenum was stored in preferences we won't // keep using that nodenum forever. Crummy guess at our nodenum (but we will check against the nodedb to avoid conflicts) - pickNewNodeNum(); + newnodeDB->pickNewNodeNum(); // Set our board type so we can share it with others owner.hw_model = HW_VENDOR; @@ -435,7 +464,7 @@ void NodeDB::init() owner.role = config.device.role; // Include our owner in the node db under our nodenum - meshtastic_NodeInfoLite *info = getOrCreateMeshNode(getNodeNum()); + meshtastic_NodeInfoLite *info = newnodeDB->getOrCreateMeshNode(newnodeDB->getNodeNum()); info->user = owner; info->has_user = true; @@ -447,8 +476,8 @@ void NodeDB::init() LOG_DEBUG("Number of Device Reboots: %d\n", myNodeInfo.reboot_count); #endif - resetRadioConfig(); // If bogus settings got saved, then fix them - LOG_DEBUG("region=%d, NODENUM=0x%x, dbsize=%d\n", config.lora.region, myNodeInfo.my_node_num, *numMeshNodes); + newnodeDB->resetRadioConfig(); // If bogus settings got saved, then fix them + // nodeDB->LOG_DEBUG("region=%d, NODENUM=0x%x, dbsize=%d\n", config.lora.region, myNodeInfo.my_node_num, numMeshNodes); if (devicestateCRC != crc32Buffer(&devicestate, sizeof(devicestate))) saveWhat |= SEGMENT_DEVICESTATE; @@ -466,8 +495,9 @@ void NodeDB::init() config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_ENABLED; config.position.gps_enabled = 0; } + return newnodeDB; - saveToDisk(saveWhat); + nodeDB->saveToDisk(saveWhat); } // We reserve a few nodenums for future use @@ -537,17 +567,21 @@ bool NodeDB::loadProto(const char *filename, size_t protoSize, size_t objSize, c void NodeDB::loadFromDisk() { // static DeviceState scratch; We no longer read into a tempbuf because this structure is 15KB of valuable RAM - if (!loadProto(prefFileName, meshtastic_DeviceState_size, sizeof(meshtastic_DeviceState), &meshtastic_DeviceState_msg, - &devicestate)) { + if (!loadProto(prefFileName, sizeof(meshtastic_DeviceState) + MAX_NUM_NODES * sizeof(meshtastic_NodeInfo), + sizeof(meshtastic_DeviceState), &meshtastic_DeviceState_msg, &devicestate)) { installDefaultDeviceState(); // Our in RAM copy might now be corrupt } else { if (devicestate.version < DEVICESTATE_MIN_VER) { LOG_WARN("Devicestate %d is old, discarding\n", devicestate.version); factoryReset(); } else { - LOG_INFO("Loaded saved devicestate version %d\n", devicestate.version); + LOG_INFO("Loaded saved devicestate version %d, with nodecount: %d\n", devicestate.version, + devicestate.node_db_lite.size()); + meshNodes = &devicestate.node_db_lite; + numMeshNodes = devicestate.node_db_lite.size(); } } + meshNodes->resize(MAX_NUM_NODES); if (!loadProto(configFileName, meshtastic_LocalConfig_size, sizeof(meshtastic_LocalConfig), &meshtastic_LocalConfig_msg, &config)) { @@ -626,7 +660,7 @@ bool NodeDB::saveProto(const char *filename, size_t protoSize, const pb_msgdesc_ if (failedCounter >= 2) { FSCom.format(); // After formatting, the device needs to be restarted - nodeDB.resetRadioConfig(true); + nodeDB->resetRadioConfig(true); } #endif } @@ -649,7 +683,8 @@ void NodeDB::saveDeviceStateToDisk() #ifdef FSCom FSCom.mkdir("/prefs"); #endif - saveProto(prefFileName, meshtastic_DeviceState_size, &meshtastic_DeviceState_msg, &devicestate); + saveProto(prefFileName, sizeof(devicestate) + numMeshNodes * meshtastic_NodeInfoLite_size, &meshtastic_DeviceState_msg, + &devicestate); } void NodeDB::saveToDisk(int saveWhat) @@ -690,8 +725,8 @@ void NodeDB::saveToDisk(int saveWhat) const meshtastic_NodeInfoLite *NodeDB::readNextMeshNode(uint32_t &readIndex) { - if (readIndex < *numMeshNodes) - return &meshNodes[readIndex++]; + if (readIndex < numMeshNodes) + return &meshNodes->at(readIndex++); else return NULL; } @@ -726,10 +761,10 @@ size_t NodeDB::getNumOnlineMeshNodes(bool localOnly) size_t numseen = 0; // FIXME this implementation is kinda expensive - for (int i = 0; i < *numMeshNodes; i++) { - if (localOnly && meshNodes[i].via_mqtt) + for (int i = 0; i < numMeshNodes; i++) { + if (localOnly && meshNodes->at(i).via_mqtt) continue; - if (sinceLastSeen(&meshNodes[i]) < NUM_ONLINE_SECS) + if (sinceLastSeen(&meshNodes->at(i)) < NUM_ONLINE_SECS) numseen++; } @@ -877,9 +912,9 @@ uint8_t NodeDB::getMeshNodeChannel(NodeNum n) /// NOTE: This function might be called from an ISR meshtastic_NodeInfoLite *NodeDB::getMeshNode(NodeNum n) { - for (int i = 0; i < *numMeshNodes; i++) - if (meshNodes[i].num == n) - return &meshNodes[i]; + for (int i = 0; i < numMeshNodes; i++) + if (meshNodes->at(i).num == n) + return &meshNodes->at(i); return NULL; } @@ -890,27 +925,27 @@ meshtastic_NodeInfoLite *NodeDB::getOrCreateMeshNode(NodeNum n) meshtastic_NodeInfoLite *lite = getMeshNode(n); if (!lite) { - if ((*numMeshNodes >= MAX_NUM_NODES) || (memGet.getFreeHeap() < meshtastic_NodeInfoLite_size * 3)) { + if ((numMeshNodes >= MAX_NUM_NODES) || (memGet.getFreeHeap() < meshtastic_NodeInfoLite_size * 3)) { if (screen) screen->print("Warn: node database full!\nErasing oldest entry\n"); LOG_INFO("Warn: node database full!\nErasing oldest entry\n"); // look for oldest node and erase it uint32_t oldest = UINT32_MAX; int oldestIndex = -1; - for (int i = 1; i < *numMeshNodes; i++) { - if (meshNodes[i].last_heard < oldest) { - oldest = meshNodes[i].last_heard; + for (int i = 1; i < numMeshNodes; i++) { + if (meshNodes->at(i).last_heard < oldest) { + oldest = meshNodes->at(i).last_heard; oldestIndex = i; } } // Shove the remaining nodes down the chain - for (int i = oldestIndex; i < *numMeshNodes - 1; i++) { - meshNodes[i] = meshNodes[i + 1]; + for (int i = oldestIndex; i < numMeshNodes - 1; i++) { + meshNodes->at(i) = meshNodes->at(i + 1); } - (*numMeshNodes)--; + (numMeshNodes)--; } // add the node at the end - lite = &meshNodes[(*numMeshNodes)++]; + lite = &meshNodes->at((numMeshNodes)++); // everything is missing except the nodenum memset(lite, 0, sizeof(*lite)); diff --git a/src/mesh/NodeDB.h b/src/mesh/NodeDB.h index 1d2086adb..ea2019c37 100644 --- a/src/mesh/NodeDB.h +++ b/src/mesh/NodeDB.h @@ -3,6 +3,7 @@ #include "Observer.h" #include #include +#include #include "MeshTypes.h" #include "NodeStatus.h" @@ -45,20 +46,20 @@ class NodeDB // Eventually use a smarter datastructure // HashMap nodes; // Note: these two references just point into our static array we serialize to/from disk - meshtastic_NodeInfoLite *meshNodes; - pb_size_t *numMeshNodes; public: + std::vector *meshNodes; bool updateGUI = false; // we think the gui should definitely be redrawn, screen will clear this once handled meshtastic_NodeInfoLite *updateGUIforNode = NULL; // if currently showing this node, we think you should update the GUI Observable newStatus; + pb_size_t numMeshNodes; /// don't do mesh based algorithm for node id assignment (initially) /// instead just store in flash - possibly even in the initial alpha release do this hack NodeDB(); /// Called from service after app start, to do init which can only be done after OS load - void init(); + static NodeDB *init(); /// write to flash void saveToDisk(int saveWhat = SEGMENT_CONFIG | SEGMENT_MODULECONFIG | SEGMENT_DEVICESTATE | SEGMENT_CHANNELS), @@ -126,12 +127,12 @@ class NodeDB meshtastic_NodeInfoLite *getMeshNodeByIndex(size_t x) { - assert(x < *numMeshNodes); - return &meshNodes[x]; + assert(x < numMeshNodes); + return &meshNodes->at(x); } meshtastic_NodeInfoLite *getMeshNode(NodeNum n); - size_t getNumMeshNodes() { return *numMeshNodes; } + size_t getNumMeshNodes() { return numMeshNodes; } void setLocalPosition(meshtastic_Position position, bool timeOnly = false) { @@ -167,7 +168,7 @@ class NodeDB void installDefaultDeviceState(), installDefaultChannels(), installDefaultConfig(), installDefaultModuleConfig(); }; -extern NodeDB nodeDB; +extern NodeDB *nodeDB; /* If is_router is set, we use a number of different default values diff --git a/src/mesh/PacketHistory.cpp b/src/mesh/PacketHistory.cpp index 9ecad47cd..26a73a3fe 100644 --- a/src/mesh/PacketHistory.cpp +++ b/src/mesh/PacketHistory.cpp @@ -2,6 +2,10 @@ #include "configuration.h" #include "mesh-pb-constants.h" +#ifdef ARCH_PORTDUINO +#include "platform/portduino/PortduinoGlue.h" +#endif + PacketHistory::PacketHistory() { recentPackets.reserve(MAX_NUM_NODES); // Prealloc the worst case # of records - to prevent heap fragmentation diff --git a/src/mesh/PhoneAPI.cpp b/src/mesh/PhoneAPI.cpp index d8e842149..48f7eb940 100644 --- a/src/mesh/PhoneAPI.cpp +++ b/src/mesh/PhoneAPI.cpp @@ -421,7 +421,7 @@ bool PhoneAPI::available() case STATE_SEND_NODEINFO: if (nodeInfoForPhone.num == 0) { - auto nextNode = nodeDB.readNextMeshNode(readIndex); + auto nextNode = nodeDB->readNextMeshNode(readIndex); if (nextNode) { nodeInfoForPhone = TypeConversions::ConvertToNodeInfo(nextNode); } diff --git a/src/mesh/ProtobufModule.h b/src/mesh/ProtobufModule.h index d87bb47c3..1067ee01e 100644 --- a/src/mesh/ProtobufModule.h +++ b/src/mesh/ProtobufModule.h @@ -56,7 +56,7 @@ template class ProtobufModule : protected SinglePortModule */ const char *getSenderShortName(const meshtastic_MeshPacket &mp) { - auto node = nodeDB.getMeshNode(getFrom(&mp)); + auto node = nodeDB->getMeshNode(getFrom(&mp)); const char *sender = (node) ? node->user.short_name : "???"; return sender; } diff --git a/src/mesh/RadioInterface.cpp b/src/mesh/RadioInterface.cpp index 7a2711251..859e7bea4 100644 --- a/src/mesh/RadioInterface.cpp +++ b/src/mesh/RadioInterface.cpp @@ -334,8 +334,8 @@ bool RadioInterface::init() notifyDeepSleepObserver.observe(¬ifyDeepSleep); // we now expect interfaces to operate in promiscuous mode - // radioIf.setThisAddress(nodeDB.getNodeNum()); // Note: we must do this here, because the nodenum isn't inited at constructor - // time. + // radioIf.setThisAddress(nodeDB->getNodeNum()); // Note: we must do this here, because the nodenum isn't inited at + // constructor time. applyModemConfig(); diff --git a/src/mesh/ReliableRouter.cpp b/src/mesh/ReliableRouter.cpp index 2327cbfb7..d3246b48d 100644 --- a/src/mesh/ReliableRouter.cpp +++ b/src/mesh/ReliableRouter.cpp @@ -76,7 +76,7 @@ bool ReliableRouter::shouldFilterReceived(const meshtastic_MeshPacket *p) * Resending real ACKs is omitted, as you might receive a packet multiple times due to flooding and * flooding this ACK back to the original sender already adds redundancy. */ bool isRepeated = p->hop_start == 0 ? (p->hop_limit == HOP_RELIABLE) : (p->hop_start == p->hop_limit); - if (wasSeenRecently(p, false) && isRepeated && !MeshModule::currentReply && p->to != nodeDB.getNodeNum()) { + if (wasSeenRecently(p, false) && isRepeated && !MeshModule::currentReply && p->to != nodeDB->getNodeNum()) { LOG_DEBUG("Resending implicit ack for a repeated floodmsg\n"); meshtastic_MeshPacket *tosend = packetPool.allocCopy(*p); tosend->hop_limit--; // bump down the hop count diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp index 7c739b8f2..7894b1b92 100644 --- a/src/mesh/Router.cpp +++ b/src/mesh/Router.cpp @@ -119,7 +119,7 @@ meshtastic_MeshPacket *Router::allocForSending() meshtastic_MeshPacket *p = packetPool.allocZeroed(); p->which_payload_variant = meshtastic_MeshPacket_decoded_tag; // Assume payload is decoded at start. - p->from = nodeDB.getNodeNum(); + p->from = nodeDB->getNodeNum(); p->to = NODENUM_BROADCAST; p->hop_limit = (config.lora.hop_limit >= HOP_MAX) ? HOP_MAX : config.lora.hop_limit; p->id = generatePacketId(); @@ -165,7 +165,7 @@ meshtastic_QueueStatus Router::getQueueStatus() ErrorCode Router::sendLocal(meshtastic_MeshPacket *p, RxSource src) { // No need to deliver externally if the destination is the local node - if (p->to == nodeDB.getNodeNum()) { + if (p->to == nodeDB->getNodeNum()) { printPacket("Enqueued local", p); enqueueReceivedMessage(p); return ERRNO_OK; @@ -182,7 +182,7 @@ ErrorCode Router::sendLocal(meshtastic_MeshPacket *p, RxSource src) } if (!p->channel) { // don't override if a channel was requested - p->channel = nodeDB.getMeshNodeChannel(p->to); + p->channel = nodeDB->getMeshNodeChannel(p->to); LOG_DEBUG("localSend to channel %d\n", p->channel); } @@ -205,7 +205,7 @@ void printBytes(const char *label, const uint8_t *p, size_t numbytes) */ ErrorCode Router::send(meshtastic_MeshPacket *p) { - if (p->to == nodeDB.getNodeNum()) { + if (p->to == nodeDB->getNodeNum()) { LOG_ERROR("BUG! send() called with packet destined for local node!\n"); packetPool.release(p); return meshtastic_Routing_Error_BAD_REQUEST; @@ -220,7 +220,7 @@ ErrorCode Router::send(meshtastic_MeshPacket *p) LOG_WARN("Duty cycle limit exceeded. Aborting send for now, you can send again in %d minutes.\n", silentMinutes); #endif meshtastic_Routing_Error err = meshtastic_Routing_Error_DUTY_CYCLE_LIMIT; - if (getFrom(p) == nodeDB.getNodeNum()) { // only send NAK to API, not to the mesh + if (getFrom(p) == nodeDB->getNodeNum()) { // only send NAK to API, not to the mesh abortSendAndNak(err, p); } else { packetPool.release(p); @@ -263,7 +263,7 @@ ErrorCode Router::send(meshtastic_MeshPacket *p) } // Only publish to MQTT if we're the original transmitter of the packet - if (moduleConfig.mqtt.enabled && p->from == nodeDB.getNodeNum() && mqtt) { + if (moduleConfig.mqtt.enabled && p->from == nodeDB->getNodeNum() && mqtt) { mqtt->onSend(*p, *p_decoded, chIndex); } packetPool.release(p_decoded); @@ -297,8 +297,8 @@ bool perhapsDecode(meshtastic_MeshPacket *p) return false; if (config.device.rebroadcast_mode == meshtastic_Config_DeviceConfig_RebroadcastMode_KNOWN_ONLY && - (nodeDB.getMeshNode(p->from) == NULL || !nodeDB.getMeshNode(p->from)->has_user)) { - LOG_DEBUG("Node 0x%x not in NodeDB. Rebroadcast mode KNOWN_ONLY will ignore packet\n", p->from); + (nodeDB->getMeshNode(p->from) == NULL || !nodeDB->getMeshNode(p->from)->has_user)) { + LOG_DEBUG("Node 0x%x not in nodeDB-> Rebroadcast mode KNOWN_ONLY will ignore packet\n", p->from); return false; } @@ -431,7 +431,7 @@ meshtastic_Routing_Error perhapsEncode(meshtastic_MeshPacket *p) NodeNum Router::getNodeNum() { - return nodeDB.getNodeNum(); + return nodeDB->getNodeNum(); } /** @@ -467,7 +467,7 @@ void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src) } // Publish received message to MQTT if we're not the original transmitter of the packet - if (!skipHandle && moduleConfig.mqtt.enabled && getFrom(p) != nodeDB.getNodeNum() && mqtt) + if (!skipHandle && moduleConfig.mqtt.enabled && getFrom(p) != nodeDB->getNodeNum() && mqtt) mqtt->onSend(*p_encrypted, *p, p->channel); } else { printPacket("packet decoding failed or skipped (no PSK?)", p); diff --git a/src/mesh/SX128xInterface.cpp b/src/mesh/SX128xInterface.cpp index d0103ec29..f2220dbcf 100644 --- a/src/mesh/SX128xInterface.cpp +++ b/src/mesh/SX128xInterface.cpp @@ -71,7 +71,7 @@ template bool SX128xInterface::init() if ((config.lora.region != meshtastic_Config_LoRaConfig_RegionCode_LORA_24) && (res == RADIOLIB_ERR_INVALID_FREQUENCY)) { LOG_WARN("Radio chip only supports 2.4GHz LoRa. Adjusting Region and rebooting.\n"); config.lora.region = meshtastic_Config_LoRaConfig_RegionCode_LORA_24; - nodeDB.saveToDisk(SEGMENT_CONFIG); + nodeDB->saveToDisk(SEGMENT_CONFIG); delay(2000); #if defined(ARCH_ESP32) ESP.restart(); @@ -251,9 +251,9 @@ template void SX128xInterface::startReceive() #endif // We use the PREAMBLE_DETECTED and HEADER_VALID IRQ flag to detect whether we are actively receiving - int err = lora.startReceive(RADIOLIB_SX128X_RX_TIMEOUT_INF, RADIOLIB_SX128X_IRQ_RX_DEFAULT | - RADIOLIB_SX128X_IRQ_PREAMBLE_DETECTED | - RADIOLIB_SX128X_IRQ_HEADER_VALID); + int err = + lora.startReceive(RADIOLIB_SX128X_RX_TIMEOUT_INF, RADIOLIB_SX128X_IRQ_RX_DEFAULT | RADIOLIB_SX128X_IRQ_PREAMBLE_DETECTED | + RADIOLIB_SX128X_IRQ_HEADER_VALID); assert(err == RADIOLIB_ERR_NONE); @@ -327,4 +327,4 @@ template bool SX128xInterface::sleep() #endif return true; -} +} \ No newline at end of file diff --git a/src/mesh/generated/meshtastic/admin.pb.c b/src/mesh/generated/meshtastic/admin.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/admin.pb.c rename to src/mesh/generated/meshtastic/admin.pb.cpp diff --git a/src/mesh/generated/meshtastic/apponly.pb.c b/src/mesh/generated/meshtastic/apponly.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/apponly.pb.c rename to src/mesh/generated/meshtastic/apponly.pb.cpp diff --git a/src/mesh/generated/meshtastic/atak.pb.c b/src/mesh/generated/meshtastic/atak.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/atak.pb.c rename to src/mesh/generated/meshtastic/atak.pb.cpp diff --git a/src/mesh/generated/meshtastic/cannedmessages.pb.c b/src/mesh/generated/meshtastic/cannedmessages.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/cannedmessages.pb.c rename to src/mesh/generated/meshtastic/cannedmessages.pb.cpp diff --git a/src/mesh/generated/meshtastic/channel.pb.c b/src/mesh/generated/meshtastic/channel.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/channel.pb.c rename to src/mesh/generated/meshtastic/channel.pb.cpp diff --git a/src/mesh/generated/meshtastic/clientonly.pb.c b/src/mesh/generated/meshtastic/clientonly.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/clientonly.pb.c rename to src/mesh/generated/meshtastic/clientonly.pb.cpp diff --git a/src/mesh/generated/meshtastic/config.pb.c b/src/mesh/generated/meshtastic/config.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/config.pb.c rename to src/mesh/generated/meshtastic/config.pb.cpp diff --git a/src/mesh/generated/meshtastic/connection_status.pb.c b/src/mesh/generated/meshtastic/connection_status.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/connection_status.pb.c rename to src/mesh/generated/meshtastic/connection_status.pb.cpp diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.c b/src/mesh/generated/meshtastic/deviceonly.pb.cpp similarity index 90% rename from src/mesh/generated/meshtastic/deviceonly.pb.c rename to src/mesh/generated/meshtastic/deviceonly.pb.cpp index 82c3fc44c..93ab3dd98 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.c +++ b/src/mesh/generated/meshtastic/deviceonly.pb.cpp @@ -6,7 +6,7 @@ #error Regenerate this file with the current version of nanopb generator. #endif -PB_BIND(meshtastic_DeviceState, meshtastic_DeviceState, 4) +PB_BIND(meshtastic_DeviceState, meshtastic_DeviceState, 2) PB_BIND(meshtastic_NodeInfoLite, meshtastic_NodeInfoLite, AUTO) diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index d6a2a0272..c286bd471 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -4,6 +4,7 @@ #ifndef PB_MESHTASTIC_MESHTASTIC_DEVICEONLY_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_DEVICEONLY_PB_H_INCLUDED #include +#include #include "meshtastic/channel.pb.h" #include "meshtastic/localonly.pb.h" #include "meshtastic/mesh.pb.h" @@ -155,8 +156,7 @@ typedef struct _meshtastic_DeviceState { pb_size_t node_remote_hardware_pins_count; meshtastic_NodeRemoteHardwarePin node_remote_hardware_pins[12]; /* New lite version of NodeDB to decrease memory footprint */ - pb_size_t node_db_lite_count; - meshtastic_NodeInfoLite node_db_lite[100]; + std::vector node_db_lite; } meshtastic_DeviceState; @@ -179,13 +179,13 @@ extern "C" { /* Initializer values for message structs */ -#define meshtastic_DeviceState_init_default {false, meshtastic_MyNodeInfo_init_default, false, meshtastic_User_init_default, 0, {meshtastic_MeshPacket_init_default}, false, meshtastic_MeshPacket_init_default, 0, 0, 0, false, meshtastic_MeshPacket_init_default, 0, {meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default}, 0, {meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default}} +#define meshtastic_DeviceState_init_default {false, meshtastic_MyNodeInfo_init_default, false, meshtastic_User_init_default, 0, {meshtastic_MeshPacket_init_default}, false, meshtastic_MeshPacket_init_default, 0, 0, 0, false, meshtastic_MeshPacket_init_default, 0, {meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default}, {{NULL}, NULL}} #define meshtastic_NodeInfoLite_init_default {0, false, meshtastic_User_init_default, false, meshtastic_PositionLite_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0, 0, 0} #define meshtastic_PositionLite_init_default {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN} #define meshtastic_ChannelFile_init_default {0, {meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default}, 0} #define meshtastic_OEMStore_init_default {0, 0, {0, {0}}, _meshtastic_ScreenFonts_MIN, "", {0, {0}}, false, meshtastic_LocalConfig_init_default, false, meshtastic_LocalModuleConfig_init_default} #define meshtastic_NodeRemoteHardwarePin_init_default {0, false, meshtastic_RemoteHardwarePin_init_default} -#define meshtastic_DeviceState_init_zero {false, meshtastic_MyNodeInfo_init_zero, false, meshtastic_User_init_zero, 0, {meshtastic_MeshPacket_init_zero}, false, meshtastic_MeshPacket_init_zero, 0, 0, 0, false, meshtastic_MeshPacket_init_zero, 0, {meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero}, 0, {meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero}} +#define meshtastic_DeviceState_init_zero {false, meshtastic_MyNodeInfo_init_zero, false, meshtastic_User_init_zero, 0, {meshtastic_MeshPacket_init_zero}, false, meshtastic_MeshPacket_init_zero, 0, 0, 0, false, meshtastic_MeshPacket_init_zero, 0, {meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero}, {{NULL}, NULL}} #define meshtastic_NodeInfoLite_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_PositionLite_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0, 0, 0} #define meshtastic_PositionLite_init_zero {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN} #define meshtastic_ChannelFile_init_zero {0, {meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero}, 0} @@ -241,8 +241,9 @@ X(a, STATIC, SINGULAR, BOOL, no_save, 9) \ X(a, STATIC, SINGULAR, BOOL, did_gps_reset, 11) \ X(a, STATIC, OPTIONAL, MESSAGE, rx_waypoint, 12) \ X(a, STATIC, REPEATED, MESSAGE, node_remote_hardware_pins, 13) \ -X(a, STATIC, REPEATED, MESSAGE, node_db_lite, 14) -#define meshtastic_DeviceState_CALLBACK NULL +X(a, CALLBACK, REPEATED, MESSAGE, node_db_lite, 14) +extern bool meshtastic_DeviceState_callback(pb_istream_t *istream, pb_ostream_t *ostream, const pb_field_t *field); +#define meshtastic_DeviceState_CALLBACK meshtastic_DeviceState_callback #define meshtastic_DeviceState_DEFAULT NULL #define meshtastic_DeviceState_my_node_MSGTYPE meshtastic_MyNodeInfo #define meshtastic_DeviceState_owner_MSGTYPE meshtastic_User @@ -321,8 +322,8 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg; #define meshtastic_NodeRemoteHardwarePin_fields &meshtastic_NodeRemoteHardwarePin_msg /* Maximum encoded size of messages (where known) */ +/* meshtastic_DeviceState_size depends on runtime parameters */ #define meshtastic_ChannelFile_size 702 -#define meshtastic_DeviceState_size 17571 #define meshtastic_NodeInfoLite_size 158 #define meshtastic_NodeRemoteHardwarePin_size 29 #define meshtastic_OEMStore_size 3278 diff --git a/src/mesh/generated/meshtastic/localonly.pb.c b/src/mesh/generated/meshtastic/localonly.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/localonly.pb.c rename to src/mesh/generated/meshtastic/localonly.pb.cpp diff --git a/src/mesh/generated/meshtastic/mesh.pb.c b/src/mesh/generated/meshtastic/mesh.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/mesh.pb.c rename to src/mesh/generated/meshtastic/mesh.pb.cpp diff --git a/src/mesh/generated/meshtastic/module_config.pb.c b/src/mesh/generated/meshtastic/module_config.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/module_config.pb.c rename to src/mesh/generated/meshtastic/module_config.pb.cpp diff --git a/src/mesh/generated/meshtastic/mqtt.pb.c b/src/mesh/generated/meshtastic/mqtt.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/mqtt.pb.c rename to src/mesh/generated/meshtastic/mqtt.pb.cpp diff --git a/src/mesh/generated/meshtastic/paxcount.pb.c b/src/mesh/generated/meshtastic/paxcount.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/paxcount.pb.c rename to src/mesh/generated/meshtastic/paxcount.pb.cpp diff --git a/src/mesh/generated/meshtastic/portnums.pb.c b/src/mesh/generated/meshtastic/portnums.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/portnums.pb.c rename to src/mesh/generated/meshtastic/portnums.pb.cpp diff --git a/src/mesh/generated/meshtastic/remote_hardware.pb.c b/src/mesh/generated/meshtastic/remote_hardware.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/remote_hardware.pb.c rename to src/mesh/generated/meshtastic/remote_hardware.pb.cpp diff --git a/src/mesh/generated/meshtastic/rtttl.pb.c b/src/mesh/generated/meshtastic/rtttl.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/rtttl.pb.c rename to src/mesh/generated/meshtastic/rtttl.pb.cpp diff --git a/src/mesh/generated/meshtastic/storeforward.pb.c b/src/mesh/generated/meshtastic/storeforward.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/storeforward.pb.c rename to src/mesh/generated/meshtastic/storeforward.pb.cpp diff --git a/src/mesh/generated/meshtastic/telemetry.pb.c b/src/mesh/generated/meshtastic/telemetry.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/telemetry.pb.c rename to src/mesh/generated/meshtastic/telemetry.pb.cpp diff --git a/src/mesh/generated/meshtastic/xmodem.pb.c b/src/mesh/generated/meshtastic/xmodem.pb.cpp similarity index 100% rename from src/mesh/generated/meshtastic/xmodem.pb.c rename to src/mesh/generated/meshtastic/xmodem.pb.cpp diff --git a/src/mesh/mesh-pb-constants.h b/src/mesh/mesh-pb-constants.h index 22a80c8e3..9e747db1d 100644 --- a/src/mesh/mesh-pb-constants.h +++ b/src/mesh/mesh-pb-constants.h @@ -1,4 +1,5 @@ #pragma once +#include #include "mesh/generated/meshtastic/admin.pb.h" #include "mesh/generated/meshtastic/deviceonly.pb.h" @@ -16,7 +17,11 @@ #define MAX_RX_TOPHONE 32 /// max number of nodes allowed in the mesh -#define MAX_NUM_NODES (member_size(meshtastic_DeviceState, node_db_lite) / member_size(meshtastic_DeviceState, node_db_lite[0])) +#if ARCH_PORTDUINO +#define MAX_NUM_NODES settingsMap[maxnodes] +#else +#define MAX_NUM_NODES 100 +#endif /// Max number of channels allowed #define MAX_NUM_CHANNELS (member_size(meshtastic_ChannelFile, channels) / member_size(meshtastic_ChannelFile, channels[0])) diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index 6c4c80dbb..6d420ddb8 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -50,7 +50,7 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta // if handled == false, then let others look at this message also if they want bool handled = false; assert(r); - bool fromOthers = mp.from != 0 && mp.from != nodeDB.getNodeNum(); + bool fromOthers = mp.from != 0 && mp.from != nodeDB->getNodeNum(); switch (r->which_payload_variant) { @@ -150,13 +150,13 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta } case meshtastic_AdminMessage_factory_reset_tag: { LOG_INFO("Initiating factory reset\n"); - nodeDB.factoryReset(); + nodeDB->factoryReset(); reboot(DEFAULT_REBOOT_SECONDS); break; } case meshtastic_AdminMessage_nodedb_reset_tag: { LOG_INFO("Initiating node-db reset\n"); - nodeDB.resetNodes(); + nodeDB->resetNodes(); reboot(DEFAULT_REBOOT_SECONDS); break; } @@ -186,7 +186,7 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta } case meshtastic_AdminMessage_remove_by_nodenum_tag: { LOG_INFO("Client is receiving a remove_nodenum command.\n"); - nodeDB.removeNodeByNum(r->remove_by_nodenum); + nodeDB->removeNodeByNum(r->remove_by_nodenum); break; } case meshtastic_AdminMessage_enter_dfu_mode_request_tag: { @@ -302,7 +302,7 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c) config.device = c.payload_variant.device; // If we're setting router role for the first time, install its intervals if (existingRole != c.payload_variant.device.role) - nodeDB.installRoleDefaults(c.payload_variant.device.role); + nodeDB->installRoleDefaults(c.payload_variant.device.role); if (config.device.node_info_broadcast_secs < min_node_info_broadcast_secs) { LOG_DEBUG("Tried to set node_info_broadcast_secs too low, setting to %d\n", min_node_info_broadcast_secs); config.device.node_info_broadcast_secs = min_node_info_broadcast_secs; @@ -608,7 +608,7 @@ void AdminModule::handleGetNodeRemoteHardwarePins(const meshtastic_MeshPacket &r continue; } meshtastic_NodeRemoteHardwarePin nodePin = meshtastic_NodeRemoteHardwarePin_init_default; - nodePin.node_num = nodeDB.getNodeNum(); + nodePin.node_num = nodeDB->getNodeNum(); nodePin.pin = moduleConfig.remote_hardware.available_pins[i]; r.get_node_remote_hardware_pins_response.node_remote_hardware_pins[i + 12] = nodePin; } diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index b2b52d1ab..3293e5d0d 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -311,18 +311,18 @@ int32_t CannedMessageModule::runOnce() switch (this->payload) { case 0xb4: // left if (this->destSelect == CANNED_MESSAGE_DESTINATION_TYPE_NODE) { - size_t numMeshNodes = nodeDB.getNumMeshNodes(); + size_t numMeshNodes = nodeDB->getNumMeshNodes(); if (this->dest == NODENUM_BROADCAST) { - this->dest = nodeDB.getNodeNum(); + this->dest = nodeDB->getNodeNum(); } for (unsigned int i = 0; i < numMeshNodes; i++) { - if (nodeDB.getMeshNodeByIndex(i)->num == this->dest) { + if (nodeDB->getMeshNodeByIndex(i)->num == this->dest) { this->dest = - (i > 0) ? nodeDB.getMeshNodeByIndex(i - 1)->num : nodeDB.getMeshNodeByIndex(numMeshNodes - 1)->num; + (i > 0) ? nodeDB->getMeshNodeByIndex(i - 1)->num : nodeDB->getMeshNodeByIndex(numMeshNodes - 1)->num; break; } } - if (this->dest == nodeDB.getNodeNum()) { + if (this->dest == nodeDB->getNodeNum()) { this->dest = NODENUM_BROADCAST; } } else if (this->destSelect == CANNED_MESSAGE_DESTINATION_TYPE_CHANNEL) { @@ -346,18 +346,18 @@ int32_t CannedMessageModule::runOnce() break; case 0xb7: // right if (this->destSelect == CANNED_MESSAGE_DESTINATION_TYPE_NODE) { - size_t numMeshNodes = nodeDB.getNumMeshNodes(); + size_t numMeshNodes = nodeDB->getNumMeshNodes(); if (this->dest == NODENUM_BROADCAST) { - this->dest = nodeDB.getNodeNum(); + this->dest = nodeDB->getNodeNum(); } for (unsigned int i = 0; i < numMeshNodes; i++) { - if (nodeDB.getMeshNodeByIndex(i)->num == this->dest) { + if (nodeDB->getMeshNodeByIndex(i)->num == this->dest) { this->dest = - (i < numMeshNodes - 1) ? nodeDB.getMeshNodeByIndex(i + 1)->num : nodeDB.getMeshNodeByIndex(0)->num; + (i < numMeshNodes - 1) ? nodeDB->getMeshNodeByIndex(i + 1)->num : nodeDB->getMeshNodeByIndex(0)->num; break; } } - if (this->dest == nodeDB.getNodeNum()) { + if (this->dest == nodeDB->getNodeNum()) { this->dest = NODENUM_BROADCAST; } } else if (this->destSelect == CANNED_MESSAGE_DESTINATION_TYPE_CHANNEL) { @@ -462,7 +462,7 @@ const char *CannedMessageModule::getNodeName(NodeNum node) if (node == NODENUM_BROADCAST) { return "Broadcast"; } else { - meshtastic_NodeInfoLite *info = nodeDB.getMeshNode(node); + meshtastic_NodeInfoLite *info = nodeDB->getMeshNode(node); if (info != NULL) { return info->user.long_name; } else { @@ -618,9 +618,9 @@ ProcessMessage CannedMessageModule::handleReceived(const meshtastic_MeshPacket & void CannedMessageModule::loadProtoForModule() { - if (!nodeDB.loadProto(cannedMessagesConfigFile, meshtastic_CannedMessageModuleConfig_size, - sizeof(meshtastic_CannedMessageModuleConfig), &meshtastic_CannedMessageModuleConfig_msg, - &cannedMessageModuleConfig)) { + if (!nodeDB->loadProto(cannedMessagesConfigFile, meshtastic_CannedMessageModuleConfig_size, + sizeof(meshtastic_CannedMessageModuleConfig), &meshtastic_CannedMessageModuleConfig_msg, + &cannedMessageModuleConfig)) { installDefaultCannedMessageModuleConfig(); } } @@ -639,8 +639,8 @@ bool CannedMessageModule::saveProtoForModule() FS.mkdir("/prefs"); #endif - okay &= nodeDB.saveProto(cannedMessagesConfigFile, meshtastic_CannedMessageModuleConfig_size, - &meshtastic_CannedMessageModuleConfig_msg, &cannedMessageModuleConfig); + okay &= nodeDB->saveProto(cannedMessagesConfigFile, meshtastic_CannedMessageModuleConfig_size, + &meshtastic_CannedMessageModuleConfig_msg, &cannedMessageModuleConfig); return okay; } diff --git a/src/modules/ExternalNotificationModule.cpp b/src/modules/ExternalNotificationModule.cpp index 652965f6d..2a4fdd0ae 100644 --- a/src/modules/ExternalNotificationModule.cpp +++ b/src/modules/ExternalNotificationModule.cpp @@ -284,8 +284,8 @@ ExternalNotificationModule::ExternalNotificationModule() // moduleConfig.external_notification.alert_message_buzzer = true; if (moduleConfig.external_notification.enabled) { - if (!nodeDB.loadProto(rtttlConfigFile, meshtastic_RTTTLConfig_size, sizeof(meshtastic_RTTTLConfig), - &meshtastic_RTTTLConfig_msg, &rtttlConfig)) { + if (!nodeDB->loadProto(rtttlConfigFile, meshtastic_RTTTLConfig_size, sizeof(meshtastic_RTTTLConfig), + &meshtastic_RTTTLConfig_msg, &rtttlConfig)) { memset(rtttlConfig.ringtone, 0, sizeof(rtttlConfig.ringtone)); strncpy(rtttlConfig.ringtone, "24:d=32,o=5,b=565:f6,p,f6,4p,p,f6,p,f6,2p,p,b6,p,b6,p,b6,p,b6,p,b,p,b,p,b,p,b,p,b,p,b,p,b,p,b,1p.,2p.,p", @@ -343,7 +343,7 @@ ProcessMessage ExternalNotificationModule::handleReceived(const meshtastic_MeshP drv.setWaveform(2, 0); drv.go(); #endif - if (getFrom(&mp) != nodeDB.getNodeNum()) { + if (getFrom(&mp) != nodeDB->getNodeNum()) { // Check if the message contains a bell character. Don't do this loop for every pin, just once. auto &p = mp.decoded; bool containsBell = false; @@ -506,6 +506,6 @@ void ExternalNotificationModule::handleSetRingtone(const char *from_msg) } if (changed) { - nodeDB.saveProto(rtttlConfigFile, meshtastic_RTTTLConfig_size, &meshtastic_RTTTLConfig_msg, &rtttlConfig); + nodeDB->saveProto(rtttlConfigFile, meshtastic_RTTTLConfig_size, &meshtastic_RTTTLConfig_msg, &rtttlConfig); } } \ No newline at end of file diff --git a/src/modules/NeighborInfoModule.cpp b/src/modules/NeighborInfoModule.cpp index 024f321e6..4d68b4a16 100644 --- a/src/modules/NeighborInfoModule.cpp +++ b/src/modules/NeighborInfoModule.cpp @@ -17,7 +17,7 @@ NOTE: For debugging only void NeighborInfoModule::printNeighborInfo(const char *header, const meshtastic_NeighborInfo *np) { LOG_DEBUG("%s NEIGHBORINFO PACKET from Node 0x%x to Node 0x%x (last sent by 0x%x)\n", header, np->node_id, - nodeDB.getNodeNum(), np->last_sent_by_id); + nodeDB->getNodeNum(), np->last_sent_by_id); LOG_DEBUG("----------------\n"); LOG_DEBUG("Packet contains %d neighbors\n", np->neighbors_count); for (int i = 0; i < np->neighbors_count; i++) { @@ -31,12 +31,12 @@ NOTE: for debugging only */ void NeighborInfoModule::printNodeDBNodes(const char *header) { - int num_nodes = nodeDB.getNumMeshNodes(); - LOG_DEBUG("%s NODEDB SELECTION from Node 0x%x:\n", header, nodeDB.getNodeNum()); + int num_nodes = nodeDB->getNumMeshNodes(); + LOG_DEBUG("%s NODEDB SELECTION from Node 0x%x:\n", header, nodeDB->getNodeNum()); LOG_DEBUG("----------------\n"); LOG_DEBUG("DB contains %d nodes\n", num_nodes); for (int i = 0; i < num_nodes; i++) { - const meshtastic_NodeInfoLite *dbEntry = nodeDB.getMeshNodeByIndex(i); + const meshtastic_NodeInfoLite *dbEntry = nodeDB->getMeshNodeByIndex(i); LOG_DEBUG(" Node %d: node_id=0x%x, snr=%.2f\n", i, dbEntry->num, dbEntry->snr); } LOG_DEBUG("----------------\n"); @@ -49,7 +49,7 @@ NOTE: for debugging only void NeighborInfoModule::printNodeDBNeighbors(const char *header) { int num_neighbors = getNumNeighbors(); - LOG_DEBUG("%s NODEDB SELECTION from Node 0x%x:\n", header, nodeDB.getNodeNum()); + LOG_DEBUG("%s NODEDB SELECTION from Node 0x%x:\n", header, nodeDB->getNodeNum()); LOG_DEBUG("----------------\n"); LOG_DEBUG("DB contains %d neighbors\n", num_neighbors); for (int i = 0; i < num_neighbors; i++) { @@ -67,7 +67,7 @@ NOTE: For debugging only void NeighborInfoModule::printNodeDBSelection(const char *header, const meshtastic_NeighborInfo *np) { int num_neighbors = getNumNeighbors(); - LOG_DEBUG("%s NODEDB SELECTION from Node 0x%x:\n", header, nodeDB.getNodeNum()); + LOG_DEBUG("%s NODEDB SELECTION from Node 0x%x:\n", header, nodeDB->getNodeNum()); LOG_DEBUG("----------------\n"); LOG_DEBUG("Selected %d neighbors of %d DB neighbors\n", np->neighbors_count, num_neighbors); for (int i = 0; i < num_neighbors; i++) { @@ -112,7 +112,7 @@ Assumes that the neighborInfo packet has been allocated */ uint32_t NeighborInfoModule::collectNeighborInfo(meshtastic_NeighborInfo *neighborInfo) { - uint my_node_id = nodeDB.getNodeNum(); + uint my_node_id = nodeDB->getNodeNum(); neighborInfo->node_id = my_node_id; neighborInfo->last_sent_by_id = my_node_id; neighborInfo->node_broadcast_interval_secs = moduleConfig.neighbor_info.update_interval; @@ -143,7 +143,7 @@ size_t NeighborInfoModule::cleanUpNeighbors() { uint32_t now = getTime(); int num_neighbors = getNumNeighbors(); - NodeNum my_node_id = nodeDB.getNodeNum(); + NodeNum my_node_id = nodeDB->getNodeNum(); // Find neighbors to remove std::vector indices_to_remove; @@ -227,7 +227,7 @@ void NeighborInfoModule::updateLastSentById(meshtastic_MeshPacket *p) pb_decode_from_bytes(incoming.payload.bytes, incoming.payload.size, &meshtastic_NeighborInfo_msg, &scratch); updated = &scratch; - updated->last_sent_by_id = nodeDB.getNodeNum(); + updated->last_sent_by_id = nodeDB->getNodeNum(); // Set updated last_sent_by_id to the payload of the to be flooded packet p->decoded.payload.size = @@ -256,7 +256,7 @@ meshtastic_Neighbor *NeighborInfoModule::getOrCreateNeighbor(NodeNum originalSen { // our node and the phone are the same node (not neighbors) if (n == 0) { - n = nodeDB.getNodeNum(); + n = nodeDB->getNodeNum(); } // look for one in the existing list for (int i = 0; i < (*numNeighbors); i++) { @@ -292,8 +292,8 @@ meshtastic_Neighbor *NeighborInfoModule::getOrCreateNeighbor(NodeNum originalSen void NeighborInfoModule::loadProtoForModule() { - if (!nodeDB.loadProto(neighborInfoConfigFile, meshtastic_NeighborInfo_size, sizeof(meshtastic_NeighborInfo), - &meshtastic_NeighborInfo_msg, &neighborState)) { + if (!nodeDB->loadProto(neighborInfoConfigFile, meshtastic_NeighborInfo_size, sizeof(meshtastic_NeighborInfo), + &meshtastic_NeighborInfo_msg, &neighborState)) { neighborState = meshtastic_NeighborInfo_init_zero; } } @@ -312,7 +312,7 @@ bool NeighborInfoModule::saveProtoForModule() FS.mkdir("/prefs"); #endif - okay &= nodeDB.saveProto(neighborInfoConfigFile, meshtastic_NeighborInfo_size, &meshtastic_NeighborInfo_msg, &neighborState); + okay &= nodeDB->saveProto(neighborInfoConfigFile, meshtastic_NeighborInfo_size, &meshtastic_NeighborInfo_msg, &neighborState); return okay; } \ No newline at end of file diff --git a/src/modules/NodeInfoModule.cpp b/src/modules/NodeInfoModule.cpp index 370847b94..f77026708 100644 --- a/src/modules/NodeInfoModule.cpp +++ b/src/modules/NodeInfoModule.cpp @@ -13,7 +13,7 @@ bool NodeInfoModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes { auto p = *pptr; - bool hasChanged = nodeDB.updateUser(getFrom(&mp), p, mp.channel); + bool hasChanged = nodeDB->updateUser(getFrom(&mp), p, mp.channel); bool wasBroadcast = mp.to == NODENUM_BROADCAST; @@ -25,7 +25,7 @@ bool NodeInfoModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes } // if user has changed while packet was not for us, inform phone - if (hasChanged && !wasBroadcast && mp.to != nodeDB.getNodeNum()) + if (hasChanged && !wasBroadcast && mp.to != nodeDB->getNodeNum()) service.sendToPhone(packetPool.allocCopy(mp)); // LOG_DEBUG("did handleReceived\n"); diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index 853808f44..0bfc775da 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -41,12 +41,12 @@ PositionModule::PositionModule() void PositionModule::clearPosition() { LOG_DEBUG("Clearing position on startup for sleepy tracker (ー。ー) zzz\n"); - meshtastic_NodeInfoLite *node = nodeDB.getMeshNode(nodeDB.getNodeNum()); + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(nodeDB->getNodeNum()); node->position.latitude_i = 0; node->position.longitude_i = 0; node->position.altitude = 0; node->position.time = 0; - nodeDB.setLocalPosition(meshtastic_Position_init_default); + nodeDB->setLocalPosition(meshtastic_Position_init_default); } bool PositionModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_Position *pptr) @@ -59,15 +59,15 @@ bool PositionModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes // FIXME this can in fact happen with packets sent from EUD (src=RX_SRC_USER) // to set fixed location, EUD-GPS location or just the time (see also issue #900) bool isLocal = false; - if (nodeDB.getNodeNum() == getFrom(&mp)) { + if (nodeDB->getNodeNum() == getFrom(&mp)) { isLocal = true; if (config.position.fixed_position) { LOG_DEBUG("Ignore incoming position update from myself except for time, because position.fixed_position is true\n"); - nodeDB.setLocalPosition(p, true); + nodeDB->setLocalPosition(p, true); return false; } else { LOG_DEBUG("Incoming update from MYSELF\n"); - nodeDB.setLocalPosition(p); + nodeDB->setLocalPosition(p); } } @@ -89,7 +89,7 @@ bool PositionModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes perhapsSetRTC(isLocal ? RTCQualityNTP : RTCQualityFromNet, &tv); } - nodeDB.updatePosition(getFrom(&mp), p); + nodeDB->updatePosition(getFrom(&mp), p); if (channels.getByIndex(mp.channel).settings.has_module_settings) { precision = channels.getByIndex(mp.channel).settings.module_settings.position_precision; } else if (channels.getByIndex(mp.channel).role == meshtastic_Channel_Role_PRIMARY) { @@ -119,7 +119,7 @@ meshtastic_MeshPacket *PositionModule::allocReply() meshtastic_Position p = meshtastic_Position_init_default; // Start with an empty structure // if localPosition is totally empty, put our last saved position (lite) in there if (localPosition.latitude_i == 0 && localPosition.longitude_i == 0) { - nodeDB.setLocalPosition(TypeConversions::ConvertToPosition(node->position)); + nodeDB->setLocalPosition(TypeConversions::ConvertToPosition(node->position)); } localPosition.seq_number++; @@ -286,7 +286,7 @@ int32_t PositionModule::runOnce() doDeepSleep(nightyNightMs, false); } - meshtastic_NodeInfoLite *node = nodeDB.getMeshNode(nodeDB.getNodeNum()); + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(nodeDB->getNodeNum()); if (node == nullptr) return RUNONCE_INTERVAL; @@ -402,7 +402,7 @@ struct SmartPosition PositionModule::getDistanceTraveledSinceLastSend(meshtastic void PositionModule::handleNewPosition() { - meshtastic_NodeInfoLite *node = nodeDB.getMeshNode(nodeDB.getNodeNum()); + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(nodeDB->getNodeNum()); const meshtastic_NodeInfoLite *node2 = service.refreshLocalMeshNode(); // should guarantee there is now a position // We limit our GPS broadcasts to a max rate uint32_t now = millis(); diff --git a/src/modules/RangeTestModule.cpp b/src/modules/RangeTestModule.cpp index 904fb25db..a66a0513e 100644 --- a/src/modules/RangeTestModule.cpp +++ b/src/modules/RangeTestModule.cpp @@ -142,14 +142,14 @@ ProcessMessage RangeTestModuleRadio::handleReceived(const meshtastic_MeshPacket LOG_INFO.getNodeNum(), mp.from, mp.to, mp.id, p.payload.size, p.payload.bytes); */ - if (getFrom(&mp) != nodeDB.getNodeNum()) { + if (getFrom(&mp) != nodeDB->getNodeNum()) { if (moduleConfig.range_test.save) { appendFile(mp); } /* - NodeInfoLite *n = nodeDB.getMeshNode(getFrom(&mp)); + NodeInfoLite *n = nodeDB->getMeshNode(getFrom(&mp)); LOG_DEBUG("-----------------------------------------\n"); LOG_DEBUG("p.payload.bytes \"%s\"\n", p.payload.bytes); @@ -188,7 +188,7 @@ bool RangeTestModuleRadio::appendFile(const meshtastic_MeshPacket &mp) #ifdef ARCH_ESP32 auto &p = mp.decoded; - meshtastic_NodeInfoLite *n = nodeDB.getMeshNode(getFrom(&mp)); + meshtastic_NodeInfoLite *n = nodeDB->getMeshNode(getFrom(&mp)); /* LOG_DEBUG("-----------------------------------------\n"); LOG_DEBUG("p.payload.bytes \"%s\"\n", p.payload.bytes); @@ -295,4 +295,4 @@ bool RangeTestModuleRadio::appendFile(const meshtastic_MeshPacket &mp) #endif return 1; -} +} \ No newline at end of file diff --git a/src/modules/RoutingModule.cpp b/src/modules/RoutingModule.cpp index 37a7c3755..a52328ca4 100644 --- a/src/modules/RoutingModule.cpp +++ b/src/modules/RoutingModule.cpp @@ -14,7 +14,7 @@ bool RoutingModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mesh // FIXME - move this to a non promsicious PhoneAPI module? // Note: we are careful not to send back packets that started with the phone back to the phone - if ((mp.to == NODENUM_BROADCAST || mp.to == nodeDB.getNodeNum()) && (mp.from != 0)) { + if ((mp.to == NODENUM_BROADCAST || mp.to == nodeDB->getNodeNum()) && (mp.from != 0)) { printPacket("Delivering rx packet", &mp); service.handleFromRadio(&mp); } @@ -63,4 +63,4 @@ RoutingModule::RoutingModule() : ProtobufModule("routing", meshtastic_PortNum_RO isPromiscuous = true; encryptedOk = config.device.rebroadcast_mode != meshtastic_Config_DeviceConfig_RebroadcastMode_LOCAL_ONLY && config.device.rebroadcast_mode != meshtastic_Config_DeviceConfig_RebroadcastMode_KNOWN_ONLY; -} +} \ No newline at end of file diff --git a/src/modules/SerialModule.cpp b/src/modules/SerialModule.cpp index 1dee42a8d..663bc1d86 100644 --- a/src/modules/SerialModule.cpp +++ b/src/modules/SerialModule.cpp @@ -190,11 +190,11 @@ int32_t SerialModule::runOnce() if (millis() - lastNmeaTime > 10000) { lastNmeaTime = millis(); uint32_t readIndex = 0; - const meshtastic_NodeInfoLite *tempNodeInfo = nodeDB.readNextMeshNode(readIndex); + const meshtastic_NodeInfoLite *tempNodeInfo = nodeDB->readNextMeshNode(readIndex); while (tempNodeInfo != NULL && tempNodeInfo->has_user && hasValidPosition(tempNodeInfo)) { printWPL(outbuf, sizeof(outbuf), tempNodeInfo->position, tempNodeInfo->user.long_name, true); serialPrint->printf("%s", outbuf); - tempNodeInfo = nodeDB.readNextMeshNode(readIndex); + tempNodeInfo = nodeDB->readNextMeshNode(readIndex); } } } @@ -265,9 +265,9 @@ ProcessMessage SerialModuleRadio::handleReceived(const meshtastic_MeshPacket &mp auto &p = mp.decoded; // LOG_DEBUG("Received text msg self=0x%0x, from=0x%0x, to=0x%0x, id=%d, msg=%.*s\n", - // nodeDB.getNodeNum(), mp.from, mp.to, mp.id, p.payload.size, p.payload.bytes); + // nodeDB->getNodeNum(), mp.from, mp.to, mp.id, p.payload.size, p.payload.bytes); - if (getFrom(&mp) == nodeDB.getNodeNum()) { + if (getFrom(&mp) == nodeDB->getNodeNum()) { /* * If moduleConfig.serial.echo is true, then echo the packets that are sent out @@ -290,7 +290,7 @@ ProcessMessage SerialModuleRadio::handleReceived(const meshtastic_MeshPacket &mp moduleConfig.serial.mode == meshtastic_ModuleConfig_SerialConfig_Serial_Mode_SIMPLE) { serialPrint->write(p.payload.bytes, p.payload.size); } else if (moduleConfig.serial.mode == meshtastic_ModuleConfig_SerialConfig_Serial_Mode_TEXTMSG) { - meshtastic_NodeInfoLite *node = nodeDB.getMeshNode(getFrom(&mp)); + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(getFrom(&mp)); String sender = (node && node->has_user) ? node->user.short_name : "???"; serialPrint->println(); serialPrint->printf("%s: %s", sender, p.payload.bytes); @@ -306,7 +306,7 @@ ProcessMessage SerialModuleRadio::handleReceived(const meshtastic_MeshPacket &mp decoded = &scratch; } // send position packet as WPL to the serial port - printWPL(outbuf, sizeof(outbuf), *decoded, nodeDB.getMeshNode(getFrom(&mp))->user.long_name, + printWPL(outbuf, sizeof(outbuf), *decoded, nodeDB->getMeshNode(getFrom(&mp))->user.long_name, moduleConfig.serial.mode == meshtastic_ModuleConfig_SerialConfig_Serial_Mode_CALTOPO); serialPrint->printf("%s", outbuf); } diff --git a/src/modules/Telemetry/DeviceTelemetry.cpp b/src/modules/Telemetry/DeviceTelemetry.cpp index 3ed106d1c..7c02b57b4 100644 --- a/src/modules/Telemetry/DeviceTelemetry.cpp +++ b/src/modules/Telemetry/DeviceTelemetry.cpp @@ -45,7 +45,7 @@ bool DeviceTelemetryModule::handleReceivedProtobuf(const meshtastic_MeshPacket & t->variant.device_metrics.air_util_tx, t->variant.device_metrics.channel_utilization, t->variant.device_metrics.battery_level, t->variant.device_metrics.voltage); #endif - nodeDB.updateTelemetry(getFrom(&mp), *t, RX_SRC_RADIO); + nodeDB->updateTelemetry(getFrom(&mp), *t, RX_SRC_RADIO); } return false; // Let others look at this message also if they want } @@ -94,7 +94,7 @@ bool DeviceTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly) p->decoded.want_response = false; p->priority = meshtastic_MeshPacket_Priority_BACKGROUND; - nodeDB.updateTelemetry(nodeDB.getNodeNum(), telemetry, RX_SRC_LOCAL); + nodeDB->updateTelemetry(nodeDB->getNodeNum(), telemetry, RX_SRC_LOCAL); if (phoneOnly) { LOG_INFO("Sending packet to phone\n"); service.sendToPhone(p); diff --git a/src/modules/esp32/AudioModule.cpp b/src/modules/esp32/AudioModule.cpp index a10cae954..4a7b1c2c6 100644 --- a/src/modules/esp32/AudioModule.cpp +++ b/src/modules/esp32/AudioModule.cpp @@ -1,4 +1,3 @@ - #include "configuration.h" #if defined(ARCH_ESP32) && defined(USE_SX1280) #include "AudioModule.h" @@ -274,7 +273,7 @@ ProcessMessage AudioModule::handleReceived(const meshtastic_MeshPacket &mp) { if ((moduleConfig.audio.codec2_enabled) && (myRegion->audioPermitted)) { auto &p = mp.decoded; - if (getFrom(&mp) != nodeDB.getNodeNum()) { + if (getFrom(&mp) != nodeDB->getNodeNum()) { memcpy(rx_encode_frame, p.payload.bytes, p.payload.size); radio_state = RadioState::rx; rx_encode_frame_index = p.payload.size; diff --git a/src/modules/esp32/StoreForwardModule.cpp b/src/modules/esp32/StoreForwardModule.cpp index 71d75750a..a60065e56 100644 --- a/src/modules/esp32/StoreForwardModule.cpp +++ b/src/modules/esp32/StoreForwardModule.cpp @@ -320,11 +320,11 @@ ProcessMessage StoreForwardModule::handleReceived(const meshtastic_MeshPacket &m if (moduleConfig.store_forward.enabled) { // The router node should not be sending messages as a client. Unless he is a ROUTER_CLIENT - if ((getFrom(&mp) != nodeDB.getNodeNum()) || (config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER_CLIENT)) { + if ((getFrom(&mp) != nodeDB->getNodeNum()) || (config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER_CLIENT)) { if ((mp.decoded.portnum == meshtastic_PortNum_TEXT_MESSAGE_APP) && is_server) { auto &p = mp.decoded; - if (mp.to == nodeDB.getNodeNum() && (p.payload.bytes[0] == 'S') && (p.payload.bytes[1] == 'F') && + if (mp.to == nodeDB->getNodeNum() && (p.payload.bytes[0] == 'S') && (p.payload.bytes[1] == 'F') && (p.payload.bytes[2] == 0x00)) { LOG_DEBUG("*** Legacy Request to send\n"); diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 7e341a18c..e29786dcb 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -135,7 +135,7 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length) // Generate an implicit ACK towards ourselves (handled and processed only locally!) for this message. // We do this because packets are not rebroadcasted back into MQTT anymore and we assume that at least one node // receives it when we get our own packet back. Then we'll stop our retransmissions. - if (e.packet && getFrom(e.packet) == nodeDB.getNodeNum()) + if (e.packet && getFrom(e.packet) == nodeDB->getNodeNum()) routingModule->sendAckNak(meshtastic_Routing_Error_NONE, getFrom(e.packet), e.packet->id, ch.index); else LOG_INFO("Ignoring downlink message we originally sent.\n"); @@ -556,7 +556,7 @@ void MQTT::perhapsReportToMap() // Allocate MeshPacket and fill it meshtastic_MeshPacket *mp = packetPool.allocZeroed(); mp->which_payload_variant = meshtastic_MeshPacket_decoded_tag; - mp->from = nodeDB.getNodeNum(); + mp->from = nodeDB->getNodeNum(); mp->to = NODENUM_BROADCAST; mp->decoded.portnum = meshtastic_PortNum_MAP_REPORT_APP; @@ -584,7 +584,7 @@ void MQTT::perhapsReportToMap() mapReport.altitude = localPosition.altitude; mapReport.position_precision = map_position_precision; - mapReport.num_online_local_nodes = nodeDB.getNumOnlineMeshNodes(true); + mapReport.num_online_local_nodes = nodeDB->getNumOnlineMeshNodes(true); // Encode MapReport message and set it to MeshPacket in ServiceEnvelope mp->decoded.payload.size = pb_encode_to_bytes(mp->decoded.payload.bytes, sizeof(mp->decoded.payload.bytes), @@ -794,7 +794,7 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp) // Lambda function for adding a long name to the route auto addToRoute = [](JSONArray *route, NodeNum num) { char long_name[40] = "Unknown"; - meshtastic_NodeInfoLite *node = nodeDB.getMeshNode(num); + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(num); bool name_known = node ? node->has_user : false; if (name_known) memcpy(long_name, node->user.long_name, sizeof(long_name)); @@ -900,7 +900,7 @@ bool MQTT::isValidJsonEnvelope(JSONObject &json) // if "sender" is provided, avoid processing packets we uplinked return (json.find("sender") != json.end() ? (json["sender"]->AsString().compare(owner.id) != 0) : true) && (json.find("from") != json.end()) && json["from"]->IsNumber() && - (json["from"]->AsNumber() == nodeDB.getNodeNum()) && // only accept message if the "from" is us + (json["from"]->AsNumber() == nodeDB->getNodeNum()) && // only accept message if the "from" is us (json.find("type") != json.end()) && json["type"]->IsString() && // should specify a type (json.find("payload") != json.end()); // should have a payload } \ No newline at end of file diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index 997058406..b255c0ce1 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -200,6 +200,8 @@ void portduinoSetup() settingsStrings[webserverrootpath] = (yamlConfig["Webserver"]["RootPath"]).as(""); } + settingsMap[maxnodes] = (yamlConfig["General"]["MaxNodes"]).as(200); + } catch (YAML::Exception e) { std::cout << "*** Exception " << e.what() << std::endl; exit(EXIT_FAILURE); diff --git a/src/platform/portduino/PortduinoGlue.h b/src/platform/portduino/PortduinoGlue.h index 3fe5f74bf..505c436d6 100644 --- a/src/platform/portduino/PortduinoGlue.h +++ b/src/platform/portduino/PortduinoGlue.h @@ -36,7 +36,8 @@ enum configNames { logoutputlevel, webserver, webserverport, - webserverrootpath + webserverrootpath, + maxnodes }; enum { no_screen, st7789, st7735, st7735s, ili9341 }; enum { no_touchscreen, xpt2046, stmpe610 }; diff --git a/src/shutdown.h b/src/shutdown.h index 6449b129e..21abba07e 100644 --- a/src/shutdown.h +++ b/src/shutdown.h @@ -26,6 +26,8 @@ void powerCommandsCheck() SPI.end(); Wire.end(); Serial1.end(); + if (screen) + delete screen; reboot(); #else rebootAtMsec = -1; diff --git a/src/sleep.cpp b/src/sleep.cpp index 6d8e4f3cc..f170e2ab7 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -198,7 +198,7 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) screen->doDeepSleep(); // datasheet says this will draw only 10ua - nodeDB.saveToDisk(); + nodeDB->saveToDisk(); #ifdef TTGO_T_ECHO #ifdef PIN_POWER_EN From fd26914d88be7fe8d5c00651659005b6049e0daa Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 21 Mar 2024 13:14:02 -0500 Subject: [PATCH 352/472] move nodeDB::init code into nodeDB constructor (#3455) --- src/main.cpp | 2 +- src/mesh/NodeDB.cpp | 119 +++++++++++++++++++++----------------------- src/mesh/NodeDB.h | 3 -- 3 files changed, 58 insertions(+), 66 deletions(-) diff --git a/src/main.cpp b/src/main.cpp index e09af0c9a..5f746f12a 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -556,7 +556,7 @@ void setup() // We do this as early as possible because this loads preferences from flash // but we need to do this after main cpu init (esp32setup), because we need the random seed set - nodeDB = NodeDB::init(); + nodeDB = new NodeDB; // If we're taking on the repeater role, use flood router and turn off 3V3_S rail because peripherals are not needed if (config.device.role == meshtastic_Config_DeviceConfig_Role_REPEATER) { diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 37232e6ed..6db8fc50b 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -92,7 +92,63 @@ uint32_t error_address = 0; static uint8_t ourMacAddr[6]; -NodeDB::NodeDB() {} +NodeDB::NodeDB() +{ + LOG_INFO("Initializing NodeDB\n"); + loadFromDisk(); + cleanupMeshDB(); + + uint32_t devicestateCRC = crc32Buffer(&devicestate, sizeof(devicestate)); + uint32_t configCRC = crc32Buffer(&config, sizeof(config)); + uint32_t channelFileCRC = crc32Buffer(&channelFile, sizeof(channelFile)); + + int saveWhat = 0; + + // likewise - we always want the app requirements to come from the running appload + myNodeInfo.min_app_version = 30200; // format is Mmmss (where M is 1+the numeric major number. i.e. 30200 means 2.2.00 + // Note! We do this after loading saved settings, so that if somehow an invalid nodenum was stored in preferences we won't + // keep using that nodenum forever. Crummy guess at our nodenum (but we will check against the nodedb to avoid conflicts) + pickNewNodeNum(); + + // Set our board type so we can share it with others + owner.hw_model = HW_VENDOR; + // Ensure user (nodeinfo) role is set to whatever we're configured to + owner.role = config.device.role; + + // Include our owner in the node db under our nodenum + meshtastic_NodeInfoLite *info = getOrCreateMeshNode(getNodeNum()); + info->user = owner; + info->has_user = true; + +#ifdef ARCH_ESP32 + Preferences preferences; + preferences.begin("meshtastic", false); + myNodeInfo.reboot_count = preferences.getUInt("rebootCounter", 0); + preferences.end(); + LOG_DEBUG("Number of Device Reboots: %d\n", myNodeInfo.reboot_count); +#endif + + resetRadioConfig(); // If bogus settings got saved, then fix them + // nodeDB->LOG_DEBUG("region=%d, NODENUM=0x%x, dbsize=%d\n", config.lora.region, myNodeInfo.my_node_num, numMeshNodes); + + if (devicestateCRC != crc32Buffer(&devicestate, sizeof(devicestate))) + saveWhat |= SEGMENT_DEVICESTATE; + if (configCRC != crc32Buffer(&config, sizeof(config))) + saveWhat |= SEGMENT_CONFIG; + if (channelFileCRC != crc32Buffer(&channelFile, sizeof(channelFile))) + saveWhat |= SEGMENT_CHANNELS; + + if (!devicestate.node_remote_hardware_pins) { + meshtastic_NodeRemoteHardwarePin empty[12] = {meshtastic_RemoteHardwarePin_init_default}; + memcpy(devicestate.node_remote_hardware_pins, empty, sizeof(empty)); + } + + if (config.position.gps_enabled) { + config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_ENABLED; + config.position.gps_enabled = 0; + } + saveToDisk(saveWhat); +} /** * Most (but not always) of the time we want to treat packets 'from' the local phone (where from == 0), as if they originated on @@ -439,67 +495,6 @@ void NodeDB::installDefaultDeviceState() memcpy(owner.macaddr, ourMacAddr, sizeof(owner.macaddr)); } -NodeDB *NodeDB::init() -{ - LOG_INFO("Initializing NodeDB\n"); - NodeDB *newnodeDB = new NodeDB; - newnodeDB->loadFromDisk(); - newnodeDB->cleanupMeshDB(); - - uint32_t devicestateCRC = crc32Buffer(&devicestate, sizeof(devicestate)); - uint32_t configCRC = crc32Buffer(&config, sizeof(config)); - uint32_t channelFileCRC = crc32Buffer(&channelFile, sizeof(channelFile)); - - int saveWhat = 0; - - // likewise - we always want the app requirements to come from the running appload - myNodeInfo.min_app_version = 30200; // format is Mmmss (where M is 1+the numeric major number. i.e. 30200 means 2.2.00 - // Note! We do this after loading saved settings, so that if somehow an invalid nodenum was stored in preferences we won't - // keep using that nodenum forever. Crummy guess at our nodenum (but we will check against the nodedb to avoid conflicts) - newnodeDB->pickNewNodeNum(); - - // Set our board type so we can share it with others - owner.hw_model = HW_VENDOR; - // Ensure user (nodeinfo) role is set to whatever we're configured to - owner.role = config.device.role; - - // Include our owner in the node db under our nodenum - meshtastic_NodeInfoLite *info = newnodeDB->getOrCreateMeshNode(newnodeDB->getNodeNum()); - info->user = owner; - info->has_user = true; - -#ifdef ARCH_ESP32 - Preferences preferences; - preferences.begin("meshtastic", false); - myNodeInfo.reboot_count = preferences.getUInt("rebootCounter", 0); - preferences.end(); - LOG_DEBUG("Number of Device Reboots: %d\n", myNodeInfo.reboot_count); -#endif - - newnodeDB->resetRadioConfig(); // If bogus settings got saved, then fix them - // nodeDB->LOG_DEBUG("region=%d, NODENUM=0x%x, dbsize=%d\n", config.lora.region, myNodeInfo.my_node_num, numMeshNodes); - - if (devicestateCRC != crc32Buffer(&devicestate, sizeof(devicestate))) - saveWhat |= SEGMENT_DEVICESTATE; - if (configCRC != crc32Buffer(&config, sizeof(config))) - saveWhat |= SEGMENT_CONFIG; - if (channelFileCRC != crc32Buffer(&channelFile, sizeof(channelFile))) - saveWhat |= SEGMENT_CHANNELS; - - if (!devicestate.node_remote_hardware_pins) { - meshtastic_NodeRemoteHardwarePin empty[12] = {meshtastic_RemoteHardwarePin_init_default}; - memcpy(devicestate.node_remote_hardware_pins, empty, sizeof(empty)); - } - - if (config.position.gps_enabled) { - config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_ENABLED; - config.position.gps_enabled = 0; - } - return newnodeDB; - - nodeDB->saveToDisk(saveWhat); -} - // We reserve a few nodenums for future use #define NUM_RESERVED 4 diff --git a/src/mesh/NodeDB.h b/src/mesh/NodeDB.h index ea2019c37..23870db74 100644 --- a/src/mesh/NodeDB.h +++ b/src/mesh/NodeDB.h @@ -58,9 +58,6 @@ class NodeDB /// instead just store in flash - possibly even in the initial alpha release do this hack NodeDB(); - /// Called from service after app start, to do init which can only be done after OS load - static NodeDB *init(); - /// write to flash void saveToDisk(int saveWhat = SEGMENT_CONFIG | SEGMENT_MODULECONFIG | SEGMENT_DEVICESTATE | SEGMENT_CHANNELS), saveChannelsToDisk(), saveDeviceStateToDisk(); From 4debcd5ccd59eae3741789ce77d4c77f0567b17b Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Thu, 21 Mar 2024 20:35:17 +0100 Subject: [PATCH 353/472] Set default position precision of mapReport to 14 (#3456) --- src/mqtt/MQTT.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/mqtt/MQTT.h b/src/mqtt/MQTT.h index dbc0c77b3..41b1601e7 100644 --- a/src/mqtt/MQTT.h +++ b/src/mqtt/MQTT.h @@ -90,8 +90,8 @@ class MQTT : private concurrency::OSThread // For map reporting (only applies when enabled) uint32_t last_report_to_map = 0; - uint32_t map_position_precision = 32; // default to full precision - uint32_t map_publish_interval_secs = 60 * 15; // default to 15 minutes + uint32_t map_position_precision = 14; // defaults to max. offset of ~1459m + uint32_t map_publish_interval_secs = 60 * 15; // defaults to 15 minutes /** return true if we have a channel that wants uplink/downlink or map reporting is enabled */ From 0a7ddb7594d4a8c514ba29b592df3039079fb7cd Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Thu, 21 Mar 2024 20:42:53 +0100 Subject: [PATCH 354/472] Let NeighborInfo Module ignore packets coming from MQTT (#3457) --- src/modules/NeighborInfoModule.h | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/modules/NeighborInfoModule.h b/src/modules/NeighborInfoModule.h index df5c2c948..820e2d0d4 100644 --- a/src/modules/NeighborInfoModule.h +++ b/src/modules/NeighborInfoModule.h @@ -75,8 +75,9 @@ class NeighborInfoModule : public ProtobufModule, priva /* Does our periodic broadcast */ int32_t runOnce() override; - // Override wantPacket to say we want to see all packets when enabled, not just those for our port number - virtual bool wantPacket(const meshtastic_MeshPacket *p) override { return enabled; } + /* Override wantPacket to say we want to see all packets when enabled, not just those for our port number. + Exception is when the packet came via MQTT */ + virtual bool wantPacket(const meshtastic_MeshPacket *p) override { return enabled && !p->via_mqtt; } /* These are for debugging only */ void printNeighborInfo(const char *header, const meshtastic_NeighborInfo *np); From 6dd337a651ffafd81f47a530a41ee23bfce286e1 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 21 Mar 2024 14:43:10 -0500 Subject: [PATCH 355/472] Clear local position on nodedb-reset (#3451) * Clear local position on nodedb-reset * NodeDB pointer now, yo --------- Co-authored-by: Jonathan Bennett --- src/mesh/NodeDB.cpp | 11 +++++++++++ src/mesh/NodeDB.h | 2 ++ src/modules/PositionModule.cpp | 14 ++------------ src/modules/PositionModule.h | 3 --- 4 files changed, 15 insertions(+), 15 deletions(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 6db8fc50b..80b46a426 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -434,6 +434,7 @@ void NodeDB::resetNodes() { numMeshNodes = 1; std::fill(devicestate.node_db_lite.begin() + 1, devicestate.node_db_lite.end(), meshtastic_NodeInfoLite()); + clearLocalPosition(); saveDeviceStateToDisk(); if (neighborInfoModule && moduleConfig.neighbor_info.enabled) neighborInfoModule->resetNeighbors(); @@ -455,6 +456,16 @@ void NodeDB::removeNodeByNum(uint nodeNum) saveDeviceStateToDisk(); } +void NodeDB::clearLocalPosition() +{ + meshtastic_NodeInfoLite *node = getMeshNode(nodeDB->getNodeNum()); + node->position.latitude_i = 0; + node->position.longitude_i = 0; + node->position.altitude = 0; + node->position.time = 0; + setLocalPosition(meshtastic_Position_init_default); +} + void NodeDB::cleanupMeshDB() { int newPos = 0, removed = 0; diff --git a/src/mesh/NodeDB.h b/src/mesh/NodeDB.h index 23870db74..4d24d7225 100644 --- a/src/mesh/NodeDB.h +++ b/src/mesh/NodeDB.h @@ -131,6 +131,8 @@ class NodeDB meshtastic_NodeInfoLite *getMeshNode(NodeNum n); size_t getNumMeshNodes() { return numMeshNodes; } + void clearLocalPosition(); + void setLocalPosition(meshtastic_Position position, bool timeOnly = false) { if (timeOnly) { diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index 0bfc775da..d22c6b699 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -34,21 +34,11 @@ PositionModule::PositionModule() if ((config.device.role == meshtastic_Config_DeviceConfig_Role_TRACKER || config.device.role == meshtastic_Config_DeviceConfig_Role_TAK_TRACKER) && config.power.is_power_saving) { - clearPosition(); + LOG_DEBUG("Clearing position on startup for sleepy tracker (ー。ー) zzz\n"); + nodeDB->clearLocalPosition(); } } -void PositionModule::clearPosition() -{ - LOG_DEBUG("Clearing position on startup for sleepy tracker (ー。ー) zzz\n"); - meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(nodeDB->getNodeNum()); - node->position.latitude_i = 0; - node->position.longitude_i = 0; - node->position.altitude = 0; - node->position.time = 0; - nodeDB->setLocalPosition(meshtastic_Position_init_default); -} - bool PositionModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_Position *pptr) { auto p = *pptr; diff --git a/src/modules/PositionModule.h b/src/modules/PositionModule.h index fddafef6f..68171ab0e 100644 --- a/src/modules/PositionModule.h +++ b/src/modules/PositionModule.h @@ -51,9 +51,6 @@ class PositionModule : public ProtobufModule, private concu struct SmartPosition getDistanceTraveledSinceLastSend(meshtastic_PositionLite currentPosition); meshtastic_MeshPacket *allocAtakPli(); uint32_t precision; - - /** Only used in power saving trackers for now */ - void clearPosition(); void sendLostAndFoundText(); }; From defeb8e52bab51eff5ab990119a0976f43730482 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 21 Mar 2024 15:24:57 -0500 Subject: [PATCH 356/472] Bump actions to node 20 (#3461) --- .github/actions/setup-base/action.yml | 6 +++--- .github/workflows/build_esp32.yml | 4 ++-- .github/workflows/build_esp32_c3.yml | 4 ++-- .github/workflows/build_esp32_s3.yml | 4 ++-- .github/workflows/build_nrf52.yml | 4 ++-- .github/workflows/build_raspbian.yml | 4 ++-- .github/workflows/build_rpi2040.yml | 4 ++-- .github/workflows/main_matrix.yml | 18 +++++++++--------- .github/workflows/nightly.yml | 2 +- .github/workflows/package_raspbian.yml | 4 ++-- .github/workflows/sec_sast_flawfinder.yml | 4 ++-- .github/workflows/sec_sast_semgrep_cron.yml | 4 ++-- .github/workflows/sec_sast_semgrep_pull.yml | 2 +- .github/workflows/trunk-check.yml | 2 +- .github/workflows/update_protobufs.yml | 2 +- 15 files changed, 34 insertions(+), 34 deletions(-) diff --git a/.github/actions/setup-base/action.yml b/.github/actions/setup-base/action.yml index 7b97e1753..7e57f6a31 100644 --- a/.github/actions/setup-base/action.yml +++ b/.github/actions/setup-base/action.yml @@ -5,7 +5,7 @@ runs: using: "composite" steps: - name: Checkout code - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: submodules: "recursive" ref: ${{github.event.pull_request.head.ref}} @@ -30,12 +30,12 @@ runs: sudo apt-get install -y libyaml-cpp-dev - name: Setup Python - uses: actions/setup-python@v4 + uses: actions/setup-python@v5 with: python-version: 3.x - name: Cache python libs - uses: actions/cache@v3 + uses: actions/cache@v4 id: cache-pip # needed in if test with: path: ~/.cache/pip diff --git a/.github/workflows/build_esp32.yml b/.github/workflows/build_esp32.yml index 31f0dd5a0..1a07d5f28 100644 --- a/.github/workflows/build_esp32.yml +++ b/.github/workflows/build_esp32.yml @@ -11,7 +11,7 @@ jobs: build-esp32: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Build base id: base uses: ./.github/actions/setup-base @@ -54,7 +54,7 @@ jobs: id: version - name: Store binaries as an artifact - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: firmware-${{ inputs.board }}-${{ steps.version.outputs.version }}.zip path: | diff --git a/.github/workflows/build_esp32_c3.yml b/.github/workflows/build_esp32_c3.yml index a30cf33f1..cdb8427c1 100644 --- a/.github/workflows/build_esp32_c3.yml +++ b/.github/workflows/build_esp32_c3.yml @@ -13,7 +13,7 @@ jobs: build-esp32-c3: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Build base id: base uses: ./.github/actions/setup-base @@ -54,7 +54,7 @@ jobs: id: version - name: Store binaries as an artifact - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: firmware-${{ inputs.board }}-${{ steps.version.outputs.version }}.zip path: | diff --git a/.github/workflows/build_esp32_s3.yml b/.github/workflows/build_esp32_s3.yml index f603a6a31..502a319c5 100644 --- a/.github/workflows/build_esp32_s3.yml +++ b/.github/workflows/build_esp32_s3.yml @@ -11,7 +11,7 @@ jobs: build-esp32-s3: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Build base id: base uses: ./.github/actions/setup-base @@ -52,7 +52,7 @@ jobs: id: version - name: Store binaries as an artifact - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: firmware-${{ inputs.board }}-${{ steps.version.outputs.version }}.zip path: | diff --git a/.github/workflows/build_nrf52.yml b/.github/workflows/build_nrf52.yml index 33ee4d00c..a37547973 100644 --- a/.github/workflows/build_nrf52.yml +++ b/.github/workflows/build_nrf52.yml @@ -11,7 +11,7 @@ jobs: build-nrf52: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Build base id: base uses: ./.github/actions/setup-base @@ -24,7 +24,7 @@ jobs: id: version - name: Store binaries as an artifact - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: firmware-${{ inputs.board }}-${{ steps.version.outputs.version }}.zip path: | diff --git a/.github/workflows/build_raspbian.yml b/.github/workflows/build_raspbian.yml index 7a25892bc..04aa2340b 100644 --- a/.github/workflows/build_raspbian.yml +++ b/.github/workflows/build_raspbian.yml @@ -11,7 +11,7 @@ jobs: runs-on: [self-hosted, linux, ARM64] steps: - name: Checkout code - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: submodules: recursive ref: ${{github.event.pull_request.head.ref}} @@ -37,7 +37,7 @@ jobs: id: version - name: Store binaries as an artifact - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: firmware-raspbian-${{ steps.version.outputs.version }}.zip path: | diff --git a/.github/workflows/build_rpi2040.yml b/.github/workflows/build_rpi2040.yml index 76ca2c20e..aac70610f 100644 --- a/.github/workflows/build_rpi2040.yml +++ b/.github/workflows/build_rpi2040.yml @@ -11,7 +11,7 @@ jobs: build-rpi2040: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Build base id: base uses: ./.github/actions/setup-base @@ -24,7 +24,7 @@ jobs: id: version - name: Store binaries as an artifact - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: firmware-${{ inputs.board }}-${{ steps.version.outputs.version }}.zip path: | diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 03d47f18e..d1c01a366 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -42,7 +42,7 @@ jobs: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Build base id: base uses: ./.github/actions/setup-base @@ -157,7 +157,7 @@ jobs: build-native: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Build base id: base uses: ./.github/actions/setup-base @@ -180,7 +180,7 @@ jobs: id: version - name: Store binaries as an artifact - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: firmware-native-${{ steps.version.outputs.version }}.zip path: | @@ -221,7 +221,7 @@ jobs: needs: [check] steps: - name: Checkout code - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: ref: ${{github.event.pull_request.head.ref}} repository: ${{github.event.pull_request.head.repo.full_name}} @@ -244,7 +244,7 @@ jobs: ] steps: - name: Checkout code - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: ref: ${{github.event.pull_request.head.ref}} repository: ${{github.event.pull_request.head.repo.full_name}} @@ -264,7 +264,7 @@ jobs: run: mv -b -t ./ ./*tbeam-2*/littlefs*.bin ./*tbeam-2*/bleota.bin ./*tbeam-s3*/bleota-s3.bin ./*esp32c3*/bleota-c3.bin ./**/firmware*.bin ./*t-echo*/Meshtastic_nRF52_factory_erase_v2.uf2 ./**/firmware-*.uf2 ./**/firmware-*-ota.zip ./**/*.elf ./*native*/*device-*.sh ./*native*/*device-*.bat ./firmware-raspbian-*/release/meshtasticd_linux_aarch64 ./firmware-raspbian-*/bin/config-dist.yaml - name: Repackage in single firmware zip - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: firmware-${{ steps.version.outputs.version }} path: | @@ -295,7 +295,7 @@ jobs: run: zip -j -9 -r ./firmware-${{ steps.version.outputs.version }}.zip ./output - name: Repackage in single elfs zip - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: debug-elfs-${{ steps.version.outputs.version }}.zip path: ./*.elf @@ -319,10 +319,10 @@ jobs: needs: [gather-artifacts, after-checks] steps: - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Setup Python - uses: actions/setup-python@v4 + uses: actions/setup-python@v5 with: python-version: 3.x diff --git a/.github/workflows/nightly.yml b/.github/workflows/nightly.yml index da59bc0fd..e249823a7 100644 --- a/.github/workflows/nightly.yml +++ b/.github/workflows/nightly.yml @@ -11,7 +11,7 @@ jobs: steps: - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Trunk Check uses: trunk-io/trunk-action@782e83f803ca6e369f035d64c6ba2768174ba61b diff --git a/.github/workflows/package_raspbian.yml b/.github/workflows/package_raspbian.yml index 377074e95..6c1ae5d60 100644 --- a/.github/workflows/package_raspbian.yml +++ b/.github/workflows/package_raspbian.yml @@ -17,7 +17,7 @@ jobs: needs: build-raspbian steps: - name: Checkout code - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: submodules: recursive ref: ${{github.event.pull_request.head.ref}} @@ -66,7 +66,7 @@ jobs: depends: libyaml-cpp0.7, openssl desc: Native Linux Meshtastic binary. - - uses: actions/upload-artifact@v3 + - uses: actions/upload-artifact@v4 with: name: artifact-deb path: | diff --git a/.github/workflows/sec_sast_flawfinder.yml b/.github/workflows/sec_sast_flawfinder.yml index 2c7e751af..59ff994ca 100644 --- a/.github/workflows/sec_sast_flawfinder.yml +++ b/.github/workflows/sec_sast_flawfinder.yml @@ -16,7 +16,7 @@ jobs: steps: # step 1 - name: clone application source code - uses: actions/checkout@v3 + uses: actions/checkout@v4 # step 2 - name: flawfinder_scan @@ -27,7 +27,7 @@ jobs: # step 3 - name: save report as pipeline artifact - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: flawfinder_report.sarif path: flawfinder_report.sarif diff --git a/.github/workflows/sec_sast_semgrep_cron.yml b/.github/workflows/sec_sast_semgrep_cron.yml index cdd2c3c37..a29e6ca02 100644 --- a/.github/workflows/sec_sast_semgrep_cron.yml +++ b/.github/workflows/sec_sast_semgrep_cron.yml @@ -17,7 +17,7 @@ jobs: steps: # step 1 - name: clone application source code - uses: actions/checkout@v3 + uses: actions/checkout@v4 # step 2 - name: full scan @@ -29,7 +29,7 @@ jobs: # step 3 - name: save report as pipeline artifact - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: report.sarif path: report.sarif diff --git a/.github/workflows/sec_sast_semgrep_pull.yml b/.github/workflows/sec_sast_semgrep_pull.yml index 1697ffb1b..b6c288494 100644 --- a/.github/workflows/sec_sast_semgrep_pull.yml +++ b/.github/workflows/sec_sast_semgrep_pull.yml @@ -11,7 +11,7 @@ jobs: steps: # step 1 - name: clone application source code - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: fetch-depth: 0 diff --git a/.github/workflows/trunk-check.yml b/.github/workflows/trunk-check.yml index e35b91cb9..6ed905bc8 100644 --- a/.github/workflows/trunk-check.yml +++ b/.github/workflows/trunk-check.yml @@ -16,7 +16,7 @@ jobs: steps: - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Trunk Check uses: trunk-io/trunk-action@v1 diff --git a/.github/workflows/update_protobufs.yml b/.github/workflows/update_protobufs.yml index 6944d827e..4c51c35c7 100644 --- a/.github/workflows/update_protobufs.yml +++ b/.github/workflows/update_protobufs.yml @@ -7,7 +7,7 @@ jobs: steps: - name: Checkout code - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: submodules: true From 9c88906acc1e910e49402bd474c7390be157a9f4 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 21 Mar 2024 16:14:45 -0500 Subject: [PATCH 357/472] Remove double run of build-raspbian --- .github/workflows/main_matrix.yml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index d1c01a366..c145feca2 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -145,11 +145,11 @@ jobs: with: board: ${{ matrix.board }} - build-raspbian: - strategy: - fail-fast: false - max-parallel: 1 - uses: ./.github/workflows/build_raspbian.yml + #build-raspbian: + # strategy: + # fail-fast: false + # max-parallel: 1 + # uses: ./.github/workflows/build_raspbian.yml package-raspbian: uses: ./.github/workflows/package_raspbian.yml From 907d075917209291338de769dedb667cfa6faf9e Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 21 Mar 2024 16:17:13 -0500 Subject: [PATCH 358/472] Revert previous attempt --- .github/workflows/main_matrix.yml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index c145feca2..d1c01a366 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -145,11 +145,11 @@ jobs: with: board: ${{ matrix.board }} - #build-raspbian: - # strategy: - # fail-fast: false - # max-parallel: 1 - # uses: ./.github/workflows/build_raspbian.yml + build-raspbian: + strategy: + fail-fast: false + max-parallel: 1 + uses: ./.github/workflows/build_raspbian.yml package-raspbian: uses: ./.github/workflows/package_raspbian.yml From 155df45d92fd23d86926d8ae46876b102b8b4b23 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Thu, 21 Mar 2024 22:20:20 +0100 Subject: [PATCH 359/472] Add sanity check for map report interval and position precision (#3459) * Add sanity check for map report interval and position precision * Use new `Default::` methods --- src/mqtt/MQTT.cpp | 8 +++++--- src/mqtt/MQTT.h | 6 ++++-- 2 files changed, 9 insertions(+), 5 deletions(-) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index e29786dcb..390d0e206 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -195,8 +195,10 @@ MQTT::MQTT() : concurrency::OSThread("mqtt"), mqttQueue(MAX_MQTT_QUEUE) } if (moduleConfig.mqtt.map_reporting_enabled && moduleConfig.mqtt.has_map_report_settings) { - map_position_precision = moduleConfig.mqtt.map_report_settings.position_precision; - map_publish_interval_secs = moduleConfig.mqtt.map_report_settings.publish_interval_secs; + map_position_precision = Default::getConfiguredOrDefault(moduleConfig.mqtt.map_report_settings.position_precision, + default_map_position_precision); + map_publish_interval_msecs = Default::getConfiguredOrDefaultMs( + moduleConfig.mqtt.map_report_settings.publish_interval_secs, default_map_publish_interval_secs); } #ifdef HAS_NETWORKING @@ -540,7 +542,7 @@ void MQTT::perhapsReportToMap() if (!moduleConfig.mqtt.map_reporting_enabled || !(moduleConfig.mqtt.proxy_to_client_enabled || isConnectedDirectly())) return; - if (millis() - last_report_to_map < map_publish_interval_secs * 1000) { + if (millis() - last_report_to_map < map_publish_interval_msecs) { return; } else { if (map_position_precision == 0 || (localPosition.latitude_i == 0 && localPosition.longitude_i == 0)) { diff --git a/src/mqtt/MQTT.h b/src/mqtt/MQTT.h index 41b1601e7..f2eb6b120 100644 --- a/src/mqtt/MQTT.h +++ b/src/mqtt/MQTT.h @@ -89,9 +89,11 @@ class MQTT : private concurrency::OSThread std::string mapTopic = "/2/map/"; // For protobuf-encoded MapReport messages // For map reporting (only applies when enabled) + const uint32_t default_map_position_precision = 14; // defaults to max. offset of ~1459m + const uint32_t default_map_publish_interval_secs = 60 * 15; // defaults to 15 minutes uint32_t last_report_to_map = 0; - uint32_t map_position_precision = 14; // defaults to max. offset of ~1459m - uint32_t map_publish_interval_secs = 60 * 15; // defaults to 15 minutes + uint32_t map_position_precision = default_map_position_precision; + uint32_t map_publish_interval_msecs = default_map_publish_interval_secs * 1000; /** return true if we have a channel that wants uplink/downlink or map reporting is enabled */ From 79cfb1e8769bfd258f91dd9193c42d424e8c450e Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 21 Mar 2024 16:50:44 -0500 Subject: [PATCH 360/472] Revert "Bump actions to node 20 (#3461)" (#3462) This reverts commit defeb8e52bab51eff5ab990119a0976f43730482. As per https://github.com/actions/upload-artifact/issues/478 the new version of upload-artifact includes a breaking change. --- .github/actions/setup-base/action.yml | 6 +++--- .github/workflows/build_esp32.yml | 4 ++-- .github/workflows/build_esp32_c3.yml | 4 ++-- .github/workflows/build_esp32_s3.yml | 4 ++-- .github/workflows/build_nrf52.yml | 4 ++-- .github/workflows/build_raspbian.yml | 4 ++-- .github/workflows/build_rpi2040.yml | 4 ++-- .github/workflows/main_matrix.yml | 18 +++++++++--------- .github/workflows/nightly.yml | 2 +- .github/workflows/package_raspbian.yml | 4 ++-- .github/workflows/sec_sast_flawfinder.yml | 4 ++-- .github/workflows/sec_sast_semgrep_cron.yml | 4 ++-- .github/workflows/sec_sast_semgrep_pull.yml | 2 +- .github/workflows/trunk-check.yml | 2 +- .github/workflows/update_protobufs.yml | 2 +- 15 files changed, 34 insertions(+), 34 deletions(-) diff --git a/.github/actions/setup-base/action.yml b/.github/actions/setup-base/action.yml index 7e57f6a31..7b97e1753 100644 --- a/.github/actions/setup-base/action.yml +++ b/.github/actions/setup-base/action.yml @@ -5,7 +5,7 @@ runs: using: "composite" steps: - name: Checkout code - uses: actions/checkout@v4 + uses: actions/checkout@v3 with: submodules: "recursive" ref: ${{github.event.pull_request.head.ref}} @@ -30,12 +30,12 @@ runs: sudo apt-get install -y libyaml-cpp-dev - name: Setup Python - uses: actions/setup-python@v5 + uses: actions/setup-python@v4 with: python-version: 3.x - name: Cache python libs - uses: actions/cache@v4 + uses: actions/cache@v3 id: cache-pip # needed in if test with: path: ~/.cache/pip diff --git a/.github/workflows/build_esp32.yml b/.github/workflows/build_esp32.yml index 1a07d5f28..31f0dd5a0 100644 --- a/.github/workflows/build_esp32.yml +++ b/.github/workflows/build_esp32.yml @@ -11,7 +11,7 @@ jobs: build-esp32: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v3 - name: Build base id: base uses: ./.github/actions/setup-base @@ -54,7 +54,7 @@ jobs: id: version - name: Store binaries as an artifact - uses: actions/upload-artifact@v4 + uses: actions/upload-artifact@v3 with: name: firmware-${{ inputs.board }}-${{ steps.version.outputs.version }}.zip path: | diff --git a/.github/workflows/build_esp32_c3.yml b/.github/workflows/build_esp32_c3.yml index cdb8427c1..a30cf33f1 100644 --- a/.github/workflows/build_esp32_c3.yml +++ b/.github/workflows/build_esp32_c3.yml @@ -13,7 +13,7 @@ jobs: build-esp32-c3: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v3 - name: Build base id: base uses: ./.github/actions/setup-base @@ -54,7 +54,7 @@ jobs: id: version - name: Store binaries as an artifact - uses: actions/upload-artifact@v4 + uses: actions/upload-artifact@v3 with: name: firmware-${{ inputs.board }}-${{ steps.version.outputs.version }}.zip path: | diff --git a/.github/workflows/build_esp32_s3.yml b/.github/workflows/build_esp32_s3.yml index 502a319c5..f603a6a31 100644 --- a/.github/workflows/build_esp32_s3.yml +++ b/.github/workflows/build_esp32_s3.yml @@ -11,7 +11,7 @@ jobs: build-esp32-s3: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v3 - name: Build base id: base uses: ./.github/actions/setup-base @@ -52,7 +52,7 @@ jobs: id: version - name: Store binaries as an artifact - uses: actions/upload-artifact@v4 + uses: actions/upload-artifact@v3 with: name: firmware-${{ inputs.board }}-${{ steps.version.outputs.version }}.zip path: | diff --git a/.github/workflows/build_nrf52.yml b/.github/workflows/build_nrf52.yml index a37547973..33ee4d00c 100644 --- a/.github/workflows/build_nrf52.yml +++ b/.github/workflows/build_nrf52.yml @@ -11,7 +11,7 @@ jobs: build-nrf52: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v3 - name: Build base id: base uses: ./.github/actions/setup-base @@ -24,7 +24,7 @@ jobs: id: version - name: Store binaries as an artifact - uses: actions/upload-artifact@v4 + uses: actions/upload-artifact@v3 with: name: firmware-${{ inputs.board }}-${{ steps.version.outputs.version }}.zip path: | diff --git a/.github/workflows/build_raspbian.yml b/.github/workflows/build_raspbian.yml index 04aa2340b..7a25892bc 100644 --- a/.github/workflows/build_raspbian.yml +++ b/.github/workflows/build_raspbian.yml @@ -11,7 +11,7 @@ jobs: runs-on: [self-hosted, linux, ARM64] steps: - name: Checkout code - uses: actions/checkout@v4 + uses: actions/checkout@v3 with: submodules: recursive ref: ${{github.event.pull_request.head.ref}} @@ -37,7 +37,7 @@ jobs: id: version - name: Store binaries as an artifact - uses: actions/upload-artifact@v4 + uses: actions/upload-artifact@v3 with: name: firmware-raspbian-${{ steps.version.outputs.version }}.zip path: | diff --git a/.github/workflows/build_rpi2040.yml b/.github/workflows/build_rpi2040.yml index aac70610f..76ca2c20e 100644 --- a/.github/workflows/build_rpi2040.yml +++ b/.github/workflows/build_rpi2040.yml @@ -11,7 +11,7 @@ jobs: build-rpi2040: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v3 - name: Build base id: base uses: ./.github/actions/setup-base @@ -24,7 +24,7 @@ jobs: id: version - name: Store binaries as an artifact - uses: actions/upload-artifact@v4 + uses: actions/upload-artifact@v3 with: name: firmware-${{ inputs.board }}-${{ steps.version.outputs.version }}.zip path: | diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index d1c01a366..03d47f18e 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -42,7 +42,7 @@ jobs: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v3 - name: Build base id: base uses: ./.github/actions/setup-base @@ -157,7 +157,7 @@ jobs: build-native: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v3 - name: Build base id: base uses: ./.github/actions/setup-base @@ -180,7 +180,7 @@ jobs: id: version - name: Store binaries as an artifact - uses: actions/upload-artifact@v4 + uses: actions/upload-artifact@v3 with: name: firmware-native-${{ steps.version.outputs.version }}.zip path: | @@ -221,7 +221,7 @@ jobs: needs: [check] steps: - name: Checkout code - uses: actions/checkout@v4 + uses: actions/checkout@v3 with: ref: ${{github.event.pull_request.head.ref}} repository: ${{github.event.pull_request.head.repo.full_name}} @@ -244,7 +244,7 @@ jobs: ] steps: - name: Checkout code - uses: actions/checkout@v4 + uses: actions/checkout@v3 with: ref: ${{github.event.pull_request.head.ref}} repository: ${{github.event.pull_request.head.repo.full_name}} @@ -264,7 +264,7 @@ jobs: run: mv -b -t ./ ./*tbeam-2*/littlefs*.bin ./*tbeam-2*/bleota.bin ./*tbeam-s3*/bleota-s3.bin ./*esp32c3*/bleota-c3.bin ./**/firmware*.bin ./*t-echo*/Meshtastic_nRF52_factory_erase_v2.uf2 ./**/firmware-*.uf2 ./**/firmware-*-ota.zip ./**/*.elf ./*native*/*device-*.sh ./*native*/*device-*.bat ./firmware-raspbian-*/release/meshtasticd_linux_aarch64 ./firmware-raspbian-*/bin/config-dist.yaml - name: Repackage in single firmware zip - uses: actions/upload-artifact@v4 + uses: actions/upload-artifact@v3 with: name: firmware-${{ steps.version.outputs.version }} path: | @@ -295,7 +295,7 @@ jobs: run: zip -j -9 -r ./firmware-${{ steps.version.outputs.version }}.zip ./output - name: Repackage in single elfs zip - uses: actions/upload-artifact@v4 + uses: actions/upload-artifact@v3 with: name: debug-elfs-${{ steps.version.outputs.version }}.zip path: ./*.elf @@ -319,10 +319,10 @@ jobs: needs: [gather-artifacts, after-checks] steps: - name: Checkout - uses: actions/checkout@v4 + uses: actions/checkout@v3 - name: Setup Python - uses: actions/setup-python@v5 + uses: actions/setup-python@v4 with: python-version: 3.x diff --git a/.github/workflows/nightly.yml b/.github/workflows/nightly.yml index e249823a7..da59bc0fd 100644 --- a/.github/workflows/nightly.yml +++ b/.github/workflows/nightly.yml @@ -11,7 +11,7 @@ jobs: steps: - name: Checkout - uses: actions/checkout@v4 + uses: actions/checkout@v3 - name: Trunk Check uses: trunk-io/trunk-action@782e83f803ca6e369f035d64c6ba2768174ba61b diff --git a/.github/workflows/package_raspbian.yml b/.github/workflows/package_raspbian.yml index 6c1ae5d60..377074e95 100644 --- a/.github/workflows/package_raspbian.yml +++ b/.github/workflows/package_raspbian.yml @@ -17,7 +17,7 @@ jobs: needs: build-raspbian steps: - name: Checkout code - uses: actions/checkout@v4 + uses: actions/checkout@v3 with: submodules: recursive ref: ${{github.event.pull_request.head.ref}} @@ -66,7 +66,7 @@ jobs: depends: libyaml-cpp0.7, openssl desc: Native Linux Meshtastic binary. - - uses: actions/upload-artifact@v4 + - uses: actions/upload-artifact@v3 with: name: artifact-deb path: | diff --git a/.github/workflows/sec_sast_flawfinder.yml b/.github/workflows/sec_sast_flawfinder.yml index 59ff994ca..2c7e751af 100644 --- a/.github/workflows/sec_sast_flawfinder.yml +++ b/.github/workflows/sec_sast_flawfinder.yml @@ -16,7 +16,7 @@ jobs: steps: # step 1 - name: clone application source code - uses: actions/checkout@v4 + uses: actions/checkout@v3 # step 2 - name: flawfinder_scan @@ -27,7 +27,7 @@ jobs: # step 3 - name: save report as pipeline artifact - uses: actions/upload-artifact@v4 + uses: actions/upload-artifact@v3 with: name: flawfinder_report.sarif path: flawfinder_report.sarif diff --git a/.github/workflows/sec_sast_semgrep_cron.yml b/.github/workflows/sec_sast_semgrep_cron.yml index a29e6ca02..cdd2c3c37 100644 --- a/.github/workflows/sec_sast_semgrep_cron.yml +++ b/.github/workflows/sec_sast_semgrep_cron.yml @@ -17,7 +17,7 @@ jobs: steps: # step 1 - name: clone application source code - uses: actions/checkout@v4 + uses: actions/checkout@v3 # step 2 - name: full scan @@ -29,7 +29,7 @@ jobs: # step 3 - name: save report as pipeline artifact - uses: actions/upload-artifact@v4 + uses: actions/upload-artifact@v3 with: name: report.sarif path: report.sarif diff --git a/.github/workflows/sec_sast_semgrep_pull.yml b/.github/workflows/sec_sast_semgrep_pull.yml index b6c288494..1697ffb1b 100644 --- a/.github/workflows/sec_sast_semgrep_pull.yml +++ b/.github/workflows/sec_sast_semgrep_pull.yml @@ -11,7 +11,7 @@ jobs: steps: # step 1 - name: clone application source code - uses: actions/checkout@v4 + uses: actions/checkout@v3 with: fetch-depth: 0 diff --git a/.github/workflows/trunk-check.yml b/.github/workflows/trunk-check.yml index 6ed905bc8..e35b91cb9 100644 --- a/.github/workflows/trunk-check.yml +++ b/.github/workflows/trunk-check.yml @@ -16,7 +16,7 @@ jobs: steps: - name: Checkout - uses: actions/checkout@v4 + uses: actions/checkout@v3 - name: Trunk Check uses: trunk-io/trunk-action@v1 diff --git a/.github/workflows/update_protobufs.yml b/.github/workflows/update_protobufs.yml index 4c51c35c7..6944d827e 100644 --- a/.github/workflows/update_protobufs.yml +++ b/.github/workflows/update_protobufs.yml @@ -7,7 +7,7 @@ jobs: steps: - name: Checkout code - uses: actions/checkout@v4 + uses: actions/checkout@v3 with: submodules: true From 35754d661d01ade60a0f27031891264d676078f8 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 21 Mar 2024 18:26:37 -0500 Subject: [PATCH 361/472] Make MAX_NUM_NODES configurable in variant.h (#3453) Co-authored-by: Ben Meadors --- src/mesh/mesh-pb-constants.h | 4 +--- variants/portduino/variant.h | 1 + 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/src/mesh/mesh-pb-constants.h b/src/mesh/mesh-pb-constants.h index 9e747db1d..b8ef236c9 100644 --- a/src/mesh/mesh-pb-constants.h +++ b/src/mesh/mesh-pb-constants.h @@ -17,9 +17,7 @@ #define MAX_RX_TOPHONE 32 /// max number of nodes allowed in the mesh -#if ARCH_PORTDUINO -#define MAX_NUM_NODES settingsMap[maxnodes] -#else +#ifndef MAX_NUM_NODES #define MAX_NUM_NODES 100 #endif diff --git a/variants/portduino/variant.h b/variants/portduino/variant.h index f47b58afc..5aad8dbfc 100644 --- a/variants/portduino/variant.h +++ b/variants/portduino/variant.h @@ -1,3 +1,4 @@ #define HAS_SCREEN 1 #define CANNED_MESSAGE_MODULE_ENABLE 1 #define HAS_GPS 1 +#define MAX_NUM_NODES settingsMap[maxnodes] From a57f7730eacc5fbe42315c638c550b724684a507 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 21 Mar 2024 18:55:50 -0500 Subject: [PATCH 362/472] [create-pull-request] automated change (#3463) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/deviceonly.pb.h | 13 +++++++++---- src/mesh/generated/meshtastic/mesh.pb.h | 13 +++++++++---- 3 files changed, 19 insertions(+), 9 deletions(-) diff --git a/protobufs b/protobufs index 556e49ba6..bcfb49c49 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 556e49ba619e2f4d8fa3c2dee2a94129a43d5f08 +Subproject commit bcfb49c4988b1539fc35e568a58b9f2f5b60738a diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index c286bd471..c65a5764f 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -70,6 +70,9 @@ typedef struct _meshtastic_NodeInfoLite { bool via_mqtt; /* Number of hops away from us this node is (0 if adjacent) */ uint8_t hops_away; + /* True if node is in our favorites list + Persists between NodeDB internal clean ups */ + bool is_favorite; } meshtastic_NodeInfoLite; /* The on-disk saved channels */ @@ -180,13 +183,13 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_DeviceState_init_default {false, meshtastic_MyNodeInfo_init_default, false, meshtastic_User_init_default, 0, {meshtastic_MeshPacket_init_default}, false, meshtastic_MeshPacket_init_default, 0, 0, 0, false, meshtastic_MeshPacket_init_default, 0, {meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default}, {{NULL}, NULL}} -#define meshtastic_NodeInfoLite_init_default {0, false, meshtastic_User_init_default, false, meshtastic_PositionLite_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0, 0, 0} +#define meshtastic_NodeInfoLite_init_default {0, false, meshtastic_User_init_default, false, meshtastic_PositionLite_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0, 0, 0, 0} #define meshtastic_PositionLite_init_default {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN} #define meshtastic_ChannelFile_init_default {0, {meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default}, 0} #define meshtastic_OEMStore_init_default {0, 0, {0, {0}}, _meshtastic_ScreenFonts_MIN, "", {0, {0}}, false, meshtastic_LocalConfig_init_default, false, meshtastic_LocalModuleConfig_init_default} #define meshtastic_NodeRemoteHardwarePin_init_default {0, false, meshtastic_RemoteHardwarePin_init_default} #define meshtastic_DeviceState_init_zero {false, meshtastic_MyNodeInfo_init_zero, false, meshtastic_User_init_zero, 0, {meshtastic_MeshPacket_init_zero}, false, meshtastic_MeshPacket_init_zero, 0, 0, 0, false, meshtastic_MeshPacket_init_zero, 0, {meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero}, {{NULL}, NULL}} -#define meshtastic_NodeInfoLite_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_PositionLite_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0, 0, 0} +#define meshtastic_NodeInfoLite_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_PositionLite_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0, 0, 0, 0} #define meshtastic_PositionLite_init_zero {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN} #define meshtastic_ChannelFile_init_zero {0, {meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero}, 0} #define meshtastic_OEMStore_init_zero {0, 0, {0, {0}}, _meshtastic_ScreenFonts_MIN, "", {0, {0}}, false, meshtastic_LocalConfig_init_zero, false, meshtastic_LocalModuleConfig_init_zero} @@ -207,6 +210,7 @@ extern "C" { #define meshtastic_NodeInfoLite_channel_tag 7 #define meshtastic_NodeInfoLite_via_mqtt_tag 8 #define meshtastic_NodeInfoLite_hops_away_tag 9 +#define meshtastic_NodeInfoLite_is_favorite_tag 10 #define meshtastic_ChannelFile_channels_tag 1 #define meshtastic_ChannelFile_version_tag 2 #define meshtastic_OEMStore_oem_icon_width_tag 1 @@ -262,7 +266,8 @@ X(a, STATIC, SINGULAR, FIXED32, last_heard, 5) \ X(a, STATIC, OPTIONAL, MESSAGE, device_metrics, 6) \ X(a, STATIC, SINGULAR, UINT32, channel, 7) \ X(a, STATIC, SINGULAR, BOOL, via_mqtt, 8) \ -X(a, STATIC, SINGULAR, UINT32, hops_away, 9) +X(a, STATIC, SINGULAR, UINT32, hops_away, 9) \ +X(a, STATIC, SINGULAR, BOOL, is_favorite, 10) #define meshtastic_NodeInfoLite_CALLBACK NULL #define meshtastic_NodeInfoLite_DEFAULT NULL #define meshtastic_NodeInfoLite_user_MSGTYPE meshtastic_User @@ -324,7 +329,7 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg; /* Maximum encoded size of messages (where known) */ /* meshtastic_DeviceState_size depends on runtime parameters */ #define meshtastic_ChannelFile_size 702 -#define meshtastic_NodeInfoLite_size 158 +#define meshtastic_NodeInfoLite_size 160 #define meshtastic_NodeRemoteHardwarePin_size 29 #define meshtastic_OEMStore_size 3278 #define meshtastic_PositionLite_size 28 diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index 2f57f1ae2..5804dd42a 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -638,6 +638,9 @@ typedef struct _meshtastic_NodeInfo { bool via_mqtt; /* Number of hops away from us this node is (0 if adjacent) */ uint8_t hops_away; + /* True if node is in our favorites list + Persists between NodeDB internal clean ups */ + bool is_favorite; } meshtastic_NodeInfo; /* Unique local debugging info for this node @@ -906,7 +909,7 @@ extern "C" { #define meshtastic_Waypoint_init_default {0, 0, 0, 0, 0, "", "", 0} #define meshtastic_MqttClientProxyMessage_init_default {"", 0, {{0, {0}}}, 0} #define meshtastic_MeshPacket_init_default {0, 0, 0, 0, {meshtastic_Data_init_default}, 0, 0, 0, 0, 0, _meshtastic_MeshPacket_Priority_MIN, 0, _meshtastic_MeshPacket_Delayed_MIN, 0, 0} -#define meshtastic_NodeInfo_init_default {0, false, meshtastic_User_init_default, false, meshtastic_Position_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0, 0, 0} +#define meshtastic_NodeInfo_init_default {0, false, meshtastic_User_init_default, false, meshtastic_Position_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0, 0, 0, 0} #define meshtastic_MyNodeInfo_init_default {0, 0, 0} #define meshtastic_LogRecord_init_default {"", 0, "", _meshtastic_LogRecord_Level_MIN} #define meshtastic_QueueStatus_init_default {0, 0, 0, 0} @@ -925,7 +928,7 @@ extern "C" { #define meshtastic_Waypoint_init_zero {0, 0, 0, 0, 0, "", "", 0} #define meshtastic_MqttClientProxyMessage_init_zero {"", 0, {{0, {0}}}, 0} #define meshtastic_MeshPacket_init_zero {0, 0, 0, 0, {meshtastic_Data_init_zero}, 0, 0, 0, 0, 0, _meshtastic_MeshPacket_Priority_MIN, 0, _meshtastic_MeshPacket_Delayed_MIN, 0, 0} -#define meshtastic_NodeInfo_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_Position_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0, 0, 0} +#define meshtastic_NodeInfo_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_Position_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0, 0, 0, 0} #define meshtastic_MyNodeInfo_init_zero {0, 0, 0} #define meshtastic_LogRecord_init_zero {"", 0, "", _meshtastic_LogRecord_Level_MIN} #define meshtastic_QueueStatus_init_zero {0, 0, 0, 0} @@ -1016,6 +1019,7 @@ extern "C" { #define meshtastic_NodeInfo_channel_tag 7 #define meshtastic_NodeInfo_via_mqtt_tag 8 #define meshtastic_NodeInfo_hops_away_tag 9 +#define meshtastic_NodeInfo_is_favorite_tag 10 #define meshtastic_MyNodeInfo_my_node_num_tag 1 #define meshtastic_MyNodeInfo_reboot_count_tag 8 #define meshtastic_MyNodeInfo_min_app_version_tag 11 @@ -1182,7 +1186,8 @@ X(a, STATIC, SINGULAR, FIXED32, last_heard, 5) \ X(a, STATIC, OPTIONAL, MESSAGE, device_metrics, 6) \ X(a, STATIC, SINGULAR, UINT32, channel, 7) \ X(a, STATIC, SINGULAR, BOOL, via_mqtt, 8) \ -X(a, STATIC, SINGULAR, UINT32, hops_away, 9) +X(a, STATIC, SINGULAR, UINT32, hops_away, 9) \ +X(a, STATIC, SINGULAR, BOOL, is_favorite, 10) #define meshtastic_NodeInfo_CALLBACK NULL #define meshtastic_NodeInfo_DEFAULT NULL #define meshtastic_NodeInfo_user_MSGTYPE meshtastic_User @@ -1350,7 +1355,7 @@ extern const pb_msgdesc_t meshtastic_Heartbeat_msg; #define meshtastic_MyNodeInfo_size 18 #define meshtastic_NeighborInfo_size 258 #define meshtastic_Neighbor_size 22 -#define meshtastic_NodeInfo_size 275 +#define meshtastic_NodeInfo_size 277 #define meshtastic_Position_size 144 #define meshtastic_QueueStatus_size 23 #define meshtastic_RouteDiscovery_size 40 From 7aa013a716aa0ed89d3fdac7eecc310ca437330f Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 21 Mar 2024 19:51:02 -0500 Subject: [PATCH 363/472] Skip favorite nodes when clearing out oldest in NodeDB (#3464) * Skip favorite nodes when clearing out oldest in NodeDB * We should actually map between the types --- src/mesh/NodeDB.cpp | 2 +- src/mesh/TypeConversions.cpp | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 80b46a426..f65fe0da3 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -939,7 +939,7 @@ meshtastic_NodeInfoLite *NodeDB::getOrCreateMeshNode(NodeNum n) uint32_t oldest = UINT32_MAX; int oldestIndex = -1; for (int i = 1; i < numMeshNodes; i++) { - if (meshNodes->at(i).last_heard < oldest) { + if (!meshNodes->at(i).is_favorite && meshNodes->at(i).last_heard < oldest) { oldest = meshNodes->at(i).last_heard; oldestIndex = i; } diff --git a/src/mesh/TypeConversions.cpp b/src/mesh/TypeConversions.cpp index 20b1cb31e..bcd600f24 100644 --- a/src/mesh/TypeConversions.cpp +++ b/src/mesh/TypeConversions.cpp @@ -12,6 +12,7 @@ meshtastic_NodeInfo TypeConversions::ConvertToNodeInfo(const meshtastic_NodeInfo info.channel = lite->channel; info.via_mqtt = lite->via_mqtt; info.hops_away = lite->hops_away; + info.is_favorite = lite->is_favorite; if (lite->has_position) { info.has_position = true; From 794e99c2f992919e1dea57e3c9cf936ca4648aed Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 21 Mar 2024 20:45:48 -0500 Subject: [PATCH 364/472] Log warning cleanup and truth (#3466) --- src/gps/GPS.cpp | 2 +- src/main.cpp | 2 +- src/mesh/MeshService.cpp | 2 +- src/mesh/NodeDB.cpp | 6 +++--- src/mesh/RF95Interface.cpp | 2 +- src/mesh/SX126xInterface.cpp | 2 +- src/mesh/SX128xInterface.cpp | 2 +- src/platform/esp32/SimpleAllocator.cpp | 2 +- 8 files changed, 10 insertions(+), 10 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 7d4f41a55..df1d40fdf 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -1278,7 +1278,7 @@ bool GPS::lookForLocation() #ifndef TINYGPS_OPTION_NO_STATISTICS if (reader.failedChecksum() > lastChecksumFailCount) { - LOG_WARN("Warning, %u new GPS checksum failures, for a total of %u.\n", reader.failedChecksum() - lastChecksumFailCount, + LOG_WARN("%u new GPS checksum failures, for a total of %u.\n", reader.failedChecksum() - lastChecksumFailCount, reader.failedChecksum()); lastChecksumFailCount = reader.failedChecksum(); } diff --git a/src/main.cpp b/src/main.cpp index 5f746f12a..f7d1a4bc0 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -631,7 +631,7 @@ void setup() #else // ESP32 SPI.begin(LORA_SCK, LORA_MISO, LORA_MOSI, LORA_CS); - LOG_WARN("SPI.begin(SCK=%d, MISO=%d, MOSI=%d, NSS=%d)\n", LORA_SCK, LORA_MISO, LORA_MOSI, LORA_CS); + LOG_DEBUG("SPI.begin(SCK=%d, MISO=%d, MOSI=%d, NSS=%d)\n", LORA_SCK, LORA_MISO, LORA_MOSI, LORA_CS); SPI.setFrequency(4000000); #endif diff --git a/src/mesh/MeshService.cpp b/src/mesh/MeshService.cpp index 31eb082ec..2df5d5797 100644 --- a/src/mesh/MeshService.cpp +++ b/src/mesh/MeshService.cpp @@ -359,7 +359,7 @@ int MeshService::onGPSChanged(const meshtastic::GPSStatus *newStatus) LOG_DEBUG("onGPSchanged() - lost validLocation\n"); #endif } - // Used fixed position if configured regalrdless of GPS lock + // Used fixed position if configured regardless of GPS lock if (config.position.fixed_position) { LOG_WARN("Using fixed position\n"); pos = TypeConversions::ConvertToPosition(node->position); diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index f65fe0da3..3734309be 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -195,7 +195,7 @@ bool NodeDB::factoryReset() // first, remove the "/prefs" (this removes most prefs) rmDir("/prefs"); if (FSCom.exists("/static/rangetest.csv") && !FSCom.remove("/static/rangetest.csv")) { - LOG_WARN("Could not remove rangetest.csv file\n"); + LOG_ERROR("Could not remove rangetest.csv file\n"); } // second, install default state (this will deal with the duplicate mac address issue) installDefaultDeviceState(); @@ -527,7 +527,7 @@ void NodeDB::pickNewNodeNum() LOG_WARN("NOTE! Our desired nodenum 0x%x is invalid or in use, so trying for 0x%x\n", nodeNum, candidate); nodeNum = candidate; } - LOG_WARN("Using nodenum 0x%x \n", nodeNum); + LOG_DEBUG("Using nodenum 0x%x \n", nodeNum); myNodeInfo.my_node_num = nodeNum; } @@ -934,7 +934,7 @@ meshtastic_NodeInfoLite *NodeDB::getOrCreateMeshNode(NodeNum n) if ((numMeshNodes >= MAX_NUM_NODES) || (memGet.getFreeHeap() < meshtastic_NodeInfoLite_size * 3)) { if (screen) screen->print("Warn: node database full!\nErasing oldest entry\n"); - LOG_INFO("Warn: node database full!\nErasing oldest entry\n"); + LOG_WARN("Node database full! Erasing oldest entry\n"); // look for oldest node and erase it uint32_t oldest = UINT32_MAX; int oldestIndex = -1; diff --git a/src/mesh/RF95Interface.cpp b/src/mesh/RF95Interface.cpp index 72e0f823f..adc512ae2 100644 --- a/src/mesh/RF95Interface.cpp +++ b/src/mesh/RF95Interface.cpp @@ -19,7 +19,7 @@ RF95Interface::RF95Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIO RADIOLIB_PIN_TYPE busy) : RadioLibInterface(hal, cs, irq, rst, busy) { - LOG_WARN("RF95Interface(cs=%d, irq=%d, rst=%d, busy=%d)\n", cs, irq, rst, busy); + LOG_DEBUG("RF95Interface(cs=%d, irq=%d, rst=%d, busy=%d)\n", cs, irq, rst, busy); } /** Some boards require GPIO control of tx vs rx paths */ diff --git a/src/mesh/SX126xInterface.cpp b/src/mesh/SX126xInterface.cpp index 7220dd3e5..104d0a5ed 100644 --- a/src/mesh/SX126xInterface.cpp +++ b/src/mesh/SX126xInterface.cpp @@ -17,7 +17,7 @@ SX126xInterface::SX126xInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs RADIOLIB_PIN_TYPE busy) : RadioLibInterface(hal, cs, irq, rst, busy, &lora), lora(&module) { - LOG_WARN("SX126xInterface(cs=%d, irq=%d, rst=%d, busy=%d)\n", cs, irq, rst, busy); + LOG_DEBUG("SX126xInterface(cs=%d, irq=%d, rst=%d, busy=%d)\n", cs, irq, rst, busy); } /// Initialise the Driver transport hardware and software. diff --git a/src/mesh/SX128xInterface.cpp b/src/mesh/SX128xInterface.cpp index f2220dbcf..45325f339 100644 --- a/src/mesh/SX128xInterface.cpp +++ b/src/mesh/SX128xInterface.cpp @@ -17,7 +17,7 @@ SX128xInterface::SX128xInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs RADIOLIB_PIN_TYPE busy) : RadioLibInterface(hal, cs, irq, rst, busy, &lora), lora(&module) { - LOG_WARN("SX128xInterface(cs=%d, irq=%d, rst=%d, busy=%d)\n", cs, irq, rst, busy); + LOG_DEBUG("SX128xInterface(cs=%d, irq=%d, rst=%d, busy=%d)\n", cs, irq, rst, busy); } /// Initialise the Driver transport hardware and software. diff --git a/src/platform/esp32/SimpleAllocator.cpp b/src/platform/esp32/SimpleAllocator.cpp index ed44722c5..63f3b02de 100644 --- a/src/platform/esp32/SimpleAllocator.cpp +++ b/src/platform/esp32/SimpleAllocator.cpp @@ -58,7 +58,7 @@ void *operator new(size_t sz) throw(std::bad_alloc) void operator delete(void *ptr) throw() { if (activeAllocator) - LOG_DEBUG("Warning: leaking an active allocator object\n"); // We don't properly handle this yet + LOG_WARN("Leaking an active allocator object\n"); // We don't properly handle this yet else free(ptr); } From c77c58d656e3c42ee69a793881e1670de92a79b2 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Fri, 22 Mar 2024 07:24:10 -0500 Subject: [PATCH 365/472] [create-pull-request] automated change (#3470) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/admin.pb.h | 8 ++++++++ 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/protobufs b/protobufs index bcfb49c49..0fe69d73e 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit bcfb49c4988b1539fc35e568a58b9f2f5b60738a +Subproject commit 0fe69d73e639372128d9480ec8cf65b182d36d30 diff --git a/src/mesh/generated/meshtastic/admin.pb.h b/src/mesh/generated/meshtastic/admin.pb.h index 28bda429d..d2f40c7f0 100644 --- a/src/mesh/generated/meshtastic/admin.pb.h +++ b/src/mesh/generated/meshtastic/admin.pb.h @@ -154,6 +154,10 @@ typedef struct _meshtastic_AdminMessage { char set_ringtone_message[231]; /* Remove the node by the specified node-num from the NodeDB on the device */ uint32_t remove_by_nodenum; + /* Set specified node-num to be favorited on the NodeDB on the device */ + uint32_t set_favorite_node; + /* Set specified node-num to be un-favorited on the NodeDB on the device */ + uint32_t remove_favorite_node; /* Begins an edit transaction for config, module config, owner, and channel settings changes This will delay the standard *implicit* save to the file system and subsequent reboot behavior until committed (commit_edit_settings) */ bool begin_edit_settings; @@ -238,6 +242,8 @@ extern "C" { #define meshtastic_AdminMessage_set_canned_message_module_messages_tag 36 #define meshtastic_AdminMessage_set_ringtone_message_tag 37 #define meshtastic_AdminMessage_remove_by_nodenum_tag 38 +#define meshtastic_AdminMessage_set_favorite_node_tag 39 +#define meshtastic_AdminMessage_remove_favorite_node_tag 40 #define meshtastic_AdminMessage_begin_edit_settings_tag 64 #define meshtastic_AdminMessage_commit_edit_settings_tag 65 #define meshtastic_AdminMessage_reboot_ota_seconds_tag 95 @@ -277,6 +283,8 @@ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,set_module_config,set_module X(a, STATIC, ONEOF, STRING, (payload_variant,set_canned_message_module_messages,set_canned_message_module_messages), 36) \ X(a, STATIC, ONEOF, STRING, (payload_variant,set_ringtone_message,set_ringtone_message), 37) \ X(a, STATIC, ONEOF, UINT32, (payload_variant,remove_by_nodenum,remove_by_nodenum), 38) \ +X(a, STATIC, ONEOF, UINT32, (payload_variant,set_favorite_node,set_favorite_node), 39) \ +X(a, STATIC, ONEOF, UINT32, (payload_variant,remove_favorite_node,remove_favorite_node), 40) \ X(a, STATIC, ONEOF, BOOL, (payload_variant,begin_edit_settings,begin_edit_settings), 64) \ X(a, STATIC, ONEOF, BOOL, (payload_variant,commit_edit_settings,commit_edit_settings), 65) \ X(a, STATIC, ONEOF, INT32, (payload_variant,reboot_ota_seconds,reboot_ota_seconds), 95) \ From 54818b5f8d2d289fb031e4a5054e81dd4203e73a Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 22 Mar 2024 07:25:00 -0500 Subject: [PATCH 366/472] Enforce consistent polite channel utilization limits except for Sensor role (#3467) --- src/modules/Telemetry/AirQualityTelemetry.cpp | 1 + src/modules/Telemetry/DeviceTelemetry.cpp | 4 ++-- src/modules/Telemetry/EnvironmentTelemetry.cpp | 1 + 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/src/modules/Telemetry/AirQualityTelemetry.cpp b/src/modules/Telemetry/AirQualityTelemetry.cpp index 3e9b069c4..a51a7cea9 100644 --- a/src/modules/Telemetry/AirQualityTelemetry.cpp +++ b/src/modules/Telemetry/AirQualityTelemetry.cpp @@ -45,6 +45,7 @@ int32_t AirQualityTelemetryModule::runOnce() uint32_t now = millis(); if (((lastSentToMesh == 0) || ((now - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.air_quality_interval))) && + airTime->isTxAllowedChannelUtil(config.device.role != meshtastic_Config_DeviceConfig_Role_SENSOR) && airTime->isTxAllowedAirUtil()) { sendTelemetry(); lastSentToMesh = now; diff --git a/src/modules/Telemetry/DeviceTelemetry.cpp b/src/modules/Telemetry/DeviceTelemetry.cpp index 7c02b57b4..2ae904b89 100644 --- a/src/modules/Telemetry/DeviceTelemetry.cpp +++ b/src/modules/Telemetry/DeviceTelemetry.cpp @@ -18,8 +18,8 @@ int32_t DeviceTelemetryModule::runOnce() uint32_t now = millis(); if (((lastSentToMesh == 0) || ((now - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.device_update_interval))) && - airTime->isTxAllowedChannelUtil() && airTime->isTxAllowedAirUtil() && - config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER && + airTime->isTxAllowedChannelUtil(config.device.role != meshtastic_Config_DeviceConfig_Role_SENSOR) && + airTime->isTxAllowedAirUtil() && config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER && config.device.role != meshtastic_Config_DeviceConfig_Role_CLIENT_HIDDEN) { sendTelemetry(); lastSentToMesh = now; diff --git a/src/modules/Telemetry/EnvironmentTelemetry.cpp b/src/modules/Telemetry/EnvironmentTelemetry.cpp index 203b632a7..908062a5b 100644 --- a/src/modules/Telemetry/EnvironmentTelemetry.cpp +++ b/src/modules/Telemetry/EnvironmentTelemetry.cpp @@ -104,6 +104,7 @@ int32_t EnvironmentTelemetryModule::runOnce() uint32_t now = millis(); if (((lastSentToMesh == 0) || ((now - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.environment_update_interval))) && + airTime->isTxAllowedChannelUtil(config.device.role != meshtastic_Config_DeviceConfig_Role_SENSOR) && airTime->isTxAllowedAirUtil()) { sendTelemetry(); lastSentToMesh = now; From 94e4301f2f5f224e0d1dc828aeca2846714d9e35 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 22 Mar 2024 10:53:18 -0500 Subject: [PATCH 367/472] Add set and remove favorite nodes admin commands (#3471) --- src/modules/AdminModule.cpp | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index 6d420ddb8..ae0dac9ff 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -189,6 +189,22 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta nodeDB->removeNodeByNum(r->remove_by_nodenum); break; } + case meshtastic_AdminMessage_set_favorite_node_tag: { + LOG_INFO("Client is receiving a set_favorite_node command.\n"); + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(r->set_favorite_node); + if (node != NULL) { + node->is_favorite = true; + } + break; + } + case meshtastic_AdminMessage_remove_favorite_node_tag: { + LOG_INFO("Client is receiving a remove_favorite_node command.\n"); + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(r->remove_favorite_node); + if (node != NULL) { + node->is_favorite = false; + } + break; + } case meshtastic_AdminMessage_enter_dfu_mode_request_tag: { LOG_INFO("Client is requesting to enter DFU mode.\n"); #if defined(ARCH_NRF52) || defined(ARCH_RP2040) From d30d6bd3eba7f0db00146449391a7c89f17df5fe Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Sat, 23 Mar 2024 13:31:58 +0100 Subject: [PATCH 368/472] Fix #3452: only alter received packet if port number matches (#3474) * Use `alterReceivedProtobuf()` for NeighborInfo and Traceroute `alterReceived()` should never return NULL Traceroute should be promiscuous * Remove extensive logging from NeighborInfo module --- src/mesh/FloodingRouter.cpp | 9 ---- src/mesh/FloodingRouter.h | 2 - src/mesh/ProtobufModule.h | 4 +- src/modules/NeighborInfoModule.cpp | 72 +++--------------------------- src/modules/NeighborInfoModule.h | 9 +--- src/modules/TraceRouteModule.cpp | 24 ++++------ src/modules/TraceRouteModule.h | 7 +-- 7 files changed, 22 insertions(+), 105 deletions(-) diff --git a/src/mesh/FloodingRouter.cpp b/src/mesh/FloodingRouter.cpp index db3f3f35e..4cfe982d8 100644 --- a/src/mesh/FloodingRouter.cpp +++ b/src/mesh/FloodingRouter.cpp @@ -49,15 +49,6 @@ void FloodingRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtas tosend->hop_limit--; // bump down the hop count - if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) { - // If it is a traceRoute request, update the route that it went via me - if (traceRouteModule && traceRouteModule->wantPacket(p)) - traceRouteModule->updateRoute(tosend); - // If it is a neighborInfo packet, update last_sent_by_id - if (neighborInfoModule && neighborInfoModule->wantPacket(p)) - neighborInfoModule->updateLastSentById(tosend); - } - LOG_INFO("Rebroadcasting received floodmsg to neighbors\n"); // Note: we are careful to resend using the original senders node id // We are careful not to call our hooked version of send() - because we don't want to check this again diff --git a/src/mesh/FloodingRouter.h b/src/mesh/FloodingRouter.h index 309035cb3..a3adfe70c 100644 --- a/src/mesh/FloodingRouter.h +++ b/src/mesh/FloodingRouter.h @@ -2,8 +2,6 @@ #include "PacketHistory.h" #include "Router.h" -#include "modules/NeighborInfoModule.h" -#include "modules/TraceRouteModule.h" /** * This is a mixin that extends Router with the ability to do Naive Flooding (in the standard mesh protocol sense) diff --git a/src/mesh/ProtobufModule.h b/src/mesh/ProtobufModule.h index 1067ee01e..a2e89e98a 100644 --- a/src/mesh/ProtobufModule.h +++ b/src/mesh/ProtobufModule.h @@ -108,8 +108,8 @@ template class ProtobufModule : protected SinglePortModule // if we can't decode it, nobody can process it! return; } - } - return alterReceivedProtobuf(mp, decoded); + return alterReceivedProtobuf(mp, decoded); + } } }; \ No newline at end of file diff --git a/src/modules/NeighborInfoModule.cpp b/src/modules/NeighborInfoModule.cpp index 4d68b4a16..1e9652469 100644 --- a/src/modules/NeighborInfoModule.cpp +++ b/src/modules/NeighborInfoModule.cpp @@ -18,73 +18,24 @@ void NeighborInfoModule::printNeighborInfo(const char *header, const meshtastic_ { LOG_DEBUG("%s NEIGHBORINFO PACKET from Node 0x%x to Node 0x%x (last sent by 0x%x)\n", header, np->node_id, nodeDB->getNodeNum(), np->last_sent_by_id); - LOG_DEBUG("----------------\n"); LOG_DEBUG("Packet contains %d neighbors\n", np->neighbors_count); for (int i = 0; i < np->neighbors_count; i++) { LOG_DEBUG("Neighbor %d: node_id=0x%x, snr=%.2f\n", i, np->neighbors[i].node_id, np->neighbors[i].snr); } - LOG_DEBUG("----------------\n"); -} -/* -Prints the nodeDB nodes so we can see whose nodeInfo we have -NOTE: for debugging only -*/ -void NeighborInfoModule::printNodeDBNodes(const char *header) -{ - int num_nodes = nodeDB->getNumMeshNodes(); - LOG_DEBUG("%s NODEDB SELECTION from Node 0x%x:\n", header, nodeDB->getNodeNum()); - LOG_DEBUG("----------------\n"); - LOG_DEBUG("DB contains %d nodes\n", num_nodes); - for (int i = 0; i < num_nodes; i++) { - const meshtastic_NodeInfoLite *dbEntry = nodeDB->getMeshNodeByIndex(i); - LOG_DEBUG(" Node %d: node_id=0x%x, snr=%.2f\n", i, dbEntry->num, dbEntry->snr); - } - LOG_DEBUG("----------------\n"); } /* Prints the nodeDB neighbors NOTE: for debugging only */ -void NeighborInfoModule::printNodeDBNeighbors(const char *header) +void NeighborInfoModule::printNodeDBNeighbors() { int num_neighbors = getNumNeighbors(); - LOG_DEBUG("%s NODEDB SELECTION from Node 0x%x:\n", header, nodeDB->getNodeNum()); - LOG_DEBUG("----------------\n"); - LOG_DEBUG("DB contains %d neighbors\n", num_neighbors); + LOG_DEBUG("Our NodeDB contains %d neighbors\n", num_neighbors); for (int i = 0; i < num_neighbors; i++) { const meshtastic_Neighbor *dbEntry = getNeighborByIndex(i); LOG_DEBUG(" Node %d: node_id=0x%x, snr=%.2f\n", i, dbEntry->node_id, dbEntry->snr); } - LOG_DEBUG("----------------\n"); -} - -/* -Prints the nodeDB with selectors for the neighbors we've chosen to send (inefficiently) -Uses LOG_DEBUG, which equates to Console.log -NOTE: For debugging only -*/ -void NeighborInfoModule::printNodeDBSelection(const char *header, const meshtastic_NeighborInfo *np) -{ - int num_neighbors = getNumNeighbors(); - LOG_DEBUG("%s NODEDB SELECTION from Node 0x%x:\n", header, nodeDB->getNodeNum()); - LOG_DEBUG("----------------\n"); - LOG_DEBUG("Selected %d neighbors of %d DB neighbors\n", np->neighbors_count, num_neighbors); - for (int i = 0; i < num_neighbors; i++) { - meshtastic_Neighbor *dbEntry = getNeighborByIndex(i); - bool chosen = false; - for (int j = 0; j < np->neighbors_count; j++) { - if (np->neighbors[j].node_id == dbEntry->node_id) { - chosen = true; - } - } - if (!chosen) { - LOG_DEBUG(" Node %d: neighbor=0x%x, snr=%.2f\n", i, dbEntry->node_id, dbEntry->snr); - } else { - LOG_DEBUG("---> Node %d: neighbor=0x%x, snr=%.2f\n", i, dbEntry->node_id, dbEntry->snr); - } - } - LOG_DEBUG("----------------\n"); } /* Send our initial owner announcement 35 seconds after we start (to give network time to setup) */ @@ -129,9 +80,7 @@ uint32_t NeighborInfoModule::collectNeighborInfo(meshtastic_NeighborInfo *neighb neighborInfo->neighbors_count++; } } - printNodeDBNodes("DBSTATE"); - printNodeDBNeighbors("NEIGHBORS"); - printNodeDBSelection("COLLECTED", neighborInfo); + printNodeDBNeighbors(); return neighborInfo->neighbors_count; } @@ -218,20 +167,13 @@ bool NeighborInfoModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, /* Copy the content of a current NeighborInfo packet into a new one and update the last_sent_by_id to our NodeNum */ -void NeighborInfoModule::updateLastSentById(meshtastic_MeshPacket *p) +void NeighborInfoModule::alterReceivedProtobuf(meshtastic_MeshPacket &p, meshtastic_NeighborInfo *n) { - auto &incoming = p->decoded; - meshtastic_NeighborInfo scratch; - meshtastic_NeighborInfo *updated = NULL; - memset(&scratch, 0, sizeof(scratch)); - pb_decode_from_bytes(incoming.payload.bytes, incoming.payload.size, &meshtastic_NeighborInfo_msg, &scratch); - updated = &scratch; - - updated->last_sent_by_id = nodeDB->getNodeNum(); + n->last_sent_by_id = nodeDB->getNodeNum(); // Set updated last_sent_by_id to the payload of the to be flooded packet - p->decoded.payload.size = - pb_encode_to_bytes(p->decoded.payload.bytes, sizeof(p->decoded.payload.bytes), &meshtastic_NeighborInfo_msg, updated); + p.decoded.payload.size = + pb_encode_to_bytes(p.decoded.payload.bytes, sizeof(p.decoded.payload.bytes), &meshtastic_NeighborInfo_msg, n); } void NeighborInfoModule::resetNeighbors() diff --git a/src/modules/NeighborInfoModule.h b/src/modules/NeighborInfoModule.h index 820e2d0d4..b4acb0f66 100644 --- a/src/modules/NeighborInfoModule.h +++ b/src/modules/NeighborInfoModule.h @@ -20,9 +20,6 @@ class NeighborInfoModule : public ProtobufModule, priva bool saveProtoForModule(); - // Let FloodingRouter call updateLastSentById upon rebroadcasting a NeighborInfo packet - friend class FloodingRouter; - protected: // Note: this holds our local info. meshtastic_NeighborInfo neighborState; @@ -68,7 +65,7 @@ class NeighborInfoModule : public ProtobufModule, priva void updateNeighbors(const meshtastic_MeshPacket &mp, const meshtastic_NeighborInfo *np); /* update a NeighborInfo packet with our NodeNum as last_sent_by_id */ - void updateLastSentById(meshtastic_MeshPacket *p); + void alterReceivedProtobuf(meshtastic_MeshPacket &p, meshtastic_NeighborInfo *n) override; void loadProtoForModule(); @@ -81,8 +78,6 @@ class NeighborInfoModule : public ProtobufModule, priva /* These are for debugging only */ void printNeighborInfo(const char *header, const meshtastic_NeighborInfo *np); - void printNodeDBNodes(const char *header); - void printNodeDBNeighbors(const char *header); - void printNodeDBSelection(const char *header, const meshtastic_NeighborInfo *np); + void printNodeDBNeighbors(); }; extern NeighborInfoModule *neighborInfoModule; \ No newline at end of file diff --git a/src/modules/TraceRouteModule.cpp b/src/modules/TraceRouteModule.cpp index 311e211f3..aa0b6a1eb 100644 --- a/src/modules/TraceRouteModule.cpp +++ b/src/modules/TraceRouteModule.cpp @@ -1,5 +1,4 @@ #include "TraceRouteModule.h" -#include "FloodingRouter.h" #include "MeshService.h" TraceRouteModule *traceRouteModule; @@ -14,23 +13,17 @@ bool TraceRouteModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, m return false; // let it be handled by RoutingModule } -void TraceRouteModule::updateRoute(meshtastic_MeshPacket *p) +void TraceRouteModule::alterReceivedProtobuf(meshtastic_MeshPacket &p, meshtastic_RouteDiscovery *r) { - auto &incoming = p->decoded; - // Only append an ID for the request (one way) - if (!incoming.request_id) { - meshtastic_RouteDiscovery scratch; - meshtastic_RouteDiscovery *updated = NULL; - memset(&scratch, 0, sizeof(scratch)); - pb_decode_from_bytes(incoming.payload.bytes, incoming.payload.size, &meshtastic_RouteDiscovery_msg, &scratch); - updated = &scratch; - - appendMyID(updated); - printRoute(updated, p->from, NODENUM_BROADCAST); + auto &incoming = p.decoded; + // Only append an ID for the request (one way) and if we are not the destination (the reply will have our NodeNum already) + if (!incoming.request_id && p.to != nodeDB->getNodeNum()) { + appendMyID(r); + printRoute(r, p.from, NODENUM_BROADCAST); // Set updated route to the payload of the to be flooded packet - p->decoded.payload.size = pb_encode_to_bytes(p->decoded.payload.bytes, sizeof(p->decoded.payload.bytes), - &meshtastic_RouteDiscovery_msg, updated); + p.decoded.payload.size = + pb_encode_to_bytes(p.decoded.payload.bytes, sizeof(p.decoded.payload.bytes), &meshtastic_RouteDiscovery_msg, r); } } @@ -85,4 +78,5 @@ TraceRouteModule::TraceRouteModule() : ProtobufModule("traceroute", meshtastic_PortNum_TRACEROUTE_APP, &meshtastic_RouteDiscovery_msg) { ourPortNum = meshtastic_PortNum_TRACEROUTE_APP; + isPromiscuous = true; // We need to update the route even if it is not destined to us } \ No newline at end of file diff --git a/src/modules/TraceRouteModule.h b/src/modules/TraceRouteModule.h index 674846ef1..15e01debd 100644 --- a/src/modules/TraceRouteModule.h +++ b/src/modules/TraceRouteModule.h @@ -9,17 +9,14 @@ class TraceRouteModule : public ProtobufModule public: TraceRouteModule(); - // Let FloodingRouter call updateRoute upon rebroadcasting a TraceRoute request - friend class FloodingRouter; - protected: bool handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_RouteDiscovery *r) override; virtual meshtastic_MeshPacket *allocReply() override; - /* Call before rebroadcasting a RouteDiscovery payload in order to update + /* Called before rebroadcasting a RouteDiscovery payload in order to update the route array containing the IDs of nodes this packet went through */ - void updateRoute(meshtastic_MeshPacket *p); + void alterReceivedProtobuf(meshtastic_MeshPacket &p, meshtastic_RouteDiscovery *r) override; private: // Call to add your ID to the route array of a RouteDiscovery message From 9e8860d1888332b3fd8588e3aaf9f3867ced3415 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sat, 23 Mar 2024 12:29:05 -0500 Subject: [PATCH 369/472] Crash fix and remove hard-coded path from PiWebServer (#3478) * Remove hard-coded path from PiWebServer * Bump portduino to pick up crash fix * Remove PiWebServer non-ASCII debug output * Trunk formatting --- arch/portduino/portduino.ini | 2 +- src/mesh/raspihttp/PiWebServer.cpp | 12 ++++++------ 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index 368fb5d0e..ef8711f8a 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -1,6 +1,6 @@ ; The Portduino based sim environment on top of any host OS, all hardware will be simulated [portduino_base] -platform = https://github.com/meshtastic/platform-native.git#a28dd5a9ccd5c48a9bede46037855ff83915d74b +platform = https://github.com/meshtastic/platform-native.git#1b8a32c60ab7495026033858d53c737f7d1cb34a framework = arduino build_src_filter = diff --git a/src/mesh/raspihttp/PiWebServer.cpp b/src/mesh/raspihttp/PiWebServer.cpp index 41f6727a4..bffd6c340 100644 --- a/src/mesh/raspihttp/PiWebServer.cpp +++ b/src/mesh/raspihttp/PiWebServer.cpp @@ -244,7 +244,7 @@ int handleAPIv1ToRadio(const struct _u_request *req, struct _u_response *res, vo // FIXME* Problem with portdunio loosing mountpoint maybe because of running in a real sep. thread - portduinoVFS->mountpoint("/home/marc/.portduino/default"); + portduinoVFS->mountpoint(configWeb.rootPath); LOG_DEBUG("Received %d bytes from PUT request\n", s); webAPI.handleToRadio(buffer, s); @@ -279,8 +279,8 @@ int handleAPIv1FromRadio(const struct _u_request *req, struct _u_response *res, const char *tmpa = (const char *)txBuf; ulfius_set_string_body_response(res, 200, tmpa); // LOG_DEBUG("\n----webAPI response all:----\n"); - LOG_DEBUG(tmpa); - LOG_DEBUG("\n"); + // LOG_DEBUG(tmpa); + // LOG_DEBUG("\n"); } // Otherwise, just return one protobuf } else { @@ -288,8 +288,8 @@ int handleAPIv1FromRadio(const struct _u_request *req, struct _u_response *res, const char *tmpa = (const char *)txBuf; ulfius_set_binary_body_response(res, 200, tmpa, len); // LOG_DEBUG("\n----webAPI response:\n"); - LOG_DEBUG(tmpa); - LOG_DEBUG("\n"); + // LOG_DEBUG(tmpa); + // LOG_DEBUG("\n"); } // LOG_DEBUG("end radio->web\n", len); @@ -508,7 +508,7 @@ PiWebServerThread::PiWebServerThread() LOG_INFO("Web Server framework started on port: %i \n", webservport); LOG_INFO("Web Server root %s\n", (char *)webrootpath.c_str()); } else { - LOG_ERROR("Error starting Web Server framework\n"); + LOG_ERROR("Error starting Web Server framework, error number: %d\n", retssl); } } } From 4cce4c7c93a5c44cb7de5ce509f63a1db0587dbf Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Sat, 23 Mar 2024 18:38:29 +0100 Subject: [PATCH 370/472] Set unused header bytes to zero for future use (#3479) --- src/mesh/RadioInterface.cpp | 2 ++ src/mesh/RadioInterface.h | 6 ++++++ 2 files changed, 8 insertions(+) diff --git a/src/mesh/RadioInterface.cpp b/src/mesh/RadioInterface.cpp index 859e7bea4..3aac9dfce 100644 --- a/src/mesh/RadioInterface.cpp +++ b/src/mesh/RadioInterface.cpp @@ -564,6 +564,8 @@ size_t RadioInterface::beginSending(meshtastic_MeshPacket *p) h->to = p->to; h->id = p->id; h->channel = p->channel; + h->next_hop = 0; // *** For future use *** + h->relay_node = 0; // *** For future use *** if (p->hop_limit > HOP_MAX) { LOG_WARN("hop limit %d is too high, setting to %d\n", p->hop_limit, HOP_RELIABLE); p->hop_limit = HOP_RELIABLE; diff --git a/src/mesh/RadioInterface.h b/src/mesh/RadioInterface.h index ee4726d74..b965328e4 100644 --- a/src/mesh/RadioInterface.h +++ b/src/mesh/RadioInterface.h @@ -34,6 +34,12 @@ typedef struct { /** The channel hash - used as a hint for the decoder to limit which channels we consider */ uint8_t channel; + + // ***For future use*** Last byte of the NodeNum of the next-hop for this packet + uint8_t next_hop; + + // ***For future use*** Last byte of the NodeNum of the node that will relay/relayed this packet + uint8_t relay_node; } PacketHeader; /** From 71ca6f768f6cd1e06ff2aa8bc1ba7e53c00e50d4 Mon Sep 17 00:00:00 2001 From: GUVWAF Date: Sat, 23 Mar 2024 19:35:12 +0100 Subject: [PATCH 371/472] Actually update last_report_to_map --- src/mqtt/MQTT.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 390d0e206..8e7c8f2cc 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -546,6 +546,7 @@ void MQTT::perhapsReportToMap() return; } else { if (map_position_precision == 0 || (localPosition.latitude_i == 0 && localPosition.longitude_i == 0)) { + last_report_to_map = millis(); LOG_WARN("MQTT Map reporting is enabled, but precision is 0 or no position available.\n"); return; } From c87fdfece73ce3a242a77e02218fd535299371c9 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sat, 23 Mar 2024 19:47:43 -0500 Subject: [PATCH 372/472] [create-pull-request] automated change (#3483) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 12603eda7..58a6c19d7 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 3 -build = 2 +build = 3 From 63df972d42b4aed34f7faea25174368a9a7f14cf Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 24 Mar 2024 08:11:47 -0500 Subject: [PATCH 373/472] Revert "[create-pull-request] automated change (#3483)" (#3484) This reverts commit c87fdfece73ce3a242a77e02218fd535299371c9. --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 58a6c19d7..12603eda7 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 3 -build = 3 +build = 2 From b4dbc2b4bf7b7f3d0c0e3107f2128b127d6521ad Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sun, 24 Mar 2024 12:44:44 -0500 Subject: [PATCH 374/472] [create-pull-request] automated change (#3485) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 12603eda7..58a6c19d7 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 3 -build = 2 +build = 3 From 5f529f7ca39ef8ca0e4a88dde3963d29422ea87c Mon Sep 17 00:00:00 2001 From: code8buster <20384924+code8buster@users.noreply.github.com> Date: Sun, 24 Mar 2024 18:41:28 +0000 Subject: [PATCH 375/472] Remove unused defines from nrf52 variants (#3482) Co-authored-by: Ben Meadors --- variants/Dongle_nRF52840-pca10059-v1/variant.h | 13 ++----------- variants/MakePython_nRF52840_eink/variant.h | 13 ++----------- variants/MakePython_nRF52840_oled/variant.h | 13 ++----------- variants/canaryone/variant.h | 11 +---------- variants/monteops_hw1/variant.h | 13 ++----------- variants/nano-g2-ultra/variant.h | 13 ++----------- variants/rak10701/variant.h | 13 ++----------- variants/rak4631/variant.h | 11 +---------- variants/rak4631_epaper/variant.h | 11 +---------- variants/rak4631_epaper_onrxtx/variant.h | 11 +---------- variants/t-echo/variant.h | 11 +---------- variants/trackerd/variant.h | 17 +++-------------- 12 files changed, 20 insertions(+), 130 deletions(-) diff --git a/variants/Dongle_nRF52840-pca10059-v1/variant.h b/variants/Dongle_nRF52840-pca10059-v1/variant.h index 0f1bf15da..533367a30 100644 --- a/variants/Dongle_nRF52840-pca10059-v1/variant.h +++ b/variants/Dongle_nRF52840-pca10059-v1/variant.h @@ -155,19 +155,10 @@ static const uint8_t SCK = PIN_SPI_SCK; // and has 12 bit resolution #define BATTERY_SENSE_RESOLUTION_BITS 12 #define BATTERY_SENSE_RESOLUTION 4096.0 -// Definition of milliVolt per LSB => 3.0V ADC range and 12-bit ADC resolution = 3000mV/4096 -#define VBAT_MV_PER_LSB (0.73242188F) -// Voltage divider value => 1.5M + 1M voltage divider on VBAT = (1.5M / (1M + 1.5M)) -#define VBAT_DIVIDER (0.4F) -// Compensation factor for the VBAT divider -#define VBAT_DIVIDER_COMP (1.73) -// Fixed calculation of milliVolt from compensation value -#define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) #undef AREF_VOLTAGE #define AREF_VOLTAGE 3.0 #define VBAT_AR_INTERNAL AR_INTERNAL_3_0 -#define ADC_MULTIPLIER VBAT_DIVIDER_COMP // REAL_VBAT_MV_PER_LSB -#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x) +#define ADC_MULTIPLIER (1.73F) #ifdef __cplusplus } @@ -177,4 +168,4 @@ static const uint8_t SCK = PIN_SPI_SCK; * Arduino objects - C++ only *----------------------------------------------------------------------------*/ -#endif +#endif \ No newline at end of file diff --git a/variants/MakePython_nRF52840_eink/variant.h b/variants/MakePython_nRF52840_eink/variant.h index 2ff9c76fd..16f803dd2 100644 --- a/variants/MakePython_nRF52840_eink/variant.h +++ b/variants/MakePython_nRF52840_eink/variant.h @@ -134,19 +134,10 @@ static const uint8_t SCK = PIN_SPI_SCK; // and has 12 bit resolution #define BATTERY_SENSE_RESOLUTION_BITS 12 #define BATTERY_SENSE_RESOLUTION 4096.0 -// Definition of milliVolt per LSB => 3.0V ADC range and 12-bit ADC resolution = 3000mV/4096 -#define VBAT_MV_PER_LSB (0.73242188F) -// Voltage divider value => 1.5M + 1M voltage divider on VBAT = (1.5M / (1M + 1.5M)) -#define VBAT_DIVIDER (0.4F) -// Compensation factor for the VBAT divider -#define VBAT_DIVIDER_COMP (1.73) -// Fixed calculation of milliVolt from compensation value -#define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) #undef AREF_VOLTAGE #define AREF_VOLTAGE 3.0 #define VBAT_AR_INTERNAL AR_INTERNAL_3_0 -#define ADC_MULTIPLIER VBAT_DIVIDER_COMP // REAL_VBAT_MV_PER_LSB -#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x) +#define ADC_MULTIPLIER (1.73F) #ifdef __cplusplus } @@ -156,4 +147,4 @@ static const uint8_t SCK = PIN_SPI_SCK; * Arduino objects - C++ only *----------------------------------------------------------------------------*/ -#endif +#endif \ No newline at end of file diff --git a/variants/MakePython_nRF52840_oled/variant.h b/variants/MakePython_nRF52840_oled/variant.h index e7375a610..a2a5fa80a 100644 --- a/variants/MakePython_nRF52840_oled/variant.h +++ b/variants/MakePython_nRF52840_oled/variant.h @@ -112,19 +112,10 @@ static const uint8_t SCK = PIN_SPI_SCK; // and has 12 bit resolution #define BATTERY_SENSE_RESOLUTION_BITS 12 #define BATTERY_SENSE_RESOLUTION 4096.0 -// Definition of milliVolt per LSB => 3.0V ADC range and 12-bit ADC resolution = 3000mV/4096 -#define VBAT_MV_PER_LSB (0.73242188F) -// Voltage divider value => 1.5M + 1M voltage divider on VBAT = (1.5M / (1M + 1.5M)) -#define VBAT_DIVIDER (0.4F) -// Compensation factor for the VBAT divider -#define VBAT_DIVIDER_COMP (1.73) -// Fixed calculation of milliVolt from compensation value -#define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) #undef AREF_VOLTAGE #define AREF_VOLTAGE 3.0 #define VBAT_AR_INTERNAL AR_INTERNAL_3_0 -#define ADC_MULTIPLIER VBAT_DIVIDER_COMP // REAL_VBAT_MV_PER_LSB -#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x) +#define ADC_MULTIPLIER (1.73F) #ifdef __cplusplus } @@ -134,4 +125,4 @@ static const uint8_t SCK = PIN_SPI_SCK; * Arduino objects - C++ only *----------------------------------------------------------------------------*/ -#endif +#endif \ No newline at end of file diff --git a/variants/canaryone/variant.h b/variants/canaryone/variant.h index 21aa921ce..d283f08f6 100644 --- a/variants/canaryone/variant.h +++ b/variants/canaryone/variant.h @@ -166,19 +166,10 @@ static const uint8_t A0 = PIN_A0; // and has 12 bit resolution #define BATTERY_SENSE_RESOLUTION_BITS 12 #define BATTERY_SENSE_RESOLUTION 4096.0 -// Definition of milliVolt per LSB => 3.0V ADC range and 12-bit ADC resolution = 3000mV/4096 -#define VBAT_MV_PER_LSB (0.73242188F) -// Voltage divider value => 100K + 100K voltage divider on VBAT = (100K / (100K + 100K)) -#define VBAT_DIVIDER (0.5F) -// Compensation factor for the VBAT divider -#define VBAT_DIVIDER_COMP (2.0) -// Fixed calculation of milliVolt from compensation value -#define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) #undef AREF_VOLTAGE #define AREF_VOLTAGE 3.0 #define VBAT_AR_INTERNAL AR_INTERNAL_3_0 -#define ADC_MULTIPLIER VBAT_DIVIDER_COMP -#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x) +#define ADC_MULTIPLIER (2.0F) #ifdef __cplusplus } diff --git a/variants/monteops_hw1/variant.h b/variants/monteops_hw1/variant.h index f7df0688b..97536b169 100644 --- a/variants/monteops_hw1/variant.h +++ b/variants/monteops_hw1/variant.h @@ -208,19 +208,10 @@ SO GPIO 39/TXEN MAY NOT BE DEFINED FOR SUCCESSFUL OPERATION OF THE SX1262 - TG // and has 12 bit resolution #define BATTERY_SENSE_RESOLUTION_BITS 12 #define BATTERY_SENSE_RESOLUTION 4096.0 -// Definition of milliVolt per LSB => 3.0V ADC range and 12-bit ADC resolution = 3000mV/4096 -#define VBAT_MV_PER_LSB (0.73242188F) -// Voltage divider value => 1.5M + 1M voltage divider on VBAT = (1.5M / (1M + 1.5M)) -#define VBAT_DIVIDER (0.4F) -// Compensation factor for the VBAT divider -#define VBAT_DIVIDER_COMP (1.73) -// Fixed calculation of milliVolt from compensation value -#define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) #undef AREF_VOLTAGE #define AREF_VOLTAGE 3.0 #define VBAT_AR_INTERNAL AR_INTERNAL_3_0 -#define ADC_MULTIPLIER VBAT_DIVIDER_COMP // REAL_VBAT_MV_PER_LSB -#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x) +#define ADC_MULTIPLIER (1.73F) // #define HAS_RTC 1 @@ -239,4 +230,4 @@ SO GPIO 39/TXEN MAY NOT BE DEFINED FOR SUCCESSFUL OPERATION OF THE SX1262 - TG * Arduino objects - C++ only *----------------------------------------------------------------------------*/ -#endif +#endif \ No newline at end of file diff --git a/variants/nano-g2-ultra/variant.h b/variants/nano-g2-ultra/variant.h index c328d2271..4d8aa5784 100644 --- a/variants/nano-g2-ultra/variant.h +++ b/variants/nano-g2-ultra/variant.h @@ -165,19 +165,10 @@ External serial flash W25Q16JV_IQ // and has 12 bit resolution #define BATTERY_SENSE_RESOLUTION_BITS 12 #define BATTERY_SENSE_RESOLUTION 4096.0 -// Definition of milliVolt per LSB => 3.0V ADC range and 12-bit ADC resolution = 3000mV/4096 -#define VBAT_MV_PER_LSB (0.73242188F) -// Voltage divider value => 100K + 100K voltage divider on VBAT = (100K / (100K + 100K)) -#define VBAT_DIVIDER (0.5F) -// Compensation factor for the VBAT divider -#define VBAT_DIVIDER_COMP (2.0F) -// Fixed calculation of milliVolt from compensation value -#define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) #undef AREF_VOLTAGE #define AREF_VOLTAGE 3.0 #define VBAT_AR_INTERNAL AR_INTERNAL_3_0 -#define ADC_MULTIPLIER VBAT_DIVIDER_COMP -#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x) +#define ADC_MULTIPLIER (2.0F) #define HAS_RTC 1 @@ -195,4 +186,4 @@ External serial flash W25Q16JV_IQ * Arduino objects - C++ only *----------------------------------------------------------------------------*/ -#endif +#endif \ No newline at end of file diff --git a/variants/rak10701/variant.h b/variants/rak10701/variant.h index d6eeb71dc..076504c16 100644 --- a/variants/rak10701/variant.h +++ b/variants/rak10701/variant.h @@ -264,19 +264,10 @@ SO GPIO 39/TXEN MAY NOT BE DEFINED FOR SUCCESSFUL OPERATION OF THE SX1262 - TG // and has 12 bit resolution #define BATTERY_SENSE_RESOLUTION_BITS 12 #define BATTERY_SENSE_RESOLUTION 4096.0 -// Definition of milliVolt per LSB => 3.0V ADC range and 12-bit ADC resolution = 3000mV/4096 -#define VBAT_MV_PER_LSB (0.73242188F) -// Voltage divider value => 1.5M + 1M voltage divider on VBAT = (1.5M / (1M + 1.5M)) -#define VBAT_DIVIDER (0.4F) -// Compensation factor for the VBAT divider -#define VBAT_DIVIDER_COMP (1.73) -// Fixed calculation of milliVolt from compensation value -#define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) #undef AREF_VOLTAGE #define AREF_VOLTAGE 3.0 #define VBAT_AR_INTERNAL AR_INTERNAL_3_0 -#define ADC_MULTIPLIER VBAT_DIVIDER_COMP // REAL_VBAT_MV_PER_LSB -#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x) +#define ADC_MULTIPLIER (1.73F) #define HAS_RTC 1 @@ -325,4 +316,4 @@ SO GPIO 39/TXEN MAY NOT BE DEFINED FOR SUCCESSFUL OPERATION OF THE SX1262 - TG * Arduino objects - C++ only *----------------------------------------------------------------------------*/ -#endif +#endif \ No newline at end of file diff --git a/variants/rak4631/variant.h b/variants/rak4631/variant.h index 0ccf3b1d7..bc5541336 100644 --- a/variants/rak4631/variant.h +++ b/variants/rak4631/variant.h @@ -246,19 +246,10 @@ SO GPIO 39/TXEN MAY NOT BE DEFINED FOR SUCCESSFUL OPERATION OF THE SX1262 - TG // and has 12 bit resolution #define BATTERY_SENSE_RESOLUTION_BITS 12 #define BATTERY_SENSE_RESOLUTION 4096.0 -// Definition of milliVolt per LSB => 3.0V ADC range and 12-bit ADC resolution = 3000mV/4096 -#define VBAT_MV_PER_LSB (0.73242188F) -// Voltage divider value => 1.5M + 1M voltage divider on VBAT = (1.5M / (1M + 1.5M)) -#define VBAT_DIVIDER (0.4F) -// Compensation factor for the VBAT divider -#define VBAT_DIVIDER_COMP (1.73F) -// Fixed calculation of milliVolt from compensation value -#define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) #undef AREF_VOLTAGE #define AREF_VOLTAGE 3.0 #define VBAT_AR_INTERNAL AR_INTERNAL_3_0 -#define ADC_MULTIPLIER VBAT_DIVIDER_COMP // REAL_VBAT_MV_PER_LSB -#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x) +#define ADC_MULTIPLIER 1.73 #define HAS_RTC 1 diff --git a/variants/rak4631_epaper/variant.h b/variants/rak4631_epaper/variant.h index b1bd84d21..0bb97498c 100644 --- a/variants/rak4631_epaper/variant.h +++ b/variants/rak4631_epaper/variant.h @@ -214,19 +214,10 @@ static const uint8_t SCK = PIN_SPI_SCK; // and has 12 bit resolution #define BATTERY_SENSE_RESOLUTION_BITS 12 #define BATTERY_SENSE_RESOLUTION 4096.0 -// Definition of milliVolt per LSB => 3.0V ADC range and 12-bit ADC resolution = 3000mV/4096 -#define VBAT_MV_PER_LSB (0.73242188F) -// Voltage divider value => 1.5M + 1M voltage divider on VBAT = (1.5M / (1M + 1.5M)) -#define VBAT_DIVIDER (0.4F) -// Compensation factor for the VBAT divider -#define VBAT_DIVIDER_COMP (1.73F) -// Fixed calculation of milliVolt from compensation value -#define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) #undef AREF_VOLTAGE #define AREF_VOLTAGE 3.0 #define VBAT_AR_INTERNAL AR_INTERNAL_3_0 -#define ADC_MULTIPLIER VBAT_DIVIDER_COMP // REAL_VBAT_MV_PER_LSB -#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x) +#define ADC_MULTIPLIER 1.73 #define HAS_RTC 1 diff --git a/variants/rak4631_epaper_onrxtx/variant.h b/variants/rak4631_epaper_onrxtx/variant.h index ec53ebd33..5888cff33 100644 --- a/variants/rak4631_epaper_onrxtx/variant.h +++ b/variants/rak4631_epaper_onrxtx/variant.h @@ -187,19 +187,10 @@ static const uint8_t SCK = PIN_SPI_SCK; // and has 12 bit resolution // #define BATTERY_SENSE_RESOLUTION_BITS 12 // #define BATTERY_SENSE_RESOLUTION 4096.0 -// Definition of milliVolt per LSB => 3.0V ADC range and 12-bit ADC resolution = 3000mV/4096 -// #define VBAT_MV_PER_LSB (0.73242188F) -// Voltage divider value => 1.5M + 1M voltage divider on VBAT = (1.5M / (1M + 1.5M)) -// #define VBAT_DIVIDER (0.4F) -// Compensation factor for the VBAT divider -// #define VBAT_DIVIDER_COMP (1.73) -// Fixed calculation of milliVolt from compensation value -// #define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) // #undef AREF_VOLTAGE // #define AREF_VOLTAGE 3.0 // #define VBAT_AR_INTERNAL AR_INTERNAL_3_0 -// #define ADC_MULTIPLIER VBAT_DIVIDER_COMP // REAL_VBAT_MV_PER_LSB -// #define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x) +// #define ADC_MULTIPLIER 1.73 // #define HAS_RTC 1 diff --git a/variants/t-echo/variant.h b/variants/t-echo/variant.h index 13f74d303..6a5146dc0 100644 --- a/variants/t-echo/variant.h +++ b/variants/t-echo/variant.h @@ -209,19 +209,10 @@ External serial flash WP25R1635FZUIL0 // and has 12 bit resolution #define BATTERY_SENSE_RESOLUTION_BITS 12 #define BATTERY_SENSE_RESOLUTION 4096.0 -// Definition of milliVolt per LSB => 3.0V ADC range and 12-bit ADC resolution = 3000mV/4096 -#define VBAT_MV_PER_LSB (0.73242188F) -// Voltage divider value => 100K + 100K voltage divider on VBAT = (100K / (100K + 100K)) -#define VBAT_DIVIDER (0.5F) -// Compensation factor for the VBAT divider -#define VBAT_DIVIDER_COMP (2.0F) -// Fixed calculation of milliVolt from compensation value -#define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) #undef AREF_VOLTAGE #define AREF_VOLTAGE 3.0 #define VBAT_AR_INTERNAL AR_INTERNAL_3_0 -#define ADC_MULTIPLIER VBAT_DIVIDER_COMP -#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x) +#define ADC_MULTIPLIER (2.0F) #define HAS_RTC 1 diff --git a/variants/trackerd/variant.h b/variants/trackerd/variant.h index b3fca367f..bd8017d8c 100644 --- a/variants/trackerd/variant.h +++ b/variants/trackerd/variant.h @@ -10,7 +10,7 @@ #define LED_PIN 13 // 13 red, 2 blue, 15 red -//#define HAS_BUTTON 0 +// #define HAS_BUTTON 0 #define BUTTON_PIN 0 #define BUTTON_NEED_PULLUP @@ -26,21 +26,10 @@ // The battery sense is hooked to pin A0 (4) // it is defined in the anlaolgue pin section of this file // and has 12 bit resolution +// #define BATTERY_SENSE_SAMPLES 15 // Set the number of samples, It has an effect of increasing sensitivity. #define BATTERY_SENSE_RESOLUTION_BITS 12 #define BATTERY_SENSE_RESOLUTION 4096.0 -// Definition of milliVolt per LSB => 3.0V ADC range and 12-bit ADC resolution = 3000mV/4096 -#define VBAT_MV_PER_LSB (0.73242188F) -// Voltage divider value => 100K + 100K voltage divider on VBAT = (100K / (100K + 100K)) -#define VBAT_DIVIDER (0.5F) -// Compensation factor for the VBAT divider -#define VBAT_DIVIDER_COMP (2.0) -// Fixed calculation of milliVolt from compensation value -#define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB) #undef AREF_VOLTAGE #define AREF_VOLTAGE 3.0 #define VBAT_AR_INTERNAL AR_INTERNAL_3_0 -#define ADC_MULTIPLIER VBAT_DIVIDER_COMP -#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x) - -//#define BATTERY_SENSE_SAMPLES 15 // Set the number of samples, It has an effect of increasing sensitivity. -//#define ADC_MULTIPLIER 3.3 \ No newline at end of file +#define ADC_MULTIPLIER (2.0F) \ No newline at end of file From b960dc1b415b76502cf71e6f9a902f0d80832a2e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sun, 24 Mar 2024 19:41:45 +0100 Subject: [PATCH 376/472] Add Shutdown and reboot to CardKB and friends (#3487) * Add Shutdown and reboot to CardKB and friends * aw shucks --- src/configuration.h | 8 ++++++++ src/input/kbI2cBase.cpp | 6 ++++++ src/modules/AdminModule.cpp | 2 -- src/modules/CannedMessageModule.cpp | 10 ++++++++++ 4 files changed, 24 insertions(+), 2 deletions(-) diff --git a/src/configuration.h b/src/configuration.h index ec32c72d1..c3dd2cb06 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -161,6 +161,14 @@ along with this program. If not, see . also enable HAS_ option not specifically disabled by variant.h */ #include "architecture.h" +#ifndef DEFAULT_REBOOT_SECONDS +#define DEFAULT_REBOOT_SECONDS 7 +#endif + +#ifndef DEFAULT_SHUTDOWN_SECONDS +#define DEFAULT_SHUTDOWN_SECONDS 2 +#endif + /* Step #3: mop up with disabled values for HAS_ options not handled by the above two */ // ----------------------------------------------------------------------------- diff --git a/src/input/kbI2cBase.cpp b/src/input/kbI2cBase.cpp index 1dba4e34d..048f8bbdc 100644 --- a/src/input/kbI2cBase.cpp +++ b/src/input/kbI2cBase.cpp @@ -216,6 +216,12 @@ int32_t KbI2cBase::runOnce() e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_RIGHT; e.kbchar = 0xb7; break; + case 0x90: // fn+r + case 0x9b: // fn+s + // just pass those unmodified + e.inputEvent = ANYKEY; + e.kbchar = c; + break; case 0x0d: // Enter e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_SELECT; break; diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index ae0dac9ff..c44048fd2 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -20,8 +20,6 @@ #include "mqtt/MQTT.h" -#define DEFAULT_REBOOT_SECONDS 7 - AdminModule *adminModule; bool hasOpenEditTransaction; diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index 3293e5d0d..60334ca03 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -409,6 +409,16 @@ int32_t CannedMessageModule::runOnce() case 0xb7: // right // already handled above break; + // handle fn+s for shutdown + case 0x9b: + screen->startShutdownScreen(); + shutdownAtMsec = millis() + DEFAULT_SHUTDOWN_SECONDS * 1000; + break; + // and fn+r for reboot + case 0x90: + screen->startRebootScreen(); + rebootAtMsec = millis() + DEFAULT_REBOOT_SECONDS * 1000; + break; default: if (this->cursor == this->freetext.length()) { this->freetext += this->payload; From 77fb230baaa3557b984a50d79970be98d0fd6618 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Sun, 24 Mar 2024 19:42:32 +0100 Subject: [PATCH 377/472] Native: fail-safes for simulated node without config file (#3486) * LinuxInput: only close if file descriptor is assigned * Native: set some defaults if no configuration file found --- src/input/LinuxInput.cpp | 3 ++- src/input/LinuxInput.h | 2 +- src/platform/portduino/PortduinoGlue.cpp | 2 ++ 3 files changed, 5 insertions(+), 2 deletions(-) diff --git a/src/input/LinuxInput.cpp b/src/input/LinuxInput.cpp index d2a94e94e..1ace2044c 100644 --- a/src/input/LinuxInput.cpp +++ b/src/input/LinuxInput.cpp @@ -24,7 +24,8 @@ LinuxInput::LinuxInput(const char *name) : concurrency::OSThread(name) void LinuxInput::deInit() { - close(fd); + if (fd >= 0) + close(fd); } int32_t LinuxInput::runOnce() diff --git a/src/input/LinuxInput.h b/src/input/LinuxInput.h index aa1e8e340..43d08493c 100644 --- a/src/input/LinuxInput.h +++ b/src/input/LinuxInput.h @@ -38,7 +38,7 @@ class LinuxInput : public Observable, public concurrency::OS int queue_progress = 0; struct epoll_event events[MAX_EVENTS]; - int fd; + int fd = -1; int ret; uint8_t report[8]; int epollfd; diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index b255c0ce1..72b2a3bc7 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -106,6 +106,8 @@ void portduinoSetup() } } else { std::cout << "No 'config.yaml' found, running simulated." << std::endl; + settingsMap[maxnodes] = 200; // Default to 200 nodes + settingsMap[logoutputlevel] = level_debug; // Default to debug // Set the random seed equal to TCPPort to have a different seed per instance randomSeed(TCPPort); return; From 728b58fb94f813a11c6aaa3d889749e0df3aa47e Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sun, 24 Mar 2024 18:50:26 -0500 Subject: [PATCH 378/472] [create-pull-request] automated change (#3489) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/admin.pb.h | 9 +++++++++ 2 files changed, 10 insertions(+), 1 deletion(-) diff --git a/protobufs b/protobufs index 0fe69d73e..95b0aa07b 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 0fe69d73e639372128d9480ec8cf65b182d36d30 +Subproject commit 95b0aa07b2bf3d2ab777f86d6ae8e256e94ced84 diff --git a/src/mesh/generated/meshtastic/admin.pb.h b/src/mesh/generated/meshtastic/admin.pb.h index d2f40c7f0..68e9c22a2 100644 --- a/src/mesh/generated/meshtastic/admin.pb.h +++ b/src/mesh/generated/meshtastic/admin.pb.h @@ -158,6 +158,10 @@ typedef struct _meshtastic_AdminMessage { uint32_t set_favorite_node; /* Set specified node-num to be un-favorited on the NodeDB on the device */ uint32_t remove_favorite_node; + /* Set fixed position data on the node and then set the position.fixed_position = true */ + meshtastic_Position set_fixed_position; + /* Clear fixed position coordinates and then set position.fixed_position = false */ + bool remove_fixed_position; /* Begins an edit transaction for config, module config, owner, and channel settings changes This will delay the standard *implicit* save to the file system and subsequent reboot behavior until committed (commit_edit_settings) */ bool begin_edit_settings; @@ -244,6 +248,8 @@ extern "C" { #define meshtastic_AdminMessage_remove_by_nodenum_tag 38 #define meshtastic_AdminMessage_set_favorite_node_tag 39 #define meshtastic_AdminMessage_remove_favorite_node_tag 40 +#define meshtastic_AdminMessage_set_fixed_position_tag 41 +#define meshtastic_AdminMessage_remove_fixed_position_tag 42 #define meshtastic_AdminMessage_begin_edit_settings_tag 64 #define meshtastic_AdminMessage_commit_edit_settings_tag 65 #define meshtastic_AdminMessage_reboot_ota_seconds_tag 95 @@ -285,6 +291,8 @@ X(a, STATIC, ONEOF, STRING, (payload_variant,set_ringtone_message,set_rin X(a, STATIC, ONEOF, UINT32, (payload_variant,remove_by_nodenum,remove_by_nodenum), 38) \ X(a, STATIC, ONEOF, UINT32, (payload_variant,set_favorite_node,set_favorite_node), 39) \ X(a, STATIC, ONEOF, UINT32, (payload_variant,remove_favorite_node,remove_favorite_node), 40) \ +X(a, STATIC, ONEOF, MESSAGE, (payload_variant,set_fixed_position,set_fixed_position), 41) \ +X(a, STATIC, ONEOF, BOOL, (payload_variant,remove_fixed_position,remove_fixed_position), 42) \ X(a, STATIC, ONEOF, BOOL, (payload_variant,begin_edit_settings,begin_edit_settings), 64) \ X(a, STATIC, ONEOF, BOOL, (payload_variant,commit_edit_settings,commit_edit_settings), 65) \ X(a, STATIC, ONEOF, INT32, (payload_variant,reboot_ota_seconds,reboot_ota_seconds), 95) \ @@ -307,6 +315,7 @@ X(a, STATIC, ONEOF, INT32, (payload_variant,nodedb_reset,nodedb_reset), #define meshtastic_AdminMessage_payload_variant_set_channel_MSGTYPE meshtastic_Channel #define meshtastic_AdminMessage_payload_variant_set_config_MSGTYPE meshtastic_Config #define meshtastic_AdminMessage_payload_variant_set_module_config_MSGTYPE meshtastic_ModuleConfig +#define meshtastic_AdminMessage_payload_variant_set_fixed_position_MSGTYPE meshtastic_Position #define meshtastic_HamParameters_FIELDLIST(X, a) \ X(a, STATIC, SINGULAR, STRING, call_sign, 1) \ From acc32916c3c7b6ac36a0c9d6c23ff1a448ab69d8 Mon Sep 17 00:00:00 2001 From: Jim Whitelaw Date: Mon, 25 Mar 2024 05:33:57 -0600 Subject: [PATCH 379/472] Add multiple configuration options for a minimized build (GPS,WiFi,BT,MQTT,Screen). (#3469) Co-authored-by: Ben Meadors --- .vscode/extensions.json | 2 +- src/ButtonThread.cpp | 8 +++-- src/Power.cpp | 4 ++- src/configuration.h | 54 ++++++++++++++++++++++++------- src/gps/GPS.cpp | 9 ++++-- src/gps/GPS.h | 5 ++- src/gps/NMEAWPL.cpp | 5 ++- src/graphics/Screen.cpp | 13 ++++++-- src/main.cpp | 37 +++++++++++++++------ src/main.h | 1 + src/mesh/Channels.cpp | 6 ++++ src/mesh/MeshService.cpp | 21 ++++++++---- src/mesh/MeshService.h | 6 ++-- src/mesh/NodeDB.cpp | 9 ++++-- src/mesh/PhoneAPI.cpp | 14 +++++--- src/mesh/Router.cpp | 11 ++++--- src/mesh/eth/ethClient.cpp | 6 +++- src/mesh/http/ContentHandler.cpp | 2 ++ src/mesh/http/WebServer.cpp | 4 +-- src/mesh/wifi/WiFiAPClient.cpp | 11 +++++-- src/mesh/wifi/WiFiAPClient.h | 2 +- src/modules/AdminModule.cpp | 8 +++-- src/modules/AdminModule.h | 2 +- src/modules/Modules.cpp | 12 ++++--- src/modules/PositionModule.cpp | 5 ++- src/modules/SerialModule.cpp | 9 +++--- src/mqtt/MQTT.cpp | 3 +- src/nimble/NimbleBluetooth.cpp | 9 ++++-- src/platform/esp32/main-esp32.cpp | 14 +++++--- src/platform/nrf52/main-nrf52.cpp | 5 ++- src/sleep.cpp | 16 ++++++--- 31 files changed, 226 insertions(+), 87 deletions(-) diff --git a/.vscode/extensions.json b/.vscode/extensions.json index 4fc84fa78..783791f0b 100644 --- a/.vscode/extensions.json +++ b/.vscode/extensions.json @@ -6,4 +6,4 @@ "platformio.platformio-ide", "trunk.io" ], -} +} \ No newline at end of file diff --git a/src/ButtonThread.cpp b/src/ButtonThread.cpp index 84d433285..a1f0170e8 100644 --- a/src/ButtonThread.cpp +++ b/src/ButtonThread.cpp @@ -1,10 +1,12 @@ #include "ButtonThread.h" +#include "configuration.h" +#if !MESHTASTIC_EXCLUDE_GPS #include "GPS.h" +#endif #include "MeshService.h" #include "PowerFSM.h" #include "RadioLibInterface.h" #include "buzz.h" -#include "graphics/Screen.h" #include "main.h" #include "modules/ExternalNotificationModule.h" #include "power.h" @@ -145,7 +147,7 @@ int32_t ButtonThread::runOnce() screen->print("Sent ad-hoc ping\n"); break; } - +#if HAS_GPS case BUTTON_EVENT_MULTI_PRESSED: { LOG_BUTTON("Multi press!\n"); if (!config.device.disable_triple_click && (gps != nullptr)) { @@ -155,7 +157,7 @@ int32_t ButtonThread::runOnce() } break; } - +#endif case BUTTON_EVENT_LONG_PRESSED: { LOG_BUTTON("Long press!\n"); powerFSM.trigger(EVENT_PRESS); diff --git a/src/Power.cpp b/src/Power.cpp index 71554daa3..779e32ff5 100644 --- a/src/Power.cpp +++ b/src/Power.cpp @@ -24,11 +24,13 @@ #include "nrfx_power.h" #endif -#ifdef DEBUG_HEAP_MQTT +#if defined(DEBUG_HEAP_MQTT) && !MESHTASTIC_EXCLUDE_MQTT #include "mqtt/MQTT.h" #include "target_specific.h" +#if !MESTASTIC_EXCLUDE_WIFI #include #endif +#endif #ifndef DELAY_FOREVER #define DELAY_FOREVER portMAX_DELAY diff --git a/src/configuration.h b/src/configuration.h index c3dd2cb06..7ce1a0b8b 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -171,17 +171,6 @@ along with this program. If not, see . /* Step #3: mop up with disabled values for HAS_ options not handled by the above two */ -// ----------------------------------------------------------------------------- -// GPS -// ----------------------------------------------------------------------------- - -#ifndef GPS_BAUDRATE -#define GPS_BAUDRATE 9600 -#endif -#ifndef GPS_THREAD_INTERVAL -#define GPS_THREAD_INTERVAL 100 -#endif - #ifndef HAS_WIFI #define HAS_WIFI 0 #endif @@ -232,7 +221,21 @@ along with this program. If not, see . #error HW_VENDOR must be defined #endif -// global switch to turn off all optional modules for a minimzed build +// ----------------------------------------------------------------------------- +// Global switches to turn off features for a minimized build +// ----------------------------------------------------------------------------- + +// #define MESHTASTIC_MINIMIZE_BUILD 1 +#ifdef MESHTASTIC_MINIMIZE_BUILD +#define MESHTASTIC_EXCLUDE_MODULES 1 +#define MESHTASTIC_EXCLUDE_WIFI 1 +#define MESHTASTIC_EXCLUDE_BLUETOOTH 1 +#define MESHTASTIC_EXCLUDE_GPS 1 +#define MESHTASTIC_EXCLUDE_SCREEN 1 +#define MESHTASTIC_EXCLUDE_MQTT 1 +#endif + +// Turn off all optional modules #ifdef MESHTASTIC_EXCLUDE_MODULES #define MESHTASTIC_EXCLUDE_AUDIO 1 #define MESHTASTIC_EXCLUDE_DETECTIONSENSOR 1 @@ -251,3 +254,30 @@ along with this program. If not, see . #define MESHTASTIC_EXCLUDE_INPUTBROKER 1 #define MESHTASTIC_EXCLUDE_SERIAL 1 #endif + +// // Turn off wifi even if HW supports wifi (webserver relies on wifi and is also disabled) +#ifdef MESHTASTIC_EXCLUDE_WIFI +#define MESHTASTIC_EXCLUDE_WEBSERVER 1 +#undef HAS_WIFI +#define HAS_WIFI 0 +#endif + +// // Turn off Bluetooth +#ifdef MESHTASTIC_EXCLUDE_BLUETOOTH +#undef HAS_BLUETOOTH +#define HAS_BLUETOOTH 0 +#endif + +// // Turn off GPS +#ifdef MESHTASTIC_EXCLUDE_GPS +#undef HAS_GPS +#define HAS_GPS 0 +#undef MESHTASTIC_EXCLUDE_RANGETEST +#define MESHTASTIC_EXCLUDE_RANGETEST 1 +#endif + +// Turn off Screen +#ifdef MESHTASTIC_EXCLUDE_SCREEN +#undef HAS_SCREEN +#define HAS_SCREEN 0 +#endif diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index df1d40fdf..a6f68f2ef 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -1,8 +1,10 @@ -#include "GPS.h" +#include "configuration.h" +#if !MESHTASTIC_EXCLUDE_GPS #include "Default.h" +#include "GPS.h" #include "NodeDB.h" #include "RTC.h" -#include "configuration.h" + #include "main.h" // pmu_found #include "sleep.h" #include "ubx.h" @@ -1481,4 +1483,5 @@ void GPS::toggleGpsMode() LOG_DEBUG("Flag set to true to restore power. GpsMode: ENABLED\n"); enable(); } -} \ No newline at end of file +} +#endif // Exclude GPS \ No newline at end of file diff --git a/src/gps/GPS.h b/src/gps/GPS.h index 502763bb6..49f27e29f 100644 --- a/src/gps/GPS.h +++ b/src/gps/GPS.h @@ -1,4 +1,6 @@ #pragma once +#include "configuration.h" +#if !MESHTASTIC_EXCLUDE_GPS #include "GPSStatus.h" #include "Observer.h" @@ -268,4 +270,5 @@ class GPS : private concurrency::OSThread GnssModel_t gnssModel = GNSS_MODEL_UNKNOWN; }; -extern GPS *gps; \ No newline at end of file +extern GPS *gps; +#endif // Exclude GPS \ No newline at end of file diff --git a/src/gps/NMEAWPL.cpp b/src/gps/NMEAWPL.cpp index 9eff4d00e..cdac3bb27 100644 --- a/src/gps/NMEAWPL.cpp +++ b/src/gps/NMEAWPL.cpp @@ -1,3 +1,4 @@ +#if !MESHTASTIC_EXCLUDE_GPS #include "NMEAWPL.h" #include "GeoCoord.h" #include "RTC.h" @@ -93,4 +94,6 @@ uint32_t printGGA(char *buf, size_t bufsz, const meshtastic_Position &pos) } len += snprintf(buf + len, bufsz - len, "*%02X\r\n", chk); return len; -} \ No newline at end of file +} + +#endif \ No newline at end of file diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 3c3777496..2453faec9 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -25,7 +25,9 @@ along with this program. If not, see . #include #include "DisplayFormatters.h" +#if !MESHTASTIC_EXCLUDE_GPS #include "GPS.h" +#endif #include "MeshService.h" #include "NodeDB.h" #include "error.h" @@ -92,8 +94,10 @@ std::vector moduleFrames; // Stores the last 4 of our hardware ID, to make finding the device for pairing easier static char ourId[5]; +#if HAS_GPS // GeoCoord object for the screen GeoCoord geoCoord; +#endif #ifdef SHOW_REDRAWS static bool heartbeat = false; @@ -483,7 +487,7 @@ static void drawNodes(OLEDDisplay *display, int16_t x, int16_t y, const NodeStat if (config.display.heading_bold) display->drawString(x + 11, y - 2, usersString); } - +#if HAS_GPS // Draw GPS status summary static void drawGPS(OLEDDisplay *display, int16_t x, int16_t y, const GPSStatus *gps) { @@ -625,7 +629,7 @@ static void drawGPScoordinates(OLEDDisplay *display, int16_t x, int16_t y, const } } } - +#endif namespace { @@ -1542,6 +1546,7 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16 } else { drawNodes(display, x + (SCREEN_WIDTH * 0.25), y + 3, nodeStatus); } +#if HAS_GPS // Display GPS status if (config.position.gps_mode != meshtastic_Config_PositionConfig_GpsMode_ENABLED) { drawGPSpowerstat(display, x, y + 2, gpsStatus); @@ -1552,7 +1557,7 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16 drawGPS(display, x + (SCREEN_WIDTH * 0.63), y + 3, gpsStatus); } } - +#endif display->setColor(WHITE); // Draw the channel name display->drawString(x, y + FONT_HEIGHT_SMALL, channelStr); @@ -1771,6 +1776,7 @@ void DebugInfo::drawFrameSettings(OLEDDisplay *display, OLEDDisplayUiState *stat char chUtil[13]; snprintf(chUtil, sizeof(chUtil), "ChUtil %2.0f%%", airTime->channelUtilizationPercent()); display->drawString(x + SCREEN_WIDTH - display->getStringWidth(chUtil), y + FONT_HEIGHT_SMALL * 1, chUtil); +#if HAS_GPS if (config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_ENABLED) { // Line 3 if (config.display.gps_format != @@ -1782,6 +1788,7 @@ void DebugInfo::drawFrameSettings(OLEDDisplay *display, OLEDDisplayUiState *stat } else { drawGPSpowerstat(display, x, y + FONT_HEIGHT_SMALL * 2, gpsStatus); } +#endif /* Display a heartbeat pixel that blinks every time the frame is redrawn */ #ifdef SHOW_REDRAWS if (heartbeat) diff --git a/src/main.cpp b/src/main.cpp index f7d1a4bc0..0c45e903a 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -1,4 +1,7 @@ +#include "configuration.h" +#if !MESHTASTIC_EXCLUDE_GPS #include "GPS.h" +#endif #include "MeshRadio.h" #include "MeshService.h" #include "NodeDB.h" @@ -6,7 +9,7 @@ #include "ReliableRouter.h" #include "airtime.h" #include "buzz.h" -#include "configuration.h" + #include "error.h" #include "power.h" // #include "debug.h" @@ -36,9 +39,11 @@ #if !MESHTASTIC_EXCLUDE_WEBSERVER #include "mesh/http/WebServer.h" #endif +#if !MESHTASTIC_EXCLUDE_BLUETOOTH #include "nimble/NimbleBluetooth.h" NimbleBluetooth *nimbleBluetooth; #endif +#endif #ifdef ARCH_NRF52 #include "NRF52Bluetooth.h" @@ -54,16 +59,21 @@ NRF52Bluetooth *nrf52Bluetooth; #include "mesh/api/ethServerAPI.h" #include "mesh/eth/ethClient.h" #endif + +#if !MESHTASTIC_EXCLUDE_MQTT #include "mqtt/MQTT.h" +#endif #include "LLCC68Interface.h" #include "RF95Interface.h" #include "SX1262Interface.h" #include "SX1268Interface.h" #include "SX1280Interface.h" + #ifdef ARCH_STM32WL #include "STM32WLE5JCInterface.h" #endif + #if !HAS_RADIO && defined(ARCH_PORTDUINO) #include "platform/portduino/SimRadio.h" #endif @@ -80,6 +90,7 @@ NRF52Bluetooth *nrf52Bluetooth; #if HAS_BUTTON || defined(ARCH_PORTDUINO) #include "ButtonThread.h" #endif + #include "PowerFSMThread.h" #if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) @@ -640,16 +651,21 @@ void setup() readFromRTC(); // read the main CPU RTC at first (in case we can't get GPS time) +#if !MESHTASTIC_EXCLUDE_GPS // If we're taking on the repeater role, ignore GPS - if (config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER && - config.position.gps_mode != meshtastic_Config_PositionConfig_GpsMode_NOT_PRESENT) { - gps = GPS::createGps(); - } - if (gps) { - gpsStatus->observe(&gps->newStatus); - } else { - LOG_DEBUG("Running without GPS.\n"); + if (HAS_GPS) { + if (config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER && + config.position.gps_mode != meshtastic_Config_PositionConfig_GpsMode_NOT_PRESENT) { + gps = GPS::createGps(); + if (gps) { + gpsStatus->observe(&gps->newStatus); + } else { + LOG_DEBUG("Running without GPS.\n"); + } + } } +#endif + nodeStatus->observe(&nodeDB->newStatus); #ifdef HAS_I2S @@ -852,9 +868,12 @@ void setup() } } +#if !MESHTASTIC_EXCLUDE_MQTT mqttInit(); +#endif #ifndef ARCH_PORTDUINO + // Initialize Wifi #if HAS_WIFI initWifi(); diff --git a/src/main.h b/src/main.h index 5af0b4082..132fd190b 100644 --- a/src/main.h +++ b/src/main.h @@ -54,6 +54,7 @@ extern int TCPPort; // set by Portduino // Global Screen singleton. extern graphics::Screen *screen; + // extern Observable newPowerStatus; //TODO: move this to main-esp32.cpp somehow or a helper class // extern meshtastic::PowerStatus *powerStatus; diff --git a/src/mesh/Channels.cpp b/src/mesh/Channels.cpp index 840e65bca..079af4eca 100644 --- a/src/mesh/Channels.cpp +++ b/src/mesh/Channels.cpp @@ -7,7 +7,9 @@ #include +#if !MESHTASTIC_EXCLUDE_MQTT #include "mqtt/MQTT.h" +#endif /// 16 bytes of random PSK for our _public_ default channel that all devices power up on (AES128) static const uint8_t defaultpsk[] = {0xd4, 0xf1, 0xbb, 0x3a, 0x20, 0x29, 0x07, 0x59, @@ -18,7 +20,9 @@ Channels channels; const char *Channels::adminChannel = "admin"; const char *Channels::gpioChannel = "gpio"; const char *Channels::serialChannel = "serial"; +#if !MESHTASTIC_EXCLUDE_MQTT const char *Channels::mqttChannel = "mqtt"; +#endif uint8_t xorHash(const uint8_t *p, size_t len) { @@ -195,10 +199,12 @@ void Channels::onConfigChanged() if (ch.role == meshtastic_Channel_Role_PRIMARY) primaryIndex = i; } +#if !MESHTASTIC_EXCLUDE_MQTT if (channels.anyMqttEnabled() && mqtt && !mqtt->isEnabled()) { LOG_DEBUG("MQTT is enabled on at least one channel, so set MQTT thread to run immediately\n"); mqtt->start(); } +#endif } meshtastic_Channel &Channels::getByIndex(ChannelIndex chIndex) diff --git a/src/mesh/MeshService.cpp b/src/mesh/MeshService.cpp index 2df5d5797..2c1969e30 100644 --- a/src/mesh/MeshService.cpp +++ b/src/mesh/MeshService.cpp @@ -1,10 +1,11 @@ #include "configuration.h" -#include -#include + +#if !MESHTASTIC_EXCLUDE_GPS +#include "GPS.h" +#endif #include "../concurrency/Periodic.h" #include "BluetoothCommon.h" // needed for updateBatteryLevel, FIXME, eventually when we pull mesh out into a lib we shouldn't be whacking bluetooth from here -#include "GPS.h" #include "MeshService.h" #include "NodeDB.h" #include "PowerFSM.h" @@ -15,8 +16,10 @@ #include "modules/NodeInfoModule.h" #include "modules/PositionModule.h" #include "power.h" +#include +#include -#ifdef ARCH_ESP32 +#if defined(ARCH_ESP32) && !MESHTASTIC_EXCLUDE_BLUETOOTH #include "nimble/NimbleBluetooth.h" #endif @@ -71,10 +74,11 @@ MeshService::MeshService() void MeshService::init() { // moved much earlier in boot (called from setup()) - // nodeDB->init(); - + // nodeDB.init(); +#if HAS_GPS if (gps) gpsObserver.observe(&gps->newStatus); +#endif } int MeshService::handleFromRadio(const meshtastic_MeshPacket *mp) @@ -270,11 +274,13 @@ void MeshService::sendNetworkPing(NodeNum dest, bool wantReplies) assert(node); if (hasValidPosition(node)) { +#if HAS_GPS if (positionModule) { LOG_INFO("Sending position ping to 0x%x, wantReplies=%d, channel=%d\n", dest, wantReplies, node->channel); positionModule->sendOurPosition(dest, wantReplies, node->channel); } } else { +#endif if (nodeInfoModule) { LOG_INFO("Sending nodeinfo ping to 0x%x, wantReplies=%d, channel=%d\n", dest, wantReplies, node->channel); nodeInfoModule->sendOurNodeInfo(dest, wantReplies, node->channel); @@ -344,6 +350,7 @@ meshtastic_NodeInfoLite *MeshService::refreshLocalMeshNode() return node; } +#if HAS_GPS int MeshService::onGPSChanged(const meshtastic::GPSStatus *newStatus) { // Update our local node info with our position (even if we don't decide to update anyone else) @@ -377,7 +384,7 @@ int MeshService::onGPSChanged(const meshtastic::GPSStatus *newStatus) return 0; } - +#endif bool MeshService::isToPhoneQueueEmpty() { return toPhoneQueue.isEmpty(); diff --git a/src/mesh/MeshService.h b/src/mesh/MeshService.h index 68287efc2..8d1434030 100644 --- a/src/mesh/MeshService.h +++ b/src/mesh/MeshService.h @@ -23,9 +23,10 @@ extern Allocator &mqttClientProxyMessagePool; */ class MeshService { +#if HAS_GPS CallbackObserver gpsObserver = CallbackObserver(this, &MeshService::onGPSChanged); - +#endif /// received packets waiting for the phone to process them /// FIXME, change to a DropOldestQueue and keep a count of the number of dropped packets to ensure /// we never hang because android hasn't been there in a while @@ -132,10 +133,11 @@ class MeshService ErrorCode sendQueueStatusToPhone(const meshtastic_QueueStatus &qs, ErrorCode res, uint32_t mesh_packet_id); private: +#if HAS_GPS /// Called when our gps position has changed - updates nodedb and sends Location message out into the mesh /// returns 0 to allow further processing int onGPSChanged(const meshtastic::GPSStatus *arg); - +#endif /// Handle a packet that just arrived from the radio. This method does _ReliableRouternot_ free the provided packet. If it /// needs to keep the packet around it makes a copy int handleFromRadio(const meshtastic_MeshPacket *p); diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 3734309be..262b0e039 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -1,11 +1,12 @@ #include "configuration.h" - +#if !MESHTASTIC_EXCLUDE_GPS +#include "GPS.h" +#endif #include "../detect/ScanI2C.h" #include "Channels.h" #include "CryptoEngine.h" #include "Default.h" #include "FSCommon.h" -#include "GPS.h" #include "MeshRadio.h" #include "NodeDB.h" #include "PacketHistory.h" @@ -25,7 +26,9 @@ #include #ifdef ARCH_ESP32 +#if !MESHTASTIC_EXCLUDE_WIFI #include "mesh/wifi/WiFiAPClient.h" +#endif #include "modules/esp32/StoreForwardModule.h" #include #include @@ -230,7 +233,7 @@ void NodeDB::installDefaultConfig() config.has_position = true; config.has_power = true; config.has_network = true; - config.has_bluetooth = true; + config.has_bluetooth = (HAS_BLUETOOTH ? true : false); config.device.rebroadcast_mode = meshtastic_Config_DeviceConfig_RebroadcastMode_ALL; config.lora.sx126x_rx_boosted_gain = true; diff --git a/src/mesh/PhoneAPI.cpp b/src/mesh/PhoneAPI.cpp index 48f7eb940..f2d2a6e9d 100644 --- a/src/mesh/PhoneAPI.cpp +++ b/src/mesh/PhoneAPI.cpp @@ -1,13 +1,16 @@ -#include "PhoneAPI.h" +#include "configuration.h" +#if !MESHTASTIC_EXCLUDE_GPS +#include "GPS.h" +#endif + #include "Channels.h" #include "Default.h" -#include "GPS.h" #include "MeshService.h" #include "NodeDB.h" +#include "PhoneAPI.h" #include "PowerFSM.h" #include "RadioInterface.h" #include "TypeConversions.h" -#include "configuration.h" #include "main.h" #include "xmodem.h" @@ -18,8 +21,9 @@ #if ToRadio_size > MAX_TO_FROM_RADIO_SIZE #error ToRadio is too big #endif - +#if !MESHTASTIC_EXCLUDE_MQTT #include "mqtt/MQTT.h" +#endif PhoneAPI::PhoneAPI() { @@ -104,6 +108,7 @@ bool PhoneAPI::handleToRadio(const uint8_t *buf, size_t bufLength) LOG_INFO("Got xmodem packet\n"); xModem.handlePacket(toRadioScratch.xmodemPacket); break; +#if !MESHTASTIC_EXCLUDE_MQTT case meshtastic_ToRadio_mqttClientProxyMessage_tag: LOG_INFO("Got MqttClientProxy message\n"); if (mqtt && moduleConfig.mqtt.proxy_to_client_enabled && moduleConfig.mqtt.enabled && @@ -114,6 +119,7 @@ bool PhoneAPI::handleToRadio(const uint8_t *buf, size_t bufLength) "not enabled\n"); } break; +#endif case meshtastic_ToRadio_heartbeat_tag: LOG_DEBUG("Got client heartbeat\n"); break; diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp index 7894b1b92..266c4f78d 100644 --- a/src/mesh/Router.cpp +++ b/src/mesh/Router.cpp @@ -11,9 +11,9 @@ extern "C" { #include "mesh/compression/unishox2.h" } - +#if !MESHTASTIC_EXCLUDE_MQTT #include "mqtt/MQTT.h" - +#endif /** * Router todo * @@ -261,11 +261,12 @@ ErrorCode Router::send(meshtastic_MeshPacket *p) abortSendAndNak(encodeResult, p); return encodeResult; // FIXME - this isn't a valid ErrorCode } - +#if !MESHTASTIC_EXCLUDE_MQTT // Only publish to MQTT if we're the original transmitter of the packet if (moduleConfig.mqtt.enabled && p->from == nodeDB->getNodeNum() && mqtt) { mqtt->onSend(*p, *p_decoded, chIndex); } +#endif packetPool.release(p_decoded); } @@ -465,10 +466,12 @@ void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src) cancelSending(p->from, p->id); skipHandle = true; } - +#if !MESHTASTIC_EXCLUDE_MQTT // Publish received message to MQTT if we're not the original transmitter of the packet if (!skipHandle && moduleConfig.mqtt.enabled && getFrom(p) != nodeDB->getNodeNum() && mqtt) mqtt->onSend(*p_encrypted, *p, p->channel); +#endif + } else { printPacket("packet decoding failed or skipped (no PSK?)", p); } diff --git a/src/mesh/eth/ethClient.cpp b/src/mesh/eth/ethClient.cpp index 97f5027bd..5373f243e 100644 --- a/src/mesh/eth/ethClient.cpp +++ b/src/mesh/eth/ethClient.cpp @@ -2,9 +2,12 @@ #include "NodeDB.h" #include "RTC.h" #include "concurrency/Periodic.h" +#include "configuration.h" #include "main.h" #include "mesh/api/ethServerAPI.h" +#if !MESHTASTIC_EXCLUDE_MQTT #include "mqtt/MQTT.h" +#endif #include "target_specific.h" #include #include @@ -66,11 +69,12 @@ static int32_t reconnectETH() ethStartupComplete = true; } - +#if !MESHTASTIC_EXCLUDE_MQTT // FIXME this is kinda yucky, instead we should just have an observable for 'wifireconnected' if (mqtt && !moduleConfig.mqtt.proxy_to_client_enabled && !mqtt->isConnectedDirectly()) { mqtt->reconnect(); } +#endif } #ifndef DISABLE_NTP diff --git a/src/mesh/http/ContentHandler.cpp b/src/mesh/http/ContentHandler.cpp index 1557948d8..7f9df058d 100644 --- a/src/mesh/http/ContentHandler.cpp +++ b/src/mesh/http/ContentHandler.cpp @@ -6,7 +6,9 @@ #include "main.h" #include "mesh/http/ContentHelper.h" #include "mesh/http/WebServer.h" +#if !MESHTASTIC_EXCLUDE_WIFI #include "mesh/wifi/WiFiAPClient.h" +#endif #include "mqtt/JSON.h" #include "power.h" #include "sleep.h" diff --git a/src/mesh/http/WebServer.cpp b/src/mesh/http/WebServer.cpp index 83fe20dd8..fc8535257 100644 --- a/src/mesh/http/WebServer.cpp +++ b/src/mesh/http/WebServer.cpp @@ -1,14 +1,14 @@ +#include "configuration.h" #if !MESHTASTIC_EXCLUDE_WEBSERVER -#include "mesh/http/WebServer.h" #include "NodeDB.h" #include "graphics/Screen.h" #include "main.h" +#include "mesh/http/WebServer.h" #include "mesh/wifi/WiFiAPClient.h" #include "sleep.h" #include #include #include - #include #include diff --git a/src/mesh/wifi/WiFiAPClient.cpp b/src/mesh/wifi/WiFiAPClient.cpp index 88764d2be..1de4d7669 100644 --- a/src/mesh/wifi/WiFiAPClient.cpp +++ b/src/mesh/wifi/WiFiAPClient.cpp @@ -1,18 +1,24 @@ -#include "mesh/wifi/WiFiAPClient.h" +#include "configuration.h" +#if !MESHTASTIC_EXCLUDE_WIFI #include "NodeDB.h" #include "RTC.h" #include "concurrency/Periodic.h" -#include "configuration.h" +#include "mesh/wifi/WiFiAPClient.h" + #include "main.h" #include "mesh/api/WiFiServerAPI.h" +#if !MESHTASTIC_EXCLUDE_MQTT #include "mqtt/MQTT.h" +#endif #include "target_specific.h" #include #include #ifdef ARCH_ESP32 #if !MESHTASTIC_EXCLUDE_WEBSERVER +#if !MESHTASTIC_EXCLUDE_WEBSERVER #include "mesh/http/WebServer.h" #endif +#endif #include #include static void WiFiEvent(WiFiEvent_t event); @@ -408,3 +414,4 @@ uint8_t getWifiDisconnectReason() { return wifiDisconnectReason; } +#endif \ No newline at end of file diff --git a/src/mesh/wifi/WiFiAPClient.h b/src/mesh/wifi/WiFiAPClient.h index 6625d3e46..5f4e2f5c9 100644 --- a/src/mesh/wifi/WiFiAPClient.h +++ b/src/mesh/wifi/WiFiAPClient.h @@ -5,7 +5,7 @@ #include #include -#if defined(HAS_WIFI) && !defined(ARCH_PORTDUINO) +#if HAS_WIFI && !defined(ARCH_PORTDUINO) #include #endif diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index c44048fd2..50cec824d 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -4,7 +4,7 @@ #include "NodeDB.h" #include "PowerFSM.h" #include -#ifdef ARCH_ESP32 +#if defined(ARCH_ESP32) && !MESHTASTIC_EXCLUDE_BLUETOOTH #include "BleOta.h" #endif #include "Router.h" @@ -18,7 +18,9 @@ #endif #include "Default.h" +#if !MESHTASTIC_EXCLUDE_MQTT #include "mqtt/MQTT.h" +#endif AdminModule *adminModule; bool hasOpenEditTransaction; @@ -119,7 +121,7 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta } case meshtastic_AdminMessage_reboot_ota_seconds_tag: { int32_t s = r->reboot_ota_seconds; -#ifdef ARCH_ESP32 +#if defined(ARCH_ESP32) && !MESHTASTIC_EXCLUDE_BLUETOOTH if (BleOta::getOtaAppVersion().isEmpty()) { LOG_INFO("No OTA firmware available, scheduling regular reboot in %d seconds\n", s); screen->startRebootScreen(); @@ -666,7 +668,9 @@ void AdminModule::handleGetDeviceConnectionStatus(const meshtastic_MeshPacket &r if (Ethernet.linkStatus() == LinkON) { conn.ethernet.status.is_connected = true; conn.ethernet.status.ip_address = Ethernet.localIP(); +#if !MESHTASTIC_EXCLUDE_MQTT conn.ethernet.status.is_mqtt_connected = mqtt && mqtt->isConnectedDirectly(); +#endif conn.ethernet.status.is_syslog_connected = false; // FIXME wire this up } else { conn.ethernet.status.is_connected = false; diff --git a/src/modules/AdminModule.h b/src/modules/AdminModule.h index 6ecc88829..32b32c253 100644 --- a/src/modules/AdminModule.h +++ b/src/modules/AdminModule.h @@ -1,6 +1,6 @@ #pragma once #include "ProtobufModule.h" -#if HAS_WIFI +#if HAS_WIFI && !MESHTASTIC_EXCLUDE_WIFI #include "mesh/wifi/WiFiAPClient.h" #endif diff --git a/src/modules/Modules.cpp b/src/modules/Modules.cpp index 97ed90cf1..5ac45577e 100644 --- a/src/modules/Modules.cpp +++ b/src/modules/Modules.cpp @@ -21,7 +21,9 @@ #include "modules/NeighborInfoModule.h" #endif #include "modules/NodeInfoModule.h" +#if !MESHTASTIC_EXCLUDE_GPS #include "modules/PositionModule.h" +#endif #if !MESHTASTIC_EXCLUDE_REMOTEHARDWARE #include "modules/RemoteHardwareModule.h" #endif @@ -61,15 +63,13 @@ #if !MESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION #include "modules/ExternalNotificationModule.h" #endif -#if !MESHTASTIC_EXCLUDE_RANGETEST +#if !MESHTASTIC_EXCLUDE_RANGETEST && !MESHTASTIC_EXCLUDE_GPS #include "modules/RangeTestModule.h" #endif -#if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)) && !defined(CONFIG_IDF_TARGET_ESP32S2) -#if !MESHTASTIC_EXCLUDE_SERIAL +#if !defined(CONFIG_IDF_TARGET_ESP32S2) && !MESHTASTIC_EXCLUDE_SERIAL #include "modules/SerialModule.h" #endif #endif -#endif /** * Create module instances here. If you are adding a new module, you must 'new' it here (or somewhere else) */ @@ -81,7 +81,9 @@ void setupModules() #endif adminModule = new AdminModule(); nodeInfoModule = new NodeInfoModule(); +#if !MESHTASTIC_EXCLUDE_GPS positionModule = new PositionModule(); +#endif #if !MESHTASTIC_EXCLUDE_WAYPOINT waypointModule = new WaypointModule(); #endif @@ -169,7 +171,7 @@ void setupModules() #if !MESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION externalNotificationModule = new ExternalNotificationModule(); #endif -#if !MESHTASTIC_EXCLUDE_RANGETEST +#if !MESHTASTIC_EXCLUDE_RANGETEST && !MESHTASTIC_EXCLUDE_GPS new RangeTestModule(); #endif #endif diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index d22c6b699..dcfe03f7f 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -1,3 +1,4 @@ +#if !MESHTASTIC_EXCLUDE_GPS #include "PositionModule.h" #include "Default.h" #include "GPS.h" @@ -418,4 +419,6 @@ void PositionModule::handleNewPosition() lastGpsSend = now; } } -} \ No newline at end of file +} + +#endif \ No newline at end of file diff --git a/src/modules/SerialModule.cpp b/src/modules/SerialModule.cpp index 663bc1d86..96a99b13e 100644 --- a/src/modules/SerialModule.cpp +++ b/src/modules/SerialModule.cpp @@ -179,14 +179,14 @@ int32_t SerialModule::runOnce() } else { if (moduleConfig.serial.mode == meshtastic_ModuleConfig_SerialConfig_Serial_Mode_PROTO) { return runOncePart(); - } else if (moduleConfig.serial.mode == meshtastic_ModuleConfig_SerialConfig_Serial_Mode_NMEA) { + } else if ((moduleConfig.serial.mode == meshtastic_ModuleConfig_SerialConfig_Serial_Mode_NMEA) && HAS_GPS) { // in NMEA mode send out GGA every 2 seconds, Don't read from Port if (millis() - lastNmeaTime > 2000) { lastNmeaTime = millis(); printGGA(outbuf, sizeof(outbuf), localPosition); serialPrint->printf("%s", outbuf); } - } else if (moduleConfig.serial.mode == meshtastic_ModuleConfig_SerialConfig_Serial_Mode_CALTOPO) { + } else if ((moduleConfig.serial.mode == meshtastic_ModuleConfig_SerialConfig_Serial_Mode_CALTOPO) && HAS_GPS) { if (millis() - lastNmeaTime > 10000) { lastNmeaTime = millis(); uint32_t readIndex = 0; @@ -295,8 +295,9 @@ ProcessMessage SerialModuleRadio::handleReceived(const meshtastic_MeshPacket &mp serialPrint->println(); serialPrint->printf("%s: %s", sender, p.payload.bytes); serialPrint->println(); - } else if (moduleConfig.serial.mode == meshtastic_ModuleConfig_SerialConfig_Serial_Mode_NMEA || - moduleConfig.serial.mode == meshtastic_ModuleConfig_SerialConfig_Serial_Mode_CALTOPO) { + } else if ((moduleConfig.serial.mode == meshtastic_ModuleConfig_SerialConfig_Serial_Mode_NMEA || + moduleConfig.serial.mode == meshtastic_ModuleConfig_SerialConfig_Serial_Mode_CALTOPO) && + HAS_GPS) { // Decode the Payload some more meshtastic_Position scratch; meshtastic_Position *decoded = NULL; diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 8e7c8f2cc..05d5486b2 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -2,6 +2,7 @@ #include "MeshService.h" #include "NodeDB.h" #include "PowerFSM.h" +#include "configuration.h" #include "main.h" #include "mesh/Channels.h" #include "mesh/Router.h" @@ -13,7 +14,7 @@ #endif #include "mesh/generated/meshtastic/remote_hardware.pb.h" #include "sleep.h" -#if HAS_WIFI +#if HAS_WIFI && !MESHTASTIC_EXCLUDE_WIFI #include "mesh/wifi/WiFiAPClient.h" #include #endif diff --git a/src/nimble/NimbleBluetooth.cpp b/src/nimble/NimbleBluetooth.cpp index 0b2a806c9..bc94abf6e 100644 --- a/src/nimble/NimbleBluetooth.cpp +++ b/src/nimble/NimbleBluetooth.cpp @@ -1,7 +1,9 @@ -#include "NimbleBluetooth.h" -#include "BluetoothCommon.h" -#include "PowerFSM.h" #include "configuration.h" +#if !MESHTASTIC_EXCLUDE_BLUETOOTH +#include "BluetoothCommon.h" +#include "NimbleBluetooth.h" +#include "PowerFSM.h" + #include "main.h" #include "mesh/PhoneAPI.h" #include "mesh/mesh-pb-constants.h" @@ -227,3 +229,4 @@ void clearNVS() ESP.restart(); #endif } +#endif \ No newline at end of file diff --git a/src/platform/esp32/main-esp32.cpp b/src/platform/esp32/main-esp32.cpp index f97f6d121..3fb6e7774 100644 --- a/src/platform/esp32/main-esp32.cpp +++ b/src/platform/esp32/main-esp32.cpp @@ -3,11 +3,14 @@ #include "esp_task_wdt.h" #include "main.h" -#if !defined(CONFIG_IDF_TARGET_ESP32S2) +#if !defined(CONFIG_IDF_TARGET_ESP32S2) && !MESHTASTIC_EXCLUDE_BLUETOOTH +#include "BleOta.h" #include "nimble/NimbleBluetooth.h" #endif -#include "BleOta.h" + +#if !MESHTASTIC_EXCLUDE_WIFI #include "mesh/wifi/WiFiAPClient.h" +#endif #include "meshUtils.h" #include "sleep.h" @@ -18,8 +21,7 @@ #include #include -#if !defined(CONFIG_IDF_TARGET_ESP32S2) - +#if !defined(CONFIG_IDF_TARGET_ESP32S2) && !MESHTASTIC_EXCLUDE_BLUETOOTH void setBluetoothEnable(bool enable) { if (!isWifiAvailable() && config.bluetooth.enabled == true) { @@ -108,12 +110,16 @@ void esp32Setup() preferences.putUInt("rebootCounter", rebootCounter); preferences.end(); LOG_DEBUG("Number of Device Reboots: %d\n", rebootCounter); +#if !MESHTASTIC_EXCLUDE_BLUETOOTH String BLEOTA = BleOta::getOtaAppVersion(); if (BLEOTA.isEmpty()) { LOG_DEBUG("No OTA firmware available\n"); } else { LOG_DEBUG("OTA firmware version %s\n", BLEOTA.c_str()); } +#else + LOG_DEBUG("No OTA firmware available\n"); +#endif // enableModemSleep(); diff --git a/src/platform/nrf52/main-nrf52.cpp b/src/platform/nrf52/main-nrf52.cpp index 2f670dee3..ecffb745d 100644 --- a/src/platform/nrf52/main-nrf52.cpp +++ b/src/platform/nrf52/main-nrf52.cpp @@ -65,6 +65,7 @@ static void initBrownout() static const bool useSoftDevice = true; // Set to false for easier debugging +#if !MESHTASTIC_EXCLUDE_BLUETOOTH void setBluetoothEnable(bool enable) { if (enable && config.bluetooth.enabled) { @@ -88,7 +89,9 @@ void setBluetoothEnable(bool enable) } } } - +#else +void setBluetoothEnable(bool enable) {} +#endif /** * Override printf to use the SEGGER output library (note - this does not effect the printf method on the debug console) */ diff --git a/src/sleep.cpp b/src/sleep.cpp index f170e2ab7..2f4bd09e1 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -1,17 +1,23 @@ -#include "sleep.h" +#include "configuration.h" + +#if !MESHTASTIC_EXCLUDE_GPS #include "GPS.h" +#endif + #include "MeshRadio.h" #include "MeshService.h" #include "NodeDB.h" -#include "configuration.h" #include "error.h" #include "main.h" +#include "sleep.h" #include "target_specific.h" #ifdef ARCH_ESP32 #include "esp32/pm.h" #include "esp_pm.h" +#if !MESHTASTIC_EXCLUDE_WIFI #include "mesh/wifi/WiFiAPClient.h" +#endif #include "rom/rtc.h" #include #include @@ -48,7 +54,7 @@ RTC_DATA_ATTR int bootCount = 0; */ void setCPUFast(bool on) { -#ifdef ARCH_ESP32 +#if defined(ARCH_ESP32) && !MESHTASTIC_EXCLUDE_WIFI if (isWifiAvailable()) { /* @@ -206,11 +212,11 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) // pinMode(PIN_POWER_EN1, INPUT_PULLDOWN); #endif #endif - +#if HAS_GPS // Kill GPS power completely (even if previously we just had it in sleep mode) if (gps) gps->setGPSPower(false, false, 0); - +#endif setLed(false); #ifdef RESET_OLED From 1542afb84766e094031323d8cd37f773e047e53c Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Tue, 26 Mar 2024 00:58:47 -0500 Subject: [PATCH 380/472] Add libulfius2.7 to .deb debendencies (#3494) --- .github/workflows/package_raspbian.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/package_raspbian.yml b/.github/workflows/package_raspbian.yml index 377074e95..dd4133dab 100644 --- a/.github/workflows/package_raspbian.yml +++ b/.github/workflows/package_raspbian.yml @@ -63,7 +63,7 @@ jobs: maintainer: Jonathan Bennett version: ${{ steps.version.outputs.version }} # refs/tags/v*.*.* arch: arm64 - depends: libyaml-cpp0.7, openssl + depends: libyaml-cpp0.7, openssl, libulfius2.7 desc: Native Linux Meshtastic binary. - uses: actions/upload-artifact@v3 From 5732eed86bc67f783c53ba02348b9fc3c831f16a Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Tue, 26 Mar 2024 07:29:07 -0500 Subject: [PATCH 381/472] Fixed position admin messages (#3490) * Bespoke admin messages for setting and clearing fixed positions * Add guards against remote admin messages setting things * Flip ifs --- src/modules/AdminModule.cpp | 26 ++++++++++++++++++++++++++ 1 file changed, 26 insertions(+) diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index 50cec824d..2c04916dd 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -17,6 +17,7 @@ #include "unistd.h" #endif #include "Default.h" +#include "TypeConversions.h" #if !MESHTASTIC_EXCLUDE_MQTT #include "mqtt/MQTT.h" @@ -205,6 +206,31 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta } break; } + case meshtastic_AdminMessage_set_fixed_position_tag: { + if (fromOthers) { + LOG_INFO("Ignoring set_fixed_position command from another node.\n"); + } else { + LOG_INFO("Client is receiving a set_fixed_position command.\n"); + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(nodeDB->getNodeNum()); + node->has_position = true; + node->position = TypeConversions::ConvertToPositionLite(r->set_fixed_position); + nodeDB->setLocalPosition(r->set_fixed_position); + config.position.fixed_position = true; + saveChanges(SEGMENT_DEVICESTATE | SEGMENT_CONFIG, false); + } + break; + } + case meshtastic_AdminMessage_remove_fixed_position_tag: { + if (fromOthers) { + LOG_INFO("Ignoring remove_fixed_position command from another node.\n"); + } else { + LOG_INFO("Client is receiving a remove_fixed_position command.\n"); + nodeDB->clearLocalPosition(); + config.position.fixed_position = false; + saveChanges(SEGMENT_DEVICESTATE | SEGMENT_CONFIG, false); + } + break; + } case meshtastic_AdminMessage_enter_dfu_mode_request_tag: { LOG_INFO("Client is requesting to enter DFU mode.\n"); #if defined(ARCH_NRF52) || defined(ARCH_RP2040) From b5ec35ec78419536d213df5d289f498234f80576 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 28 Mar 2024 06:44:34 -0500 Subject: [PATCH 382/472] [create-pull-request] automated change (#3502) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/admin.pb.h | 1 - .../generated/meshtastic/deviceonly.pb.cpp | 3 - src/mesh/generated/meshtastic/deviceonly.pb.h | 128 +++++++----------- src/mesh/generated/meshtastic/mesh.pb.cpp | 3 + src/mesh/generated/meshtastic/mesh.pb.h | 24 ++++ 6 files changed, 80 insertions(+), 81 deletions(-) diff --git a/protobufs b/protobufs index 95b0aa07b..dea3a82ef 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 95b0aa07b2bf3d2ab777f86d6ae8e256e94ced84 +Subproject commit dea3a82ef2accd25112b4ef1c6f8991b579740f4 diff --git a/src/mesh/generated/meshtastic/admin.pb.h b/src/mesh/generated/meshtastic/admin.pb.h index 68e9c22a2..f0d4e81b6 100644 --- a/src/mesh/generated/meshtastic/admin.pb.h +++ b/src/mesh/generated/meshtastic/admin.pb.h @@ -7,7 +7,6 @@ #include "meshtastic/channel.pb.h" #include "meshtastic/config.pb.h" #include "meshtastic/connection_status.pb.h" -#include "meshtastic/deviceonly.pb.h" #include "meshtastic/mesh.pb.h" #include "meshtastic/module_config.pb.h" diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.cpp b/src/mesh/generated/meshtastic/deviceonly.pb.cpp index 93ab3dd98..a9925b517 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.cpp +++ b/src/mesh/generated/meshtastic/deviceonly.pb.cpp @@ -21,8 +21,5 @@ PB_BIND(meshtastic_ChannelFile, meshtastic_ChannelFile, 2) PB_BIND(meshtastic_OEMStore, meshtastic_OEMStore, 2) -PB_BIND(meshtastic_NodeRemoteHardwarePin, meshtastic_NodeRemoteHardwarePin, AUTO) - - diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index c65a5764f..18617390a 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -27,6 +27,48 @@ typedef enum _meshtastic_ScreenFonts { } meshtastic_ScreenFonts; /* Struct definitions */ +/* This message is never sent over the wire, but it is used for serializing DB + state to flash in the device code + FIXME, since we write this each time we enter deep sleep (and have infinite + flash) it would be better to use some sort of append only data structure for + the receive queue and use the preferences store for the other stuff */ +typedef struct _meshtastic_DeviceState { + /* Read only settings/info about this node */ + bool has_my_node; + meshtastic_MyNodeInfo my_node; + /* My owner info */ + bool has_owner; + meshtastic_User owner; + /* Received packets saved for delivery to the phone */ + pb_size_t receive_queue_count; + meshtastic_MeshPacket receive_queue[1]; + /* We keep the last received text message (only) stored in the device flash, + so we can show it on the screen. + Might be null */ + bool has_rx_text_message; + meshtastic_MeshPacket rx_text_message; + /* A version integer used to invalidate old save files when we make + incompatible changes This integer is set at build time and is private to + NodeDB.cpp in the device code. */ + uint32_t version; + /* Used only during development. + Indicates developer is testing and changes should never be saved to flash. + Deprecated in 2.3.1 */ + bool no_save; + /* Some GPS receivers seem to have bogus settings from the factory, so we always do one factory reset. */ + bool did_gps_reset; + /* We keep the last received waypoint stored in the device flash, + so we can show it on the screen. + Might be null */ + bool has_rx_waypoint; + meshtastic_MeshPacket rx_waypoint; + /* The mesh's nodes with their available gpio pins for RemoteHardware module */ + pb_size_t node_remote_hardware_pins_count; + meshtastic_NodeRemoteHardwarePin node_remote_hardware_pins[12]; + /* New lite version of NodeDB to decrease memory footprint */ + std::vector node_db_lite; +} meshtastic_DeviceState; + /* Position with static location information only for NodeDBLite */ typedef struct _meshtastic_PositionLite { /* The new preferred location encoding, multiply by 1e-7 to get degrees @@ -111,57 +153,6 @@ typedef struct _meshtastic_OEMStore { meshtastic_LocalModuleConfig oem_local_module_config; } meshtastic_OEMStore; -/* RemoteHardwarePins associated with a node */ -typedef struct _meshtastic_NodeRemoteHardwarePin { - /* The node_num exposing the available gpio pin */ - uint32_t node_num; - /* The the available gpio pin for usage with RemoteHardware module */ - bool has_pin; - meshtastic_RemoteHardwarePin pin; -} meshtastic_NodeRemoteHardwarePin; - -/* This message is never sent over the wire, but it is used for serializing DB - state to flash in the device code - FIXME, since we write this each time we enter deep sleep (and have infinite - flash) it would be better to use some sort of append only data structure for - the receive queue and use the preferences store for the other stuff */ -typedef struct _meshtastic_DeviceState { - /* Read only settings/info about this node */ - bool has_my_node; - meshtastic_MyNodeInfo my_node; - /* My owner info */ - bool has_owner; - meshtastic_User owner; - /* Received packets saved for delivery to the phone */ - pb_size_t receive_queue_count; - meshtastic_MeshPacket receive_queue[1]; - /* We keep the last received text message (only) stored in the device flash, - so we can show it on the screen. - Might be null */ - bool has_rx_text_message; - meshtastic_MeshPacket rx_text_message; - /* A version integer used to invalidate old save files when we make - incompatible changes This integer is set at build time and is private to - NodeDB.cpp in the device code. */ - uint32_t version; - /* Used only during development. - Indicates developer is testing and changes should never be saved to flash. - Deprecated in 2.3.1 */ - bool no_save; - /* Some GPS receivers seem to have bogus settings from the factory, so we always do one factory reset. */ - bool did_gps_reset; - /* We keep the last received waypoint stored in the device flash, - so we can show it on the screen. - Might be null */ - bool has_rx_waypoint; - meshtastic_MeshPacket rx_waypoint; - /* The mesh's nodes with their available gpio pins for RemoteHardware module */ - pb_size_t node_remote_hardware_pins_count; - meshtastic_NodeRemoteHardwarePin node_remote_hardware_pins[12]; - /* New lite version of NodeDB to decrease memory footprint */ - std::vector node_db_lite; -} meshtastic_DeviceState; - #ifdef __cplusplus extern "C" { @@ -180,22 +171,29 @@ extern "C" { #define meshtastic_OEMStore_oem_font_ENUMTYPE meshtastic_ScreenFonts - /* Initializer values for message structs */ #define meshtastic_DeviceState_init_default {false, meshtastic_MyNodeInfo_init_default, false, meshtastic_User_init_default, 0, {meshtastic_MeshPacket_init_default}, false, meshtastic_MeshPacket_init_default, 0, 0, 0, false, meshtastic_MeshPacket_init_default, 0, {meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default}, {{NULL}, NULL}} #define meshtastic_NodeInfoLite_init_default {0, false, meshtastic_User_init_default, false, meshtastic_PositionLite_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0, 0, 0, 0} #define meshtastic_PositionLite_init_default {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN} #define meshtastic_ChannelFile_init_default {0, {meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default}, 0} #define meshtastic_OEMStore_init_default {0, 0, {0, {0}}, _meshtastic_ScreenFonts_MIN, "", {0, {0}}, false, meshtastic_LocalConfig_init_default, false, meshtastic_LocalModuleConfig_init_default} -#define meshtastic_NodeRemoteHardwarePin_init_default {0, false, meshtastic_RemoteHardwarePin_init_default} #define meshtastic_DeviceState_init_zero {false, meshtastic_MyNodeInfo_init_zero, false, meshtastic_User_init_zero, 0, {meshtastic_MeshPacket_init_zero}, false, meshtastic_MeshPacket_init_zero, 0, 0, 0, false, meshtastic_MeshPacket_init_zero, 0, {meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero}, {{NULL}, NULL}} #define meshtastic_NodeInfoLite_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_PositionLite_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0, 0, 0, 0} #define meshtastic_PositionLite_init_zero {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN} #define meshtastic_ChannelFile_init_zero {0, {meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero}, 0} #define meshtastic_OEMStore_init_zero {0, 0, {0, {0}}, _meshtastic_ScreenFonts_MIN, "", {0, {0}}, false, meshtastic_LocalConfig_init_zero, false, meshtastic_LocalModuleConfig_init_zero} -#define meshtastic_NodeRemoteHardwarePin_init_zero {0, false, meshtastic_RemoteHardwarePin_init_zero} /* Field tags (for use in manual encoding/decoding) */ +#define meshtastic_DeviceState_my_node_tag 2 +#define meshtastic_DeviceState_owner_tag 3 +#define meshtastic_DeviceState_receive_queue_tag 5 +#define meshtastic_DeviceState_rx_text_message_tag 7 +#define meshtastic_DeviceState_version_tag 8 +#define meshtastic_DeviceState_no_save_tag 9 +#define meshtastic_DeviceState_did_gps_reset_tag 11 +#define meshtastic_DeviceState_rx_waypoint_tag 12 +#define meshtastic_DeviceState_node_remote_hardware_pins_tag 13 +#define meshtastic_DeviceState_node_db_lite_tag 14 #define meshtastic_PositionLite_latitude_i_tag 1 #define meshtastic_PositionLite_longitude_i_tag 2 #define meshtastic_PositionLite_altitude_tag 3 @@ -221,18 +219,6 @@ extern "C" { #define meshtastic_OEMStore_oem_aes_key_tag 6 #define meshtastic_OEMStore_oem_local_config_tag 7 #define meshtastic_OEMStore_oem_local_module_config_tag 8 -#define meshtastic_NodeRemoteHardwarePin_node_num_tag 1 -#define meshtastic_NodeRemoteHardwarePin_pin_tag 2 -#define meshtastic_DeviceState_my_node_tag 2 -#define meshtastic_DeviceState_owner_tag 3 -#define meshtastic_DeviceState_receive_queue_tag 5 -#define meshtastic_DeviceState_rx_text_message_tag 7 -#define meshtastic_DeviceState_version_tag 8 -#define meshtastic_DeviceState_no_save_tag 9 -#define meshtastic_DeviceState_did_gps_reset_tag 11 -#define meshtastic_DeviceState_rx_waypoint_tag 12 -#define meshtastic_DeviceState_node_remote_hardware_pins_tag 13 -#define meshtastic_DeviceState_node_db_lite_tag 14 /* Struct field encoding specification for nanopb */ #define meshtastic_DeviceState_FIELDLIST(X, a) \ @@ -304,19 +290,11 @@ X(a, STATIC, OPTIONAL, MESSAGE, oem_local_module_config, 8) #define meshtastic_OEMStore_oem_local_config_MSGTYPE meshtastic_LocalConfig #define meshtastic_OEMStore_oem_local_module_config_MSGTYPE meshtastic_LocalModuleConfig -#define meshtastic_NodeRemoteHardwarePin_FIELDLIST(X, a) \ -X(a, STATIC, SINGULAR, UINT32, node_num, 1) \ -X(a, STATIC, OPTIONAL, MESSAGE, pin, 2) -#define meshtastic_NodeRemoteHardwarePin_CALLBACK NULL -#define meshtastic_NodeRemoteHardwarePin_DEFAULT NULL -#define meshtastic_NodeRemoteHardwarePin_pin_MSGTYPE meshtastic_RemoteHardwarePin - extern const pb_msgdesc_t meshtastic_DeviceState_msg; extern const pb_msgdesc_t meshtastic_NodeInfoLite_msg; extern const pb_msgdesc_t meshtastic_PositionLite_msg; extern const pb_msgdesc_t meshtastic_ChannelFile_msg; extern const pb_msgdesc_t meshtastic_OEMStore_msg; -extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg; /* Defines for backwards compatibility with code written before nanopb-0.4.0 */ #define meshtastic_DeviceState_fields &meshtastic_DeviceState_msg @@ -324,13 +302,11 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg; #define meshtastic_PositionLite_fields &meshtastic_PositionLite_msg #define meshtastic_ChannelFile_fields &meshtastic_ChannelFile_msg #define meshtastic_OEMStore_fields &meshtastic_OEMStore_msg -#define meshtastic_NodeRemoteHardwarePin_fields &meshtastic_NodeRemoteHardwarePin_msg /* Maximum encoded size of messages (where known) */ /* meshtastic_DeviceState_size depends on runtime parameters */ #define meshtastic_ChannelFile_size 702 #define meshtastic_NodeInfoLite_size 160 -#define meshtastic_NodeRemoteHardwarePin_size 29 #define meshtastic_OEMStore_size 3278 #define meshtastic_PositionLite_size 28 diff --git a/src/mesh/generated/meshtastic/mesh.pb.cpp b/src/mesh/generated/meshtastic/mesh.pb.cpp index 97bb7e53b..39713ae8d 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.cpp +++ b/src/mesh/generated/meshtastic/mesh.pb.cpp @@ -63,6 +63,9 @@ PB_BIND(meshtastic_DeviceMetadata, meshtastic_DeviceMetadata, AUTO) PB_BIND(meshtastic_Heartbeat, meshtastic_Heartbeat, AUTO) +PB_BIND(meshtastic_NodeRemoteHardwarePin, meshtastic_NodeRemoteHardwarePin, AUTO) + + diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index 5804dd42a..fcefe508b 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -826,6 +826,15 @@ typedef struct _meshtastic_ToRadio { }; } meshtastic_ToRadio; +/* RemoteHardwarePins associated with a node */ +typedef struct _meshtastic_NodeRemoteHardwarePin { + /* The node_num exposing the available gpio pin */ + uint32_t node_num; + /* The the available gpio pin for usage with RemoteHardware module */ + bool has_pin; + meshtastic_RemoteHardwarePin pin; +} meshtastic_NodeRemoteHardwarePin; + #ifdef __cplusplus extern "C" { @@ -900,6 +909,7 @@ extern "C" { + /* Initializer values for message structs */ #define meshtastic_Position_init_default {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN, _meshtastic_Position_AltSource_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_User_init_default {"", "", "", {0}, _meshtastic_HardwareModel_MIN, 0, _meshtastic_Config_DeviceConfig_Role_MIN} @@ -920,6 +930,7 @@ extern "C" { #define meshtastic_Neighbor_init_default {0, 0, 0, 0} #define meshtastic_DeviceMetadata_init_default {"", 0, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_Role_MIN, 0, _meshtastic_HardwareModel_MIN, 0} #define meshtastic_Heartbeat_init_default {0} +#define meshtastic_NodeRemoteHardwarePin_init_default {0, false, meshtastic_RemoteHardwarePin_init_default} #define meshtastic_Position_init_zero {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN, _meshtastic_Position_AltSource_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_User_init_zero {"", "", "", {0}, _meshtastic_HardwareModel_MIN, 0, _meshtastic_Config_DeviceConfig_Role_MIN} #define meshtastic_RouteDiscovery_init_zero {0, {0, 0, 0, 0, 0, 0, 0, 0}} @@ -939,6 +950,7 @@ extern "C" { #define meshtastic_Neighbor_init_zero {0, 0, 0, 0} #define meshtastic_DeviceMetadata_init_zero {"", 0, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_Role_MIN, 0, _meshtastic_HardwareModel_MIN, 0} #define meshtastic_Heartbeat_init_zero {0} +#define meshtastic_NodeRemoteHardwarePin_init_zero {0, false, meshtastic_RemoteHardwarePin_init_zero} /* Field tags (for use in manual encoding/decoding) */ #define meshtastic_Position_latitude_i_tag 1 @@ -1071,6 +1083,8 @@ extern "C" { #define meshtastic_ToRadio_xmodemPacket_tag 5 #define meshtastic_ToRadio_mqttClientProxyMessage_tag 6 #define meshtastic_ToRadio_heartbeat_tag 7 +#define meshtastic_NodeRemoteHardwarePin_node_num_tag 1 +#define meshtastic_NodeRemoteHardwarePin_pin_tag 2 /* Struct field encoding specification for nanopb */ #define meshtastic_Position_FIELDLIST(X, a) \ @@ -1302,6 +1316,13 @@ X(a, STATIC, SINGULAR, BOOL, hasRemoteHardware, 10) #define meshtastic_Heartbeat_CALLBACK NULL #define meshtastic_Heartbeat_DEFAULT NULL +#define meshtastic_NodeRemoteHardwarePin_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, UINT32, node_num, 1) \ +X(a, STATIC, OPTIONAL, MESSAGE, pin, 2) +#define meshtastic_NodeRemoteHardwarePin_CALLBACK NULL +#define meshtastic_NodeRemoteHardwarePin_DEFAULT NULL +#define meshtastic_NodeRemoteHardwarePin_pin_MSGTYPE meshtastic_RemoteHardwarePin + extern const pb_msgdesc_t meshtastic_Position_msg; extern const pb_msgdesc_t meshtastic_User_msg; extern const pb_msgdesc_t meshtastic_RouteDiscovery_msg; @@ -1321,6 +1342,7 @@ extern const pb_msgdesc_t meshtastic_NeighborInfo_msg; extern const pb_msgdesc_t meshtastic_Neighbor_msg; extern const pb_msgdesc_t meshtastic_DeviceMetadata_msg; extern const pb_msgdesc_t meshtastic_Heartbeat_msg; +extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg; /* Defines for backwards compatibility with code written before nanopb-0.4.0 */ #define meshtastic_Position_fields &meshtastic_Position_msg @@ -1342,6 +1364,7 @@ extern const pb_msgdesc_t meshtastic_Heartbeat_msg; #define meshtastic_Neighbor_fields &meshtastic_Neighbor_msg #define meshtastic_DeviceMetadata_fields &meshtastic_DeviceMetadata_msg #define meshtastic_Heartbeat_fields &meshtastic_Heartbeat_msg +#define meshtastic_NodeRemoteHardwarePin_fields &meshtastic_NodeRemoteHardwarePin_msg /* Maximum encoded size of messages (where known) */ #define meshtastic_Compressed_size 243 @@ -1356,6 +1379,7 @@ extern const pb_msgdesc_t meshtastic_Heartbeat_msg; #define meshtastic_NeighborInfo_size 258 #define meshtastic_Neighbor_size 22 #define meshtastic_NodeInfo_size 277 +#define meshtastic_NodeRemoteHardwarePin_size 29 #define meshtastic_Position_size 144 #define meshtastic_QueueStatus_size 23 #define meshtastic_RouteDiscovery_size 40 From 4c2d5c6a8956f9d7447503a407a18c4cd26c3b3f Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 28 Mar 2024 07:16:07 -0500 Subject: [PATCH 383/472] Reorder structs to fix build --- src/mesh/generated/meshtastic/deviceonly.pb.h | 95 ++++++++++--------- 1 file changed, 48 insertions(+), 47 deletions(-) diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index 18617390a..c75f35c04 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -15,6 +15,54 @@ #error Regenerate this file with the current version of nanopb generator. #endif +/* Position with static location information only for NodeDBLite */ +typedef struct _meshtastic_PositionLite { + /* The new preferred location encoding, multiply by 1e-7 to get degrees + in floating point */ + int32_t latitude_i; + /* TODO: REPLACE */ + int32_t longitude_i; + /* In meters above MSL (but see issue #359) */ + int32_t altitude; + /* This is usually not sent over the mesh (to save space), but it is sent + from the phone so that the local device can set its RTC If it is sent over + the mesh (because there are devices on the mesh without GPS), it will only + be sent by devices which has a hardware GPS clock. + seconds since 1970 */ + uint32_t time; + /* TODO: REPLACE */ + meshtastic_Position_LocSource location_source; +} meshtastic_PositionLite; + +typedef struct _meshtastic_NodeInfoLite { + /* The node number */ + uint32_t num; + /* The user info for this node */ + bool has_user; + meshtastic_User user; + /* This position data. Note: before 1.2.14 we would also store the last time we've heard from this node in position.time, that is no longer true. + Position.time now indicates the last time we received a POSITION from that node. */ + bool has_position; + meshtastic_PositionLite position; + /* Returns the Signal-to-noise ratio (SNR) of the last received message, + as measured by the receiver. Return SNR of the last received message in dB */ + float snr; + /* Set to indicate the last time we received a packet from this node */ + uint32_t last_heard; + /* The latest device metrics for the node. */ + bool has_device_metrics; + meshtastic_DeviceMetrics device_metrics; + /* local channel index we heard that node on. Only populated if its not the default channel. */ + uint8_t channel; + /* True if we witnessed the node over MQTT instead of LoRA transport */ + bool via_mqtt; + /* Number of hops away from us this node is (0 if adjacent) */ + uint8_t hops_away; + /* True if node is in our favorites list + Persists between NodeDB internal clean ups */ + bool is_favorite; +} meshtastic_NodeInfoLite; + /* Enum definitions */ /* TODO: REPLACE */ typedef enum _meshtastic_ScreenFonts { @@ -69,53 +117,6 @@ typedef struct _meshtastic_DeviceState { std::vector node_db_lite; } meshtastic_DeviceState; -/* Position with static location information only for NodeDBLite */ -typedef struct _meshtastic_PositionLite { - /* The new preferred location encoding, multiply by 1e-7 to get degrees - in floating point */ - int32_t latitude_i; - /* TODO: REPLACE */ - int32_t longitude_i; - /* In meters above MSL (but see issue #359) */ - int32_t altitude; - /* This is usually not sent over the mesh (to save space), but it is sent - from the phone so that the local device can set its RTC If it is sent over - the mesh (because there are devices on the mesh without GPS), it will only - be sent by devices which has a hardware GPS clock. - seconds since 1970 */ - uint32_t time; - /* TODO: REPLACE */ - meshtastic_Position_LocSource location_source; -} meshtastic_PositionLite; - -typedef struct _meshtastic_NodeInfoLite { - /* The node number */ - uint32_t num; - /* The user info for this node */ - bool has_user; - meshtastic_User user; - /* This position data. Note: before 1.2.14 we would also store the last time we've heard from this node in position.time, that is no longer true. - Position.time now indicates the last time we received a POSITION from that node. */ - bool has_position; - meshtastic_PositionLite position; - /* Returns the Signal-to-noise ratio (SNR) of the last received message, - as measured by the receiver. Return SNR of the last received message in dB */ - float snr; - /* Set to indicate the last time we received a packet from this node */ - uint32_t last_heard; - /* The latest device metrics for the node. */ - bool has_device_metrics; - meshtastic_DeviceMetrics device_metrics; - /* local channel index we heard that node on. Only populated if its not the default channel. */ - uint8_t channel; - /* True if we witnessed the node over MQTT instead of LoRA transport */ - bool via_mqtt; - /* Number of hops away from us this node is (0 if adjacent) */ - uint8_t hops_away; - /* True if node is in our favorites list - Persists between NodeDB internal clean ups */ - bool is_favorite; -} meshtastic_NodeInfoLite; /* The on-disk saved channels */ typedef struct _meshtastic_ChannelFile { From daa4d387c605295d1c161d7eab01e204095c9519 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 28 Mar 2024 18:14:15 -0500 Subject: [PATCH 384/472] Don't reboot for non-radio lora config changes (#3505) --- src/PowerFSM.cpp | 1 - src/modules/AdminModule.cpp | 17 ++++++++++++++++- 2 files changed, 16 insertions(+), 2 deletions(-) diff --git a/src/PowerFSM.cpp b/src/PowerFSM.cpp index 5d86987df..b6e267e28 100644 --- a/src/PowerFSM.cpp +++ b/src/PowerFSM.cpp @@ -246,7 +246,6 @@ Fsm powerFSM(&stateBOOT); void PowerFSM_setup() { bool isRouter = (config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER ? 1 : 0); - bool isInfrastructureRole = isRouter || config.device.role == meshtastic_Config_DeviceConfig_Role_REPEATER; bool isTrackerOrSensor = config.device.role == meshtastic_Config_DeviceConfig_Role_TRACKER || config.device.role == meshtastic_Config_DeviceConfig_Role_TAK_TRACKER || config.device.role == meshtastic_Config_DeviceConfig_Role_SENSOR; diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index 2c04916dd..b40633af0 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -336,6 +336,7 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c) auto changes = SEGMENT_CONFIG; auto existingRole = config.device.role; bool isRegionUnset = (config.lora.region == meshtastic_Config_LoRaConfig_RegionCode_UNSET); + bool requiresReboot = true; switch (c.which_payload_variant) { case meshtastic_Config_device_tag: @@ -375,7 +376,21 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c) case meshtastic_Config_lora_tag: LOG_INFO("Setting config: LoRa\n"); config.has_lora = true; + // If no lora radio parameters change, don't need to reboot + if (config.lora.use_preset == c.payload_variant.lora.use_preset && config.lora.region == c.payload_variant.lora.region && + config.lora.modem_preset == c.payload_variant.lora.modem_preset && + config.lora.bandwidth == c.payload_variant.lora.bandwidth && + config.lora.spread_factor == c.payload_variant.lora.spread_factor && + config.lora.coding_rate == c.payload_variant.lora.coding_rate && + config.lora.tx_power == c.payload_variant.lora.tx_power && + config.lora.frequency_offset == c.payload_variant.lora.frequency_offset && + config.lora.override_frequency == c.payload_variant.lora.override_frequency && + config.lora.channel_num == c.payload_variant.lora.channel_num && + config.lora.sx126x_rx_boosted_gain == c.payload_variant.lora.sx126x_rx_boosted_gain) { + requiresReboot = false; + } config.lora = c.payload_variant.lora; + // If we're setting region for the first time, init the region if (isRegionUnset && config.lora.region > meshtastic_Config_LoRaConfig_RegionCode_UNSET) { config.lora.tx_enabled = true; initRegion(); @@ -395,7 +410,7 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c) break; } - saveChanges(changes); + saveChanges(changes, requiresReboot); } void AdminModule::handleSetModuleConfig(const meshtastic_ModuleConfig &c) From 8187fa7115c928e32417a056bf10efd86f512395 Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Fri, 29 Mar 2024 12:31:11 +1300 Subject: [PATCH 385/472] E-Ink Screensaver (#3477) * fix Wireless Paper double-clear screen at boot * log when flooded with "responsive" frames * show the "resuming" screen when waking from deep-sleep * rename drawDeepSleepScreen avoid future confusion with "Screen Paused" screen * show a screensaver frame when screen off The frame shown during deep sleep is now also passed through showScreensaverFrames() * Add macros for E-Ink color values. OLEDDISPLAY_COLOR is inverted. Result of light-mode on E-Ink vs dark-mode on OLED? * adapt drawDeepSleepScreen to new screensaver convention * Mark Wireless Paper V1.1 as having problems with ghosting Any other issues can be marked in a similar way, then handled in code where relevant * Change screensaver from fullscreen logo to overlay * identify "quirks" rather than "problems" * move async refresh polling from display() to a NotifiedWorkerThread * Prevent skipping of deep-sleep screen (Hopefully) * Redesign screensaver overlay Now displays short name * Optimize refresh for different displays * Support older EInkDisplay class * Don't assume text alignment * fix spelling of a quirk macro (No impact to code, but avoids future issues) * Handle impossibly unlikely millis() overflow error Should have just let it go, but here we are.. --------- Co-authored-by: Ben Meadors --- src/graphics/EInkDisplay2.cpp | 1 - src/graphics/EInkDynamicDisplay.cpp | 62 ++++++--- src/graphics/EInkDynamicDisplay.h | 35 +++-- src/graphics/Screen.cpp | 125 ++++++++++++++++-- src/graphics/Screen.h | 19 ++- variants/heltec_wireless_paper/platformio.ini | 2 + .../heltec_wireless_paper_v1/platformio.ini | 3 +- 7 files changed, 204 insertions(+), 43 deletions(-) diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index 6f7885b45..0c5fab4fb 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -184,7 +184,6 @@ bool EInkDisplay::connect() // Init GxEPD2 adafruitDisplay->init(); adafruitDisplay->setRotation(3); - adafruitDisplay->clearScreen(); // Clearing now, so the boot logo will draw nice and smoothe (fast refresh) } #elif defined(PCA10059) { diff --git a/src/graphics/EInkDynamicDisplay.cpp b/src/graphics/EInkDynamicDisplay.cpp index 732f6d3fb..f61cf891e 100644 --- a/src/graphics/EInkDynamicDisplay.cpp +++ b/src/graphics/EInkDynamicDisplay.cpp @@ -5,7 +5,7 @@ // Constructor EInkDynamicDisplay::EInkDynamicDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY geometry, HW_I2C i2cBus) - : EInkDisplay(address, sda, scl, geometry, i2cBus) + : EInkDisplay(address, sda, scl, geometry, i2cBus), NotifiedWorkerThread("EInkDynamicDisplay") { // If tracking ghost pixels, grab memory #ifdef EINK_LIMIT_GHOSTING_PX @@ -112,12 +112,15 @@ void EInkDynamicDisplay::endOrDetach() // If the GxEPD2 version reports that it has the async modifications #ifdef HAS_EINK_ASYNCFULL if (previousRefresh == FULL) { - asyncRefreshRunning = true; // Set the flag - picked up at start of determineMode(), next loop. + asyncRefreshRunning = true; // Set the flag - checked in determineMode(); cleared by onNotify() if (previousFrameFlags & BLOCKING) awaitRefresh(); - else - LOG_DEBUG("Async full-refresh begins\n"); + else { + // Async begins + LOG_DEBUG("Async full-refresh begins (dropping frames)\n"); + notifyLater(intervalPollAsyncRefresh, DUE_POLL_ASYNCREFRESH, true); // Hand-off to NotifiedWorkerThread + } } // Fast Refresh @@ -141,7 +144,7 @@ bool EInkDynamicDisplay::determineMode() checkInitialized(); checkForPromotion(); #if defined(HAS_EINK_ASYNCFULL) - checkAsyncFullRefresh(); + checkBusyAsyncRefresh(); #endif checkRateLimiting(); @@ -252,6 +255,7 @@ void EInkDynamicDisplay::checkRateLimiting() if (now - previousRunMs < EINK_LIMIT_RATE_RESPONSIVE_SEC * 1000) { refresh = SKIPPED; reason = EXCEEDED_RATELIMIT_FAST; + LOG_DEBUG("refresh=SKIPPED, reason=EXCEEDED_RATELIMIT_FAST, frameFlags=0x%x\n", frameFlags); return; } } @@ -447,9 +451,44 @@ void EInkDynamicDisplay::resetGhostPixelTracking() } #endif // EINK_LIMIT_GHOSTING_PX +// Handle any asyc tasks +void EInkDynamicDisplay::onNotify(uint32_t notification) +{ + // Which task + switch (notification) { + case DUE_POLL_ASYNCREFRESH: + pollAsyncRefresh(); + break; + } +} + #ifdef HAS_EINK_ASYNCFULL -// Check the status of an "async full-refresh", and run the finish-up code if the hardware is ready -void EInkDynamicDisplay::checkAsyncFullRefresh() +// Run the post-update code if the hardware is ready +void EInkDynamicDisplay::pollAsyncRefresh() +{ + // We shouldn't be here.. + if (!asyncRefreshRunning) + return; + + // Still running, check back later + if (adafruitDisplay->epd2.isBusy()) { + // Schedule next call of pollAsyncRefresh() + NotifiedWorkerThread::notifyLater(intervalPollAsyncRefresh, DUE_POLL_ASYNCREFRESH, true); + return; + } + + // If asyncRefreshRunning flag is still set, but display's BUSY pin reports the refresh is done + adafruitDisplay->endAsyncFull(); // Run the end of nextPage() code + EInkDisplay::endUpdate(); // Run base-class code to finish off update (NOT our derived class override) + asyncRefreshRunning = false; // Unset the flag + LOG_DEBUG("Async full-refresh complete\n"); + + // Note: this code only works because of a modification to meshtastic/GxEPD2. + // It is only equipped to intercept calls to nextPage() +} + +// Check the status of "async full-refresh"; skip if running +void EInkDynamicDisplay::checkBusyAsyncRefresh() { // No refresh taking place, continue with determineMode() if (!asyncRefreshRunning) @@ -472,15 +511,6 @@ void EInkDynamicDisplay::checkAsyncFullRefresh() return; } - - // If we asyncRefreshRunning flag is still set, but display's BUSY pin reports the refresh is done - adafruitDisplay->endAsyncFull(); // Run the end of nextPage() code - EInkDisplay::endUpdate(); // Run base-class code to finish off update (NOT our derived class override) - asyncRefreshRunning = false; // Unset the flag - LOG_DEBUG("Async full-refresh complete\n"); - - // Note: this code only works because of a modification to meshtastic/GxEPD2. - // It is only equipped to intercept calls to nextPage() } // Hold control while an async refresh runs diff --git a/src/graphics/EInkDynamicDisplay.h b/src/graphics/EInkDynamicDisplay.h index 81963df58..39953b62a 100644 --- a/src/graphics/EInkDynamicDisplay.h +++ b/src/graphics/EInkDynamicDisplay.h @@ -6,6 +6,7 @@ #include "EInkDisplay2.h" #include "GxEPD2_BW.h" +#include "concurrency/NotifiedWorkerThread.h" /* Derives from the EInkDisplay adapter class. @@ -14,7 +15,7 @@ (Full, Fast, Skip) */ -class EInkDynamicDisplay : public EInkDisplay +class EInkDynamicDisplay : public EInkDisplay, protected concurrency::NotifiedWorkerThread { public: // Constructor @@ -61,13 +62,20 @@ class EInkDynamicDisplay : public EInkDisplay REDRAW_WITH_FULL, }; - void configForFastRefresh(); // GxEPD2 code to set fast-refresh - void configForFullRefresh(); // GxEPD2 code to set full-refresh - bool determineMode(); // Assess situation, pick a refresh type - void applyRefreshMode(); // Run any relevant GxEPD2 code, so next update will use correct refresh type - void adjustRefreshCounters(); // Update fastRefreshCount - bool update(); // Trigger the display update - determine mode, then call base class - void endOrDetach(); // Run the post-update code, or delegate it off to checkAsyncFullRefresh() + enum notificationTypes : uint8_t { // What was onNotify() called for + NONE = 0, // This behavior (NONE=0) is fixed by NotifiedWorkerThread class + DUE_POLL_ASYNCREFRESH = 1, + }; + const uint32_t intervalPollAsyncRefresh = 100; + + void onNotify(uint32_t notification) override; // Handle any async tasks - overrides NotifiedWorkerThread + void configForFastRefresh(); // GxEPD2 code to set fast-refresh + void configForFullRefresh(); // GxEPD2 code to set full-refresh + bool determineMode(); // Assess situation, pick a refresh type + void applyRefreshMode(); // Run any relevant GxEPD2 code, so next update will use correct refresh type + void adjustRefreshCounters(); // Update fastRefreshCount + bool update(); // Trigger the display update - determine mode, then call base class + void endOrDetach(); // Run the post-update code, or delegate it off to checkBusyAsyncRefresh() // Checks as part of determineMode() void checkInitialized(); // Is this the very first frame? @@ -111,10 +119,13 @@ class EInkDynamicDisplay : public EInkDisplay // Conditional - async full refresh - only with modified meshtastic/GxEPD2 #if defined(HAS_EINK_ASYNCFULL) - void checkAsyncFullRefresh(); // Check the status of "async full-refresh"; run the post-update code if the hardware is ready - void awaitRefresh(); // Hold control while an async refresh runs - void endUpdate() override {} // Disable base-class behavior of running post-update immediately after forceDisplay() - bool asyncRefreshRunning = false; // Flag, checked by checkAsyncFullRefresh() + void pollAsyncRefresh(); // Run the post-update code if the hardware is ready + void checkBusyAsyncRefresh(); // Check if display is busy running an async full-refresh (rejecting new frames) + void awaitRefresh(); // Hold control while an async refresh runs + void endUpdate() override {} // Disable base-class behavior of running post-update immediately after forceDisplay() + bool asyncRefreshRunning = false; // Flag, checked by checkBusyAsyncRefresh() +#else + void pollAsyncRefresh() {} // Dummy method. In theory, not reachable #endif }; diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 2453faec9..52829d1f7 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -262,14 +262,65 @@ static void drawWelcomeScreen(OLEDDisplay *display, OLEDDisplayUiState *state, i #ifdef USE_EINK /// Used on eink displays while in deep sleep -static void drawSleepScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) +static void drawDeepSleepScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) { // Next frame should use full-refresh, and block while running, else device will sleep before async callback EINK_ADD_FRAMEFLAG(display, COSMETIC); EINK_ADD_FRAMEFLAG(display, BLOCKING); + LOG_DEBUG("Drawing deep sleep screen\n"); drawIconScreen("Sleeping...", display, state, x, y); } + +/// Used on eink displays when screen updates are paused +static void drawScreensaverOverlay(OLEDDisplay *display, OLEDDisplayUiState *state) +{ + LOG_DEBUG("Drawing screensaver overlay\n"); + + EINK_ADD_FRAMEFLAG(display, COSMETIC); // Take the opportunity for a full-refresh + + // Config + display->setFont(FONT_SMALL); + display->setTextAlignment(TEXT_ALIGN_LEFT); + const char *pauseText = "Screen Paused"; + const char *idText = owner.short_name; + constexpr uint16_t padding = 5; + constexpr uint8_t dividerGap = 1; + constexpr uint8_t imprecision = 5; // How far the box origins can drift from center. Combat burn-in. + + // Dimensions + const uint16_t idTextWidth = display->getStringWidth(idText, strlen(idText)); + const uint16_t pauseTextWidth = display->getStringWidth(pauseText, strlen(pauseText)); + const uint16_t boxWidth = padding + idTextWidth + padding + padding + pauseTextWidth + padding; + const uint16_t boxHeight = padding + FONT_HEIGHT_SMALL + padding; + + // Position + const int16_t boxLeft = (display->width() / 2) - (boxWidth / 2) + random(-imprecision, imprecision + 1); + // const int16_t boxRight = boxLeft + boxWidth - 1; + const int16_t boxTop = (display->height() / 2) - (boxHeight / 2 + random(-imprecision, imprecision + 1)); + const int16_t boxBottom = boxTop + boxHeight - 1; + const int16_t idTextLeft = boxLeft + padding; + const int16_t idTextTop = boxTop + padding; + const int16_t pauseTextLeft = boxLeft + padding + idTextWidth + padding + padding; + const int16_t pauseTextTop = boxTop + padding; + const int16_t dividerX = boxLeft + padding + idTextWidth + padding; + const int16_t dividerTop = boxTop + 1 + dividerGap; + const int16_t dividerBottom = boxBottom - 1 - dividerGap; + + // Draw: box + display->setColor(EINK_WHITE); + display->fillRect(boxLeft - 1, boxTop - 1, boxWidth + 2, boxHeight + 2); // Clear a slightly oversized area for the box + display->setColor(EINK_BLACK); + display->drawRect(boxLeft, boxTop, boxWidth, boxHeight); + + // Draw: Text + display->drawString(idTextLeft, idTextTop, idText); + display->drawString(pauseTextLeft, pauseTextTop, pauseText); + display->drawString(pauseTextLeft + 1, pauseTextTop, pauseText); // Faux bold + + // Draw: divider + display->drawLine(dividerX, dividerTop, dividerX, dividerBottom); +} #endif static void drawModuleFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) @@ -948,18 +999,17 @@ Screen::~Screen() void Screen::doDeepSleep() { #ifdef USE_EINK - static FrameCallback sleepFrames[] = {drawSleepScreen}; - static const int sleepFrameCount = sizeof(sleepFrames) / sizeof(sleepFrames[0]); - ui->setFrames(sleepFrames, sleepFrameCount); - ui->update(); + setOn(false, drawDeepSleepScreen); #ifdef PIN_EINK_EN digitalWrite(PIN_EINK_EN, LOW); // power off backlight #endif -#endif +#else + // Without E-Ink display: setOn(false); +#endif } -void Screen::handleSetOn(bool on) +void Screen::handleSetOn(bool on, FrameCallback einkScreensaver) { if (!useDisplay) return; @@ -978,6 +1028,10 @@ void Screen::handleSetOn(bool on) setInterval(0); // Draw ASAP runASAP = true; } else { +#ifdef USE_EINK + // eInkScreensaver parameter is usually NULL (default argument), default frame used instead + setScreensaverFrames(einkScreensaver); +#endif LOG_INFO("Turning off screen\n"); dispdev->displayOff(); #ifdef T_WATCH_S3 @@ -1028,6 +1082,7 @@ void Screen::setup() logo_timeout *= 2; // Add frames. + EINK_ADD_FRAMEFLAG(dispdev, DEMAND_FAST); static FrameCallback bootFrames[] = {drawBootScreen}; static const int bootFrameCount = sizeof(bootFrames) / sizeof(bootFrames[0]); ui->setFrames(bootFrames, bootFrameCount); @@ -1283,6 +1338,58 @@ void Screen::setWelcomeFrames() } } +#ifdef USE_EINK +/// Determine which screensaver frame to use, then set the FrameCallback +void Screen::setScreensaverFrames(FrameCallback einkScreensaver) +{ + // Remember current frame, restore position at power-on + uint8_t frameNumber = ui->getUiState()->currentFrame; + + // Retain specified frame / overlay callback beyond scope of this method + static FrameCallback screensaverFrame; + static OverlayCallback screensaverOverlay; + + // If: one-off screensaver frame passed as argument. Handles doDeepSleep() + if (einkScreensaver != NULL) { + screensaverFrame = einkScreensaver; + ui->setFrames(&screensaverFrame, 1); + } + + // Else, display the usual "overlay" screensaver + else { + screensaverOverlay = drawScreensaverOverlay; + ui->setOverlays(&screensaverOverlay, 1); + } + + // Request new frame, ASAP + setFastFramerate(); + uint64_t startUpdate; + do { + startUpdate = millis(); // Handle impossibly unlikely corner case of a millis() overflow.. + delay(1); + ui->update(); + } while (ui->getUiState()->lastUpdate < startUpdate); + +#ifndef USE_EINK_DYNAMICDISPLAY + // Retrofit to EInkDisplay class + delay(10); + screen->forceDisplay(); +#endif + + // Prepare now for next frame, shown when display wakes + ui->setOverlays(NULL, 0); // Clear overlay + setFrames(); // Return to normal display updates + ui->switchToFrame(frameNumber); // Attempt to return to same frame after power-on + + // Pick a refresh method, for when display wakes +#ifdef EINK_HASQUIRK_GHOSTING + EINK_ADD_FRAMEFLAG(dispdev, COSMETIC); // Really ugly to see ghosting from "screen paused" +#else + EINK_ADD_FRAMEFLAG(dispdev, RESPONSIVE); // Really nice to wake screen with a fast-refresh +#endif +} +#endif + // restore our regular frame list void Screen::setFrames() { @@ -1383,7 +1490,8 @@ void Screen::handleShutdownScreen() { LOG_DEBUG("showing shutdown screen\n"); showingNormalScreen = false; - EINK_ADD_FRAMEFLAG(dispdev, DEMAND_FAST); // E-Ink: Explicitly use fast-refresh for next frame + EINK_ADD_FRAMEFLAG(dispdev, DEMAND_FAST); // E-Ink: Use fast-refresh for next frame, no skip please + EINK_ADD_FRAMEFLAG(dispdev, BLOCKING); // Edge case: if this frame is promoted to COSMETIC, wait for update auto frame = [](OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) -> void { drawFrameText(display, state, x, y, "Shutting down..."); @@ -1391,6 +1499,7 @@ void Screen::handleShutdownScreen() static FrameCallback frames[] = {frame}; setFrameImmediateDraw(frames); + forceDisplay(); } void Screen::handleRebootScreen() diff --git a/src/graphics/Screen.h b/src/graphics/Screen.h index a66cc44ec..971146012 100644 --- a/src/graphics/Screen.h +++ b/src/graphics/Screen.h @@ -73,6 +73,10 @@ class Screen #define MILES_TO_FEET 5280 #endif +// Intuitive colors. E-Ink display is inverted from OLED(?) +#define EINK_BLACK OLEDDISPLAY_COLOR::WHITE +#define EINK_WHITE OLEDDISPLAY_COLOR::BLACK + namespace graphics { @@ -139,12 +143,12 @@ class Screen : public concurrency::OSThread // Not thread safe - must be called before any other methods are called. void setup(); - /// Turns the screen on/off. - void setOn(bool on) + /// Turns the screen on/off. Optionally, pass a custom screensaver frame for E-Ink + void setOn(bool on, FrameCallback einkScreensaver = NULL) { if (!on) - handleSetOn( - false); // We handle off commands immediately, because they might be called because the CPU is shutting down + // We handle off commands immediately, because they might be called because the CPU is shutting down + handleSetOn(false, einkScreensaver); else enqueueCmd(ScreenCmd{.cmd = on ? Cmd::SET_ON : Cmd::SET_OFF}); } @@ -321,6 +325,11 @@ class Screen : public concurrency::OSThread void setWelcomeFrames(); +#ifdef USE_EINK + /// Draw an image to remain on E-Ink display after screen off + void setScreensaverFrames(FrameCallback einkScreensaver = NULL); +#endif + protected: /// Updates the UI. // @@ -351,7 +360,7 @@ class Screen : public concurrency::OSThread } // Implementations of various commands, called from doTask(). - void handleSetOn(bool on); + void handleSetOn(bool on, FrameCallback einkScreensaver = NULL); void handleOnPress(); void handleShowNextFrame(); void handleShowPrevFrame(); diff --git a/variants/heltec_wireless_paper/platformio.ini b/variants/heltec_wireless_paper/platformio.ini index 1e1bb9376..d7aac5e22 100644 --- a/variants/heltec_wireless_paper/platformio.ini +++ b/variants/heltec_wireless_paper/platformio.ini @@ -14,6 +14,8 @@ build_flags = -D EINK_LIMIT_RATE_RESPONSIVE_SEC=1 ; Minimum interval between RESPONSIVE updates -D EINK_LIMIT_GHOSTING_PX=2000 ; (Optional) How much image ghosting is tolerated -D EINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. + -D EINK_HASQUIRK_GHOSTING ; Display model is identified as "prone to ghosting" + -D EINK_HASQUIRK_WEAKFASTREFRESH ; Pixels set with fast-refresh are easy to clear, disrupted by sunlight lib_deps = ${esp32s3_base.lib_deps} https://github.com/meshtastic/GxEPD2#55f618961db45a23eff0233546430f1e5a80f63a diff --git a/variants/heltec_wireless_paper_v1/platformio.ini b/variants/heltec_wireless_paper_v1/platformio.ini index cae1940b3..999f1586a 100644 --- a/variants/heltec_wireless_paper_v1/platformio.ini +++ b/variants/heltec_wireless_paper_v1/platformio.ini @@ -13,7 +13,8 @@ build_flags = -D EINK_LIMIT_RATE_BACKGROUND_SEC=30 ; Minimum interval between BACKGROUND updates -D EINK_LIMIT_RATE_RESPONSIVE_SEC=1 ; Minimum interval between RESPONSIVE updates -D EINK_LIMIT_GHOSTING_PX=2000 ; (Optional) How much image ghosting is tolerated - ;-D EINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. + ;-D EINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. + -D EINK_HASQUIRK_VICIOUSFASTREFRESH ; Identify that pixels drawn by fast-refresh are harder to clear lib_deps = ${esp32s3_base.lib_deps} https://github.com/meshtastic/GxEPD2#55f618961db45a23eff0233546430f1e5a80f63a From 7b391d1a9f36ee387cf6a81d748f47ab70f6cef3 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 28 Mar 2024 19:27:34 -0500 Subject: [PATCH 386/472] [create-pull-request] automated change (#3507) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 58a6c19d7..5f162b8ae 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 3 -build = 3 +build = 4 From 64fd8664942ca272104059c3976896ff417b2cd4 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Fri, 29 Mar 2024 00:03:19 -0500 Subject: [PATCH 387/472] Make native honor HAS_SCREEN 0 (#3509) This allows easier building of the native target without the LovyanGFX libraries. --- src/graphics/TFTDisplay.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/graphics/TFTDisplay.cpp b/src/graphics/TFTDisplay.cpp index 9475e0296..79f521fbb 100644 --- a/src/graphics/TFTDisplay.cpp +++ b/src/graphics/TFTDisplay.cpp @@ -333,7 +333,7 @@ static LGFX *tft = nullptr; #include // Graphics and font library for ILI9341 driver chip static TFT_eSPI *tft = nullptr; // Invoke library, pins defined in User_Setup.h -#elif ARCH_PORTDUINO +#elif ARCH_PORTDUINO && HAS_SCREEN != 0 #include // Graphics and font library for ST7735 driver chip class LGFX : public lgfx::LGFX_Device @@ -404,7 +404,8 @@ class LGFX : public lgfx::LGFX_Device static LGFX *tft = nullptr; #endif -#if defined(ST7735_CS) || defined(ST7789_CS) || defined(ILI9341_DRIVER) || defined(RAK14014) || ARCH_PORTDUINO +#if defined(ST7735_CS) || defined(ST7789_CS) || defined(ILI9341_DRIVER) || defined(RAK14014) || \ + (ARCH_PORTDUINO && HAS_SCREEN != 0) #include "SPILock.h" #include "TFTDisplay.h" #include From 3cf6c47bab231736292a57c0cb756f89a3ba960e Mon Sep 17 00:00:00 2001 From: Jorropo Date: Fri, 29 Mar 2024 07:01:40 +0100 Subject: [PATCH 388/472] replace arch with uname -m for arch linux (#3508) From the manpage: > arch - print machine hardware name (same as uname -m) Arch Linux does not have the `arch` alias, only `uname`, so use `uname` to fix this issue: > ``` > ./bin/build-native.sh: line 18: arch: command not found > ``` Co-authored-by: Jonathan Bennett --- bin/build-native.sh | 2 +- bin/native-install.sh | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/bin/build-native.sh b/bin/build-native.sh index 7e9fcb632..7065ea54f 100755 --- a/bin/build-native.sh +++ b/bin/build-native.sh @@ -15,6 +15,6 @@ rm -r $OUTDIR/* || true # Important to pull latest version of libs into all device flavors, otherwise some devices might be stale platformio pkg update pio run --environment native -cp .pio/build/native/program "$OUTDIR/meshtasticd_linux_$(arch)" +cp .pio/build/native/program "$OUTDIR/meshtasticd_linux_$(uname -m)" cp bin/device-install.* $OUTDIR cp bin/device-update.* $OUTDIR diff --git a/bin/native-install.sh b/bin/native-install.sh index cc6d968f9..ba71c4f46 100755 --- a/bin/native-install.sh +++ b/bin/native-install.sh @@ -1,6 +1,6 @@ #!/usr/bin/env bash -cp "release/meshtasticd_linux_$(arch)" /usr/sbin/meshtasticd +cp "release/meshtasticd_linux_$(uname -m)" /usr/sbin/meshtasticd mkdir /etc/meshtasticd if [[ -f "/etc/meshtasticd/config.yaml" ]]; then cp bin/config-dist.yaml /etc/meshtasticd/config-upgrade.yaml From 279464f96d5139920b017d437501233737daf407 Mon Sep 17 00:00:00 2001 From: Jorropo Date: Fri, 29 Mar 2024 13:42:20 +0100 Subject: [PATCH 389/472] linux-native: only install linux native deps (#3510) This is a couple times faster because platformio checks all environment sequentially. Co-authored-by: Ben Meadors --- bin/build-native.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bin/build-native.sh b/bin/build-native.sh index 7065ea54f..9d31d091a 100755 --- a/bin/build-native.sh +++ b/bin/build-native.sh @@ -13,7 +13,7 @@ mkdir -p $OUTDIR/ rm -r $OUTDIR/* || true # Important to pull latest version of libs into all device flavors, otherwise some devices might be stale -platformio pkg update +platformio pkg update --environment native pio run --environment native cp .pio/build/native/program "$OUTDIR/meshtasticd_linux_$(uname -m)" cp bin/device-install.* $OUTDIR From 46a63bf293b2f7d6e1a4306b6cdbdc08d3acb19c Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Mon, 1 Apr 2024 01:04:05 +1300 Subject: [PATCH 390/472] Handle edge cases for E-Ink screensaver (#3518) * remove redundant logic * Handle special screens for old EInkDisplayClass * Handle special screens for EInkDynamicDisplay class * Join an async refresh in progress to avoid skipping screensaver * attempt trunk fix --- src/graphics/EInkDynamicDisplay.cpp | 27 +++++++++++++++++++++++++-- src/graphics/EInkDynamicDisplay.h | 12 +++++++++++- src/graphics/Screen.cpp | 25 ++++++++++++++++++------- src/graphics/Screen.h | 2 +- src/platform/nrf52/NRF52Bluetooth.cpp | 2 ++ 5 files changed, 57 insertions(+), 11 deletions(-) diff --git a/src/graphics/EInkDynamicDisplay.cpp b/src/graphics/EInkDynamicDisplay.cpp index f61cf891e..b396446fa 100644 --- a/src/graphics/EInkDynamicDisplay.cpp +++ b/src/graphics/EInkDynamicDisplay.cpp @@ -463,10 +463,33 @@ void EInkDynamicDisplay::onNotify(uint32_t notification) } #ifdef HAS_EINK_ASYNCFULL -// Run the post-update code if the hardware is ready +// Public: wait for an refresh already in progress, then run the post-update code. See Screen::setScreensaverFrames() +void EInkDynamicDisplay::joinAsyncRefresh() +{ + // If no async refresh running, nothing to do + if (!asyncRefreshRunning) + return; + + LOG_DEBUG("Joining an async refresh in progress\n"); + + // Continually poll the BUSY pin + while (adafruitDisplay->epd2.isBusy()) + yield(); + + // If asyncRefreshRunning flag is still set, but display's BUSY pin reports the refresh is done + adafruitDisplay->endAsyncFull(); // Run the end of nextPage() code + EInkDisplay::endUpdate(); // Run base-class code to finish off update (NOT our derived class override) + asyncRefreshRunning = false; // Unset the flag + LOG_DEBUG("Refresh complete\n"); + + // Note: this code only works because of a modification to meshtastic/GxEPD2. + // It is only equipped to intercept calls to nextPage() +} + +// Called from NotifiedWorkerThread. Run the post-update code if the hardware is ready void EInkDynamicDisplay::pollAsyncRefresh() { - // We shouldn't be here.. + // In theory, this condition should never be met if (!asyncRefreshRunning) return; diff --git a/src/graphics/EInkDynamicDisplay.h b/src/graphics/EInkDynamicDisplay.h index 39953b62a..8f3ce205a 100644 --- a/src/graphics/EInkDynamicDisplay.h +++ b/src/graphics/EInkDynamicDisplay.h @@ -119,20 +119,30 @@ class EInkDynamicDisplay : public EInkDisplay, protected concurrency::NotifiedWo // Conditional - async full refresh - only with modified meshtastic/GxEPD2 #if defined(HAS_EINK_ASYNCFULL) + public: + void joinAsyncRefresh(); // Main thread joins an async refresh already in progress. Blocks, then runs post-update code + + protected: void pollAsyncRefresh(); // Run the post-update code if the hardware is ready void checkBusyAsyncRefresh(); // Check if display is busy running an async full-refresh (rejecting new frames) void awaitRefresh(); // Hold control while an async refresh runs void endUpdate() override {} // Disable base-class behavior of running post-update immediately after forceDisplay() bool asyncRefreshRunning = false; // Flag, checked by checkBusyAsyncRefresh() #else + public: + void joinAsyncRefresh() {} // Dummy method + + protected: void pollAsyncRefresh() {} // Dummy method. In theory, not reachable #endif }; -// Tidier calls to addFrameFlag() from outside class +// Hide the ugly casts used in Screen.cpp #define EINK_ADD_FRAMEFLAG(display, flag) static_cast(display)->addFrameFlag(EInkDynamicDisplay::flag) +#define EINK_JOIN_ASYNCREFRESH(display) static_cast(display)->joinAsyncRefresh() #else // !USE_EINK_DYNAMICDISPLAY // Dummy-macro, removes the need for include guards #define EINK_ADD_FRAMEFLAG(display, flag) +#define EINK_JOIN_ASYNCREFRESH(display) #endif \ No newline at end of file diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 52829d1f7..2087b8daf 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -1349,6 +1349,12 @@ void Screen::setScreensaverFrames(FrameCallback einkScreensaver) static FrameCallback screensaverFrame; static OverlayCallback screensaverOverlay; +#if defined(HAS_EINK_ASYNCFULL) && defined(USE_EINK_DYNAMICDISPLAY) + // Join (await) a currently running async refresh, then run the post-update code. + // Avoid skipping of screensaver frame. Would otherwise be handled by NotifiedWorkerThread. + EINK_JOIN_ASYNCREFRESH(dispdev); +#endif + // If: one-off screensaver frame passed as argument. Handles doDeepSleep() if (einkScreensaver != NULL) { screensaverFrame = einkScreensaver; @@ -1370,10 +1376,9 @@ void Screen::setScreensaverFrames(FrameCallback einkScreensaver) ui->update(); } while (ui->getUiState()->lastUpdate < startUpdate); -#ifndef USE_EINK_DYNAMICDISPLAY - // Retrofit to EInkDisplay class - delay(10); - screen->forceDisplay(); + // Old EInkDisplay class +#if !defined(USE_EINK_DYNAMICDISPLAY) + static_cast(dispdev)->forceDisplay(0); // Screen::forceDisplay(), but override rate-limit #endif // Prepare now for next frame, shown when display wakes @@ -1490,8 +1495,11 @@ void Screen::handleShutdownScreen() { LOG_DEBUG("showing shutdown screen\n"); showingNormalScreen = false; - EINK_ADD_FRAMEFLAG(dispdev, DEMAND_FAST); // E-Ink: Use fast-refresh for next frame, no skip please +#ifdef USE_EINK + EINK_ADD_FRAMEFLAG(dispdev, DEMAND_FAST); // Use fast-refresh for next frame, no skip please EINK_ADD_FRAMEFLAG(dispdev, BLOCKING); // Edge case: if this frame is promoted to COSMETIC, wait for update + handleSetOn(true); // Ensure power-on to receive deep-sleep screensaver (PowerFSM should handle?) +#endif auto frame = [](OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) -> void { drawFrameText(display, state, x, y, "Shutting down..."); @@ -1499,14 +1507,17 @@ void Screen::handleShutdownScreen() static FrameCallback frames[] = {frame}; setFrameImmediateDraw(frames); - forceDisplay(); } void Screen::handleRebootScreen() { LOG_DEBUG("showing reboot screen\n"); showingNormalScreen = false; - EINK_ADD_FRAMEFLAG(dispdev, DEMAND_FAST); // E-Ink: Explicitly use fast-refresh for next frame +#ifdef USE_EINK + EINK_ADD_FRAMEFLAG(dispdev, DEMAND_FAST); // Use fast-refresh for next frame, no skip please + EINK_ADD_FRAMEFLAG(dispdev, BLOCKING); // Edge case: if this frame is promoted to COSMETIC, wait for update + handleSetOn(true); // Power-on to show rebooting screen (PowerFSM should handle?) +#endif auto frame = [](OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) -> void { drawFrameText(display, state, x, y, "Rebooting..."); diff --git a/src/graphics/Screen.h b/src/graphics/Screen.h index 971146012..d03ba4320 100644 --- a/src/graphics/Screen.h +++ b/src/graphics/Screen.h @@ -150,7 +150,7 @@ class Screen : public concurrency::OSThread // We handle off commands immediately, because they might be called because the CPU is shutting down handleSetOn(false, einkScreensaver); else - enqueueCmd(ScreenCmd{.cmd = on ? Cmd::SET_ON : Cmd::SET_OFF}); + enqueueCmd(ScreenCmd{.cmd = Cmd::SET_ON}); } /** diff --git a/src/platform/nrf52/NRF52Bluetooth.cpp b/src/platform/nrf52/NRF52Bluetooth.cpp index e1914a184..759cbb404 100644 --- a/src/platform/nrf52/NRF52Bluetooth.cpp +++ b/src/platform/nrf52/NRF52Bluetooth.cpp @@ -1,5 +1,6 @@ #include "NRF52Bluetooth.h" #include "BluetoothCommon.h" +#include "PowerFSM.h" #include "configuration.h" #include "main.h" #include "mesh/PhoneAPI.h" @@ -318,6 +319,7 @@ void NRF52Bluetooth::onConnectionSecured(uint16_t conn_handle) bool NRF52Bluetooth::onPairingPasskey(uint16_t conn_handle, uint8_t const passkey[6], bool match_request) { LOG_INFO("BLE pairing process started with passkey %.3s %.3s\n", passkey, passkey + 3); + powerFSM.trigger(EVENT_BLUETOOTH_PAIR); screen->startBluetoothPinScreen(configuredPasskey); if (match_request) { From a4c22321fca6fc8da7bab157c3812055603512ba Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Sun, 31 Mar 2024 15:03:29 +0200 Subject: [PATCH 391/472] Don't save Neighbors to flash when receiving (#3519) * Don't save Neighbors to flash when receiving * Move `shouldSave` to `saveProtoForModule()` --------- Co-authored-by: Ben Meadors --- src/modules/NeighborInfoModule.cpp | 9 +++++---- src/modules/NeighborInfoModule.h | 3 +++ 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/src/modules/NeighborInfoModule.cpp b/src/modules/NeighborInfoModule.cpp index 1e9652469..92395ffc5 100644 --- a/src/modules/NeighborInfoModule.cpp +++ b/src/modules/NeighborInfoModule.cpp @@ -114,8 +114,8 @@ size_t NeighborInfoModule::cleanUpNeighbors() (*numNeighbors)--; } - // Save the neighbor list if we removed any neighbors - if (indices_to_remove.size() > 0) { + // Save the neighbor list if we removed any neighbors or neighbors were already updated upon receiving a packet + if (indices_to_remove.size() > 0 || shouldSave) { saveProtoForModule(); } @@ -210,7 +210,6 @@ meshtastic_Neighbor *NeighborInfoModule::getOrCreateNeighbor(NodeNum originalSen // Only if this is the original sender, the broadcast interval corresponds to it if (originalSender == n && node_broadcast_interval_secs != 0) nbr->node_broadcast_interval_secs = node_broadcast_interval_secs; - saveProtoForModule(); // Save the updated neighbor return nbr; } } @@ -228,7 +227,7 @@ meshtastic_Neighbor *NeighborInfoModule::getOrCreateNeighbor(NodeNum originalSen new_nbr->node_broadcast_interval_secs = node_broadcast_interval_secs; else // Assume the same broadcast interval as us for the neighbor if we don't know it new_nbr->node_broadcast_interval_secs = moduleConfig.neighbor_info.update_interval; - saveProtoForModule(); // Save the new neighbor + shouldSave = true; // Save the new neighbor upon next cleanup return new_nbr; } @@ -255,6 +254,8 @@ bool NeighborInfoModule::saveProtoForModule() #endif okay &= nodeDB->saveProto(neighborInfoConfigFile, meshtastic_NeighborInfo_size, &meshtastic_NeighborInfo_msg, &neighborState); + if (okay) + shouldSave = false; return okay; } \ No newline at end of file diff --git a/src/modules/NeighborInfoModule.h b/src/modules/NeighborInfoModule.h index b4acb0f66..d47004981 100644 --- a/src/modules/NeighborInfoModule.h +++ b/src/modules/NeighborInfoModule.h @@ -20,6 +20,9 @@ class NeighborInfoModule : public ProtobufModule, priva bool saveProtoForModule(); + private: + bool shouldSave = false; // Whether we should save the neighbor info to flash + protected: // Note: this holds our local info. meshtastic_NeighborInfo neighborState; From 15501e84ddd6d3fcc7a86d4419e7e1e260f7f728 Mon Sep 17 00:00:00 2001 From: rcarteraz Date: Mon, 1 Apr 2024 03:53:19 -0700 Subject: [PATCH 392/472] Add Station-G2 to install scripts (#3525) * add station g2 to device-install.bat * add station-g2 to device-install.sh * remove extra space --- bin/device-install.bat | 2 +- bin/device-install.sh | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/bin/device-install.bat b/bin/device-install.bat index cb652346f..1fe1df52a 100755 --- a/bin/device-install.bat +++ b/bin/device-install.bat @@ -32,7 +32,7 @@ IF EXIST %FILENAME% IF x%FILENAME:update=%==x%FILENAME% ( %PYTHON% -m esptool --baud 115200 write_flash 0x00 %FILENAME% @REM Account for S3 and C3 board's different OTA partition - IF x%FILENAME:s3=%==x%FILENAME% IF x%FILENAME:v3=%==x%FILENAME% IF x%FILENAME:t-deck=%==x%FILENAME% IF x%FILENAME:wireless-paper=%==x%FILENAME% IF x%FILENAME:wireless-tracker=%==x%FILENAME% ( + IF x%FILENAME:s3=%==x%FILENAME% IF x%FILENAME:v3=%==x%FILENAME% IF x%FILENAME:t-deck=%==x%FILENAME% IF x%FILENAME:wireless-paper=%==x%FILENAME% IF x%FILENAME:wireless-tracker=%==x%FILENAME% IF x%FILENAME:station-g2=%==x%FILENAME% ( IF x%FILENAME:esp32c3=%==x%FILENAME% ( %PYTHON% -m esptool --baud 115200 write_flash 0x260000 bleota.bin ) else ( diff --git a/bin/device-install.sh b/bin/device-install.sh index 0e7bd8ada..6ef7b1204 100755 --- a/bin/device-install.sh +++ b/bin/device-install.sh @@ -52,7 +52,7 @@ if [ -f "${FILENAME}" ] && [ -n "${FILENAME##*"update"*}" ]; then "$PYTHON" -m esptool erase_flash "$PYTHON" -m esptool write_flash 0x00 ${FILENAME} # Account for S3 board's different OTA partition - if [ -n "${FILENAME##*"s3"*}" ] && [ -n "${FILENAME##*"-v3"*}" ] && [ -n "${FILENAME##*"t-deck"*}" ] && [ -n "${FILENAME##*"wireless-paper"*}" ] && [ -n "${FILENAME##*"wireless-tracker"*}" ]; then + if [ -n "${FILENAME##*"s3"*}" ] && [ -n "${FILENAME##*"-v3"*}" ] && [ -n "${FILENAME##*"t-deck"*}" ] && [ -n "${FILENAME##*"wireless-paper"*}" ] && [ -n "${FILENAME##*"wireless-tracker"*}" ] && [ -n "${FILENAME##*"station-g2"*}" ]; then if [ -n "${FILENAME##*"esp32c3"*}" ]; then "$PYTHON" -m esptool write_flash 0x260000 bleota.bin else From 8bb562c5fa79c330b424ff49d61cc74a92828387 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Mon, 1 Apr 2024 18:31:36 -0500 Subject: [PATCH 393/472] Add spiTransfer function to Native to support Linux-managed CS (#3524) * Add spiTransfer function to Native to support Linux-managed CS * Trunk --------- Co-authored-by: Ben Meadors --- arch/portduino/portduino.ini | 2 +- src/mesh/RadioLibInterface.cpp | 6 ++++++ src/mesh/RadioLibInterface.h | 3 +++ variants/portduino/variant.h | 1 + 4 files changed, 11 insertions(+), 1 deletion(-) diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index ef8711f8a..077a49b3f 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -1,6 +1,6 @@ ; The Portduino based sim environment on top of any host OS, all hardware will be simulated [portduino_base] -platform = https://github.com/meshtastic/platform-native.git#1b8a32c60ab7495026033858d53c737f7d1cb34a +platform = https://github.com/meshtastic/platform-native.git#117acc5e7fcc2047e9ba1dc11789daea26fc36d2 framework = arduino build_src_filter = diff --git a/src/mesh/RadioLibInterface.cpp b/src/mesh/RadioLibInterface.cpp index 9f42afa6d..3ad2abe23 100644 --- a/src/mesh/RadioLibInterface.cpp +++ b/src/mesh/RadioLibInterface.cpp @@ -22,6 +22,12 @@ void LockingArduinoHal::spiEndTransaction() ArduinoHal::spiEndTransaction(); } +#if ARCH_PORTDUINO +void LockingArduinoHal::spiTransfer(uint8_t *out, size_t len, uint8_t *in) +{ + spi->transfer(out, in, len); +} +#endif RadioLibInterface::RadioLibInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, RADIOLIB_PIN_TYPE busy, PhysicalLayer *_iface) diff --git a/src/mesh/RadioLibInterface.h b/src/mesh/RadioLibInterface.h index 4634ca7ee..62720cfc9 100644 --- a/src/mesh/RadioLibInterface.h +++ b/src/mesh/RadioLibInterface.h @@ -25,6 +25,9 @@ class LockingArduinoHal : public ArduinoHal void spiBeginTransaction() override; void spiEndTransaction() override; +#if ARCH_PORTDUINO + void spiTransfer(uint8_t *out, size_t len, uint8_t *in) override; +#endif }; #if defined(USE_STM32WLx) diff --git a/variants/portduino/variant.h b/variants/portduino/variant.h index 5aad8dbfc..414a3fa56 100644 --- a/variants/portduino/variant.h +++ b/variants/portduino/variant.h @@ -2,3 +2,4 @@ #define CANNED_MESSAGE_MODULE_ENABLE 1 #define HAS_GPS 1 #define MAX_NUM_NODES settingsMap[maxnodes] +#define RADIOLIB_GODMODE 1 From f2ed0f7c8c0333d6dff91718a11d5e10062d5942 Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Wed, 3 Apr 2024 08:55:48 +1300 Subject: [PATCH 394/472] Fix Light-sleep for ESP32 (#3521) * Change wakeup source from EXT0 to GPIO * Avoid ISR issue on wake * Detect press from wake reason, instead of digitalRead * Missing #ifdef Risky phone-typed commit * Fix PowerFSM timed transition preventing light sleep Addresses https://github.com/meshtastic/firmware/issues/3517 --------- Co-authored-by: Ben Meadors --- src/PowerFSM.cpp | 39 ++++++++++++++++++++++----------------- src/sleep.cpp | 18 +++++++++++------- 2 files changed, 33 insertions(+), 24 deletions(-) diff --git a/src/PowerFSM.cpp b/src/PowerFSM.cpp index b6e267e28..0002a62b4 100644 --- a/src/PowerFSM.cpp +++ b/src/PowerFSM.cpp @@ -102,23 +102,18 @@ static void lsIdle() powerFSM.trigger(EVENT_SERIAL_CONNECTED); break; + case ESP_SLEEP_WAKEUP_GPIO: + // GPIO wakeup is now used for all ESP32 devices during light sleep + powerFSM.trigger(EVENT_PRESS); + break; + default: - // We woke for some other reason (button press, device interrupt) - // uint64_t status = esp_sleep_get_ext1_wakeup_status(); + // We woke for some other reason (device interrupt?) LOG_INFO("wakeCause2 %d\n", wakeCause2); -#ifdef BUTTON_PIN - bool pressed = !digitalRead(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN); -#else - bool pressed = false; -#endif - if (pressed) { // If we woke because of press, instead generate a PRESS event. - powerFSM.trigger(EVENT_PRESS); - } else { - // Otherwise let the NB state handle the IRQ (and that state will handle stuff like IRQs etc) - // we lie and say "wake timer" because the interrupt will be handled by the regular IRQ code - powerFSM.trigger(EVENT_WAKE_TIMER); - } + // Let the NB state handle the IRQ (and that state will handle stuff like IRQs etc) + // we lie and say "wake timer" because the interrupt will be handled by the regular IRQ code + powerFSM.trigger(EVENT_WAKE_TIMER); break; } } else { @@ -348,9 +343,6 @@ void PowerFSM_setup() powerFSM.add_timed_transition(&statePOWER, &stateDARK, Default::getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, "Screen-on timeout"); - powerFSM.add_timed_transition(&stateDARK, &stateDARK, - Default::getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, - "Screen-on timeout"); // We never enter light-sleep or NB states on NRF52 (because the CPU uses so little power normally) #ifdef ARCH_ESP32 @@ -361,11 +353,24 @@ void PowerFSM_setup() powerFSM.add_timed_transition(&stateNB, &stateLS, Default::getConfiguredOrDefaultMs(config.power.min_wake_secs, default_min_wake_secs), NULL, "Min wake timeout"); + + // If ESP32 and using power-saving, timer mover from DARK to light-sleep + // Also serves purpose of the old DARK to DARK transition(?) See https://github.com/meshtastic/firmware/issues/3517 powerFSM.add_timed_transition( &stateDARK, &stateLS, Default::getConfiguredOrDefaultMs(config.power.wait_bluetooth_secs, default_wait_bluetooth_secs), NULL, "Bluetooth timeout"); + } else { + // If ESP32, but not using power-saving, check periodically if config has drifted out of stateDark + powerFSM.add_timed_transition(&stateDARK, &stateDARK, + Default::getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), + NULL, "Screen-on timeout"); } +#else + // If not ESP32, light-sleep not used. Check periodically if config has drifted out of stateDark + powerFSM.add_timed_transition(&stateDARK, &stateDARK, + Default::getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, + "Screen-on timeout"); #endif powerFSM.run_machine(); // run one iteration of the state machine, so we run our on enter tasks for the initial DARK state diff --git a/src/sleep.cpp b/src/sleep.cpp index 2f4bd09e1..e91bda782 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -312,13 +312,11 @@ esp_sleep_wakeup_cause_t doLightSleep(uint64_t sleepMsec) // FIXME, use a more r // assert(esp_sleep_enable_uart_wakeup(0) == ESP_OK); #endif #ifdef BUTTON_PIN -#if SOC_PM_SUPPORT_EXT_WAKEUP - esp_sleep_enable_ext0_wakeup((gpio_num_t)(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN), - LOW); // when user presses, this button goes low -#else + // The enableLoraInterrupt() method is using ext0_wakeup, so we are forced to use GPIO wakeup + gpio_num_t pin = (gpio_num_t)(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN); + gpio_intr_disable(pin); + gpio_wakeup_enable(pin, GPIO_INTR_LOW_LEVEL); esp_sleep_enable_gpio_wakeup(); - gpio_wakeup_enable((gpio_num_t)BUTTON_PIN, GPIO_INTR_LOW_LEVEL); -#endif #endif enableLoraInterrupt(); #ifdef PMU_IRQ @@ -342,6 +340,12 @@ esp_sleep_wakeup_cause_t doLightSleep(uint64_t sleepMsec) // FIXME, use a more r } assert(res == ESP_OK); +#ifdef BUTTON_PIN + gpio_wakeup_disable(pin); + // Would have thought that need gpio_intr_enable() here, but nope.. + // Works fine without it; crashes with it. +#endif + esp_sleep_wakeup_cause_t cause = esp_sleep_get_wakeup_cause(); #ifdef BUTTON_PIN if (cause == ESP_SLEEP_WAKEUP_GPIO) { @@ -406,4 +410,4 @@ void enableLoraInterrupt() gpio_wakeup_enable((gpio_num_t)RF95_IRQ, GPIO_INTR_HIGH_LEVEL); // RF95 interrupt, active high #endif } -#endif \ No newline at end of file +#endif From 2caed6d29c68163673f934896122020bb78eabe3 Mon Sep 17 00:00:00 2001 From: AeroXuk Date: Tue, 2 Apr 2024 21:36:15 +0100 Subject: [PATCH 395/472] Feature parity between Pico and Pico W (#3538) --- variants/rpipicow/variant.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/variants/rpipicow/variant.h b/variants/rpipicow/variant.h index 27117680f..a17f05ee0 100644 --- a/variants/rpipicow/variant.h +++ b/variants/rpipicow/variant.h @@ -21,6 +21,8 @@ #define EXT_NOTIFY_OUT 22 #define BUTTON_PIN 17 +#define LED_PIN LED_BUILTIN + #define BATTERY_PIN 26 // ratio of voltage divider = 3.0 (R17=200k, R18=100k) #define ADC_MULTIPLIER 3.1 // 3.0 + a bit for being optimistic @@ -51,4 +53,4 @@ #define SX126X_RESET LORA_RESET #define SX126X_DIO2_AS_RF_SWITCH #define SX126X_DIO3_TCXO_VOLTAGE 1.8 -#endif \ No newline at end of file +#endif From a570e50acad384a2754b6735891aeead3931ab9d Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Thu, 4 Apr 2024 00:59:53 +1300 Subject: [PATCH 396/472] Disable holds / isolations on RTC IO pads after deep sleep (#3539) * disable holds on RTC IO pads after deep sleep * Don't assume SOC_RTCIO_HOLD_SUPPORTED --- src/graphics/EInkDisplay2.cpp | 23 ++--------------------- src/sleep.cpp | 12 ++++++++++++ 2 files changed, 14 insertions(+), 21 deletions(-) diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index 0c5fab4fb..04915fe07 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -151,31 +151,12 @@ bool EInkDisplay::connect() #elif defined(HELTEC_WIRELESS_PAPER_V1_0) || defined(HELTEC_WIRELESS_PAPER) { - // Is this a normal boot, or a wake from deep sleep? - esp_sleep_wakeup_cause_t wakeReason = esp_sleep_get_wakeup_cause(); - - // If waking from sleep, need to reverse rtc_gpio_isolate(), called in cpuDeepSleep() - // Otherwise, SPI won't work - if (wakeReason != ESP_SLEEP_WAKEUP_UNDEFINED) { - // HSPI + other display pins - rtc_gpio_hold_dis((gpio_num_t)PIN_EINK_SCLK); - rtc_gpio_hold_dis((gpio_num_t)PIN_EINK_DC); - rtc_gpio_hold_dis((gpio_num_t)PIN_EINK_RES); - rtc_gpio_hold_dis((gpio_num_t)PIN_EINK_BUSY); - rtc_gpio_hold_dis((gpio_num_t)PIN_EINK_CS); - rtc_gpio_hold_dis((gpio_num_t)PIN_EINK_MOSI); - } - // Start HSPI hspi = new SPIClass(HSPI); hspi->begin(PIN_EINK_SCLK, -1, PIN_EINK_MOSI, PIN_EINK_CS); // SCLK, MISO, MOSI, SS - // Enable VExt (ACTIVE LOW) - // Unsure if called elsewhere first? - delay(100); - pinMode(Vext, OUTPUT); - digitalWrite(Vext, LOW); - delay(100); + // VExt already enabled in setup() + // RTC GPIO hold disabled in setup() // Create GxEPD2 objects auto lowLevel = new EINK_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY, *hspi); diff --git a/src/sleep.cpp b/src/sleep.cpp index e91bda782..ddea9942c 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -147,6 +147,18 @@ void initDeepSleep() LOG_INFO("Booted, wake cause %d (boot count %d), reset_reason=%s\n", wakeCause, bootCount, reason); #endif + +#if SOC_RTCIO_HOLD_SUPPORTED + // If waking from sleep, release any and all RTC GPIOs + if (wakeCause != ESP_SLEEP_WAKEUP_UNDEFINED) { + LOG_DEBUG("Disabling any holds on RTC IO pads\n"); + for (uint8_t i = 0; i <= 45; i++) { + if (rtc_gpio_is_valid_gpio((gpio_num_t)i)) + rtc_gpio_hold_dis((gpio_num_t)i); + } + } +#endif + #endif } From 46ad4bf0e5bcfbb6c8b903b7436bec7b50ecdc9f Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Wed, 3 Apr 2024 08:47:47 -0500 Subject: [PATCH 397/472] [create-pull-request] automated change (#3542) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/config.pb.h | 6 +- .../generated/meshtastic/deviceonly.pb.cpp | 4 +- src/mesh/generated/meshtastic/deviceonly.pb.h | 119 +++++++++--------- src/mesh/generated/meshtastic/mesh.pb.h | 7 +- src/mesh/generated/meshtastic/mqtt.pb.h | 2 +- 6 files changed, 72 insertions(+), 68 deletions(-) diff --git a/protobufs b/protobufs index dea3a82ef..6157a5723 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit dea3a82ef2accd25112b4ef1c6f8991b579740f4 +Subproject commit 6157a5723745b3a750720b94676198a7f3839e2a diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index c56cf65a0..67c745214 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -30,12 +30,12 @@ typedef enum _meshtastic_Config_DeviceConfig_Role { meshtastic_Config_DeviceConfig_Role_REPEATER = 4, /* Description: Broadcasts GPS position packets as priority. Technical Details: Position Mesh packets will be prioritized higher and sent more frequently by default. - When used in conjunction with power.is_power_saving = true, nodes will wake up, + When used in conjunction with power.is_power_saving = true, nodes will wake up, send position, and then sleep for position.position_broadcast_secs seconds. */ meshtastic_Config_DeviceConfig_Role_TRACKER = 5, /* Description: Broadcasts telemetry packets as priority. Technical Details: Telemetry Mesh packets will be prioritized higher and sent more frequently by default. - When used in conjunction with power.is_power_saving = true, nodes will wake up, + When used in conjunction with power.is_power_saving = true, nodes will wake up, send environment telemetry, and then sleep for telemetry.environment_update_interval seconds. */ meshtastic_Config_DeviceConfig_Role_SENSOR = 6, /* Description: Optimized for ATAK system communication and reduces routine broadcasts. @@ -50,7 +50,7 @@ typedef enum _meshtastic_Config_DeviceConfig_Role { Can be used for clandestine operation or to dramatically reduce airtime / power consumption */ meshtastic_Config_DeviceConfig_Role_CLIENT_HIDDEN = 8, /* Description: Broadcasts location as message to default channel regularly for to assist with device recovery. - Technical Details: Used to automatically send a text message to the mesh + Technical Details: Used to automatically send a text message to the mesh with the current position of the device on a frequent interval: "I'm lost! Position: lat / long" */ meshtastic_Config_DeviceConfig_Role_LOST_AND_FOUND = 9, diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.cpp b/src/mesh/generated/meshtastic/deviceonly.pb.cpp index a9925b517..127319b14 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.cpp +++ b/src/mesh/generated/meshtastic/deviceonly.pb.cpp @@ -6,13 +6,13 @@ #error Regenerate this file with the current version of nanopb generator. #endif -PB_BIND(meshtastic_DeviceState, meshtastic_DeviceState, 2) +PB_BIND(meshtastic_PositionLite, meshtastic_PositionLite, AUTO) PB_BIND(meshtastic_NodeInfoLite, meshtastic_NodeInfoLite, AUTO) -PB_BIND(meshtastic_PositionLite, meshtastic_PositionLite, AUTO) +PB_BIND(meshtastic_DeviceState, meshtastic_DeviceState, 2) PB_BIND(meshtastic_ChannelFile, meshtastic_ChannelFile, 2) diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index c75f35c04..cdd59d871 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -8,13 +8,25 @@ #include "meshtastic/channel.pb.h" #include "meshtastic/localonly.pb.h" #include "meshtastic/mesh.pb.h" -#include "meshtastic/telemetry.pb.h" #include "meshtastic/module_config.pb.h" +#include "meshtastic/telemetry.pb.h" #if PB_PROTO_HEADER_VERSION != 40 #error Regenerate this file with the current version of nanopb generator. #endif +/* Enum definitions */ +/* Font sizes for the device screen */ +typedef enum _meshtastic_ScreenFonts { + /* TODO: REPLACE */ + meshtastic_ScreenFonts_FONT_SMALL = 0, + /* TODO: REPLACE */ + meshtastic_ScreenFonts_FONT_MEDIUM = 1, + /* TODO: REPLACE */ + meshtastic_ScreenFonts_FONT_LARGE = 2 +} meshtastic_ScreenFonts; + +/* Struct definitions */ /* Position with static location information only for NodeDBLite */ typedef struct _meshtastic_PositionLite { /* The new preferred location encoding, multiply by 1e-7 to get degrees @@ -63,18 +75,6 @@ typedef struct _meshtastic_NodeInfoLite { bool is_favorite; } meshtastic_NodeInfoLite; -/* Enum definitions */ -/* TODO: REPLACE */ -typedef enum _meshtastic_ScreenFonts { - /* TODO: REPLACE */ - meshtastic_ScreenFonts_FONT_SMALL = 0, - /* TODO: REPLACE */ - meshtastic_ScreenFonts_FONT_MEDIUM = 1, - /* TODO: REPLACE */ - meshtastic_ScreenFonts_FONT_LARGE = 2 -} meshtastic_ScreenFonts; - -/* Struct definitions */ /* This message is never sent over the wire, but it is used for serializing DB state to flash in the device code FIXME, since we write this each time we enter deep sleep (and have infinite @@ -117,7 +117,6 @@ typedef struct _meshtastic_DeviceState { std::vector node_db_lite; } meshtastic_DeviceState; - /* The on-disk saved channels */ typedef struct _meshtastic_ChannelFile { /* The channels our node knows about */ @@ -164,37 +163,27 @@ extern "C" { #define _meshtastic_ScreenFonts_MAX meshtastic_ScreenFonts_FONT_LARGE #define _meshtastic_ScreenFonts_ARRAYSIZE ((meshtastic_ScreenFonts)(meshtastic_ScreenFonts_FONT_LARGE+1)) - - #define meshtastic_PositionLite_location_source_ENUMTYPE meshtastic_Position_LocSource + + #define meshtastic_OEMStore_oem_font_ENUMTYPE meshtastic_ScreenFonts /* Initializer values for message structs */ -#define meshtastic_DeviceState_init_default {false, meshtastic_MyNodeInfo_init_default, false, meshtastic_User_init_default, 0, {meshtastic_MeshPacket_init_default}, false, meshtastic_MeshPacket_init_default, 0, 0, 0, false, meshtastic_MeshPacket_init_default, 0, {meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default}, {{NULL}, NULL}} -#define meshtastic_NodeInfoLite_init_default {0, false, meshtastic_User_init_default, false, meshtastic_PositionLite_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0, 0, 0, 0} #define meshtastic_PositionLite_init_default {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN} +#define meshtastic_NodeInfoLite_init_default {0, false, meshtastic_User_init_default, false, meshtastic_PositionLite_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0, 0, 0, 0} +#define meshtastic_DeviceState_init_default {false, meshtastic_MyNodeInfo_init_default, false, meshtastic_User_init_default, 0, {meshtastic_MeshPacket_init_default}, false, meshtastic_MeshPacket_init_default, 0, 0, 0, false, meshtastic_MeshPacket_init_default, 0, {meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default}, {{NULL}, NULL}} #define meshtastic_ChannelFile_init_default {0, {meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default}, 0} #define meshtastic_OEMStore_init_default {0, 0, {0, {0}}, _meshtastic_ScreenFonts_MIN, "", {0, {0}}, false, meshtastic_LocalConfig_init_default, false, meshtastic_LocalModuleConfig_init_default} -#define meshtastic_DeviceState_init_zero {false, meshtastic_MyNodeInfo_init_zero, false, meshtastic_User_init_zero, 0, {meshtastic_MeshPacket_init_zero}, false, meshtastic_MeshPacket_init_zero, 0, 0, 0, false, meshtastic_MeshPacket_init_zero, 0, {meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero}, {{NULL}, NULL}} -#define meshtastic_NodeInfoLite_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_PositionLite_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0, 0, 0, 0} #define meshtastic_PositionLite_init_zero {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN} +#define meshtastic_NodeInfoLite_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_PositionLite_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0, 0, 0, 0} +#define meshtastic_DeviceState_init_zero {false, meshtastic_MyNodeInfo_init_zero, false, meshtastic_User_init_zero, 0, {meshtastic_MeshPacket_init_zero}, false, meshtastic_MeshPacket_init_zero, 0, 0, 0, false, meshtastic_MeshPacket_init_zero, 0, {meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero}, {{NULL}, NULL}} #define meshtastic_ChannelFile_init_zero {0, {meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero}, 0} #define meshtastic_OEMStore_init_zero {0, 0, {0, {0}}, _meshtastic_ScreenFonts_MIN, "", {0, {0}}, false, meshtastic_LocalConfig_init_zero, false, meshtastic_LocalModuleConfig_init_zero} /* Field tags (for use in manual encoding/decoding) */ -#define meshtastic_DeviceState_my_node_tag 2 -#define meshtastic_DeviceState_owner_tag 3 -#define meshtastic_DeviceState_receive_queue_tag 5 -#define meshtastic_DeviceState_rx_text_message_tag 7 -#define meshtastic_DeviceState_version_tag 8 -#define meshtastic_DeviceState_no_save_tag 9 -#define meshtastic_DeviceState_did_gps_reset_tag 11 -#define meshtastic_DeviceState_rx_waypoint_tag 12 -#define meshtastic_DeviceState_node_remote_hardware_pins_tag 13 -#define meshtastic_DeviceState_node_db_lite_tag 14 #define meshtastic_PositionLite_latitude_i_tag 1 #define meshtastic_PositionLite_longitude_i_tag 2 #define meshtastic_PositionLite_altitude_tag 3 @@ -210,6 +199,16 @@ extern "C" { #define meshtastic_NodeInfoLite_via_mqtt_tag 8 #define meshtastic_NodeInfoLite_hops_away_tag 9 #define meshtastic_NodeInfoLite_is_favorite_tag 10 +#define meshtastic_DeviceState_my_node_tag 2 +#define meshtastic_DeviceState_owner_tag 3 +#define meshtastic_DeviceState_receive_queue_tag 5 +#define meshtastic_DeviceState_rx_text_message_tag 7 +#define meshtastic_DeviceState_version_tag 8 +#define meshtastic_DeviceState_no_save_tag 9 +#define meshtastic_DeviceState_did_gps_reset_tag 11 +#define meshtastic_DeviceState_rx_waypoint_tag 12 +#define meshtastic_DeviceState_node_remote_hardware_pins_tag 13 +#define meshtastic_DeviceState_node_db_lite_tag 14 #define meshtastic_ChannelFile_channels_tag 1 #define meshtastic_ChannelFile_version_tag 2 #define meshtastic_OEMStore_oem_icon_width_tag 1 @@ -222,6 +221,32 @@ extern "C" { #define meshtastic_OEMStore_oem_local_module_config_tag 8 /* Struct field encoding specification for nanopb */ +#define meshtastic_PositionLite_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, SFIXED32, latitude_i, 1) \ +X(a, STATIC, SINGULAR, SFIXED32, longitude_i, 2) \ +X(a, STATIC, SINGULAR, INT32, altitude, 3) \ +X(a, STATIC, SINGULAR, FIXED32, time, 4) \ +X(a, STATIC, SINGULAR, UENUM, location_source, 5) +#define meshtastic_PositionLite_CALLBACK NULL +#define meshtastic_PositionLite_DEFAULT NULL + +#define meshtastic_NodeInfoLite_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, UINT32, num, 1) \ +X(a, STATIC, OPTIONAL, MESSAGE, user, 2) \ +X(a, STATIC, OPTIONAL, MESSAGE, position, 3) \ +X(a, STATIC, SINGULAR, FLOAT, snr, 4) \ +X(a, STATIC, SINGULAR, FIXED32, last_heard, 5) \ +X(a, STATIC, OPTIONAL, MESSAGE, device_metrics, 6) \ +X(a, STATIC, SINGULAR, UINT32, channel, 7) \ +X(a, STATIC, SINGULAR, BOOL, via_mqtt, 8) \ +X(a, STATIC, SINGULAR, UINT32, hops_away, 9) \ +X(a, STATIC, SINGULAR, BOOL, is_favorite, 10) +#define meshtastic_NodeInfoLite_CALLBACK NULL +#define meshtastic_NodeInfoLite_DEFAULT NULL +#define meshtastic_NodeInfoLite_user_MSGTYPE meshtastic_User +#define meshtastic_NodeInfoLite_position_MSGTYPE meshtastic_PositionLite +#define meshtastic_NodeInfoLite_device_metrics_MSGTYPE meshtastic_DeviceMetrics + #define meshtastic_DeviceState_FIELDLIST(X, a) \ X(a, STATIC, OPTIONAL, MESSAGE, my_node, 2) \ X(a, STATIC, OPTIONAL, MESSAGE, owner, 3) \ @@ -244,32 +269,6 @@ extern bool meshtastic_DeviceState_callback(pb_istream_t *istream, pb_ostream_t #define meshtastic_DeviceState_node_remote_hardware_pins_MSGTYPE meshtastic_NodeRemoteHardwarePin #define meshtastic_DeviceState_node_db_lite_MSGTYPE meshtastic_NodeInfoLite -#define meshtastic_NodeInfoLite_FIELDLIST(X, a) \ -X(a, STATIC, SINGULAR, UINT32, num, 1) \ -X(a, STATIC, OPTIONAL, MESSAGE, user, 2) \ -X(a, STATIC, OPTIONAL, MESSAGE, position, 3) \ -X(a, STATIC, SINGULAR, FLOAT, snr, 4) \ -X(a, STATIC, SINGULAR, FIXED32, last_heard, 5) \ -X(a, STATIC, OPTIONAL, MESSAGE, device_metrics, 6) \ -X(a, STATIC, SINGULAR, UINT32, channel, 7) \ -X(a, STATIC, SINGULAR, BOOL, via_mqtt, 8) \ -X(a, STATIC, SINGULAR, UINT32, hops_away, 9) \ -X(a, STATIC, SINGULAR, BOOL, is_favorite, 10) -#define meshtastic_NodeInfoLite_CALLBACK NULL -#define meshtastic_NodeInfoLite_DEFAULT NULL -#define meshtastic_NodeInfoLite_user_MSGTYPE meshtastic_User -#define meshtastic_NodeInfoLite_position_MSGTYPE meshtastic_PositionLite -#define meshtastic_NodeInfoLite_device_metrics_MSGTYPE meshtastic_DeviceMetrics - -#define meshtastic_PositionLite_FIELDLIST(X, a) \ -X(a, STATIC, SINGULAR, SFIXED32, latitude_i, 1) \ -X(a, STATIC, SINGULAR, SFIXED32, longitude_i, 2) \ -X(a, STATIC, SINGULAR, INT32, altitude, 3) \ -X(a, STATIC, SINGULAR, FIXED32, time, 4) \ -X(a, STATIC, SINGULAR, UENUM, location_source, 5) -#define meshtastic_PositionLite_CALLBACK NULL -#define meshtastic_PositionLite_DEFAULT NULL - #define meshtastic_ChannelFile_FIELDLIST(X, a) \ X(a, STATIC, REPEATED, MESSAGE, channels, 1) \ X(a, STATIC, SINGULAR, UINT32, version, 2) @@ -291,16 +290,16 @@ X(a, STATIC, OPTIONAL, MESSAGE, oem_local_module_config, 8) #define meshtastic_OEMStore_oem_local_config_MSGTYPE meshtastic_LocalConfig #define meshtastic_OEMStore_oem_local_module_config_MSGTYPE meshtastic_LocalModuleConfig -extern const pb_msgdesc_t meshtastic_DeviceState_msg; -extern const pb_msgdesc_t meshtastic_NodeInfoLite_msg; extern const pb_msgdesc_t meshtastic_PositionLite_msg; +extern const pb_msgdesc_t meshtastic_NodeInfoLite_msg; +extern const pb_msgdesc_t meshtastic_DeviceState_msg; extern const pb_msgdesc_t meshtastic_ChannelFile_msg; extern const pb_msgdesc_t meshtastic_OEMStore_msg; /* Defines for backwards compatibility with code written before nanopb-0.4.0 */ -#define meshtastic_DeviceState_fields &meshtastic_DeviceState_msg -#define meshtastic_NodeInfoLite_fields &meshtastic_NodeInfoLite_msg #define meshtastic_PositionLite_fields &meshtastic_PositionLite_msg +#define meshtastic_NodeInfoLite_fields &meshtastic_NodeInfoLite_msg +#define meshtastic_DeviceState_fields &meshtastic_DeviceState_msg #define meshtastic_ChannelFile_fields &meshtastic_ChannelFile_msg #define meshtastic_OEMStore_fields &meshtastic_OEMStore_msg diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index fcefe508b..d15f968d4 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -141,6 +141,11 @@ typedef enum _meshtastic_HardwareModel { /* Heltec Wireless Tracker with ESP32-S3 CPU, built-in GPS, and TFT Older "V1.0" Variant */ meshtastic_HardwareModel_HELTEC_WIRELESS_TRACKER_V1_0 = 58, + /* unPhone with ESP32-S3, TFT touchscreen, LSM6DS3TR-C accelerometer and gyroscope */ + meshtastic_HardwareModel_UNPHONE = 59, + /* Teledatics TD-LORAC NRF52840 based M.2 LoRA module + Compatible with the TD-WRLS development board */ + meshtastic_HardwareModel_TD_LORAC = 60, /* ------------------------------------------------------------------------------------------------------------------------------------------ Reserved ID For developing private Ports. These will show up in live traffic sparsely, so we can use a high number. Keep it within 8 bits. ------------------------------------------------------------------------------------------------------------------------------------------ */ @@ -593,7 +598,7 @@ typedef struct _meshtastic_MeshPacket { meshtastic_MeshPacket_Delayed delayed; /* Describes whether this packet passed via MQTT somewhere along the path it currently took. */ bool via_mqtt; - /* Hop limit with which the original packet started. Sent via LoRa using three bits in the unencrypted header. + /* Hop limit with which the original packet started. Sent via LoRa using three bits in the unencrypted header. When receiving a packet, the difference between hop_start and hop_limit gives how many hops it traveled. */ uint8_t hop_start; } meshtastic_MeshPacket; diff --git a/src/mesh/generated/meshtastic/mqtt.pb.h b/src/mesh/generated/meshtastic/mqtt.pb.h index 8ca570d78..9ec29d5b1 100644 --- a/src/mesh/generated/meshtastic/mqtt.pb.h +++ b/src/mesh/generated/meshtastic/mqtt.pb.h @@ -4,8 +4,8 @@ #ifndef PB_MESHTASTIC_MESHTASTIC_MQTT_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_MQTT_PB_H_INCLUDED #include -#include "meshtastic/mesh.pb.h" #include "meshtastic/config.pb.h" +#include "meshtastic/mesh.pb.h" #if PB_PROTO_HEADER_VERSION != 40 #error Regenerate this file with the current version of nanopb generator. From eb0e705ba973a9596bf677c5ce185bbcfc279f7d Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Thu, 4 Apr 2024 17:04:10 +1300 Subject: [PATCH 398/472] de-init bluetooth --- src/nimble/NimbleBluetooth.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/nimble/NimbleBluetooth.cpp b/src/nimble/NimbleBluetooth.cpp index bc94abf6e..0b91bf44f 100644 --- a/src/nimble/NimbleBluetooth.cpp +++ b/src/nimble/NimbleBluetooth.cpp @@ -112,6 +112,12 @@ void NimbleBluetooth::shutdown() NimBLEAdvertising *pAdvertising = NimBLEDevice::getAdvertising(); pAdvertising->reset(); pAdvertising->stop(); + +#if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0) + // Saving of ~1mA + // Probably applicable to other ESP32 boards - unverified + NimBLEDevice::deinit(); +#endif } bool NimbleBluetooth::isActive() From d1db51830b90241e0f5f0b6259ae0d027c5e5fd1 Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Thu, 4 Apr 2024 17:05:12 +1300 Subject: [PATCH 399/472] set GPIOs for sleep --- src/sleep.cpp | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/src/sleep.cpp b/src/sleep.cpp index ddea9942c..67b7f5c7c 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -277,6 +277,17 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) if (shouldLoraWake(msecToWake)) { enableLoraInterrupt(); } + +#if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0) // Applicable to most ESP32 boards? + // Avoid leakage through button pin + pinMode(0, INPUT); + rtc_gpio_hold_en((gpio_num_t)0); + + // LoRa CS (RADIO_NSS) needs to stay HIGH, even during deep sleep + pinMode(LORA_CS, OUTPUT); + digitalWrite(LORA_CS, HIGH); + rtc_gpio_hold_en((gpio_num_t)LORA_CS); +#endif #endif cpuDeepSleep(msecToWake); } From 30ebb6ae46560a81eb33e102f14bc873ddc000a5 Mon Sep 17 00:00:00 2001 From: Todd Herbert Date: Thu, 4 Apr 2024 17:18:40 +1300 Subject: [PATCH 400/472] use BUTTON_PIN macro --- src/sleep.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/sleep.cpp b/src/sleep.cpp index 67b7f5c7c..0d36112c1 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -280,8 +280,8 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) #if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0) // Applicable to most ESP32 boards? // Avoid leakage through button pin - pinMode(0, INPUT); - rtc_gpio_hold_en((gpio_num_t)0); + pinMode(BUTTON_PIN, INPUT); + rtc_gpio_hold_en((gpio_num_t)BUTTON_PIN); // LoRa CS (RADIO_NSS) needs to stay HIGH, even during deep sleep pinMode(LORA_CS, OUTPUT); From be889015f7792d8a15367d0ac471cb66b2f5d6cb Mon Sep 17 00:00:00 2001 From: Gareth Coleman Date: Wed, 3 Apr 2024 20:17:13 +0100 Subject: [PATCH 401/472] New device unPhone using HX8357D LCD and XPT2046 touchscreen --- src/graphics/Screen.cpp | 15 ++-- src/graphics/ScreenFonts.h | 2 +- src/graphics/TFTDisplay.cpp | 113 +++++++++++++++++++++++++++++- src/graphics/images.h | 5 +- src/main.cpp | 18 ++++- src/platform/esp32/architecture.h | 4 +- variants/unphone/platformio.ini | 16 +++++ variants/unphone/variant.h | 61 ++++++++++++++++ 8 files changed, 218 insertions(+), 16 deletions(-) create mode 100644 variants/unphone/platformio.ini create mode 100644 variants/unphone/variant.h diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 2087b8daf..8510562c4 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -528,7 +528,7 @@ static void drawNodes(OLEDDisplay *display, int16_t x, int16_t y, const NodeStat { char usersString[20]; snprintf(usersString, sizeof(usersString), "%d/%d", nodeStatus->getNumOnline(), nodeStatus->getNumTotal()); -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \ +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS) || defined(HX8357_CS)) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) display->drawFastImage(x, y + 3, 8, 8, imgUser); #else @@ -955,7 +955,7 @@ Screen::Screen(ScanI2C::DeviceAddress address, meshtastic_Config_DisplayConfig_O #elif defined(USE_SSD1306) dispdev = new SSD1306Wire(address.address, -1, -1, geometry, (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); -#elif defined(ST7735_CS) || defined(ILI9341_DRIVER) || defined(ST7789_CS) || defined(RAK14014) +#elif defined(ST7735_CS) || defined(ILI9341_DRIVER) || defined(ST7789_CS) || defined(RAK14014) || defined(HX8357_CS) dispdev = new TFTDisplay(address.address, -1, -1, geometry, (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); #elif defined(USE_EINK) && !defined(USE_EINK_DYNAMICDISPLAY) @@ -1101,7 +1101,7 @@ void Screen::setup() // Standard behaviour is to FLIP the screen (needed on T-Beam). If this config item is set, unflip it, and thereby logically // flip it. If you have a headache now, you're welcome. if (!config.display.flip_screen) { -#if defined(ST7735_CS) || defined(ILI9341_DRIVER) || defined(ST7789_CS) || defined(RAK14014) +#if defined(ST7735_CS) || defined(ILI9341_DRIVER) || defined(ST7789_CS) || defined(RAK14014) || defined(HX8357_CS) static_cast(dispdev)->flipScreenVertically(); #else dispdev->flipScreenVertically(); @@ -1686,7 +1686,7 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16 #ifdef ARCH_ESP32 if (millis() - storeForwardModule->lastHeartbeat > (storeForwardModule->heartbeatInterval * 1200)) { // no heartbeat, overlap a bit -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \ +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS) || defined(HX8357_CS)) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) display->drawFastImage(x + SCREEN_WIDTH - 14 - display->getStringWidth(ourId), y + 3 + FONT_HEIGHT_SMALL, 12, 8, imgQuestionL1); @@ -1697,7 +1697,7 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16 imgQuestion); #endif } else { -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \ +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS) || defined(HX8357_CS)) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) display->drawFastImage(x + SCREEN_WIDTH - 18 - display->getStringWidth(ourId), y + 3 + FONT_HEIGHT_SMALL, 16, 8, imgSFL1); @@ -1711,7 +1711,8 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16 #endif } else { // TODO: Raspberry Pi supports more than just the one screen size -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS) || ARCH_PORTDUINO) && \ +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS) || defined(HX8357_CS) || \ + ARCH_PORTDUINO) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) display->drawFastImage(x + SCREEN_WIDTH - 14 - display->getStringWidth(ourId), y + 3 + FONT_HEIGHT_SMALL, 12, 8, imgInfoL1); @@ -1974,4 +1975,4 @@ int Screen::handleInputEvent(const InputEvent *event) } // namespace graphics #else graphics::Screen::Screen(ScanI2C::DeviceAddress, meshtastic_Config_DisplayConfig_OledType, OLEDDISPLAY_GEOMETRY) {} -#endif // HAS_SCREEN \ No newline at end of file +#endif // HAS_SCREEN diff --git a/src/graphics/ScreenFonts.h b/src/graphics/ScreenFonts.h index d858add2c..4b34563f7 100644 --- a/src/graphics/ScreenFonts.h +++ b/src/graphics/ScreenFonts.h @@ -8,7 +8,7 @@ #include "graphics/fonts/OLEDDisplayFontsUA.h" #endif -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \ +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS) || defined(HX8357_CS)) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) // The screen is bigger so use bigger fonts #define FONT_SMALL ArialMT_Plain_16 // Height: 19 diff --git a/src/graphics/TFTDisplay.cpp b/src/graphics/TFTDisplay.cpp index 79f521fbb..c1f482b84 100644 --- a/src/graphics/TFTDisplay.cpp +++ b/src/graphics/TFTDisplay.cpp @@ -402,9 +402,95 @@ class LGFX : public lgfx::LGFX_Device }; static LGFX *tft = nullptr; + +#elif defined(HX8357_CS) +#include // Graphics and font library for HX8357 driver chip + +class LGFX : public lgfx::LGFX_Device +{ + lgfx::Panel_HX8357D _panel_instance; + lgfx::Bus_SPI _bus_instance; + #if defined(USE_XPT2046) + lgfx::ITouch *_touch_instance; + // lgfx::Touch_XPT2046 _touch_instance; + #endif + + public: + LGFX(void) + { + // Panel_HX8357D + { + // configure SPI + auto cfg = _bus_instance.config(); + + cfg.spi_host = HX8357_SPI_HOST; + cfg.spi_mode = 0; + cfg.freq_write = SPI_FREQUENCY; // SPI clock for transmission (up to 80MHz, rounded to the value obtained by dividing + // 80MHz by an integer) + cfg.freq_read = SPI_READ_FREQUENCY; // SPI clock when receiving + cfg.spi_3wire = false; // Set to true if reception is done on the MOSI pin + cfg.use_lock = true; // Set to true to use transaction locking + cfg.dma_channel = SPI_DMA_CH_AUTO; // SPI_DMA_CH_AUTO; // Set DMA channel to use (0=not use DMA / 1=1ch / 2=ch / + // SPI_DMA_CH_AUTO=auto setting) + cfg.pin_sclk = HX8357_SCK; // Set SPI SCLK pin number + cfg.pin_mosi = HX8357_MOSI; // Set SPI MOSI pin number + cfg.pin_miso = HX8357_MISO; // Set SPI MISO pin number (-1 = disable) + cfg.pin_dc = HX8357_RS; // Set SPI DC pin number (-1 = disable) + + _bus_instance.config(cfg); // applies the set value to the bus. + _panel_instance.setBus(&_bus_instance); // set the bus on the panel. + } + { + // Set the display panel control. + auto cfg = _panel_instance.config(); // Gets a structure for display panel settings. + + cfg.pin_cs = HX8357_CS; // Pin number where CS is connected (-1 = disable) + cfg.pin_rst = HX8357_RESET; // Pin number where RST is connected (-1 = disable) + cfg.pin_busy = HX8357_BUSY; // Pin number where BUSY is connected (-1 = disable) + + cfg.panel_width = TFT_WIDTH; // actual displayable width + cfg.panel_height = TFT_HEIGHT; // actual displayable height + cfg.offset_x = TFT_OFFSET_X; // Panel offset amount in X direction + cfg.offset_y = TFT_OFFSET_Y; // Panel offset amount in Y direction + cfg.offset_rotation = TFT_OFFSET_ROTATION; // Rotation direction value offset 0~7 (4~7 is upside down) + cfg.dummy_read_pixel = 8; // Number of bits for dummy read before pixel readout + cfg.dummy_read_bits = 1; // Number of bits for dummy read before non-pixel data read + cfg.readable = true; // Set to true if data can be read + cfg.invert = TFT_INVERT; // Set to true if the light/darkness of the panel is reversed + cfg.rgb_order = false; // Set to true if the panel's red and blue are swapped + cfg.dlen_16bit = false; + cfg.bus_shared = true; // If the bus is shared with the SD card, set to true (bus control with drawJpgFile etc.) + + _panel_instance.config(cfg); + } + #if defined(USE_XPT2046) + { + // Configure settings for touch control. + _touch_instance = new lgfx::Touch_XPT2046; + auto touch_cfg = _touch_instance->config(); + + touch_cfg.pin_cs = TOUCH_CS; + touch_cfg.x_min = 0; + touch_cfg.x_max = TFT_HEIGHT - 1; + touch_cfg.y_min = 0; + touch_cfg.y_max = TFT_WIDTH - 1; + touch_cfg.pin_int = -1; + touch_cfg.bus_shared = true; + touch_cfg.offset_rotation = 1; + + _touch_instance->config(touch_cfg); + //_panel_instance->setTouch(_touch_instance); + } + #endif + setPanel(&_panel_instance); + } +}; + +static LGFX *tft = nullptr; + #endif -#if defined(ST7735_CS) || defined(ST7789_CS) || defined(ILI9341_DRIVER) || defined(RAK14014) || \ +#if defined(ST7735_CS) || defined(ST7789_CS) || defined(ILI9341_DRIVER) || defined(RAK14014) || defined(HX8357_CS) || \ (ARCH_PORTDUINO && HAS_SCREEN != 0) #include "SPILock.h" #include "TFTDisplay.h" @@ -487,7 +573,13 @@ void TFTDisplay::sendCommand(uint8_t com) #ifdef VTFT_CTRL digitalWrite(VTFT_CTRL, LOW); #endif - +#ifdef UNPHONE + Wire.beginTransmission(0x26); + Wire.write(0x02); + Wire.write(0x04); // Backlight on + Wire.write(0x22); // G&B LEDs off + Wire.endTransmission(); +#endif #ifdef RAK14014 #elif !defined(M5STACK) tft->setBrightness(172); @@ -514,6 +606,13 @@ void TFTDisplay::sendCommand(uint8_t com) #ifdef VTFT_CTRL digitalWrite(VTFT_CTRL, HIGH); #endif +#ifdef UNPHONE + Wire.beginTransmission(0x26); + Wire.write(0x02); + Wire.write(0x00); // Backlight off + Wire.write(0x22); // G&B LEDs off + Wire.endTransmission(); +#endif #ifdef RAK14014 #elif !defined(M5STACK) tft->setBrightness(0); @@ -585,6 +684,14 @@ bool TFTDisplay::connect() pinMode(ST7735_BL_V05, OUTPUT); digitalWrite(ST7735_BL_V05, TFT_BACKLIGHT_ON); #endif +#ifdef UNPHONE + Wire.beginTransmission(0x26); + Wire.write(0x02); + Wire.write(0x04); // Backlight on + Wire.write(0x22); // G&B LEDs off + Wire.endTransmission(); + LOG_INFO("Power to TFT Backlight\n"); +#endif tft->init(); @@ -606,4 +713,4 @@ bool TFTDisplay::connect() return true; } -#endif \ No newline at end of file +#endif diff --git a/src/graphics/images.h b/src/graphics/images.h index 207fc3a86..5c6fb4275 100644 --- a/src/graphics/images.h +++ b/src/graphics/images.h @@ -14,7 +14,8 @@ const uint8_t imgUser[] PROGMEM = {0x3C, 0x42, 0x99, 0xA5, 0xA5, 0x99, 0x42, 0x3 const uint8_t imgPositionEmpty[] PROGMEM = {0x20, 0x30, 0x28, 0x24, 0x42, 0xFF}; const uint8_t imgPositionSolid[] PROGMEM = {0x20, 0x30, 0x38, 0x3C, 0x7E, 0xFF}; -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS) || ARCH_PORTDUINO) && \ +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS) || defined(HX8357_CS) || \ + ARCH_PORTDUINO) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) const uint8_t imgQuestionL1[] PROGMEM = {0xff, 0x01, 0x01, 0x32, 0x7b, 0x49, 0x49, 0x6f, 0x26, 0x01, 0x01, 0xff}; const uint8_t imgQuestionL2[] PROGMEM = {0x0f, 0x08, 0x08, 0x08, 0x06, 0x0f, 0x0f, 0x06, 0x08, 0x08, 0x08, 0x0f}; @@ -30,4 +31,4 @@ const uint8_t imgQuestion[] PROGMEM = {0xbf, 0x41, 0xc0, 0x8b, 0xdb, 0x70, 0xa1, const uint8_t imgSF[] PROGMEM = {0xd2, 0xb7, 0xad, 0xbb, 0x92, 0x01, 0xfd, 0xfd, 0x15, 0x85, 0xf5}; #endif -#include "img/icon.xbm" \ No newline at end of file +#include "img/icon.xbm" diff --git a/src/main.cpp b/src/main.cpp index 0c45e903a..e93acf0ff 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -589,6 +589,20 @@ void setup() if (config.display.oled != meshtastic_Config_DisplayConfig_OledType_OLED_AUTO) screen_model = config.display.oled; +#ifdef UNPHONE + // initialise IO expander with pinmodes + Wire.beginTransmission(0x26); + Wire.write(0x06); + Wire.write(0x7A); + Wire.write(0xDD); + Wire.endTransmission(); + Wire.beginTransmission(0x26); + Wire.write(0x02); + Wire.write(0x04); // Backlight on + Wire.write(0x22); // G&B LEDs off + Wire.endTransmission(); +#endif + #if defined(USE_SH1107) screen_model = meshtastic_Config_DisplayConfig_OledType_OLED_SH1107; // set dimension of 128x128 display_geometry = GEOMETRY_128_128; @@ -686,7 +700,7 @@ void setup() // Don't call screen setup until after nodedb is setup (because we need // the current region name) -#if defined(ST7735_CS) || defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7789_CS) +#if defined(ST7735_CS) || defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7789_CS) || defined(HX8357_CS) screen->setup(); #elif defined(ARCH_PORTDUINO) if (screen_found.port != ScanI2C::I2CPort::NO_I2C || settingsMap[displayPanel]) { @@ -986,4 +1000,4 @@ void loop() mainDelay.delay(delayMsec); } // if (didWake) LOG_DEBUG("wake!\n"); -} \ No newline at end of file +} diff --git a/src/platform/esp32/architecture.h b/src/platform/esp32/architecture.h index 703bcefc9..6855265ac 100644 --- a/src/platform/esp32/architecture.h +++ b/src/platform/esp32/architecture.h @@ -135,6 +135,8 @@ #define HW_VENDOR meshtastic_HardwareModel_CHATTER_2 #elif defined(STATION_G2) #define HW_VENDOR meshtastic_HardwareModel_STATION_G2 +#elif defined(UNPHONE) +#define HW_VENDOR meshtastic_HardwareModel_UNPHONE #endif // ----------------------------------------------------------------------------- @@ -157,4 +159,4 @@ #define LORA_CS 18 #endif -#define SERIAL0_RX_GPIO 3 // Always GPIO3 on ESP32 // FIXME: may be different on ESP32-S3, etc. \ No newline at end of file +#define SERIAL0_RX_GPIO 3 // Always GPIO3 on ESP32 // FIXME: may be different on ESP32-S3, etc. diff --git a/variants/unphone/platformio.ini b/variants/unphone/platformio.ini new file mode 100644 index 000000000..9a4a63807 --- /dev/null +++ b/variants/unphone/platformio.ini @@ -0,0 +1,16 @@ +[env:unphone] +;build_type = debug ; to make it possible to step through our jtag debugger +extends = esp32s3_base +board_level = extra +board = unphone9 +upload_speed = 921600 +monitor_speed = 115200 +monitor_filters = esp32_exception_decoder + +build_flags = ${esp32_base.build_flags} + -D UNPHONE + -D BOARD_HAS_PSRAM + -I variants/unphone + +lib_deps = ${esp32s3_base.lib_deps} + lovyan03/LovyanGFX@^1.1.8 \ No newline at end of file diff --git a/variants/unphone/variant.h b/variants/unphone/variant.h new file mode 100644 index 000000000..3032156f4 --- /dev/null +++ b/variants/unphone/variant.h @@ -0,0 +1,61 @@ +#define SPI_SCK 39 +#define SPI_MOSI 40 +#define SPI_MISO 41 + +// We use the RFM95W LoRa module +#define USE_RF95 +#define LORA_SCK SPI_SCK +#define LORA_MOSI SPI_MOSI +#define LORA_MISO SPI_MISO +#define LORA_CS 44 +#define LORA_DIO0 10 // AKA LORA_IRQ +#define LORA_RESET 42 +#define LORA_DIO1 11 +#define LORA_DIO2 RADIOLIB_NC // Not really used + +// HX8357 TFT LCD +#define HX8357_CS 48 +#define HX8357_RS 47 // AKA DC +#define HX8357_RESET 46 +#define HX8357_SCK SPI_SCK +#define HX8357_MOSI SPI_MOSI +#define HX8357_MISO SPI_MISO +#define HX8357_BUSY -1 +#define HX8357_SPI_HOST SPI2_HOST +#define SPI_FREQUENCY 40000000 +#define SPI_READ_FREQUENCY 16000000 +#define TFT_HEIGHT 480 +#define TFT_WIDTH 320 +#define TFT_OFFSET_X 0 +#define TFT_OFFSET_Y 0 +#define TFT_OFFSET_ROTATION 6 // the unPhone's screen is wired unusually, 0 is typical value here +#define TFT_INVERT false +#define SCREEN_ROTATE true +#define SCREEN_TRANSITION_FRAMERATE 5 + +#define HAS_TOUCHSCREEN 1 +#define USE_XPT2046 1 +#define TOUCH_CS 38 + +#define HAS_GPS 0 // the unphone doesn't have a gps module +#undef GPS_RX_PIN +#undef GPS_TX_PIN + +#define HAS_SDCARD 1 +#define SDCARD_CS 43 + +#define LED_PIN 13 // the red part of the RGB LED +#define LED_INVERTED 1 + +#define BUTTON_PIN 21 // Button 3 - square - top button in landscape mode +#define BUTTON_NEED_PULLUP // we do need a helping hand up + +#define I2C_SDA 3 // I2C pins for this board +#define I2C_SCL 4 + +// ratio of voltage divider = 3.20 (R1=100k, R2=220k) +// #define ADC_MULTIPLIER 3.2 + +// #define BATTERY_PIN 13 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage +// #define ADC_CHANNEL ADC2_GPIO13_CHANNEL +// #define BAT_MEASURE_ADC_UNIT 2 \ No newline at end of file From 4cdfae71cfe2a47b6265adb6bc2041384dcc6114 Mon Sep 17 00:00:00 2001 From: Gareth Coleman Date: Wed, 3 Apr 2024 20:34:31 +0100 Subject: [PATCH 402/472] first attempt at getting trunk to do linting --- src/graphics/TFTDisplay.cpp | 10 +++++----- variants/unphone/variant.h | 10 +++++----- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/src/graphics/TFTDisplay.cpp b/src/graphics/TFTDisplay.cpp index c1f482b84..8de415185 100644 --- a/src/graphics/TFTDisplay.cpp +++ b/src/graphics/TFTDisplay.cpp @@ -410,10 +410,10 @@ class LGFX : public lgfx::LGFX_Device { lgfx::Panel_HX8357D _panel_instance; lgfx::Bus_SPI _bus_instance; - #if defined(USE_XPT2046) +#if defined(USE_XPT2046) lgfx::ITouch *_touch_instance; - // lgfx::Touch_XPT2046 _touch_instance; - #endif +// lgfx::Touch_XPT2046 _touch_instance; +#endif public: LGFX(void) @@ -463,7 +463,7 @@ class LGFX : public lgfx::LGFX_Device _panel_instance.config(cfg); } - #if defined(USE_XPT2046) +#if defined(USE_XPT2046) { // Configure settings for touch control. _touch_instance = new lgfx::Touch_XPT2046; @@ -481,7 +481,7 @@ class LGFX : public lgfx::LGFX_Device _touch_instance->config(touch_cfg); //_panel_instance->setTouch(_touch_instance); } - #endif +#endif setPanel(&_panel_instance); } }; diff --git a/variants/unphone/variant.h b/variants/unphone/variant.h index 3032156f4..dff03b8d5 100644 --- a/variants/unphone/variant.h +++ b/variants/unphone/variant.h @@ -28,7 +28,7 @@ #define TFT_WIDTH 320 #define TFT_OFFSET_X 0 #define TFT_OFFSET_Y 0 -#define TFT_OFFSET_ROTATION 6 // the unPhone's screen is wired unusually, 0 is typical value here +#define TFT_OFFSET_ROTATION 6 // the unPhone's screen is wired unusually, 0 is typical value here #define TFT_INVERT false #define SCREEN_ROTATE true #define SCREEN_TRANSITION_FRAMERATE 5 @@ -37,20 +37,20 @@ #define USE_XPT2046 1 #define TOUCH_CS 38 -#define HAS_GPS 0 // the unphone doesn't have a gps module +#define HAS_GPS 0 // the unphone doesn't have a gps module #undef GPS_RX_PIN #undef GPS_TX_PIN #define HAS_SDCARD 1 #define SDCARD_CS 43 -#define LED_PIN 13 // the red part of the RGB LED +#define LED_PIN 13 // the red part of the RGB LED #define LED_INVERTED 1 -#define BUTTON_PIN 21 // Button 3 - square - top button in landscape mode +#define BUTTON_PIN 21 // Button 3 - square - top button in landscape mode #define BUTTON_NEED_PULLUP // we do need a helping hand up -#define I2C_SDA 3 // I2C pins for this board +#define I2C_SDA 3 // I2C pins for this board #define I2C_SCL 4 // ratio of voltage divider = 3.20 (R1=100k, R2=220k) From 902f38238daefe5b6acb13ca86d73de9ea4dcd8d Mon Sep 17 00:00:00 2001 From: Gareth Coleman <30833824+garethhcoleman@users.noreply.github.com> Date: Fri, 5 Apr 2024 13:20:22 +0100 Subject: [PATCH 403/472] This change to the I2C Scan is to distinguish between two devices (#3554) sharing the same I2C address, the QMI8658 IMU and BQ24295 PMU. --- src/detect/ScanI2C.h | 1 + src/detect/ScanI2CTwoWire.cpp | 13 ++++++++++++- 2 files changed, 13 insertions(+), 1 deletion(-) diff --git a/src/detect/ScanI2C.h b/src/detect/ScanI2C.h index 66e683982..ecb6db225 100644 --- a/src/detect/ScanI2C.h +++ b/src/detect/ScanI2C.h @@ -38,6 +38,7 @@ class ScanI2C MPU6050, LIS3DH, BMA423, + BQ24295, #ifdef HAS_NCP5623 NCP5623, #endif diff --git a/src/detect/ScanI2CTwoWire.cpp b/src/detect/ScanI2CTwoWire.cpp index 146daa3dc..ea6e692df 100644 --- a/src/detect/ScanI2CTwoWire.cpp +++ b/src/detect/ScanI2CTwoWire.cpp @@ -293,7 +293,18 @@ void ScanI2CTwoWire::scanPort(I2CPort port) SCAN_SIMPLE_CASE(LPS22HB_ADDR, LPS22HB, "LPS22HB sensor found\n") SCAN_SIMPLE_CASE(QMC6310_ADDR, QMC6310, "QMC6310 Highrate 3-Axis magnetic sensor found\n") - SCAN_SIMPLE_CASE(QMI8658_ADDR, QMI8658, "QMI8658 Highrate 6-Axis inertial measurement sensor found\n") + + case QMI8658_ADDR: + registerValue = getRegisterValue(ScanI2CTwoWire::RegisterLocation(addr, 0x0A), 1); // get ID + if (registerValue == 0xC0) { + type = BQ24295; + LOG_INFO("BQ24295 PMU found\n"); + } else { + type = QMI8658; + LOG_INFO("QMI8658 Highrate 6-Axis inertial measurement sensor found\n"); + } + break; + SCAN_SIMPLE_CASE(QMC5883L_ADDR, QMC5883L, "QMC5883L Highrate 3-Axis magnetic sensor found\n") SCAN_SIMPLE_CASE(PMSA0031_ADDR, PMSA0031, "PMSA0031 air quality sensor found\n") From f6e6f975c03920a46ae3be2ab23132c3fd3df7ae Mon Sep 17 00:00:00 2001 From: fuutott Date: Fri, 5 Apr 2024 14:58:00 +0100 Subject: [PATCH 404/472] Update platformio.ini should be dash instead of underscore --- variants/rpipico-slowclock/platformio.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/variants/rpipico-slowclock/platformio.ini b/variants/rpipico-slowclock/platformio.ini index e583c4b0d..eec76ca0f 100644 --- a/variants/rpipico-slowclock/platformio.ini +++ b/variants/rpipico-slowclock/platformio.ini @@ -15,7 +15,7 @@ debug_init_cmds = # add our variants files to the include and src paths build_flags = ${rp2040_base.build_flags} -DRPI_PICO - -Ivariants/rpipico_slowclock + -Ivariants/rpipico-slowclock -DDEBUG_RP2040_PORT=Serial2 -DHW_SPI1_DEVICE -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m0plus" @@ -25,4 +25,4 @@ lib_deps = ${rp2040_base.lib_deps} debug_build_flags = ${rp2040_base.build_flags} -g - -DNO_USB \ No newline at end of file + -DNO_USB From 5b5f9c62b5d0afc691487da33eed4446fded04a2 Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Sun, 7 Apr 2024 02:04:26 +1300 Subject: [PATCH 405/472] Remap backlight toggle and touch button (#3560) * Update E-Ink display after sending adhoc ping or disable/enable GPS * Resume display updates when touch button pressed * Use touch hold as modifier; change double-click behavior for user button * Fix preprocessor exclusions * Purge backlight behavior * Distinguish between 3x and 4x multi-presses * Touch button considers "Wake screen on tap or motion" user-setting * Don't assume device has BUTTON_PIN * Rename misleading method --- src/ButtonThread.cpp | 84 ++++++++++++++++++++++++++++++++--------- src/ButtonThread.h | 10 +++-- src/graphics/Screen.cpp | 25 +++++++++++- src/graphics/Screen.h | 4 +- 4 files changed, 99 insertions(+), 24 deletions(-) diff --git a/src/ButtonThread.cpp b/src/ButtonThread.cpp index a1f0170e8..069a92308 100644 --- a/src/ButtonThread.cpp +++ b/src/ButtonThread.cpp @@ -48,7 +48,7 @@ ButtonThread::ButtonThread() : OSThread("Button") userButton.setPressMs(c_longPressTime); userButton.setDebounceMs(1); userButton.attachDoubleClick(userButtonDoublePressed); - userButton.attachMultiClick(userButtonMultiPressed); + userButton.attachMultiClick(userButtonMultiPressed, this); // Reference to instance: get click count from non-static OneButton #ifndef T_DECK // T-Deck immediately wakes up after shutdown, so disable this function userButton.attachLongPressStart(userButtonPressedLongStart); userButton.attachLongPressStop(userButtonPressedLongStop); @@ -86,7 +86,8 @@ ButtonThread::ButtonThread() : OSThread("Button") #ifdef BUTTON_PIN_TOUCH userButtonTouch = OneButton(BUTTON_PIN_TOUCH, true, true); - userButtonTouch.attachClick(touchPressed); + userButtonTouch.setPressMs(400); + userButtonTouch.attachLongPressStart(touchPressedLongStart); // Better handling with longpress than click? wakeOnIrq(BUTTON_PIN_TOUCH, FALLING); #endif } @@ -138,26 +139,42 @@ int32_t ButtonThread::runOnce() case BUTTON_EVENT_DOUBLE_PRESSED: { LOG_BUTTON("Double press!\n"); -#if defined(USE_EINK) && defined(PIN_EINK_EN) - digitalWrite(PIN_EINK_EN, digitalRead(PIN_EINK_EN) == LOW); -#endif service.refreshLocalMeshNode(); service.sendNetworkPing(NODENUM_BROADCAST, true); - if (screen) + if (screen) { screen->print("Sent ad-hoc ping\n"); - break; - } -#if HAS_GPS - case BUTTON_EVENT_MULTI_PRESSED: { - LOG_BUTTON("Multi press!\n"); - if (!config.device.disable_triple_click && (gps != nullptr)) { - gps->toggleGpsMode(); - if (screen) - screen->forceDisplay(); + screen->forceDisplay(true); // Force a new UI frame, then force an EInk update } break; } + + case BUTTON_EVENT_MULTI_PRESSED: { + LOG_BUTTON("Mulitipress! %hux\n", multipressClickCount); + switch (multipressClickCount) { +#if HAS_GPS + // 3 clicks: toggle GPS + case 3: + if (!config.device.disable_triple_click && (gps != nullptr)) { + gps->toggleGpsMode(); + if (screen) + screen->forceDisplay(true); // Force a new UI frame, then force an EInk update + } + break; #endif +#if defined(USE_EINK) && defined(PIN_EINK_EN) // i.e. T-Echo + // 4 clicks: toggle backlight + case 4: + digitalWrite(PIN_EINK_EN, digitalRead(PIN_EINK_EN) == LOW); + break; +#endif + // No valid multipress action + default: + break; + } // end switch: click count + + break; + } // end multipress event + case BUTTON_EVENT_LONG_PRESSED: { LOG_BUTTON("Long press!\n"); powerFSM.trigger(EVENT_PRESS); @@ -176,12 +193,24 @@ int32_t ButtonThread::runOnce() power->shutdown(); break; } - case BUTTON_EVENT_TOUCH_PRESSED: { + +#ifdef BUTTON_PIN_TOUCH + case BUTTON_EVENT_TOUCH_LONG_PRESSED: { LOG_BUTTON("Touch press!\n"); - if (screen) - screen->forceDisplay(); + if (config.display.wake_on_tap_or_motion) { + if (screen) { + // Wake if asleep + if (powerFSM.getState() == &stateDARK) + powerFSM.trigger(EVENT_PRESS); + + // Update display (legacy behaviour) + screen->forceDisplay(); + } + } break; } +#endif // BUTTON_PIN_TOUCH + default: break; } @@ -206,6 +235,25 @@ void ButtonThread::wakeOnIrq(int irq, int mode) FALLING); } +// Static callback +void ButtonThread::userButtonMultiPressed(void *callerThread) +{ + // Grab click count from non-static button, while the info is still valid + ButtonThread *thread = (ButtonThread *)callerThread; + thread->storeClickCount(); + + // Then handle later, in the usual way + btnEvent = BUTTON_EVENT_MULTI_PRESSED; +} + +// Non-static method, runs during callback. Grabs info while still valid +void ButtonThread::storeClickCount() +{ +#ifdef BUTTON_PIN + multipressClickCount = userButton.getNumberClicks(); +#endif +} + void ButtonThread::userButtonPressedLongStart() { if (millis() > c_holdOffTime) { diff --git a/src/ButtonThread.h b/src/ButtonThread.h index 554c1f0c4..3f177302d 100644 --- a/src/ButtonThread.h +++ b/src/ButtonThread.h @@ -17,11 +17,12 @@ class ButtonThread : public concurrency::OSThread BUTTON_EVENT_MULTI_PRESSED, BUTTON_EVENT_LONG_PRESSED, BUTTON_EVENT_LONG_RELEASED, - BUTTON_EVENT_TOUCH_PRESSED + BUTTON_EVENT_TOUCH_LONG_PRESSED, }; ButtonThread(); int32_t runOnce() override; + void storeClickCount(); private: #ifdef BUTTON_PIN @@ -40,13 +41,16 @@ class ButtonThread : public concurrency::OSThread // set during IRQ static volatile ButtonEventType btnEvent; + // Store click count during callback, for later use + volatile int multipressClickCount = 0; + static void wakeOnIrq(int irq, int mode); // IRQ callbacks - static void touchPressed() { btnEvent = BUTTON_EVENT_TOUCH_PRESSED; } static void userButtonPressed() { btnEvent = BUTTON_EVENT_PRESSED; } static void userButtonDoublePressed() { btnEvent = BUTTON_EVENT_DOUBLE_PRESSED; } - static void userButtonMultiPressed() { btnEvent = BUTTON_EVENT_MULTI_PRESSED; } + static void userButtonMultiPressed(void *callerThread); // Retrieve click count from non-static Onebutton while still valid static void userButtonPressedLongStart(); static void userButtonPressedLongStop(); + static void touchPressedLongStart() { btnEvent = BUTTON_EVENT_TOUCH_LONG_PRESSED; } }; diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 8510562c4..11c0b7aa0 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -1153,10 +1153,33 @@ void Screen::setup() MeshModule::observeUIEvents(&uiFrameEventObserver); } -void Screen::forceDisplay() +void Screen::forceDisplay(bool forceUiUpdate) { // Nasty hack to force epaper updates for 'key' frames. FIXME, cleanup. #ifdef USE_EINK + // If requested, make sure queued commands are run, and UI has rendered a new frame + if (forceUiUpdate) { + // No delay between UI frame rendering + setFastFramerate(); + + // Make sure all CMDs have run first + while (!cmdQueue.isEmpty()) + runOnce(); + + // Ensure at least one frame has drawn + uint64_t startUpdate; + do { + startUpdate = millis(); // Handle impossibly unlikely corner case of a millis() overflow.. + delay(10); + ui->update(); + } while (ui->getUiState()->lastUpdate < startUpdate); + + // Return to normal frame rate + targetFramerate = IDLE_FRAMERATE; + ui->setTargetFPS(targetFramerate); + } + + // Tell EInk class to update the display static_cast(dispdev)->forceDisplay(); #endif } diff --git a/src/graphics/Screen.h b/src/graphics/Screen.h index d03ba4320..2cb1cd5a9 100644 --- a/src/graphics/Screen.h +++ b/src/graphics/Screen.h @@ -20,7 +20,7 @@ class Screen void setOn(bool) {} void print(const char *) {} void doDeepSleep() {} - void forceDisplay() {} + void forceDisplay(bool forceUiUpdate = false) {} void startBluetoothPinScreen(uint32_t pin) {} void stopBluetoothPinScreen() {} void startRebootScreen() {} @@ -318,7 +318,7 @@ class Screen : public concurrency::OSThread int handleInputEvent(const InputEvent *arg); /// Used to force (super slow) eink displays to draw critical frames - void forceDisplay(); + void forceDisplay(bool forceUiUpdate = false); /// Draws our SSL cert screen during boot (called from WebServer) void setSSLFrames(); From 03f60dcb49184bab4474b9a0e8cf1302ac278da8 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sat, 6 Apr 2024 08:04:49 -0500 Subject: [PATCH 406/472] Make instructions clearer in config.yaml comments (#3559) --- bin/config-dist.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/bin/config-dist.yaml b/bin/config-dist.yaml index 22ca3e7db..5a8e658cb 100644 --- a/bin/config-dist.yaml +++ b/bin/config-dist.yaml @@ -1,5 +1,6 @@ ### Define your devices here using Broadcom pin numbering ### Uncomment the block that corresponds to your hardware +### Including the "Module:" line! --- Lora: # Module: sx1262 # Waveshare SX126X XXXM From 0e9f1beb4055264d585c5cabf36c757b6f0929e6 Mon Sep 17 00:00:00 2001 From: Jared Quinn Date: Sun, 7 Apr 2024 02:32:15 +1100 Subject: [PATCH 407/472] Native Linux Build (ARM support and webserver deps) (#3506) * Added webserver libraries to build libs * Revert "Added webserver libraries to build libs" This reverts commit bcc72a06b9e1d26f57f46089ab96f502703bff3c. * Added piwebserver library dependencies to native build * Add webserver libraries to apt install for native build * Revert additional libraries added by mistake * Address trunk check issues on Dockerfile * Ignore linter checks for pinning build packages and apt-get --------- Co-authored-by: Jonathan Bennett Co-authored-by: Ben Meadors --- Dockerfile | 52 +++++++++++++++++++++++------------- arch/portduino/portduino.ini | 2 +- 2 files changed, 34 insertions(+), 20 deletions(-) diff --git a/Dockerfile b/Dockerfile index 21e42ad87..76aa3e2a1 100644 --- a/Dockerfile +++ b/Dockerfile @@ -1,4 +1,4 @@ -FROM debian:bullseye-slim AS builder +FROM debian:bookworm-slim AS builder ENV DEBIAN_FRONTEND=noninteractive ENV TZ=Etc/UTC @@ -11,31 +11,45 @@ SHELL ["/bin/bash", "-o", "pipefail", "-c"] # Install build deps USER root -RUN apt-get update && \ - apt-get -y install wget python3 g++ zip python3-venv git vim ca-certificates libgpiod-dev libyaml-cpp-dev libbluetooth-dev -# create a non-priveleged user & group +# trunk-ignore(terrascan/AC_DOCKER_0002): Known terrascan issue +# trunk-ignore(hadolint/DL3008): Use latest version of packages for buildchain +RUN apt-get update && apt-get install --no-install-recommends -y wget python3 python3-pip python3-wheel python3-venv g++ zip git \ + ca-certificates libgpiod-dev libyaml-cpp-dev libbluetooth-dev \ + libulfius-dev liborcania-dev libssl-dev pkg-config && \ + apt-get clean && rm -rf /var/lib/apt/lists/* + RUN groupadd -g 1000 mesh && useradd -ml -u 1000 -g 1000 mesh - USER mesh -RUN wget https://raw.githubusercontent.com/platformio/platformio-core-installer/master/get-platformio.py -qO /tmp/get-platformio.py && \ - chmod +x /tmp/get-platformio.py && \ - python3 /tmp/get-platformio.py && \ - git clone https://github.com/meshtastic/firmware --recurse-submodules /tmp/firmware && \ - cd /tmp/firmware && \ - chmod +x /tmp/firmware/bin/build-native.sh && \ - source ~/.platformio/penv/bin/activate && \ - ./bin/build-native.sh -FROM frolvlad/alpine-glibc:glibc-2.31 +WORKDIR /tmp/firmware +RUN python3 -m venv /tmp/firmware +RUN source ./bin/activate && pip3 install --no-cache-dir -U platformio==6.1.14 -RUN apk --update add --no-cache g++ shadow && \ - groupadd -g 1000 mesh && useradd -ml -u 1000 -g 1000 mesh +COPY . /tmp/firmware +RUN source ./bin/activate && chmod +x /tmp/firmware/bin/build-native.sh && ./bin/build-native.sh +RUN cp "/tmp/firmware/release/meshtasticd_linux_$(uname -m)" "/tmp/firmware/release/meshtasticd" -COPY --from=builder /tmp/firmware/release/meshtasticd_linux_x86_64 /home/mesh/ +##### PRODUCTION BUILD ############# + +FROM debian:bookworm-slim +ENV DEBIAN_FRONTEND=noninteractive +ENV TZ=Etc/UTC + +# trunk-ignore(terrascan/AC_DOCKER_0002): Known terrascan issue +# trunk-ignore(hadolint/DL3008): Use latest version of packages for buildchain +RUN apt-get update && apt-get --no-install-recommends -y install libc-bin libc6 libgpiod2 libyaml-cpp0.7 libulfius2.7 liborcania2.3 libssl3 && \ + apt-get clean && rm -rf /var/lib/apt/lists/* + +RUN groupadd -g 1000 mesh && useradd -ml -u 1000 -g 1000 mesh USER mesh + WORKDIR /home/mesh -CMD sh -cx "./meshtasticd_linux_x86_64 --hwid '${HWID:-$RANDOM}'" +COPY --from=builder /tmp/firmware/release/meshtasticd /home/mesh/ -HEALTHCHECK NONE \ No newline at end of file +VOLUME /home/mesh/data + +CMD [ "sh", "-cx", "./meshtasticd -d /home/mesh/data --hwid=${HWID:-$RANDOM}" ] + +HEALTHCHECK NONE diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index 077a49b3f..3c996741c 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -34,4 +34,4 @@ build_flags = -DPORTDUINO_LINUX_HARDWARE -lbluetooth -lgpiod - -lyaml-cpp \ No newline at end of file + -lyaml-cpp From 1baad2875a122fcd876024f5145587b38e711efd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sun, 7 Apr 2024 02:12:57 +0200 Subject: [PATCH 408/472] Add keymappings for several utility functions (#3536) * - map fn+m to mute and unmute the external notification module - map fn+t to be an alternative for the TAB key * add whitelist to inputbroker * (maybe) sweet-talking t-deck into tabbing... * now for real - back in Kansas * More fancy mappings --------- Co-authored-by: Ben Meadors --- src/input/kbI2cBase.cpp | 4 +++ src/modules/CannedMessageModule.cpp | 42 ++++++++++++++++++++-- src/modules/ExternalNotificationModule.cpp | 4 +-- src/modules/ExternalNotificationModule.h | 5 +++ 4 files changed, 50 insertions(+), 5 deletions(-) diff --git a/src/input/kbI2cBase.cpp b/src/input/kbI2cBase.cpp index 048f8bbdc..74a6c718d 100644 --- a/src/input/kbI2cBase.cpp +++ b/src/input/kbI2cBase.cpp @@ -217,7 +217,11 @@ int32_t KbI2cBase::runOnce() e.kbchar = 0xb7; break; case 0x90: // fn+r + case 0x91: // fn+t case 0x9b: // fn+s + case 0xac: // fn+m + case 0x9e: // fn+g + case 0xaf: // fn+space // just pass those unmodified e.inputEvent = ANYKEY; e.kbchar = c; diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index 60334ca03..c1cf90325 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -12,7 +12,11 @@ #include "detect/ScanI2C.h" #include "mesh/generated/meshtastic/cannedmessages.pb.h" -#include "main.h" // for cardkb_found +#include "main.h" // for cardkb_found +#include "modules/ExternalNotificationModule.h" // for buzzer control +#if !MESHTASTIC_EXCLUDE_GPS +#include "GPS.h" +#endif #ifndef INPUTBROKER_MATRIX_TYPE #define INPUTBROKER_MATRIX_TYPE 0 @@ -397,6 +401,7 @@ int32_t CannedMessageModule::runOnce() } break; case 0x09: // tab + case 0x91: // alt+t for T-Deck that doesn't have a tab key if (this->destSelect == CANNED_MESSAGE_DESTINATION_TYPE_CHANNEL) { this->destSelect = CANNED_MESSAGE_DESTINATION_TYPE_NONE; } else if (this->destSelect == CANNED_MESSAGE_DESTINATION_TYPE_NODE) { @@ -411,13 +416,44 @@ int32_t CannedMessageModule::runOnce() break; // handle fn+s for shutdown case 0x9b: - screen->startShutdownScreen(); + if (screen) + screen->startShutdownScreen(); shutdownAtMsec = millis() + DEFAULT_SHUTDOWN_SECONDS * 1000; + runState = CANNED_MESSAGE_RUN_STATE_INACTIVE; break; // and fn+r for reboot case 0x90: - screen->startRebootScreen(); + if (screen) + screen->startRebootScreen(); rebootAtMsec = millis() + DEFAULT_REBOOT_SECONDS * 1000; + runState = CANNED_MESSAGE_RUN_STATE_INACTIVE; + break; + case 0x9e: // toggle GPS like triple press does + if (gps != nullptr) { + gps->toggleGpsMode(); + } + if (screen) + screen->forceDisplay(); + runState = CANNED_MESSAGE_RUN_STATE_INACTIVE; + break; + + // mute (switch off/toggle) external notifications on fn+m + case 0xac: + if (moduleConfig.external_notification.enabled == true) { + if (externalNotificationModule->getMute()) { + externalNotificationModule->setMute(false); + runState = CANNED_MESSAGE_RUN_STATE_INACTIVE; + } else { + externalNotificationModule->stopNow(); // this will turn off all GPIO and sounds and idle the loop + externalNotificationModule->setMute(true); + runState = CANNED_MESSAGE_RUN_STATE_INACTIVE; + } + } + break; + case 0xaf: // fn+space send network ping like double press does + service.refreshLocalMeshNode(); + service.sendNetworkPing(NODENUM_BROADCAST, true); + runState = CANNED_MESSAGE_RUN_STATE_INACTIVE; break; default: if (this->cursor == this->freetext.length()) { diff --git a/src/modules/ExternalNotificationModule.cpp b/src/modules/ExternalNotificationModule.cpp index 2a4fdd0ae..617796544 100644 --- a/src/modules/ExternalNotificationModule.cpp +++ b/src/modules/ExternalNotificationModule.cpp @@ -336,7 +336,7 @@ ExternalNotificationModule::ExternalNotificationModule() ProcessMessage ExternalNotificationModule::handleReceived(const meshtastic_MeshPacket &mp) { - if (moduleConfig.external_notification.enabled) { + if (moduleConfig.external_notification.enabled && !isMuted) { #ifdef T_WATCH_S3 drv.setWaveform(0, 75); drv.setWaveform(1, 56); @@ -445,7 +445,7 @@ ProcessMessage ExternalNotificationModule::handleReceived(const meshtastic_MeshP setIntervalFromNow(0); // run once so we know if we should do something } } else { - LOG_INFO("External Notification Module Disabled\n"); + LOG_INFO("External Notification Module Disabled or muted\n"); } return ProcessMessage::CONTINUE; // Let others look at this message also if they want diff --git a/src/modules/ExternalNotificationModule.h b/src/modules/ExternalNotificationModule.h index 3331ec428..08e72c35a 100644 --- a/src/modules/ExternalNotificationModule.h +++ b/src/modules/ExternalNotificationModule.h @@ -38,6 +38,9 @@ class ExternalNotificationModule : public SinglePortModule, private concurrency: void setExternalOff(uint8_t index = 0); bool getExternal(uint8_t index = 0); + void setMute(bool mute) { isMuted = mute; } + bool getMute() { return isMuted; } + void stopNow(); void handleGetRingtone(const meshtastic_MeshPacket &req, meshtastic_AdminMessage *response); @@ -56,6 +59,8 @@ class ExternalNotificationModule : public SinglePortModule, private concurrency: bool isNagging = false; + bool isMuted = false; + virtual AdminMessageHandleResult handleAdminMessageForModule(const meshtastic_MeshPacket &mp, meshtastic_AdminMessage *request, meshtastic_AdminMessage *response) override; From 2db061ded9df0a495f83d0d1c0bdc5d11f14569b Mon Sep 17 00:00:00 2001 From: caveman99 Date: Sun, 7 Apr 2024 13:58:58 +0000 Subject: [PATCH 409/472] [create-pull-request] automated change --- protobufs | 2 +- src/mesh/generated/meshtastic/config.pb.h | 12 ++++++++---- src/mesh/generated/meshtastic/deviceonly.pb.h | 2 +- src/mesh/generated/meshtastic/localonly.pb.h | 2 +- 4 files changed, 11 insertions(+), 7 deletions(-) diff --git a/protobufs b/protobufs index 6157a5723..68720ed8d 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 6157a5723745b3a750720b94676198a7f3839e2a +Subproject commit 68720ed8dbcb2c055e3d1ecd4f78d60692f59493 diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index 67c745214..ed512f12f 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -281,6 +281,8 @@ typedef struct _meshtastic_Config_DeviceConfig { bool is_managed; /* Disables the triple-press of user button to enable or disable GPS */ bool disable_triple_click; + /* POSIX Timezone definition string from https://github.com/nayarsystems/posix_tz_db/blob/master/zones.csv. */ + char tzdef[65]; } meshtastic_Config_DeviceConfig; /* Position Config */ @@ -583,7 +585,7 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_Config_init_default {0, {meshtastic_Config_DeviceConfig_init_default}} -#define meshtastic_Config_DeviceConfig_init_default {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0, 0} +#define meshtastic_Config_DeviceConfig_init_default {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0, 0, ""} #define meshtastic_Config_PositionConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, _meshtastic_Config_PositionConfig_GpsMode_MIN} #define meshtastic_Config_PowerConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_Config_NetworkConfig_init_default {0, "", "", "", 0, _meshtastic_Config_NetworkConfig_AddressMode_MIN, false, meshtastic_Config_NetworkConfig_IpV4Config_init_default, ""} @@ -592,7 +594,7 @@ extern "C" { #define meshtastic_Config_LoRaConfig_init_default {0, _meshtastic_Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, _meshtastic_Config_LoRaConfig_RegionCode_MIN, 0, 0, 0, 0, 0, 0, 0, 0, {0, 0, 0}, 0} #define meshtastic_Config_BluetoothConfig_init_default {0, _meshtastic_Config_BluetoothConfig_PairingMode_MIN, 0} #define meshtastic_Config_init_zero {0, {meshtastic_Config_DeviceConfig_init_zero}} -#define meshtastic_Config_DeviceConfig_init_zero {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0, 0} +#define meshtastic_Config_DeviceConfig_init_zero {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0, 0, ""} #define meshtastic_Config_PositionConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, _meshtastic_Config_PositionConfig_GpsMode_MIN} #define meshtastic_Config_PowerConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_Config_NetworkConfig_init_zero {0, "", "", "", 0, _meshtastic_Config_NetworkConfig_AddressMode_MIN, false, meshtastic_Config_NetworkConfig_IpV4Config_init_zero, ""} @@ -612,6 +614,7 @@ extern "C" { #define meshtastic_Config_DeviceConfig_double_tap_as_button_press_tag 8 #define meshtastic_Config_DeviceConfig_is_managed_tag 9 #define meshtastic_Config_DeviceConfig_disable_triple_click_tag 10 +#define meshtastic_Config_DeviceConfig_tzdef_tag 11 #define meshtastic_Config_PositionConfig_position_broadcast_secs_tag 1 #define meshtastic_Config_PositionConfig_position_broadcast_smart_enabled_tag 2 #define meshtastic_Config_PositionConfig_fixed_position_tag 3 @@ -711,7 +714,8 @@ X(a, STATIC, SINGULAR, UENUM, rebroadcast_mode, 6) \ X(a, STATIC, SINGULAR, UINT32, node_info_broadcast_secs, 7) \ X(a, STATIC, SINGULAR, BOOL, double_tap_as_button_press, 8) \ X(a, STATIC, SINGULAR, BOOL, is_managed, 9) \ -X(a, STATIC, SINGULAR, BOOL, disable_triple_click, 10) +X(a, STATIC, SINGULAR, BOOL, disable_triple_click, 10) \ +X(a, STATIC, SINGULAR, STRING, tzdef, 11) #define meshtastic_Config_DeviceConfig_CALLBACK NULL #define meshtastic_Config_DeviceConfig_DEFAULT NULL @@ -829,7 +833,7 @@ extern const pb_msgdesc_t meshtastic_Config_BluetoothConfig_msg; /* Maximum encoded size of messages (where known) */ #define meshtastic_Config_BluetoothConfig_size 10 -#define meshtastic_Config_DeviceConfig_size 32 +#define meshtastic_Config_DeviceConfig_size 98 #define meshtastic_Config_DisplayConfig_size 28 #define meshtastic_Config_LoRaConfig_size 80 #define meshtastic_Config_NetworkConfig_IpV4Config_size 20 diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index cdd59d871..bec15eb90 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -307,7 +307,7 @@ extern const pb_msgdesc_t meshtastic_OEMStore_msg; /* meshtastic_DeviceState_size depends on runtime parameters */ #define meshtastic_ChannelFile_size 702 #define meshtastic_NodeInfoLite_size 160 -#define meshtastic_OEMStore_size 3278 +#define meshtastic_OEMStore_size 3344 #define meshtastic_PositionLite_size 28 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/localonly.pb.h b/src/mesh/generated/meshtastic/localonly.pb.h index f27c119bd..1f431d788 100644 --- a/src/mesh/generated/meshtastic/localonly.pb.h +++ b/src/mesh/generated/meshtastic/localonly.pb.h @@ -180,7 +180,7 @@ extern const pb_msgdesc_t meshtastic_LocalModuleConfig_msg; #define meshtastic_LocalModuleConfig_fields &meshtastic_LocalModuleConfig_msg /* Maximum encoded size of messages (where known) */ -#define meshtastic_LocalConfig_size 469 +#define meshtastic_LocalConfig_size 535 #define meshtastic_LocalModuleConfig_size 663 #ifdef __cplusplus From 40a7fd145a9f3e00712b33bd5c5223182e90fd0a Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 7 Apr 2024 14:15:03 -0500 Subject: [PATCH 410/472] Update Dockerfile to remove sticky bit during build (#3567) * Update Dockerfile to remove sticky bit during build * no sudo? --- Dockerfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Dockerfile b/Dockerfile index 76aa3e2a1..a6176c32b 100644 --- a/Dockerfile +++ b/Dockerfile @@ -27,7 +27,7 @@ RUN python3 -m venv /tmp/firmware RUN source ./bin/activate && pip3 install --no-cache-dir -U platformio==6.1.14 COPY . /tmp/firmware -RUN source ./bin/activate && chmod +x /tmp/firmware/bin/build-native.sh && ./bin/build-native.sh +RUN source ./bin/activate && chmod -t /tmp/firmware -R && chmod +x /tmp/firmware/bin/build-native.sh && ./bin/build-native.sh RUN cp "/tmp/firmware/release/meshtasticd_linux_$(uname -m)" "/tmp/firmware/release/meshtasticd" From fde20db95f75aae36589474a1ad68997ddf1e9e9 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 7 Apr 2024 14:22:39 -0500 Subject: [PATCH 411/472] move chmod -t to root section --- Dockerfile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Dockerfile b/Dockerfile index a6176c32b..230ddc787 100644 --- a/Dockerfile +++ b/Dockerfile @@ -17,7 +17,7 @@ USER root RUN apt-get update && apt-get install --no-install-recommends -y wget python3 python3-pip python3-wheel python3-venv g++ zip git \ ca-certificates libgpiod-dev libyaml-cpp-dev libbluetooth-dev \ libulfius-dev liborcania-dev libssl-dev pkg-config && \ - apt-get clean && rm -rf /var/lib/apt/lists/* + apt-get clean && rm -rf /var/lib/apt/lists/* && mkdir /tmp/firmware && chmod -t /tmp/firmware RUN groupadd -g 1000 mesh && useradd -ml -u 1000 -g 1000 mesh USER mesh @@ -27,7 +27,7 @@ RUN python3 -m venv /tmp/firmware RUN source ./bin/activate && pip3 install --no-cache-dir -U platformio==6.1.14 COPY . /tmp/firmware -RUN source ./bin/activate && chmod -t /tmp/firmware -R && chmod +x /tmp/firmware/bin/build-native.sh && ./bin/build-native.sh +RUN source ./bin/activate && chmod +x /tmp/firmware/bin/build-native.sh && ./bin/build-native.sh RUN cp "/tmp/firmware/release/meshtasticd_linux_$(uname -m)" "/tmp/firmware/release/meshtasticd" From 47b8f7b6c63f919ebdb3658d28cb0e09d0b8fcc1 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 7 Apr 2024 14:34:19 -0500 Subject: [PATCH 412/472] Don't forget to change directory owner --- Dockerfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Dockerfile b/Dockerfile index 230ddc787..cd848208d 100644 --- a/Dockerfile +++ b/Dockerfile @@ -19,7 +19,7 @@ RUN apt-get update && apt-get install --no-install-recommends -y wget python3 py libulfius-dev liborcania-dev libssl-dev pkg-config && \ apt-get clean && rm -rf /var/lib/apt/lists/* && mkdir /tmp/firmware && chmod -t /tmp/firmware -RUN groupadd -g 1000 mesh && useradd -ml -u 1000 -g 1000 mesh +RUN groupadd -g 1000 mesh && useradd -ml -u 1000 -g 1000 mesh && chown mesh:mesh /tmp/firmware USER mesh WORKDIR /tmp/firmware From 68e657fd07f416b855b7c4cd70d9c1b15b05e55a Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 7 Apr 2024 15:52:43 -0500 Subject: [PATCH 413/472] Actually fix Docker - hopefully --- Dockerfile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Dockerfile b/Dockerfile index cd848208d..fc6648dec 100644 --- a/Dockerfile +++ b/Dockerfile @@ -17,7 +17,7 @@ USER root RUN apt-get update && apt-get install --no-install-recommends -y wget python3 python3-pip python3-wheel python3-venv g++ zip git \ ca-certificates libgpiod-dev libyaml-cpp-dev libbluetooth-dev \ libulfius-dev liborcania-dev libssl-dev pkg-config && \ - apt-get clean && rm -rf /var/lib/apt/lists/* && mkdir /tmp/firmware && chmod -t /tmp/firmware + apt-get clean && rm -rf /var/lib/apt/lists/* && mkdir /tmp/firmware RUN groupadd -g 1000 mesh && useradd -ml -u 1000 -g 1000 mesh && chown mesh:mesh /tmp/firmware USER mesh @@ -26,7 +26,7 @@ WORKDIR /tmp/firmware RUN python3 -m venv /tmp/firmware RUN source ./bin/activate && pip3 install --no-cache-dir -U platformio==6.1.14 -COPY . /tmp/firmware +COPY --chown=mesh:mesh . /tmp/firmware RUN source ./bin/activate && chmod +x /tmp/firmware/bin/build-native.sh && ./bin/build-native.sh RUN cp "/tmp/firmware/release/meshtasticd_linux_$(uname -m)" "/tmp/firmware/release/meshtasticd" From aa3280c18c500cc29b9aac3cd19b6be4e37cf39d Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 7 Apr 2024 17:08:17 -0500 Subject: [PATCH 414/472] add trunk ignore for docker chmod (#3568) * add trunk ignore for docker chmod * Fix incorrect comment type --- Dockerfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Dockerfile b/Dockerfile index fc6648dec..fee6c62d4 100644 --- a/Dockerfile +++ b/Dockerfile @@ -25,7 +25,7 @@ USER mesh WORKDIR /tmp/firmware RUN python3 -m venv /tmp/firmware RUN source ./bin/activate && pip3 install --no-cache-dir -U platformio==6.1.14 - +# trunk-ignore(terrascan/AC_DOCKER_00024): We would actually like these files to be owned by mesh tyvm COPY --chown=mesh:mesh . /tmp/firmware RUN source ./bin/activate && chmod +x /tmp/firmware/bin/build-native.sh && ./bin/build-native.sh RUN cp "/tmp/firmware/release/meshtasticd_linux_$(uname -m)" "/tmp/firmware/release/meshtasticd" From 65e5bdc212e42f3a94f75d84e7ef9cc9c8cc6651 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Mon, 8 Apr 2024 00:01:44 +0200 Subject: [PATCH 415/472] display log and onscreen times in local timezone --- src/RedirectablePrint.cpp | 2 +- src/gps/RTC.cpp | 39 +++++++++++++++++++++++++++++++++------ src/gps/RTC.h | 4 ++-- src/graphics/Screen.cpp | 2 +- src/main.cpp | 9 +++++++++ 5 files changed, 46 insertions(+), 10 deletions(-) diff --git a/src/RedirectablePrint.cpp b/src/RedirectablePrint.cpp index d3f39c377..16906e2e0 100644 --- a/src/RedirectablePrint.cpp +++ b/src/RedirectablePrint.cpp @@ -99,7 +99,7 @@ size_t RedirectablePrint::log(const char *logLevel, const char *format, ...) // If we are the first message on a report, include the header if (!isContinuationMessage) { - uint32_t rtc_sec = getValidTime(RTCQuality::RTCQualityDevice); + uint32_t rtc_sec = getValidTime(RTCQuality::RTCQualityDevice, true); // display local time on logfile if (rtc_sec > 0) { long hms = rtc_sec % SEC_PER_DAY; // hms += tz.tz_dsttime * SEC_PER_HOUR; diff --git a/src/gps/RTC.cpp b/src/gps/RTC.cpp index 10e9e0331..58b267a6c 100644 --- a/src/gps/RTC.cpp +++ b/src/gps/RTC.cpp @@ -128,7 +128,7 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv) #else rtc.initI2C(); #endif - tm *t = localtime(&tv->tv_sec); + tm *t = gmtime(&tv->tv_sec); rtc.setTime(t->tm_year + 1900, t->tm_mon + 1, t->tm_wday, t->tm_mday, t->tm_hour, t->tm_min, t->tm_sec); LOG_DEBUG("RV3028_RTC setTime %02d-%02d-%02d %02d:%02d:%02d %ld\n", t->tm_year + 1900, t->tm_mon + 1, t->tm_mday, t->tm_hour, t->tm_min, t->tm_sec, tv->tv_sec); @@ -142,7 +142,7 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv) #else rtc.begin(); #endif - tm *t = localtime(&tv->tv_sec); + tm *t = gmtime(&tv->tv_sec); rtc.setDateTime(t->tm_year + 1900, t->tm_mon + 1, t->tm_mday, t->tm_hour, t->tm_min, t->tm_sec); LOG_DEBUG("PCF8563_RTC setDateTime %02d-%02d-%02d %02d:%02d:%02d %ld\n", t->tm_year + 1900, t->tm_mon + 1, t->tm_mday, t->tm_hour, t->tm_min, t->tm_sec, tv->tv_sec); @@ -175,7 +175,15 @@ bool perhapsSetRTC(RTCQuality q, struct tm &t) The Unix epoch (or Unix time or POSIX time or Unix timestamp) is the number of seconds that have elapsed since January 1, 1970 (midnight UTC/GMT), not counting leap seconds (in ISO 8601: 1970-01-01T00:00:00Z). */ + // horrible hack to make mktime TZ agnostic - best practise according to + // https://www.gnu.org/software/libc/manual/html_node/Broken_002ddown-Time.html + setenv("TZ", "GMT0", 1); time_t res = mktime(&t); + if (*config.device.tzdef) { + setenv("TZ", config.device.tzdef, 1); + } else { + setenv("TZ", "UTC0", 1); + } struct timeval tv; tv.tv_sec = res; tv.tv_usec = 0; // time.centisecond() * (10 / 1000); @@ -189,14 +197,33 @@ bool perhapsSetRTC(RTCQuality q, struct tm &t) } } +/** + * Returns the timezone offset in seconds. + * + * @return The timezone offset in seconds. + */ +int32_t getTZOffset() +{ + time_t now; + struct tm *gmt; + now = time(NULL); + gmt = gmtime(&now); + gmt->tm_isdst = -1; + return (int16_t)difftime(now, mktime(gmt)); +} + /** * Returns the current time in seconds since the Unix epoch (January 1, 1970). * * @return The current time in seconds since the Unix epoch. */ -uint32_t getTime() +uint32_t getTime(bool local) { - return (((uint32_t)millis() - timeStartMsec) / 1000) + zeroOffsetSecs; + if (local) { + return (((uint32_t)millis() - timeStartMsec) / 1000) + zeroOffsetSecs + getTZOffset(); + } else { + return (((uint32_t)millis() - timeStartMsec) / 1000) + zeroOffsetSecs; + } } /** @@ -205,7 +232,7 @@ uint32_t getTime() * @param minQuality The minimum quality of the RTC time required for it to be considered valid. * @return The current time from the RTC if it meets the minimum quality requirement, or 0 if the time is not valid. */ -uint32_t getValidTime(RTCQuality minQuality) +uint32_t getValidTime(RTCQuality minQuality, bool local) { - return (currentQuality >= minQuality) ? getTime() : 0; + return (currentQuality >= minQuality) ? getTime(local) : 0; } diff --git a/src/gps/RTC.h b/src/gps/RTC.h index 527b31f46..f74e17cd0 100644 --- a/src/gps/RTC.h +++ b/src/gps/RTC.h @@ -29,10 +29,10 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv); bool perhapsSetRTC(RTCQuality q, struct tm &t); /// Return time since 1970 in secs. While quality is RTCQualityNone we will be returning time based at zero -uint32_t getTime(); +uint32_t getTime(bool local = false); /// Return time since 1970 in secs. If quality is RTCQualityNone return zero -uint32_t getValidTime(RTCQuality minQuality); +uint32_t getValidTime(RTCQuality minQuality, bool local = false); void readFromRTC(); diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 11c0b7aa0..e5f392036 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -1896,7 +1896,7 @@ void DebugInfo::drawFrameSettings(OLEDDisplay *display, OLEDDisplayUiState *stat // Show uptime as days, hours, minutes OR seconds std::string uptime = screen->drawTimeDelta(days, hours, minutes, seconds); - uint32_t rtc_sec = getValidTime(RTCQuality::RTCQualityDevice); + uint32_t rtc_sec = getValidTime(RTCQuality::RTCQualityDevice, true); // Display local timezone if (rtc_sec > 0) { long hms = rtc_sec % SEC_PER_DAY; // hms += tz.tz_dsttime * SEC_PER_HOUR; diff --git a/src/main.cpp b/src/main.cpp index e93acf0ff..47f3e2c22 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -663,6 +663,15 @@ void setup() // Initialize the screen first so we can show the logo while we start up everything else. screen = new graphics::Screen(screen_found, screen_model, screen_geometry); + // setup TZ prior to time actions. + if (*config.device.tzdef) { + setenv("TZ", config.device.tzdef, 1); + } else { + setenv("TZ", "GMT0", 1); + } + tzset(); + LOG_DEBUG("Set Timezone to %s\n", getenv("TZ")); + readFromRTC(); // read the main CPU RTC at first (in case we can't get GPS time) #if !MESHTASTIC_EXCLUDE_GPS From ea61808fd94a74e3a6c24a8cb7fb0df5a5133236 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Tue, 9 Apr 2024 00:26:23 +0200 Subject: [PATCH 416/472] tryfix: use UTC on Phone API (#3576) --- src/gps/GPS.cpp | 2 +- src/gps/NMEAWPL.cpp | 4 ++-- src/gps/RTC.cpp | 24 +++++++++++++++--------- src/gps/RTC.h | 2 ++ 4 files changed, 20 insertions(+), 12 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index a6f68f2ef..6a0e3e44a 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -1379,7 +1379,7 @@ bool GPS::lookForLocation() t.tm_mon = reader.date.month() - 1; t.tm_year = reader.date.year() - 1900; t.tm_isdst = false; - p.timestamp = mktime(&t); + p.timestamp = gm_mktime(&t); // Nice to have, if available if (reader.satellites.isUpdated()) { diff --git a/src/gps/NMEAWPL.cpp b/src/gps/NMEAWPL.cpp index cdac3bb27..71943b76c 100644 --- a/src/gps/NMEAWPL.cpp +++ b/src/gps/NMEAWPL.cpp @@ -75,10 +75,10 @@ uint32_t printWPL(char *buf, size_t bufsz, const meshtastic_Position &pos, const uint32_t printGGA(char *buf, size_t bufsz, const meshtastic_Position &pos) { GeoCoord geoCoord(pos.latitude_i, pos.longitude_i, pos.altitude); - tm *t = localtime((time_t *)&pos.timestamp); + tm *t = gmtime((time_t *)&pos.timestamp); if (getRTCQuality() > 0) { // use the device clock if we got time from somewhere. If not, use the GPS timestamp. uint32_t rtc_sec = getValidTime(RTCQuality::RTCQualityDevice); - t = localtime((time_t *)&rtc_sec); + t = gmtime((time_t *)&rtc_sec); } uint32_t len = snprintf( diff --git a/src/gps/RTC.cpp b/src/gps/RTC.cpp index 58b267a6c..26af7cac2 100644 --- a/src/gps/RTC.cpp +++ b/src/gps/RTC.cpp @@ -40,7 +40,7 @@ void readFromRTC() t.tm_hour = rtc.getHour(); t.tm_min = rtc.getMinute(); t.tm_sec = rtc.getSecond(); - tv.tv_sec = mktime(&t); + tv.tv_sec = gm_mktime(&t); tv.tv_usec = 0; LOG_DEBUG("Read RTC time from RV3028 as %ld\n", tv.tv_sec); timeStartMsec = now; @@ -68,7 +68,7 @@ void readFromRTC() t.tm_hour = tc.hour; t.tm_min = tc.minute; t.tm_sec = tc.second; - tv.tv_sec = mktime(&t); + tv.tv_sec = gm_mktime(&t); tv.tv_usec = 0; LOG_DEBUG("Read RTC time from PCF8563 as %ld\n", tv.tv_sec); timeStartMsec = now; @@ -177,13 +177,7 @@ bool perhapsSetRTC(RTCQuality q, struct tm &t) */ // horrible hack to make mktime TZ agnostic - best practise according to // https://www.gnu.org/software/libc/manual/html_node/Broken_002ddown-Time.html - setenv("TZ", "GMT0", 1); - time_t res = mktime(&t); - if (*config.device.tzdef) { - setenv("TZ", config.device.tzdef, 1); - } else { - setenv("TZ", "UTC0", 1); - } + time_t res = gm_mktime(&t); struct timeval tv; tv.tv_sec = res; tv.tv_usec = 0; // time.centisecond() * (10 / 1000); @@ -236,3 +230,15 @@ uint32_t getValidTime(RTCQuality minQuality, bool local) { return (currentQuality >= minQuality) ? getTime(local) : 0; } + +time_t gm_mktime(struct tm *tm) +{ + setenv("TZ", "GMT0", 1); + time_t res = mktime(tm); + if (*config.device.tzdef) { + setenv("TZ", config.device.tzdef, 1); + } else { + setenv("TZ", "UTC0", 1); + } + return res; +} diff --git a/src/gps/RTC.h b/src/gps/RTC.h index f74e17cd0..0561819bd 100644 --- a/src/gps/RTC.h +++ b/src/gps/RTC.h @@ -36,6 +36,8 @@ uint32_t getValidTime(RTCQuality minQuality, bool local = false); void readFromRTC(); +time_t gm_mktime(struct tm *tm); + #define SEC_PER_DAY 86400 #define SEC_PER_HOUR 3600 #define SEC_PER_MIN 60 \ No newline at end of file From e89575bfd173852ea60bd515b0735db9b1ac4580 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Mon, 8 Apr 2024 18:43:10 -0500 Subject: [PATCH 417/472] [create-pull-request] automated change (#3577) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 5f162b8ae..6aedf1e72 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 3 -build = 4 +build = 5 From ec74fba2bd452cd40999158b322a628910210029 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Tue, 9 Apr 2024 14:40:55 +0200 Subject: [PATCH 418/472] update to nanopb 0.4.8 and fix proto regen script (#3578) * update to nanopb 0.4.8 and fix proto regen script * trunk, damnit --- .github/workflows/update_protobufs.yml | 6 +++--- bin/regen-protos.bat | 2 +- bin/regen-protos.sh | 14 +++----------- 3 files changed, 7 insertions(+), 15 deletions(-) diff --git a/.github/workflows/update_protobufs.yml b/.github/workflows/update_protobufs.yml index 6944d827e..30f9b3578 100644 --- a/.github/workflows/update_protobufs.yml +++ b/.github/workflows/update_protobufs.yml @@ -17,9 +17,9 @@ jobs: - name: Download nanopb run: | - wget https://jpa.kapsi.fi/nanopb/download/nanopb-0.4.7-linux-x86.tar.gz - tar xvzf nanopb-0.4.7-linux-x86.tar.gz - mv nanopb-0.4.7-linux-x86 nanopb-0.4.7 + wget https://jpa.kapsi.fi/nanopb/download/nanopb-0.4.8-linux-x86.tar.gz + tar xvzf nanopb-0.4.8-linux-x86.tar.gz + mv nanopb-0.4.8-linux-x86 nanopb-0.4.8 - name: Re-generate protocol buffers run: | diff --git a/bin/regen-protos.bat b/bin/regen-protos.bat index 1d55c2506..f28ef0025 100644 --- a/bin/regen-protos.bat +++ b/bin/regen-protos.bat @@ -1 +1 @@ -cd protobufs && ..\nanopb-0.4.7\generator-bin\protoc.exe --experimental_allow_proto3_optional "--nanopb_out=-S.cpp -v:..\src\mesh\generated\" -I=..\protobufs ..\protobufs\meshtastic\*.proto +cd protobufs && ..\nanopb-0.4.8\generator-bin\protoc.exe --experimental_allow_proto3_optional "--nanopb_out=-S.cpp -v:..\src\mesh\generated" -I=..\protobufs\ ..\protobufs\meshtastic\*.proto diff --git a/bin/regen-protos.sh b/bin/regen-protos.sh index 7c751208a..2e60784e3 100755 --- a/bin/regen-protos.sh +++ b/bin/regen-protos.sh @@ -2,18 +2,10 @@ set -e -echo "This script requires https://jpa.kapsi.fi/nanopb/download/ version 0.4.7 to be located in the" +echo "This script requires https://jpa.kapsi.fi/nanopb/download/ version 0.4.8 to be located in the" echo "firmware root directory if the following step fails, you should download the correct" -echo "prebuilt binaries for your computer into nanopb-0.4.7" +echo "prebuilt binaries for your computer into nanopb-0.4.8" # the nanopb tool seems to require that the .options file be in the current directory! cd protobufs -../nanopb-0.4.7/generator-bin/protoc "--nanopb_out=-S.cpp -v:../src/mesh/generated/" -I=../protobufs meshtastic/*.proto --experimental_allow_proto3_optional - -# sed -i 's/#include "meshtastic/#include "./g' -- * - -# sed -i 's/meshtastic_//g' -- * - -#echo "Regenerating protobuf documentation - if you see an error message" -#echo "you can ignore it unless doing a new protobuf release to github." -#bin/regen-docs.sh +../nanopb-0.4.8/generator-bin/protoc --experimental_allow_proto3_optional "--nanopb_out=-S.cpp -v:../src/mesh/generated/" -I=../protobufs meshtastic/*.proto From daa64b055a17a5060baf71e3259a9d323600b6e5 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Tue, 9 Apr 2024 08:00:19 -0500 Subject: [PATCH 419/472] [create-pull-request] automated change (#3579) Co-authored-by: caveman99 --- protobufs | 2 +- src/mesh/generated/meshtastic/admin.pb.cpp | 2 +- src/mesh/generated/meshtastic/admin.pb.h | 3 ++- src/mesh/generated/meshtastic/apponly.pb.cpp | 2 +- src/mesh/generated/meshtastic/apponly.pb.h | 3 ++- src/mesh/generated/meshtastic/atak.pb.cpp | 2 +- src/mesh/generated/meshtastic/atak.pb.h | 3 ++- .../generated/meshtastic/cannedmessages.pb.cpp | 2 +- .../generated/meshtastic/cannedmessages.pb.h | 3 ++- src/mesh/generated/meshtastic/channel.pb.cpp | 2 +- src/mesh/generated/meshtastic/channel.pb.h | 3 ++- src/mesh/generated/meshtastic/clientonly.pb.cpp | 2 +- src/mesh/generated/meshtastic/clientonly.pb.h | 2 +- src/mesh/generated/meshtastic/config.pb.cpp | 2 +- src/mesh/generated/meshtastic/config.pb.h | 3 ++- .../meshtastic/connection_status.pb.cpp | 2 +- .../generated/meshtastic/connection_status.pb.h | 3 ++- src/mesh/generated/meshtastic/deviceonly.pb.cpp | 2 +- src/mesh/generated/meshtastic/deviceonly.pb.h | 7 ++++--- src/mesh/generated/meshtastic/localonly.pb.cpp | 2 +- src/mesh/generated/meshtastic/localonly.pb.h | 3 ++- src/mesh/generated/meshtastic/mesh.pb.cpp | 2 +- src/mesh/generated/meshtastic/mesh.pb.h | 3 ++- .../generated/meshtastic/module_config.pb.cpp | 2 +- src/mesh/generated/meshtastic/module_config.pb.h | 3 ++- src/mesh/generated/meshtastic/mqtt.pb.cpp | 2 +- src/mesh/generated/meshtastic/mqtt.pb.h | 3 ++- src/mesh/generated/meshtastic/paxcount.pb.cpp | 2 +- src/mesh/generated/meshtastic/paxcount.pb.h | 3 ++- src/mesh/generated/meshtastic/portnums.pb.cpp | 2 +- src/mesh/generated/meshtastic/portnums.pb.h | 2 +- .../generated/meshtastic/remote_hardware.pb.cpp | 2 +- .../generated/meshtastic/remote_hardware.pb.h | 3 ++- src/mesh/generated/meshtastic/rtttl.pb.cpp | 2 +- src/mesh/generated/meshtastic/rtttl.pb.h | 3 ++- .../generated/meshtastic/storeforward.pb.cpp | 2 +- src/mesh/generated/meshtastic/storeforward.pb.h | 3 ++- src/mesh/generated/meshtastic/telemetry.pb.cpp | 2 +- src/mesh/generated/meshtastic/telemetry.pb.h | 16 +++++++++++----- src/mesh/generated/meshtastic/xmodem.pb.cpp | 2 +- src/mesh/generated/meshtastic/xmodem.pb.h | 3 ++- 41 files changed, 70 insertions(+), 47 deletions(-) diff --git a/protobufs b/protobufs index 68720ed8d..22cbd0d4c 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 68720ed8dbcb2c055e3d1ecd4f78d60692f59493 +Subproject commit 22cbd0d4cfafa4b8c1e64517e06edc2d7a22cca9 diff --git a/src/mesh/generated/meshtastic/admin.pb.cpp b/src/mesh/generated/meshtastic/admin.pb.cpp index 92835c89c..339960302 100644 --- a/src/mesh/generated/meshtastic/admin.pb.cpp +++ b/src/mesh/generated/meshtastic/admin.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/admin.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/admin.pb.h b/src/mesh/generated/meshtastic/admin.pb.h index f0d4e81b6..d692a3f30 100644 --- a/src/mesh/generated/meshtastic/admin.pb.h +++ b/src/mesh/generated/meshtastic/admin.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_ADMIN_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_ADMIN_PB_H_INCLUDED @@ -340,6 +340,7 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePinsResponse_msg; #define meshtastic_NodeRemoteHardwarePinsResponse_fields &meshtastic_NodeRemoteHardwarePinsResponse_msg /* Maximum encoded size of messages (where known) */ +#define MESHTASTIC_MESHTASTIC_ADMIN_PB_H_MAX_SIZE meshtastic_AdminMessage_size #define meshtastic_AdminMessage_size 500 #define meshtastic_HamParameters_size 32 #define meshtastic_NodeRemoteHardwarePinsResponse_size 496 diff --git a/src/mesh/generated/meshtastic/apponly.pb.cpp b/src/mesh/generated/meshtastic/apponly.pb.cpp index 8c3801ed7..44b0ea3cc 100644 --- a/src/mesh/generated/meshtastic/apponly.pb.cpp +++ b/src/mesh/generated/meshtastic/apponly.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/apponly.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/apponly.pb.h b/src/mesh/generated/meshtastic/apponly.pb.h index 253fdd8ef..54629f522 100644 --- a/src/mesh/generated/meshtastic/apponly.pb.h +++ b/src/mesh/generated/meshtastic/apponly.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_APPONLY_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_APPONLY_PB_H_INCLUDED @@ -54,6 +54,7 @@ extern const pb_msgdesc_t meshtastic_ChannelSet_msg; #define meshtastic_ChannelSet_fields &meshtastic_ChannelSet_msg /* Maximum encoded size of messages (where known) */ +#define MESHTASTIC_MESHTASTIC_APPONLY_PB_H_MAX_SIZE meshtastic_ChannelSet_size #define meshtastic_ChannelSet_size 658 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/atak.pb.cpp b/src/mesh/generated/meshtastic/atak.pb.cpp index 1413b748e..491336bcf 100644 --- a/src/mesh/generated/meshtastic/atak.pb.cpp +++ b/src/mesh/generated/meshtastic/atak.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/atak.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/atak.pb.h b/src/mesh/generated/meshtastic/atak.pb.h index 17d3cd3b9..c094727ed 100644 --- a/src/mesh/generated/meshtastic/atak.pb.h +++ b/src/mesh/generated/meshtastic/atak.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_ATAK_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_ATAK_PB_H_INCLUDED @@ -260,6 +260,7 @@ extern const pb_msgdesc_t meshtastic_PLI_msg; #define meshtastic_PLI_fields &meshtastic_PLI_msg /* Maximum encoded size of messages (where known) */ +#define MESHTASTIC_MESHTASTIC_ATAK_PB_H_MAX_SIZE meshtastic_TAKPacket_size #define meshtastic_Contact_size 242 #define meshtastic_GeoChat_size 323 #define meshtastic_Group_size 4 diff --git a/src/mesh/generated/meshtastic/cannedmessages.pb.cpp b/src/mesh/generated/meshtastic/cannedmessages.pb.cpp index fffa3fdf9..71e659be2 100644 --- a/src/mesh/generated/meshtastic/cannedmessages.pb.cpp +++ b/src/mesh/generated/meshtastic/cannedmessages.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/cannedmessages.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/cannedmessages.pb.h b/src/mesh/generated/meshtastic/cannedmessages.pb.h index b81f65d0d..c3f9a8b9b 100644 --- a/src/mesh/generated/meshtastic/cannedmessages.pb.h +++ b/src/mesh/generated/meshtastic/cannedmessages.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_CANNEDMESSAGES_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_CANNEDMESSAGES_PB_H_INCLUDED @@ -40,6 +40,7 @@ extern const pb_msgdesc_t meshtastic_CannedMessageModuleConfig_msg; #define meshtastic_CannedMessageModuleConfig_fields &meshtastic_CannedMessageModuleConfig_msg /* Maximum encoded size of messages (where known) */ +#define MESHTASTIC_MESHTASTIC_CANNEDMESSAGES_PB_H_MAX_SIZE meshtastic_CannedMessageModuleConfig_size #define meshtastic_CannedMessageModuleConfig_size 203 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/channel.pb.cpp b/src/mesh/generated/meshtastic/channel.pb.cpp index f604f64e9..fe76d8140 100644 --- a/src/mesh/generated/meshtastic/channel.pb.cpp +++ b/src/mesh/generated/meshtastic/channel.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/channel.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/channel.pb.h b/src/mesh/generated/meshtastic/channel.pb.h index 1587483c0..185a47a98 100644 --- a/src/mesh/generated/meshtastic/channel.pb.h +++ b/src/mesh/generated/meshtastic/channel.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_CHANNEL_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_CHANNEL_PB_H_INCLUDED @@ -181,6 +181,7 @@ extern const pb_msgdesc_t meshtastic_Channel_msg; #define meshtastic_Channel_fields &meshtastic_Channel_msg /* Maximum encoded size of messages (where known) */ +#define MESHTASTIC_MESHTASTIC_CHANNEL_PB_H_MAX_SIZE meshtastic_Channel_size #define meshtastic_ChannelSettings_size 70 #define meshtastic_Channel_size 85 #define meshtastic_ModuleSettings_size 6 diff --git a/src/mesh/generated/meshtastic/clientonly.pb.cpp b/src/mesh/generated/meshtastic/clientonly.pb.cpp index ebc2ffabc..44c6f95ce 100644 --- a/src/mesh/generated/meshtastic/clientonly.pb.cpp +++ b/src/mesh/generated/meshtastic/clientonly.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/clientonly.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/clientonly.pb.h b/src/mesh/generated/meshtastic/clientonly.pb.h index 0f70e09c6..dc323292a 100644 --- a/src/mesh/generated/meshtastic/clientonly.pb.h +++ b/src/mesh/generated/meshtastic/clientonly.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_CLIENTONLY_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_CLIENTONLY_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/config.pb.cpp b/src/mesh/generated/meshtastic/config.pb.cpp index 0fa8ba588..f05e47573 100644 --- a/src/mesh/generated/meshtastic/config.pb.cpp +++ b/src/mesh/generated/meshtastic/config.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/config.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index ed512f12f..fd040c57f 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_CONFIG_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_CONFIG_PB_H_INCLUDED @@ -832,6 +832,7 @@ extern const pb_msgdesc_t meshtastic_Config_BluetoothConfig_msg; #define meshtastic_Config_BluetoothConfig_fields &meshtastic_Config_BluetoothConfig_msg /* Maximum encoded size of messages (where known) */ +#define MESHTASTIC_MESHTASTIC_CONFIG_PB_H_MAX_SIZE meshtastic_Config_size #define meshtastic_Config_BluetoothConfig_size 10 #define meshtastic_Config_DeviceConfig_size 98 #define meshtastic_Config_DisplayConfig_size 28 diff --git a/src/mesh/generated/meshtastic/connection_status.pb.cpp b/src/mesh/generated/meshtastic/connection_status.pb.cpp index 0675bc815..fc5a364dd 100644 --- a/src/mesh/generated/meshtastic/connection_status.pb.cpp +++ b/src/mesh/generated/meshtastic/connection_status.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/connection_status.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/connection_status.pb.h b/src/mesh/generated/meshtastic/connection_status.pb.h index 19ed69455..1c618e4d4 100644 --- a/src/mesh/generated/meshtastic/connection_status.pb.h +++ b/src/mesh/generated/meshtastic/connection_status.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_CONNECTION_STATUS_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_CONNECTION_STATUS_PB_H_INCLUDED @@ -175,6 +175,7 @@ extern const pb_msgdesc_t meshtastic_SerialConnectionStatus_msg; #define meshtastic_SerialConnectionStatus_fields &meshtastic_SerialConnectionStatus_msg /* Maximum encoded size of messages (where known) */ +#define MESHTASTIC_MESHTASTIC_CONNECTION_STATUS_PB_H_MAX_SIZE meshtastic_DeviceConnectionStatus_size #define meshtastic_BluetoothConnectionStatus_size 19 #define meshtastic_DeviceConnectionStatus_size 106 #define meshtastic_EthernetConnectionStatus_size 13 diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.cpp b/src/mesh/generated/meshtastic/deviceonly.pb.cpp index 127319b14..672192f67 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.cpp +++ b/src/mesh/generated/meshtastic/deviceonly.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/deviceonly.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index bec15eb90..9b3767180 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_DEVICEONLY_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_DEVICEONLY_PB_H_INCLUDED @@ -174,12 +174,12 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_PositionLite_init_default {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN} #define meshtastic_NodeInfoLite_init_default {0, false, meshtastic_User_init_default, false, meshtastic_PositionLite_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0, 0, 0, 0} -#define meshtastic_DeviceState_init_default {false, meshtastic_MyNodeInfo_init_default, false, meshtastic_User_init_default, 0, {meshtastic_MeshPacket_init_default}, false, meshtastic_MeshPacket_init_default, 0, 0, 0, false, meshtastic_MeshPacket_init_default, 0, {meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default}, {{NULL}, NULL}} +#define meshtastic_DeviceState_init_default {false, meshtastic_MyNodeInfo_init_default, false, meshtastic_User_init_default, 0, {meshtastic_MeshPacket_init_default}, false, meshtastic_MeshPacket_init_default, 0, 0, 0, false, meshtastic_MeshPacket_init_default, 0, {meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default}, {0}} #define meshtastic_ChannelFile_init_default {0, {meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default}, 0} #define meshtastic_OEMStore_init_default {0, 0, {0, {0}}, _meshtastic_ScreenFonts_MIN, "", {0, {0}}, false, meshtastic_LocalConfig_init_default, false, meshtastic_LocalModuleConfig_init_default} #define meshtastic_PositionLite_init_zero {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN} #define meshtastic_NodeInfoLite_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_PositionLite_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0, 0, 0, 0} -#define meshtastic_DeviceState_init_zero {false, meshtastic_MyNodeInfo_init_zero, false, meshtastic_User_init_zero, 0, {meshtastic_MeshPacket_init_zero}, false, meshtastic_MeshPacket_init_zero, 0, 0, 0, false, meshtastic_MeshPacket_init_zero, 0, {meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero}, {{NULL}, NULL}} +#define meshtastic_DeviceState_init_zero {false, meshtastic_MyNodeInfo_init_zero, false, meshtastic_User_init_zero, 0, {meshtastic_MeshPacket_init_zero}, false, meshtastic_MeshPacket_init_zero, 0, 0, 0, false, meshtastic_MeshPacket_init_zero, 0, {meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero}, {0}} #define meshtastic_ChannelFile_init_zero {0, {meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero}, 0} #define meshtastic_OEMStore_init_zero {0, 0, {0, {0}}, _meshtastic_ScreenFonts_MIN, "", {0, {0}}, false, meshtastic_LocalConfig_init_zero, false, meshtastic_LocalModuleConfig_init_zero} @@ -305,6 +305,7 @@ extern const pb_msgdesc_t meshtastic_OEMStore_msg; /* Maximum encoded size of messages (where known) */ /* meshtastic_DeviceState_size depends on runtime parameters */ +#define MESHTASTIC_MESHTASTIC_DEVICEONLY_PB_H_MAX_SIZE meshtastic_OEMStore_size #define meshtastic_ChannelFile_size 702 #define meshtastic_NodeInfoLite_size 160 #define meshtastic_OEMStore_size 3344 diff --git a/src/mesh/generated/meshtastic/localonly.pb.cpp b/src/mesh/generated/meshtastic/localonly.pb.cpp index 8fc3f1139..9bc98fb85 100644 --- a/src/mesh/generated/meshtastic/localonly.pb.cpp +++ b/src/mesh/generated/meshtastic/localonly.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/localonly.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/localonly.pb.h b/src/mesh/generated/meshtastic/localonly.pb.h index 1f431d788..fa7ebcfee 100644 --- a/src/mesh/generated/meshtastic/localonly.pb.h +++ b/src/mesh/generated/meshtastic/localonly.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_LOCALONLY_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_LOCALONLY_PB_H_INCLUDED @@ -180,6 +180,7 @@ extern const pb_msgdesc_t meshtastic_LocalModuleConfig_msg; #define meshtastic_LocalModuleConfig_fields &meshtastic_LocalModuleConfig_msg /* Maximum encoded size of messages (where known) */ +#define MESHTASTIC_MESHTASTIC_LOCALONLY_PB_H_MAX_SIZE meshtastic_LocalModuleConfig_size #define meshtastic_LocalConfig_size 535 #define meshtastic_LocalModuleConfig_size 663 diff --git a/src/mesh/generated/meshtastic/mesh.pb.cpp b/src/mesh/generated/meshtastic/mesh.pb.cpp index 39713ae8d..4907affc6 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.cpp +++ b/src/mesh/generated/meshtastic/mesh.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/mesh.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index d15f968d4..14b6b4c1f 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_MESH_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_MESH_PB_H_INCLUDED @@ -1372,6 +1372,7 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg; #define meshtastic_NodeRemoteHardwarePin_fields &meshtastic_NodeRemoteHardwarePin_msg /* Maximum encoded size of messages (where known) */ +#define MESHTASTIC_MESHTASTIC_MESH_PB_H_MAX_SIZE meshtastic_FromRadio_size #define meshtastic_Compressed_size 243 #define meshtastic_Data_size 270 #define meshtastic_DeviceMetadata_size 46 diff --git a/src/mesh/generated/meshtastic/module_config.pb.cpp b/src/mesh/generated/meshtastic/module_config.pb.cpp index 594cf9628..88a771d5b 100644 --- a/src/mesh/generated/meshtastic/module_config.pb.cpp +++ b/src/mesh/generated/meshtastic/module_config.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/module_config.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/module_config.pb.h b/src/mesh/generated/meshtastic/module_config.pb.h index a2adbc1b9..ffda48704 100644 --- a/src/mesh/generated/meshtastic/module_config.pb.h +++ b/src/mesh/generated/meshtastic/module_config.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_MODULE_CONFIG_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_MODULE_CONFIG_PB_H_INCLUDED @@ -827,6 +827,7 @@ extern const pb_msgdesc_t meshtastic_RemoteHardwarePin_msg; #define meshtastic_RemoteHardwarePin_fields &meshtastic_RemoteHardwarePin_msg /* Maximum encoded size of messages (where known) */ +#define MESHTASTIC_MESHTASTIC_MODULE_CONFIG_PB_H_MAX_SIZE meshtastic_ModuleConfig_size #define meshtastic_ModuleConfig_AmbientLightingConfig_size 14 #define meshtastic_ModuleConfig_AudioConfig_size 19 #define meshtastic_ModuleConfig_CannedMessageConfig_size 49 diff --git a/src/mesh/generated/meshtastic/mqtt.pb.cpp b/src/mesh/generated/meshtastic/mqtt.pb.cpp index a43f364e1..f00dd823b 100644 --- a/src/mesh/generated/meshtastic/mqtt.pb.cpp +++ b/src/mesh/generated/meshtastic/mqtt.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/mqtt.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/mqtt.pb.h b/src/mesh/generated/meshtastic/mqtt.pb.h index 9ec29d5b1..8ec9f98c3 100644 --- a/src/mesh/generated/meshtastic/mqtt.pb.h +++ b/src/mesh/generated/meshtastic/mqtt.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_MQTT_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_MQTT_PB_H_INCLUDED @@ -120,6 +120,7 @@ extern const pb_msgdesc_t meshtastic_MapReport_msg; /* Maximum encoded size of messages (where known) */ /* meshtastic_ServiceEnvelope_size depends on runtime parameters */ +#define MESHTASTIC_MESHTASTIC_MQTT_PB_H_MAX_SIZE meshtastic_MapReport_size #define meshtastic_MapReport_size 108 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/paxcount.pb.cpp b/src/mesh/generated/meshtastic/paxcount.pb.cpp index 57d5f5be9..67f07a31b 100644 --- a/src/mesh/generated/meshtastic/paxcount.pb.cpp +++ b/src/mesh/generated/meshtastic/paxcount.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/paxcount.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/paxcount.pb.h b/src/mesh/generated/meshtastic/paxcount.pb.h index 4b643293c..09377d833 100644 --- a/src/mesh/generated/meshtastic/paxcount.pb.h +++ b/src/mesh/generated/meshtastic/paxcount.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_PAXCOUNT_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_PAXCOUNT_PB_H_INCLUDED @@ -48,6 +48,7 @@ extern const pb_msgdesc_t meshtastic_Paxcount_msg; #define meshtastic_Paxcount_fields &meshtastic_Paxcount_msg /* Maximum encoded size of messages (where known) */ +#define MESHTASTIC_MESHTASTIC_PAXCOUNT_PB_H_MAX_SIZE meshtastic_Paxcount_size #define meshtastic_Paxcount_size 18 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/portnums.pb.cpp b/src/mesh/generated/meshtastic/portnums.pb.cpp index dd0d00e20..8f32c0851 100644 --- a/src/mesh/generated/meshtastic/portnums.pb.cpp +++ b/src/mesh/generated/meshtastic/portnums.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/portnums.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/portnums.pb.h b/src/mesh/generated/meshtastic/portnums.pb.h index f576c7893..233e8d653 100644 --- a/src/mesh/generated/meshtastic/portnums.pb.h +++ b/src/mesh/generated/meshtastic/portnums.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_PORTNUMS_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_PORTNUMS_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/remote_hardware.pb.cpp b/src/mesh/generated/meshtastic/remote_hardware.pb.cpp index f368ec1ef..4a23698b2 100644 --- a/src/mesh/generated/meshtastic/remote_hardware.pb.cpp +++ b/src/mesh/generated/meshtastic/remote_hardware.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/remote_hardware.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/remote_hardware.pb.h b/src/mesh/generated/meshtastic/remote_hardware.pb.h index 26df97616..936034b62 100644 --- a/src/mesh/generated/meshtastic/remote_hardware.pb.h +++ b/src/mesh/generated/meshtastic/remote_hardware.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_REMOTE_HARDWARE_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_REMOTE_HARDWARE_PB_H_INCLUDED @@ -84,6 +84,7 @@ extern const pb_msgdesc_t meshtastic_HardwareMessage_msg; #define meshtastic_HardwareMessage_fields &meshtastic_HardwareMessage_msg /* Maximum encoded size of messages (where known) */ +#define MESHTASTIC_MESHTASTIC_REMOTE_HARDWARE_PB_H_MAX_SIZE meshtastic_HardwareMessage_size #define meshtastic_HardwareMessage_size 24 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/rtttl.pb.cpp b/src/mesh/generated/meshtastic/rtttl.pb.cpp index 685bbde45..8367fdbce 100644 --- a/src/mesh/generated/meshtastic/rtttl.pb.cpp +++ b/src/mesh/generated/meshtastic/rtttl.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/rtttl.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/rtttl.pb.h b/src/mesh/generated/meshtastic/rtttl.pb.h index aa55d0b7d..452b0cf4b 100644 --- a/src/mesh/generated/meshtastic/rtttl.pb.h +++ b/src/mesh/generated/meshtastic/rtttl.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_RTTTL_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_RTTTL_PB_H_INCLUDED @@ -40,6 +40,7 @@ extern const pb_msgdesc_t meshtastic_RTTTLConfig_msg; #define meshtastic_RTTTLConfig_fields &meshtastic_RTTTLConfig_msg /* Maximum encoded size of messages (where known) */ +#define MESHTASTIC_MESHTASTIC_RTTTL_PB_H_MAX_SIZE meshtastic_RTTTLConfig_size #define meshtastic_RTTTLConfig_size 232 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/storeforward.pb.cpp b/src/mesh/generated/meshtastic/storeforward.pb.cpp index 44a1c70c1..5b3fadd9a 100644 --- a/src/mesh/generated/meshtastic/storeforward.pb.cpp +++ b/src/mesh/generated/meshtastic/storeforward.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/storeforward.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/storeforward.pb.h b/src/mesh/generated/meshtastic/storeforward.pb.h index 55ab0b510..311596c7f 100644 --- a/src/mesh/generated/meshtastic/storeforward.pb.h +++ b/src/mesh/generated/meshtastic/storeforward.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_STOREFORWARD_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_STOREFORWARD_PB_H_INCLUDED @@ -207,6 +207,7 @@ extern const pb_msgdesc_t meshtastic_StoreAndForward_Heartbeat_msg; #define meshtastic_StoreAndForward_Heartbeat_fields &meshtastic_StoreAndForward_Heartbeat_msg /* Maximum encoded size of messages (where known) */ +#define MESHTASTIC_MESHTASTIC_STOREFORWARD_PB_H_MAX_SIZE meshtastic_StoreAndForward_size #define meshtastic_StoreAndForward_Heartbeat_size 12 #define meshtastic_StoreAndForward_History_size 18 #define meshtastic_StoreAndForward_Statistics_size 50 diff --git a/src/mesh/generated/meshtastic/telemetry.pb.cpp b/src/mesh/generated/meshtastic/telemetry.pb.cpp index 046998ae9..6388e37a0 100644 --- a/src/mesh/generated/meshtastic/telemetry.pb.cpp +++ b/src/mesh/generated/meshtastic/telemetry.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/telemetry.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/telemetry.pb.h b/src/mesh/generated/meshtastic/telemetry.pb.h index d73c6baa1..6955ac4e9 100644 --- a/src/mesh/generated/meshtastic/telemetry.pb.h +++ b/src/mesh/generated/meshtastic/telemetry.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_TELEMETRY_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_TELEMETRY_PB_H_INCLUDED @@ -73,6 +73,9 @@ typedef struct _meshtastic_EnvironmentMetrics { float voltage; /* Current measured (To be depreciated in favor of PowerMetrics in Meshtastic 3.x) */ float current; + /* relative scale IAQ value as measured by Bosch BME680 . value 0-500. + Belongs to Air Quality but is not particle but VOC measurement. Other VOC values can also be put in here. */ + uint16_t iaq; } meshtastic_EnvironmentMetrics; /* Power Metrics (voltage / current / etc) */ @@ -154,12 +157,12 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_DeviceMetrics_init_default {0, 0, 0, 0} -#define meshtastic_EnvironmentMetrics_init_default {0, 0, 0, 0, 0, 0} +#define meshtastic_EnvironmentMetrics_init_default {0, 0, 0, 0, 0, 0, 0} #define meshtastic_PowerMetrics_init_default {0, 0, 0, 0, 0, 0} #define meshtastic_AirQualityMetrics_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_Telemetry_init_default {0, 0, {meshtastic_DeviceMetrics_init_default}} #define meshtastic_DeviceMetrics_init_zero {0, 0, 0, 0} -#define meshtastic_EnvironmentMetrics_init_zero {0, 0, 0, 0, 0, 0} +#define meshtastic_EnvironmentMetrics_init_zero {0, 0, 0, 0, 0, 0, 0} #define meshtastic_PowerMetrics_init_zero {0, 0, 0, 0, 0, 0} #define meshtastic_AirQualityMetrics_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_Telemetry_init_zero {0, 0, {meshtastic_DeviceMetrics_init_zero}} @@ -175,6 +178,7 @@ extern "C" { #define meshtastic_EnvironmentMetrics_gas_resistance_tag 4 #define meshtastic_EnvironmentMetrics_voltage_tag 5 #define meshtastic_EnvironmentMetrics_current_tag 6 +#define meshtastic_EnvironmentMetrics_iaq_tag 7 #define meshtastic_PowerMetrics_ch1_voltage_tag 1 #define meshtastic_PowerMetrics_ch1_current_tag 2 #define meshtastic_PowerMetrics_ch2_voltage_tag 3 @@ -214,7 +218,8 @@ X(a, STATIC, SINGULAR, FLOAT, relative_humidity, 2) \ X(a, STATIC, SINGULAR, FLOAT, barometric_pressure, 3) \ X(a, STATIC, SINGULAR, FLOAT, gas_resistance, 4) \ X(a, STATIC, SINGULAR, FLOAT, voltage, 5) \ -X(a, STATIC, SINGULAR, FLOAT, current, 6) +X(a, STATIC, SINGULAR, FLOAT, current, 6) \ +X(a, STATIC, SINGULAR, UINT32, iaq, 7) #define meshtastic_EnvironmentMetrics_CALLBACK NULL #define meshtastic_EnvironmentMetrics_DEFAULT NULL @@ -271,9 +276,10 @@ extern const pb_msgdesc_t meshtastic_Telemetry_msg; #define meshtastic_Telemetry_fields &meshtastic_Telemetry_msg /* Maximum encoded size of messages (where known) */ +#define MESHTASTIC_MESHTASTIC_TELEMETRY_PB_H_MAX_SIZE meshtastic_Telemetry_size #define meshtastic_AirQualityMetrics_size 72 #define meshtastic_DeviceMetrics_size 21 -#define meshtastic_EnvironmentMetrics_size 30 +#define meshtastic_EnvironmentMetrics_size 34 #define meshtastic_PowerMetrics_size 30 #define meshtastic_Telemetry_size 79 diff --git a/src/mesh/generated/meshtastic/xmodem.pb.cpp b/src/mesh/generated/meshtastic/xmodem.pb.cpp index 9692a5eb4..8e5cde457 100644 --- a/src/mesh/generated/meshtastic/xmodem.pb.cpp +++ b/src/mesh/generated/meshtastic/xmodem.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #include "meshtastic/xmodem.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/xmodem.pb.h b/src/mesh/generated/meshtastic/xmodem.pb.h index 48d5aa5cd..67bd0869f 100644 --- a/src/mesh/generated/meshtastic/xmodem.pb.h +++ b/src/mesh/generated/meshtastic/xmodem.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.7 */ +/* Generated by nanopb-0.4.8 */ #ifndef PB_MESHTASTIC_MESHTASTIC_XMODEM_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_XMODEM_PB_H_INCLUDED @@ -68,6 +68,7 @@ extern const pb_msgdesc_t meshtastic_XModem_msg; #define meshtastic_XModem_fields &meshtastic_XModem_msg /* Maximum encoded size of messages (where known) */ +#define MESHTASTIC_MESHTASTIC_XMODEM_PB_H_MAX_SIZE meshtastic_XModem_size #define meshtastic_XModem_size 141 #ifdef __cplusplus From 77082e35f5f53bf36db4403bd4bda19b1d92e6bb Mon Sep 17 00:00:00 2001 From: rcarteraz Date: Tue, 9 Apr 2024 09:37:38 -0700 Subject: [PATCH 420/472] Add unPhone to S3 build scripts (#3583) * add unphone to s3 devices * add unphone --- bin/device-install.bat | 2 +- bin/device-install.sh | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/bin/device-install.bat b/bin/device-install.bat index 1fe1df52a..6c880185e 100755 --- a/bin/device-install.bat +++ b/bin/device-install.bat @@ -32,7 +32,7 @@ IF EXIST %FILENAME% IF x%FILENAME:update=%==x%FILENAME% ( %PYTHON% -m esptool --baud 115200 write_flash 0x00 %FILENAME% @REM Account for S3 and C3 board's different OTA partition - IF x%FILENAME:s3=%==x%FILENAME% IF x%FILENAME:v3=%==x%FILENAME% IF x%FILENAME:t-deck=%==x%FILENAME% IF x%FILENAME:wireless-paper=%==x%FILENAME% IF x%FILENAME:wireless-tracker=%==x%FILENAME% IF x%FILENAME:station-g2=%==x%FILENAME% ( + IF x%FILENAME:s3=%==x%FILENAME% IF x%FILENAME:v3=%==x%FILENAME% IF x%FILENAME:t-deck=%==x%FILENAME% IF x%FILENAME:wireless-paper=%==x%FILENAME% IF x%FILENAME:wireless-tracker=%==x%FILENAME% IF x%FILENAME:station-g2=%==x%FILENAME% IF x%FILENAME:unphone=%==x%FILENAME% ( IF x%FILENAME:esp32c3=%==x%FILENAME% ( %PYTHON% -m esptool --baud 115200 write_flash 0x260000 bleota.bin ) else ( diff --git a/bin/device-install.sh b/bin/device-install.sh index 6ef7b1204..563a87af4 100755 --- a/bin/device-install.sh +++ b/bin/device-install.sh @@ -52,7 +52,7 @@ if [ -f "${FILENAME}" ] && [ -n "${FILENAME##*"update"*}" ]; then "$PYTHON" -m esptool erase_flash "$PYTHON" -m esptool write_flash 0x00 ${FILENAME} # Account for S3 board's different OTA partition - if [ -n "${FILENAME##*"s3"*}" ] && [ -n "${FILENAME##*"-v3"*}" ] && [ -n "${FILENAME##*"t-deck"*}" ] && [ -n "${FILENAME##*"wireless-paper"*}" ] && [ -n "${FILENAME##*"wireless-tracker"*}" ] && [ -n "${FILENAME##*"station-g2"*}" ]; then + if [ -n "${FILENAME##*"s3"*}" ] && [ -n "${FILENAME##*"-v3"*}" ] && [ -n "${FILENAME##*"t-deck"*}" ] && [ -n "${FILENAME##*"wireless-paper"*}" ] && [ -n "${FILENAME##*"wireless-tracker"*}" ] && [ -n "${FILENAME##*"station-g2"*}" ] && [ -n "${FILENAME##*"unphone"*}" ]; then if [ -n "${FILENAME##*"esp32c3"*}" ]; then "$PYTHON" -m esptool write_flash 0x260000 bleota.bin else From 6e7405e56b9ea31e324ad30a353898d537eb5ce8 Mon Sep 17 00:00:00 2001 From: rcarteraz Date: Tue, 9 Apr 2024 10:26:03 -0700 Subject: [PATCH 421/472] add unphone (#3584) --- .github/workflows/main_matrix.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 03d47f18e..9ca0764b5 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -100,6 +100,7 @@ jobs: - board: t-deck - board: picomputer-s3 - board: station-g2 + - board: unphone uses: ./.github/workflows/build_esp32_s3.yml with: board: ${{ matrix.board }} From cfd98b2c918e6e14da8e839de4b95dc6e2e504d2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Tue, 9 Apr 2024 15:15:21 +0200 Subject: [PATCH 422/472] add BME680 IAQ reading. Range is from 0 (clean) - 500 (extremely polluted) --- src/modules/Telemetry/EnvironmentTelemetry.cpp | 2 ++ src/modules/Telemetry/Sensor/BME680Sensor.cpp | 1 + 2 files changed, 3 insertions(+) diff --git a/src/modules/Telemetry/EnvironmentTelemetry.cpp b/src/modules/Telemetry/EnvironmentTelemetry.cpp index 908062a5b..189ab7ed0 100644 --- a/src/modules/Telemetry/EnvironmentTelemetry.cpp +++ b/src/modules/Telemetry/EnvironmentTelemetry.cpp @@ -181,6 +181,8 @@ void EnvironmentTelemetryModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiSt display->drawString(x, y += fontHeight(FONT_SMALL), "Volt/Cur: " + String(lastMeasurement.variant.environment_metrics.voltage, 0) + "V / " + String(lastMeasurement.variant.environment_metrics.current, 0) + "mA"); + if (lastMeasurement.variant.environment_metrics.iaq != 0) + display->drawString(x, y += fontHeight(FONT_SMALL), "IAQ: " + String(lastMeasurement.variant.environment_metrics.iaq)); } bool EnvironmentTelemetryModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_Telemetry *t) diff --git a/src/modules/Telemetry/Sensor/BME680Sensor.cpp b/src/modules/Telemetry/Sensor/BME680Sensor.cpp index 323dce31f..217fb5737 100644 --- a/src/modules/Telemetry/Sensor/BME680Sensor.cpp +++ b/src/modules/Telemetry/Sensor/BME680Sensor.cpp @@ -57,6 +57,7 @@ bool BME680Sensor::getMetrics(meshtastic_Telemetry *measurement) measurement->variant.environment_metrics.barometric_pressure = bme680.getData(BSEC_OUTPUT_RAW_PRESSURE).signal / 100.0F; measurement->variant.environment_metrics.gas_resistance = bme680.getData(BSEC_OUTPUT_RAW_GAS).signal / 1000.0; // Check if we need to save state to filesystem (every STATE_SAVE_PERIOD ms) + measurement->variant.environment_metrics.iaq = bme680.getData(BSEC_OUTPUT_IAQ).signal; updateState(); return true; } From 2d81c97b9816de793677e6a640190389d2c29acd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Tue, 9 Apr 2024 15:50:15 +0200 Subject: [PATCH 423/472] fix #2586 (lower IAQ quality for saving to 2 and rework save logic) --- src/modules/Telemetry/Sensor/BME680Sensor.cpp | 21 +++++++------------ 1 file changed, 7 insertions(+), 14 deletions(-) diff --git a/src/modules/Telemetry/Sensor/BME680Sensor.cpp b/src/modules/Telemetry/Sensor/BME680Sensor.cpp index 217fb5737..e1222bba4 100644 --- a/src/modules/Telemetry/Sensor/BME680Sensor.cpp +++ b/src/modules/Telemetry/Sensor/BME680Sensor.cpp @@ -86,17 +86,17 @@ void BME680Sensor::updateState() if (stateUpdateCounter == 0) { /* First state update when IAQ accuracy is >= 3 */ accuracy = bme680.getData(BSEC_OUTPUT_IAQ).accuracy; - if (accuracy >= 3) { - LOG_DEBUG("%s state update IAQ accuracy %u >= 3\n", sensorName, accuracy); + if (accuracy >= 2) { + LOG_DEBUG("%s state update IAQ accuracy %u >= 2\n", sensorName, accuracy); update = true; stateUpdateCounter++; } else { - LOG_DEBUG("%s not updated, IAQ accuracy is %u >= 3\n", sensorName, accuracy); + LOG_DEBUG("%s not updated, IAQ accuracy is %u < 2\n", sensorName, accuracy); } } else { /* Update every STATE_SAVE_PERIOD minutes */ if ((stateUpdateCounter * STATE_SAVE_PERIOD) < millis()) { - LOG_DEBUG("%s state update every %d minutes\n", sensorName, STATE_SAVE_PERIOD); + LOG_DEBUG("%s state update every %d minutes\n", sensorName, STATE_SAVE_PERIOD / 60000); update = true; stateUpdateCounter++; } @@ -104,22 +104,15 @@ void BME680Sensor::updateState() if (update) { bme680.getState(bsecState); - std::string filenameTmp = bsecConfigFileName; - filenameTmp += ".tmp"; + if (FSCom.exists(bsecConfigFileName) && !FSCom.remove(bsecConfigFileName)) { + LOG_WARN("Can't remove old state file\n"); + } auto file = FSCom.open(bsecConfigFileName, FILE_O_WRITE); if (file) { LOG_INFO("%s state write to %s.\n", sensorName, bsecConfigFileName); file.write((uint8_t *)&bsecState, BSEC_MAX_STATE_BLOB_SIZE); file.flush(); file.close(); - // brief window of risk here ;-) - if (FSCom.exists(bsecConfigFileName) && !FSCom.remove(bsecConfigFileName)) { - LOG_WARN("Can't remove old state file\n"); - } - if (!renameFile(filenameTmp.c_str(), bsecConfigFileName)) { - LOG_ERROR("Error: can't rename new state file\n"); - } - } else { LOG_INFO("Can't write %s state (File: %s).\n", sensorName, bsecConfigFileName); } From 3bee6ce9c33faf7b84a964d49024d3324fb04843 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Wed, 10 Apr 2024 18:29:29 +0200 Subject: [PATCH 424/472] Only set NodeNum based on MAC if it's still zero (#3585) * Only set NodeNum based on MAC if it's still zero * Already declared --- src/mesh/NodeDB.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 262b0e039..fb2b79048 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -517,11 +517,12 @@ void NodeDB::installDefaultDeviceState() */ void NodeDB::pickNewNodeNum() { - - getMacAddr(ourMacAddr); // Make sure ourMacAddr is set - - // Pick an initial nodenum based on the macaddr - NodeNum nodeNum = (ourMacAddr[2] << 24) | (ourMacAddr[3] << 16) | (ourMacAddr[4] << 8) | ourMacAddr[5]; + NodeNum nodeNum = myNodeInfo.my_node_num; + if (nodeNum == 0) { + getMacAddr(ourMacAddr); // Make sure ourMacAddr is set + // Pick an initial nodenum based on the macaddr + nodeNum = (ourMacAddr[2] << 24) | (ourMacAddr[3] << 16) | (ourMacAddr[4] << 8) | ourMacAddr[5]; + } meshtastic_NodeInfoLite *found; while ((nodeNum == NODENUM_BROADCAST || nodeNum < NUM_RESERVED) || From 8e29efcb5021201cd4c1ed0cd5600a066085a85d Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Fri, 12 Apr 2024 00:02:50 +1200 Subject: [PATCH 425/472] Fix button interrupt after light sleep (#3587) * Make ButtonThread instance extern Previously was a static local instance in setup(). Now declared in ButtonThread.cpp, accessible via extern declaration in ButtonThread. * Extract attachInterrupt() calls to public method; create matching method for detachInterrupt() * Change suspension of button interrupts for light-sleep * Fix declaration for ARCH_PORTDUINO * Remove LOG_DEBUG used during testing * Don't assume device has a button.. * Guard entire constructor code * Don't use BUTTON_PIN with ARCH_PORTDUINO --------- Co-authored-by: Manuel <71137295+mverch67@users.noreply.github.com> --- src/ButtonThread.cpp | 86 ++++++++++++++++++++++++++++++++++---------- src/ButtonThread.h | 11 +++--- src/main.cpp | 3 -- src/sleep.cpp | 10 ++++-- 4 files changed, 80 insertions(+), 30 deletions(-) diff --git a/src/ButtonThread.cpp b/src/ButtonThread.cpp index 069a92308..206bb7239 100644 --- a/src/ButtonThread.cpp +++ b/src/ButtonThread.cpp @@ -23,18 +23,24 @@ using namespace concurrency; +ButtonThread *buttonThread; // Declared extern in header volatile ButtonThread::ButtonEventType ButtonThread::btnEvent = ButtonThread::BUTTON_EVENT_NONE; +#if defined(BUTTON_PIN) || defined(ARCH_PORTDUINO) +OneButton ButtonThread::userButton; // Get reference to static member +#endif + ButtonThread::ButtonThread() : OSThread("Button") { -#if defined(ARCH_PORTDUINO) || defined(BUTTON_PIN) +#if defined(BUTTON_PIN) || defined(ARCH_PORTDUINO) + #if defined(ARCH_PORTDUINO) if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) { - userButton = OneButton(settingsMap[user], true, true); + this->userButton = OneButton(settingsMap[user], true, true); LOG_DEBUG("Using GPIO%02d for button\n", settingsMap[user]); } #elif defined(BUTTON_PIN) - int pin = config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN; + int pin = config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN; // Resolved button pin this->userButton = OneButton(pin, true, true); LOG_DEBUG("Using GPIO%02d for button\n", pin); #endif @@ -43,6 +49,8 @@ ButtonThread::ButtonThread() : OSThread("Button") // Some platforms (nrf52) have a SENSE variant which allows wake from sleep - override what OneButton did pinMode(pin, INPUT_PULLUP_SENSE); #endif + +#if defined(BUTTON_PIN) || defined(ARCH_PORTDUINO) userButton.attachClick(userButtonPressed); userButton.setClickMs(250); userButton.setPressMs(c_longPressTime); @@ -53,21 +61,8 @@ ButtonThread::ButtonThread() : OSThread("Button") userButton.attachLongPressStart(userButtonPressedLongStart); userButton.attachLongPressStop(userButtonPressedLongStop); #endif -#if defined(ARCH_PORTDUINO) - if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) - wakeOnIrq(settingsMap[user], FALLING); -#else - static OneButton *pBtn = &userButton; // only one instance of ButtonThread is created, so static is safe - attachInterrupt( - pin, - []() { - BaseType_t higherWake = 0; - mainDelay.interruptFromISR(&higherWake); - pBtn->tick(); - }, - CHANGE); -#endif #endif + #ifdef BUTTON_PIN_ALT userButtonAlt = OneButton(BUTTON_PIN_ALT, true, true); #ifdef INPUT_PULLUP_SENSE @@ -81,14 +76,15 @@ ButtonThread::ButtonThread() : OSThread("Button") userButtonAlt.attachDoubleClick(userButtonDoublePressed); userButtonAlt.attachLongPressStart(userButtonPressedLongStart); userButtonAlt.attachLongPressStop(userButtonPressedLongStop); - wakeOnIrq(BUTTON_PIN_ALT, FALLING); #endif #ifdef BUTTON_PIN_TOUCH userButtonTouch = OneButton(BUTTON_PIN_TOUCH, true, true); userButtonTouch.setPressMs(400); userButtonTouch.attachLongPressStart(touchPressedLongStart); // Better handling with longpress than click? - wakeOnIrq(BUTTON_PIN_TOUCH, FALLING); +#endif + + attachButtonInterrupts(); #endif } @@ -220,6 +216,58 @@ int32_t ButtonThread::runOnce() return 50; } +/* + * Attach (or re-attach) hardware interrupts for buttons + * Public method. Used outside class when waking from MCU sleep + */ +void ButtonThread::attachButtonInterrupts() +{ +#if defined(ARCH_PORTDUINO) + if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) + wakeOnIrq(settingsMap[user], FALLING); +#elif defined(BUTTON_PIN) + // Interrupt for user button, during normal use. Improves responsiveness. + attachInterrupt( + config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN, + []() { + BaseType_t higherWake = 0; + mainDelay.interruptFromISR(&higherWake); + ButtonThread::userButton.tick(); + }, + CHANGE); +#endif + +#ifdef BUTTON_PIN_ALT + wakeOnIrq(BUTTON_PIN_ALT, FALLING); +#endif + +#ifdef BUTTON_PIN_TOUCH + wakeOnIrq(BUTTON_PIN_TOUCH, FALLING); +#endif +} + +/* + * Detach the "normal" button interrupts. + * Public method. Used before attaching a "wake-on-button" interrupt for MCU sleep + */ +void ButtonThread::detachButtonInterrupts() +{ +#if defined(ARCH_PORTDUINO) + if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) + detachInterrupt(settingsMap[user]); +#elif defined(BUTTON_PIN) + detachInterrupt(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN); +#endif + +#ifdef BUTTON_PIN_ALT + detachInterrupt(BUTTON_PIN_ALT); +#endif + +#ifdef BUTTON_PIN_TOUCH + detachInterrupt(BUTTON_PIN_TOUCH); +#endif +} + /** * Watch a GPIO and if we get an IRQ, wake the main thread. * Use to add wake on button press diff --git a/src/ButtonThread.h b/src/ButtonThread.h index 3f177302d..07c7ccff7 100644 --- a/src/ButtonThread.h +++ b/src/ButtonThread.h @@ -22,11 +22,13 @@ class ButtonThread : public concurrency::OSThread ButtonThread(); int32_t runOnce() override; + void attachButtonInterrupts(); + void detachButtonInterrupts(); void storeClickCount(); private: -#ifdef BUTTON_PIN - OneButton userButton; +#if defined(BUTTON_PIN) || defined(ARCH_PORTDUINO) + static OneButton userButton; // Static - accessed from an interrupt #endif #ifdef BUTTON_PIN_ALT OneButton userButtonAlt; @@ -34,9 +36,6 @@ class ButtonThread : public concurrency::OSThread #ifdef BUTTON_PIN_TOUCH OneButton userButtonTouch; #endif -#if defined(ARCH_PORTDUINO) - OneButton userButton; -#endif // set during IRQ static volatile ButtonEventType btnEvent; @@ -54,3 +53,5 @@ class ButtonThread : public concurrency::OSThread static void userButtonPressedLongStop(); static void touchPressedLongStart() { btnEvent = BUTTON_EVENT_TOUCH_LONG_PRESSED; } }; + +extern ButtonThread *buttonThread; diff --git a/src/main.cpp b/src/main.cpp index 47f3e2c22..0f2ef7e67 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -188,9 +188,6 @@ uint32_t timeLastPowered = 0; static Periodic *ledPeriodic; static OSThread *powerFSMthread; -#if HAS_BUTTON || defined(ARCH_PORTDUINO) -static OSThread *buttonThread; -#endif static OSThread *accelerometerThread; static OSThread *ambientLightingThread; SPISettings spiSettings(4000000, MSBFIRST, SPI_MODE0); diff --git a/src/sleep.cpp b/src/sleep.cpp index 0d36112c1..5fbb733e6 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -4,6 +4,7 @@ #include "GPS.h" #endif +#include "ButtonThread.h" #include "MeshRadio.h" #include "MeshService.h" #include "NodeDB.h" @@ -337,7 +338,10 @@ esp_sleep_wakeup_cause_t doLightSleep(uint64_t sleepMsec) // FIXME, use a more r #ifdef BUTTON_PIN // The enableLoraInterrupt() method is using ext0_wakeup, so we are forced to use GPIO wakeup gpio_num_t pin = (gpio_num_t)(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN); - gpio_intr_disable(pin); + + // Have to *fully* detach the normal button-interrupts first + buttonThread->detachButtonInterrupts(); + gpio_wakeup_enable(pin, GPIO_INTR_LOW_LEVEL); esp_sleep_enable_gpio_wakeup(); #endif @@ -364,9 +368,9 @@ esp_sleep_wakeup_cause_t doLightSleep(uint64_t sleepMsec) // FIXME, use a more r assert(res == ESP_OK); #ifdef BUTTON_PIN + // Disable wake-on-button interrupt. Re-attach normal button-interrupts gpio_wakeup_disable(pin); - // Would have thought that need gpio_intr_enable() here, but nope.. - // Works fine without it; crashes with it. + buttonThread->attachButtonInterrupts(); #endif esp_sleep_wakeup_cause_t cause = esp_sleep_get_wakeup_cause(); From a4a8556aa2ad2fee6aa5556313f87088d90ff826 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 11 Apr 2024 07:41:37 -0500 Subject: [PATCH 426/472] [create-pull-request] automated change (#3595) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/deviceonly.pb.h | 2 +- src/mesh/generated/meshtastic/mesh.pb.h | 2 +- src/mesh/generated/meshtastic/telemetry.pb.h | 12 ++++++++---- 4 files changed, 11 insertions(+), 7 deletions(-) diff --git a/protobufs b/protobufs index 22cbd0d4c..f92900c5f 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 22cbd0d4cfafa4b8c1e64517e06edc2d7a22cca9 +Subproject commit f92900c5f884b04388fb7abf61d4df66783015e4 diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index 9b3767180..856eb6f4a 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -307,7 +307,7 @@ extern const pb_msgdesc_t meshtastic_OEMStore_msg; /* meshtastic_DeviceState_size depends on runtime parameters */ #define MESHTASTIC_MESHTASTIC_DEVICEONLY_PB_H_MAX_SIZE meshtastic_OEMStore_size #define meshtastic_ChannelFile_size 702 -#define meshtastic_NodeInfoLite_size 160 +#define meshtastic_NodeInfoLite_size 166 #define meshtastic_OEMStore_size 3344 #define meshtastic_PositionLite_size 28 diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index 14b6b4c1f..e674e28bb 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -1384,7 +1384,7 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg; #define meshtastic_MyNodeInfo_size 18 #define meshtastic_NeighborInfo_size 258 #define meshtastic_Neighbor_size 22 -#define meshtastic_NodeInfo_size 277 +#define meshtastic_NodeInfo_size 283 #define meshtastic_NodeRemoteHardwarePin_size 29 #define meshtastic_Position_size 144 #define meshtastic_QueueStatus_size 23 diff --git a/src/mesh/generated/meshtastic/telemetry.pb.h b/src/mesh/generated/meshtastic/telemetry.pb.h index 6955ac4e9..b6d3811a4 100644 --- a/src/mesh/generated/meshtastic/telemetry.pb.h +++ b/src/mesh/generated/meshtastic/telemetry.pb.h @@ -57,6 +57,8 @@ typedef struct _meshtastic_DeviceMetrics { float channel_utilization; /* Percent of airtime for transmission used within the last hour. */ float air_util_tx; + /* How long the device has been running since the last reboot (in seconds) */ + uint32_t uptime_seconds; } meshtastic_DeviceMetrics; /* Weather station or other environmental metrics */ @@ -156,12 +158,12 @@ extern "C" { /* Initializer values for message structs */ -#define meshtastic_DeviceMetrics_init_default {0, 0, 0, 0} +#define meshtastic_DeviceMetrics_init_default {0, 0, 0, 0, 0} #define meshtastic_EnvironmentMetrics_init_default {0, 0, 0, 0, 0, 0, 0} #define meshtastic_PowerMetrics_init_default {0, 0, 0, 0, 0, 0} #define meshtastic_AirQualityMetrics_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_Telemetry_init_default {0, 0, {meshtastic_DeviceMetrics_init_default}} -#define meshtastic_DeviceMetrics_init_zero {0, 0, 0, 0} +#define meshtastic_DeviceMetrics_init_zero {0, 0, 0, 0, 0} #define meshtastic_EnvironmentMetrics_init_zero {0, 0, 0, 0, 0, 0, 0} #define meshtastic_PowerMetrics_init_zero {0, 0, 0, 0, 0, 0} #define meshtastic_AirQualityMetrics_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} @@ -172,6 +174,7 @@ extern "C" { #define meshtastic_DeviceMetrics_voltage_tag 2 #define meshtastic_DeviceMetrics_channel_utilization_tag 3 #define meshtastic_DeviceMetrics_air_util_tx_tag 4 +#define meshtastic_DeviceMetrics_uptime_seconds_tag 5 #define meshtastic_EnvironmentMetrics_temperature_tag 1 #define meshtastic_EnvironmentMetrics_relative_humidity_tag 2 #define meshtastic_EnvironmentMetrics_barometric_pressure_tag 3 @@ -208,7 +211,8 @@ extern "C" { X(a, STATIC, SINGULAR, UINT32, battery_level, 1) \ X(a, STATIC, SINGULAR, FLOAT, voltage, 2) \ X(a, STATIC, SINGULAR, FLOAT, channel_utilization, 3) \ -X(a, STATIC, SINGULAR, FLOAT, air_util_tx, 4) +X(a, STATIC, SINGULAR, FLOAT, air_util_tx, 4) \ +X(a, STATIC, SINGULAR, UINT32, uptime_seconds, 5) #define meshtastic_DeviceMetrics_CALLBACK NULL #define meshtastic_DeviceMetrics_DEFAULT NULL @@ -278,7 +282,7 @@ extern const pb_msgdesc_t meshtastic_Telemetry_msg; /* Maximum encoded size of messages (where known) */ #define MESHTASTIC_MESHTASTIC_TELEMETRY_PB_H_MAX_SIZE meshtastic_Telemetry_size #define meshtastic_AirQualityMetrics_size 72 -#define meshtastic_DeviceMetrics_size 21 +#define meshtastic_DeviceMetrics_size 27 #define meshtastic_EnvironmentMetrics_size 34 #define meshtastic_PowerMetrics_size 30 #define meshtastic_Telemetry_size 79 From 927d07e2c6bb1a60f3b3e89ed65402843cc84d0d Mon Sep 17 00:00:00 2001 From: Manuel <71137295+mverch67@users.noreply.github.com> Date: Fri, 12 Apr 2024 02:39:07 +0200 Subject: [PATCH 427/472] fix: device PMU shutdown (part 2) (#3596) * fix: device PMU shutdown (part 2) * fix error + enable nimble deinit --- src/Power.cpp | 7 +----- src/nimble/NimbleBluetooth.cpp | 4 ++-- src/sleep.cpp | 39 ++++++++++++++++++++-------------- 3 files changed, 26 insertions(+), 24 deletions(-) diff --git a/src/Power.cpp b/src/Power.cpp index 779e32ff5..d13fd6891 100644 --- a/src/Power.cpp +++ b/src/Power.cpp @@ -500,12 +500,7 @@ void Power::shutdown() { LOG_INFO("Shutting down\n"); -#ifdef HAS_PMU - if (pmu_found == true) { - PMU->setChargingLedMode(XPOWERS_CHG_LED_OFF); - PMU->shutdown(); - } -#elif defined(ARCH_NRF52) || defined(ARCH_ESP32) +#if defined(ARCH_NRF52) || defined(ARCH_ESP32) #ifdef PIN_LED1 ledOff(PIN_LED1); #endif diff --git a/src/nimble/NimbleBluetooth.cpp b/src/nimble/NimbleBluetooth.cpp index 0b91bf44f..42b296e45 100644 --- a/src/nimble/NimbleBluetooth.cpp +++ b/src/nimble/NimbleBluetooth.cpp @@ -113,8 +113,8 @@ void NimbleBluetooth::shutdown() pAdvertising->reset(); pAdvertising->stop(); -#if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0) - // Saving of ~1mA +#if defined(ARCH_ESP32) + // Saving of ~1mA for esp32-s3 and 0.1mA for esp32 // Probably applicable to other ESP32 boards - unverified NimBLEDevice::deinit(); #endif diff --git a/src/sleep.cpp b/src/sleep.cpp index 5fbb733e6..7ed264183 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -245,6 +245,22 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) digitalWrite(VEXT_ENABLE, 1); // turn off the display power #endif +#ifdef ARCH_ESP32 + if (shouldLoraWake(msecToWake)) { + enableLoraInterrupt(); + } +#ifdef BUTTON_PIN + // Avoid leakage through button pin + pinMode(BUTTON_PIN, INPUT); + gpio_hold_en((gpio_num_t)BUTTON_PIN); +#endif + + // LoRa CS (RADIO_NSS) needs to stay HIGH, even during deep sleep + pinMode(LORA_CS, OUTPUT); + digitalWrite(LORA_CS, HIGH); + gpio_hold_en((gpio_num_t)LORA_CS); +#endif + #ifdef HAS_PMU if (pmu_found && PMU) { // Obsolete comment: from back when we we used to receive lora packets while CPU was in deep sleep. @@ -257,6 +273,7 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) // If we want to leave the radio receiving in would be 11.5mA current draw, but most of the time it is just waiting // in its sequencer (true?) so the average power draw should be much lower even if we were listinging for packets // all the time. + PMU->setChargingLedMode(XPOWERS_CHG_LED_OFF); uint8_t model = PMU->getChipModel(); if (model == XPOWERS_AXP2101) { @@ -271,25 +288,15 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) // t-beam v1.1 radio power channel PMU->disablePowerOutput(XPOWERS_LDO2); // lora radio power channel } + if (msecToWake == portMAX_DELAY) { + LOG_INFO("PMU shutdown.\n"); + console->flush(); + PMU->shutdown(); + } } #endif -#ifdef ARCH_ESP32 - if (shouldLoraWake(msecToWake)) { - enableLoraInterrupt(); - } - -#if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0) // Applicable to most ESP32 boards? - // Avoid leakage through button pin - pinMode(BUTTON_PIN, INPUT); - rtc_gpio_hold_en((gpio_num_t)BUTTON_PIN); - - // LoRa CS (RADIO_NSS) needs to stay HIGH, even during deep sleep - pinMode(LORA_CS, OUTPUT); - digitalWrite(LORA_CS, HIGH); - rtc_gpio_hold_en((gpio_num_t)LORA_CS); -#endif -#endif + console->flush(); cpuDeepSleep(msecToWake); } From f4a2023dbad5e50ca6e0d4aa197a9bf92fb78041 Mon Sep 17 00:00:00 2001 From: Gareth Coleman <30833824+garethhcoleman@users.noreply.github.com> Date: Fri, 12 Apr 2024 01:40:14 +0100 Subject: [PATCH 428/472] LSM6DS3TR-C support (#3593) * started work on pulling in the unphone library and dependencies, to do e.g. power switch management and etc.; currently failing at Adafruit_ImageReader * now compiles with unphoneLibrary included * successfully pulled in unphone library to manage power switch and init vibe motor and etc. doesnt print to serial tho... * simplified the build a bit; when doing meshtastic do not depend on the MCCI lora libs etc., then also no need to config them via build flags * version that doesnt trigger brownout * cleaned up initVariant a little * note re. GPS * back to mesh upstream version * this time we're back to mesh upstream version * getting LSM6DS3TRC driver installed * shake to wake works, set threshold quite low may need increasing * whats the crack with these end of file changes? * paramatize the wake threshold * try to get the PR to just include real changes * got the right config item and also not giving compiler messages * moved the lib_deps for the LSM6DS3TRC driver from our variant platformio.ini to the main one in root so all boards have it * stuupid error #define-ing --------- Co-authored-by: Hamish Cunningham Co-authored-by: Ben Meadors --- platformio.ini | 1 + src/AccelerometerThread.h | 16 +++++++++++++++- src/configuration.h | 3 ++- src/detect/ScanI2C.cpp | 4 ++-- src/detect/ScanI2C.h | 1 + src/detect/ScanI2CTwoWire.cpp | 1 + variants/unphone/variant.h | 2 ++ 7 files changed, 24 insertions(+), 4 deletions(-) diff --git a/platformio.ini b/platformio.ini index 2c373ab00..d54a06d3e 100644 --- a/platformio.ini +++ b/platformio.ini @@ -132,3 +132,4 @@ lib_deps = adafruit/Adafruit MPU6050@^2.2.4 adafruit/Adafruit LIS3DH@^1.2.4 https://github.com/lewisxhe/SensorLib#27fd0f721e20cd09e1f81383f0ba58a54fe84a17 + adafruit/Adafruit LSM6DS@^4.7.2 \ No newline at end of file diff --git a/src/AccelerometerThread.h b/src/AccelerometerThread.h index 6827908b7..fa5acdaae 100644 --- a/src/AccelerometerThread.h +++ b/src/AccelerometerThread.h @@ -5,6 +5,7 @@ #include "power.h" #include +#include #include #include #include @@ -108,6 +109,15 @@ class AccelerometerThread : public concurrency::OSThread bmaSensor.enableTiltIRQ(); // It corresponds to isDoubleClick interrupt bmaSensor.enableWakeupIRQ(); + } else if (acceleremoter_type == ScanI2C::DeviceType::LSM6DS3 && lsm.begin_I2C(accelerometer_found.address)) { + LOG_DEBUG("LSM6DS3 initializing\n"); + // Default threshold of 2G, less sensitive options are 4, 8 or 16G + lsm.setAccelRange(LSM6DS_ACCEL_RANGE_2_G); +#ifndef LSM6DS3_WAKE_THRESH +#define LSM6DS3_WAKE_THRESH 20 +#endif + lsm.enableWakeup(config.display.wake_on_tap_or_motion, 1, LSM6DS3_WAKE_THRESH); + // Duration is number of occurances needed to trigger, higher threshold is less sensitive } } @@ -133,6 +143,9 @@ class AccelerometerThread : public concurrency::OSThread wakeScreen(); return 500; } + } else if (acceleremoter_type == ScanI2C::DeviceType::LSM6DS3 && lsm.shake()) { + wakeScreen(); + return 500; } return ACCELEROMETER_CHECK_INTERVAL_MS; @@ -156,6 +169,7 @@ class AccelerometerThread : public concurrency::OSThread ScanI2C::DeviceType acceleremoter_type; Adafruit_MPU6050 mpu; Adafruit_LIS3DH lis; + Adafruit_LSM6DS3TRC lsm; }; -} // namespace concurrency +} // namespace concurrency \ No newline at end of file diff --git a/src/configuration.h b/src/configuration.h index 7ce1a0b8b..66ec607ff 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -128,6 +128,7 @@ along with this program. If not, see . #define MPU6050_ADDR 0x68 #define LIS3DH_ADR 0x18 #define BMA423_ADDR 0x19 +#define LSM6DS3_ADDR 0x6A // ----------------------------------------------------------------------------- // LED @@ -280,4 +281,4 @@ along with this program. If not, see . #ifdef MESHTASTIC_EXCLUDE_SCREEN #undef HAS_SCREEN #define HAS_SCREEN 0 -#endif +#endif \ No newline at end of file diff --git a/src/detect/ScanI2C.cpp b/src/detect/ScanI2C.cpp index bf206c190..149bb95f0 100644 --- a/src/detect/ScanI2C.cpp +++ b/src/detect/ScanI2C.cpp @@ -36,8 +36,8 @@ ScanI2C::FoundDevice ScanI2C::firstKeyboard() const ScanI2C::FoundDevice ScanI2C::firstAccelerometer() const { - ScanI2C::DeviceType types[] = {MPU6050, LIS3DH, BMA423}; - return firstOfOrNONE(3, types); + ScanI2C::DeviceType types[] = {MPU6050, LIS3DH, BMA423, LSM6DS3}; + return firstOfOrNONE(4, types); } ScanI2C::FoundDevice ScanI2C::find(ScanI2C::DeviceType) const diff --git a/src/detect/ScanI2C.h b/src/detect/ScanI2C.h index ecb6db225..e87ede0a4 100644 --- a/src/detect/ScanI2C.h +++ b/src/detect/ScanI2C.h @@ -39,6 +39,7 @@ class ScanI2C LIS3DH, BMA423, BQ24295, + LSM6DS3, #ifdef HAS_NCP5623 NCP5623, #endif diff --git a/src/detect/ScanI2CTwoWire.cpp b/src/detect/ScanI2CTwoWire.cpp index ea6e692df..335892131 100644 --- a/src/detect/ScanI2CTwoWire.cpp +++ b/src/detect/ScanI2CTwoWire.cpp @@ -310,6 +310,7 @@ void ScanI2CTwoWire::scanPort(I2CPort port) SCAN_SIMPLE_CASE(PMSA0031_ADDR, PMSA0031, "PMSA0031 air quality sensor found\n") SCAN_SIMPLE_CASE(MPU6050_ADDR, MPU6050, "MPU6050 accelerometer found\n"); SCAN_SIMPLE_CASE(BMA423_ADDR, BMA423, "BMA423 accelerometer found\n"); + SCAN_SIMPLE_CASE(LSM6DS3_ADDR, LSM6DS3, "LSM6DS3 accelerometer found\n"); default: LOG_INFO("Device found at address 0x%x was not able to be enumerated\n", addr.address); diff --git a/variants/unphone/variant.h b/variants/unphone/variant.h index dff03b8d5..9306537f2 100644 --- a/variants/unphone/variant.h +++ b/variants/unphone/variant.h @@ -53,6 +53,8 @@ #define I2C_SDA 3 // I2C pins for this board #define I2C_SCL 4 +#define LSM6DS3_WAKE_THRESH 5 // higher values reduce the sensitivity of the wake threshold + // ratio of voltage divider = 3.20 (R1=100k, R2=220k) // #define ADC_MULTIPLIER 3.2 From 6de0363eea1ff91eeca219ef6a47a122a8de706e Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Fri, 12 Apr 2024 07:17:43 -0500 Subject: [PATCH 429/472] Pin RadioLib to 6.5.x (#3601) --- platformio.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/platformio.ini b/platformio.ini index d54a06d3e..27f9cf546 100644 --- a/platformio.ini +++ b/platformio.ini @@ -74,7 +74,7 @@ build_flags = -Wno-missing-field-initializers monitor_speed = 115200 lib_deps = - jgromes/RadioLib@^6.4.0 + jgromes/RadioLib@~6.5.0 https://github.com/meshtastic/esp8266-oled-ssd1306.git#ee628ee6c9588d4c56c9e3da35f0fc9448ad54a8 ; ESP8266_SSD1306 mathertel/OneButton@^2.5.0 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 @@ -132,4 +132,4 @@ lib_deps = adafruit/Adafruit MPU6050@^2.2.4 adafruit/Adafruit LIS3DH@^1.2.4 https://github.com/lewisxhe/SensorLib#27fd0f721e20cd09e1f81383f0ba58a54fe84a17 - adafruit/Adafruit LSM6DS@^4.7.2 \ No newline at end of file + adafruit/Adafruit LSM6DS@^4.7.2 From 178877f2d9eccd7a046c142b6abee5d08ba9a817 Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Sat, 13 Apr 2024 00:18:36 +1200 Subject: [PATCH 430/472] Enable T-Echo touch button by default (#3604) Co-authored-by: Ben Meadors --- src/mesh/NodeDB.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index fb2b79048..ea0a27992 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -346,6 +346,9 @@ void NodeDB::installDefaultModuleConfig() moduleConfig.external_notification.alert_message = true; moduleConfig.external_notification.output_ms = 100; moduleConfig.external_notification.active = true; +#endif +#ifdef TTGO_T_ECHO + config.display.wake_on_tap_or_motion = true; // Enable touch button for screen-on / refresh #endif moduleConfig.has_canned_message = true; From 8fd32f34525613448f17f962cd6e00f84b53a59f Mon Sep 17 00:00:00 2001 From: Oliver Seiler Date: Sat, 13 Apr 2024 00:19:48 +1200 Subject: [PATCH 431/472] enable USB CDC (#3597) --- boards/tbeam-s3-core.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/boards/tbeam-s3-core.json b/boards/tbeam-s3-core.json index 7bda2e5a0..8d2c3eed6 100644 --- a/boards/tbeam-s3-core.json +++ b/boards/tbeam-s3-core.json @@ -8,7 +8,7 @@ "-DBOARD_HAS_PSRAM", "-DLILYGO_TBEAM_S3_CORE", "-DARDUINO_USB_CDC_ON_BOOT=1", - "-DARDUINO_USB_MODE=0", + "-DARDUINO_USB_MODE=1", "-DARDUINO_RUNNING_CORE=1", "-DARDUINO_EVENT_RUNNING_CORE=1" ], From 4c9646f7d97a063d366061adff9c9686da51f3e7 Mon Sep 17 00:00:00 2001 From: Manuel <71137295+mverch67@users.noreply.github.com> Date: Fri, 12 Apr 2024 17:01:24 +0200 Subject: [PATCH 432/472] fix: device sleep (part 1) (#3590) * fix sleep part 1 * always show wakeup reason in debug log * fix screen turn on issue * avoid unnecessary reboot when entering light sleep * set DIO1 based on radio type --------- Co-authored-by: Ben Meadors --- src/PowerFSM.cpp | 23 +++++++------- src/detect/LoRaRadioType.h | 5 ++++ src/main.cpp | 11 +++++++ src/sleep.cpp | 61 +++++++++++++++++++++++++++++--------- 4 files changed, 76 insertions(+), 24 deletions(-) create mode 100644 src/detect/LoRaRadioType.h diff --git a/src/PowerFSM.cpp b/src/PowerFSM.cpp index 0002a62b4..a6b2aea27 100644 --- a/src/PowerFSM.cpp +++ b/src/PowerFSM.cpp @@ -102,18 +102,21 @@ static void lsIdle() powerFSM.trigger(EVENT_SERIAL_CONNECTED); break; - case ESP_SLEEP_WAKEUP_GPIO: - // GPIO wakeup is now used for all ESP32 devices during light sleep - powerFSM.trigger(EVENT_PRESS); - break; - default: - // We woke for some other reason (device interrupt?) - LOG_INFO("wakeCause2 %d\n", wakeCause2); + // We woke for some other reason (button press, device IRQ interrupt) - // Let the NB state handle the IRQ (and that state will handle stuff like IRQs etc) - // we lie and say "wake timer" because the interrupt will be handled by the regular IRQ code - powerFSM.trigger(EVENT_WAKE_TIMER); +#ifdef BUTTON_PIN + bool pressed = !digitalRead(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN); +#else + bool pressed = false; +#endif + if (pressed) { // If we woke because of press, instead generate a PRESS event. + powerFSM.trigger(EVENT_PRESS); + } else { + // Otherwise let the NB state handle the IRQ (and that state will handle stuff like IRQs etc) + // we lie and say "wake timer" because the interrupt will be handled by the regular IRQ code + powerFSM.trigger(EVENT_WAKE_TIMER); + } break; } } else { diff --git a/src/detect/LoRaRadioType.h b/src/detect/LoRaRadioType.h new file mode 100644 index 000000000..eadd92e64 --- /dev/null +++ b/src/detect/LoRaRadioType.h @@ -0,0 +1,5 @@ +#pragma once + +enum LoRaRadioType { NO_RADIO, STM32WLx_RADIO, SIM_RADIO, RF95_RADIO, SX1262_RADIO, SX1268_RADIO, LLCC68_RADIO, SX1280_RADIO }; + +extern LoRaRadioType radioType; \ No newline at end of file diff --git a/src/main.cpp b/src/main.cpp index 0f2ef7e67..32ac91412 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -69,6 +69,7 @@ NRF52Bluetooth *nrf52Bluetooth; #include "SX1262Interface.h" #include "SX1268Interface.h" #include "SX1280Interface.h" +#include "detect/LoRaRadioType.h" #ifdef ARCH_STM32WL #include "STM32WLE5JCInterface.h" @@ -142,6 +143,9 @@ ATECCX08A atecc; Adafruit_DRV2605 drv; #endif +// Global LoRa radio type +LoRaRadioType radioType = NO_RADIO; + bool isVibrating = false; bool eink_found = true; @@ -793,6 +797,7 @@ void setup() rIf = NULL; } else { LOG_INFO("STM32WL Radio init succeeded, using STM32WL radio\n"); + radioType = STM32WLx_RADIO; } } #endif @@ -806,6 +811,7 @@ void setup() rIf = NULL; } else { LOG_INFO("Using SIMULATED radio!\n"); + radioType = SIM_RADIO; } } #endif @@ -819,6 +825,7 @@ void setup() rIf = NULL; } else { LOG_INFO("RF95 Radio init succeeded, using RF95 radio\n"); + radioType = RF95_RADIO; } } #endif @@ -832,6 +839,7 @@ void setup() rIf = NULL; } else { LOG_INFO("SX1262 Radio init succeeded, using SX1262 radio\n"); + radioType = SX1262_RADIO; } } #endif @@ -845,6 +853,7 @@ void setup() rIf = NULL; } else { LOG_INFO("SX1268 Radio init succeeded, using SX1268 radio\n"); + radioType = SX1268_RADIO; } } #endif @@ -858,6 +867,7 @@ void setup() rIf = NULL; } else { LOG_INFO("LLCC68 Radio init succeeded, using LLCC68 radio\n"); + radioType = LLCC68_RADIO; } } #endif @@ -871,6 +881,7 @@ void setup() rIf = NULL; } else { LOG_INFO("SX1280 Radio init succeeded, using SX1280 radio\n"); + radioType = SX1280_RADIO; } } #endif diff --git a/src/sleep.cpp b/src/sleep.cpp index 7ed264183..fdfaf5e35 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -8,6 +8,7 @@ #include "MeshRadio.h" #include "MeshService.h" #include "NodeDB.h" +#include "detect/LoRaRadioType.h" #include "error.h" #include "main.h" #include "sleep.h" @@ -153,7 +154,7 @@ void initDeepSleep() // If waking from sleep, release any and all RTC GPIOs if (wakeCause != ESP_SLEEP_WAKEUP_UNDEFINED) { LOG_DEBUG("Disabling any holds on RTC IO pads\n"); - for (uint8_t i = 0; i <= 45; i++) { + for (uint8_t i = 0; i <= GPIO_NUM_MAX; i++) { if (rtc_gpio_is_valid_gpio((gpio_num_t)i)) rtc_gpio_hold_dis((gpio_num_t)i); } @@ -360,19 +361,23 @@ esp_sleep_wakeup_cause_t doLightSleep(uint64_t sleepMsec) // FIXME, use a more r #endif auto res = esp_sleep_enable_gpio_wakeup(); if (res != ESP_OK) { - LOG_DEBUG("esp_sleep_enable_gpio_wakeup result %d\n", res); + LOG_ERROR("esp_sleep_enable_gpio_wakeup result %d\n", res); } assert(res == ESP_OK); res = esp_sleep_enable_timer_wakeup(sleepUsec); if (res != ESP_OK) { - LOG_DEBUG("esp_sleep_enable_timer_wakeup result %d\n", res); + LOG_ERROR("esp_sleep_enable_timer_wakeup result %d\n", res); } assert(res == ESP_OK); + + console->flush(); res = esp_light_sleep_start(); if (res != ESP_OK) { - LOG_DEBUG("esp_light_sleep_start result %d\n", res); + LOG_ERROR("esp_light_sleep_start result %d\n", res); } - assert(res == ESP_OK); + // commented out because it's not that crucial; + // if it sporadically happens the node will go into light sleep during the next round + // assert(res == ESP_OK); #ifdef BUTTON_PIN // Disable wake-on-button interrupt. Re-attach normal button-interrupts @@ -380,13 +385,27 @@ esp_sleep_wakeup_cause_t doLightSleep(uint64_t sleepMsec) // FIXME, use a more r buttonThread->attachButtonInterrupts(); #endif +#if !defined(SOC_PM_SUPPORT_EXT_WAKEUP) && defined(LORA_DIO1) && (LORA_DIO1 != RADIOLIB_NC) + if (radioType != RF95_RADIO) { + gpio_wakeup_disable((gpio_num_t)LORA_DIO1); + } +#endif +#if defined(RF95_IRQ) && (RF95_IRQ != RADIOLIB_NC) + if (radioType == RF95_RADIO) { + gpio_wakeup_disable((gpio_num_t)RF95_IRQ); + } +#endif + esp_sleep_wakeup_cause_t cause = esp_sleep_get_wakeup_cause(); #ifdef BUTTON_PIN if (cause == ESP_SLEEP_WAKEUP_GPIO) { LOG_INFO("Exit light sleep gpio: btn=%d\n", !digitalRead(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN)); - } + } else #endif + { + LOG_INFO("Exit light sleep cause: %d\n", cause); + } return cause; } @@ -428,20 +447,34 @@ bool shouldLoraWake(uint32_t msecToWake) void enableLoraInterrupt() { #if SOC_PM_SUPPORT_EXT_WAKEUP && defined(LORA_DIO1) && (LORA_DIO1 != RADIOLIB_NC) - rtc_gpio_pulldown_en((gpio_num_t)LORA_DIO1); + gpio_pulldown_en((gpio_num_t)LORA_DIO1); #if defined(LORA_RESET) && (LORA_RESET != RADIOLIB_NC) - rtc_gpio_pullup_en((gpio_num_t)LORA_RESET); + gpio_pullup_en((gpio_num_t)LORA_RESET); #endif #if defined(LORA_CS) && (LORA_CS != RADIOLIB_NC) - rtc_gpio_pullup_en((gpio_num_t)LORA_CS); + gpio_pullup_en((gpio_num_t)LORA_CS); #endif - // Setup deep sleep with wakeup by external source - esp_sleep_enable_ext0_wakeup((gpio_num_t)LORA_DIO1, RISING); + + if (rtc_gpio_is_valid_gpio((gpio_num_t)LORA_DIO1)) { + // Setup light/deep sleep with wakeup by external source + LOG_INFO("setup LORA_DIO1 (GPIO%02d) with wakeup by external source\n", LORA_DIO1); + esp_sleep_enable_ext0_wakeup((gpio_num_t)LORA_DIO1, HIGH); + } else { + LOG_INFO("setup LORA_DIO1 (GPIO%02d) with wakeup by gpio interrupt\n", LORA_DIO1); + gpio_wakeup_enable((gpio_num_t)LORA_DIO1, GPIO_INTR_HIGH_LEVEL); + } + #elif defined(LORA_DIO1) && (LORA_DIO1 != RADIOLIB_NC) - gpio_wakeup_enable((gpio_num_t)LORA_DIO1, GPIO_INTR_HIGH_LEVEL); // SX126x/SX128x interrupt, active high + if (radioType != RF95_RADIO) { + LOG_INFO("setup LORA_DIO1 (GPIO%02d) with wakeup by gpio interrupt\n", LORA_DIO1); + gpio_wakeup_enable((gpio_num_t)LORA_DIO1, GPIO_INTR_HIGH_LEVEL); // SX126x/SX128x interrupt, active high + } #endif -#ifdef RF95_IRQ - gpio_wakeup_enable((gpio_num_t)RF95_IRQ, GPIO_INTR_HIGH_LEVEL); // RF95 interrupt, active high +#if defined(RF95_IRQ) && (RF95_IRQ != RADIOLIB_NC) + if (radioType == RF95_RADIO) { + LOG_INFO("setup RF95_IRQ (GPIO%02d) with wakeup by gpio interrupt\n", RF95_IRQ); + gpio_wakeup_enable((gpio_num_t)RF95_IRQ, GPIO_INTR_HIGH_LEVEL); // RF95 interrupt, active high + } #endif } #endif From 2c4db163364893becd37d6be48f40773eb2b51c0 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 12 Apr 2024 10:49:14 -0500 Subject: [PATCH 433/472] TinyGPSAltitude support for negative altitude (#3605) --- platformio.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/platformio.ini b/platformio.ini index 27f9cf546..c5cbaf908 100644 --- a/platformio.ini +++ b/platformio.ini @@ -78,7 +78,7 @@ lib_deps = https://github.com/meshtastic/esp8266-oled-ssd1306.git#ee628ee6c9588d4c56c9e3da35f0fc9448ad54a8 ; ESP8266_SSD1306 mathertel/OneButton@^2.5.0 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 - https://github.com/meshtastic/TinyGPSPlus.git#f9f4fef2183514aa52be91d714c1455dd6f26e45 + https://github.com/meshtastic/TinyGPSPlus.git#bc14cc3146b33e295fc845026289a472004d48dc https://github.com/meshtastic/ArduinoThread.git#1ae8778c85d0a2a729f989e0b1e7d7c4dc84eef0 nanopb/Nanopb@^0.4.7 erriez/ErriezCRC32@^1.0.1 @@ -132,4 +132,4 @@ lib_deps = adafruit/Adafruit MPU6050@^2.2.4 adafruit/Adafruit LIS3DH@^1.2.4 https://github.com/lewisxhe/SensorLib#27fd0f721e20cd09e1f81383f0ba58a54fe84a17 - adafruit/Adafruit LSM6DS@^4.7.2 + adafruit/Adafruit LSM6DS@^4.7.2 \ No newline at end of file From 917b739e6294cb9c081877fde9d2379703021ad7 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Fri, 12 Apr 2024 11:29:08 -0500 Subject: [PATCH 434/472] Update TinyGPS version to un-derped commit --- platformio.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/platformio.ini b/platformio.ini index c5cbaf908..e28b7424d 100644 --- a/platformio.ini +++ b/platformio.ini @@ -78,7 +78,7 @@ lib_deps = https://github.com/meshtastic/esp8266-oled-ssd1306.git#ee628ee6c9588d4c56c9e3da35f0fc9448ad54a8 ; ESP8266_SSD1306 mathertel/OneButton@^2.5.0 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 - https://github.com/meshtastic/TinyGPSPlus.git#bc14cc3146b33e295fc845026289a472004d48dc + https://github.com/meshtastic/TinyGPSPlus.git#f5b67909745c44590048594727865b3e9b055014 https://github.com/meshtastic/ArduinoThread.git#1ae8778c85d0a2a729f989e0b1e7d7c4dc84eef0 nanopb/Nanopb@^0.4.7 erriez/ErriezCRC32@^1.0.1 @@ -132,4 +132,4 @@ lib_deps = adafruit/Adafruit MPU6050@^2.2.4 adafruit/Adafruit LIS3DH@^1.2.4 https://github.com/lewisxhe/SensorLib#27fd0f721e20cd09e1f81383f0ba58a54fe84a17 - adafruit/Adafruit LSM6DS@^4.7.2 \ No newline at end of file + adafruit/Adafruit LSM6DS@^4.7.2 From b4009f9f2f6245cbdb5e93cb1163403ade3d3693 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 12 Apr 2024 11:49:35 -0500 Subject: [PATCH 435/472] New fixed copy-pasted more corrector hash --- platformio.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/platformio.ini b/platformio.ini index e28b7424d..a1082a84a 100644 --- a/platformio.ini +++ b/platformio.ini @@ -78,7 +78,7 @@ lib_deps = https://github.com/meshtastic/esp8266-oled-ssd1306.git#ee628ee6c9588d4c56c9e3da35f0fc9448ad54a8 ; ESP8266_SSD1306 mathertel/OneButton@^2.5.0 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 - https://github.com/meshtastic/TinyGPSPlus.git#f5b67909745c44590048594727865b3e9b055014 + https://github.com/meshtastic/TinyGPSPlus.git#964f75a72cccd6b53cd74e4add1f7a42c6f7344d https://github.com/meshtastic/ArduinoThread.git#1ae8778c85d0a2a729f989e0b1e7d7c4dc84eef0 nanopb/Nanopb@^0.4.7 erriez/ErriezCRC32@^1.0.1 @@ -132,4 +132,4 @@ lib_deps = adafruit/Adafruit MPU6050@^2.2.4 adafruit/Adafruit LIS3DH@^1.2.4 https://github.com/lewisxhe/SensorLib#27fd0f721e20cd09e1f81383f0ba58a54fe84a17 - adafruit/Adafruit LSM6DS@^4.7.2 + adafruit/Adafruit LSM6DS@^4.7.2 \ No newline at end of file From 11adfe05cea06ed21b781e53095cc498aaa5253e Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Fri, 12 Apr 2024 14:06:05 -0500 Subject: [PATCH 436/472] Drop unishox2 functions from Router (#3606) --- src/mesh/Router.cpp | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp index 266c4f78d..3fa933bb1 100644 --- a/src/mesh/Router.cpp +++ b/src/mesh/Router.cpp @@ -8,9 +8,6 @@ #include "main.h" #include "mesh-pb-constants.h" #include "modules/RoutingModule.h" -extern "C" { -#include "mesh/compression/unishox2.h" -} #if !MESHTASTIC_EXCLUDE_MQTT #include "mqtt/MQTT.h" #endif @@ -332,6 +329,7 @@ bool perhapsDecode(meshtastic_MeshPacket *p) p->which_payload_variant = meshtastic_MeshPacket_decoded_tag; // change type to decoded p->channel = chIndex; // change to store the index instead of the hash + /* Not actually ever used. // Decompress if needed. jm if (p->decoded.portnum == meshtastic_PortNum_TEXT_MESSAGE_COMPRESSED_APP) { // Decompress the payload @@ -349,7 +347,7 @@ bool perhapsDecode(meshtastic_MeshPacket *p) // Switch the port from PortNum_TEXT_MESSAGE_COMPRESSED_APP to PortNum_TEXT_MESSAGE_APP p->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_APP; - } + } */ printPacket("decoded message", p); return true; @@ -371,6 +369,7 @@ meshtastic_Routing_Error perhapsEncode(meshtastic_MeshPacket *p) if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) { size_t numbytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_Data_msg, &p->decoded); + /* Not actually used, so save the cycles // Only allow encryption on the text message app. // TODO: Allow modules to opt into compression. if (p->decoded.portnum == meshtastic_PortNum_TEXT_MESSAGE_APP) { @@ -404,7 +403,7 @@ meshtastic_Routing_Error perhapsEncode(meshtastic_MeshPacket *p) p->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_COMPRESSED_APP; } - } + } */ if (numbytes > MAX_RHPACKETLEN) return meshtastic_Routing_Error_TOO_LARGE; @@ -500,4 +499,4 @@ void Router::perhapsHandleReceived(meshtastic_MeshPacket *p) handleReceived(p); packetPool.release(p); -} \ No newline at end of file +} From 3f45c2d4f06b51c5d02f70d37524bf3bb2d1236f Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Fri, 12 Apr 2024 14:14:56 -0500 Subject: [PATCH 437/472] Fix another LOG_DEBUG message that should be LOG_ERROR (#3607) --- src/mesh/RadioLibInterface.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/mesh/RadioLibInterface.cpp b/src/mesh/RadioLibInterface.cpp index 3ad2abe23..fc1563ee3 100644 --- a/src/mesh/RadioLibInterface.cpp +++ b/src/mesh/RadioLibInterface.cpp @@ -319,7 +319,7 @@ void RadioLibInterface::handleReceiveInterrupt() // when this is called, we should be in receive mode - if we are not, just jump out instead of bombing. Possible Race // Condition? if (!isReceiving) { - LOG_DEBUG("*** WAS_ASSERT *** handleReceiveInterrupt called when not in receive mode\n"); + LOG_ERROR("handleReceiveInterrupt called when not in receive mode, which shouldn't happen.\n"); return; } @@ -414,4 +414,4 @@ void RadioLibInterface::startSend(meshtastic_MeshPacket *txp) // bits enableInterrupt(isrTxLevel0); } -} \ No newline at end of file +} From 2a6e26620e3976b23aba66da28e9d6034ae1362a Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 12 Apr 2024 20:17:25 -0500 Subject: [PATCH 438/472] Auto-favorite our node (#3609) --- src/mesh/PhoneAPI.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/mesh/PhoneAPI.cpp b/src/mesh/PhoneAPI.cpp index f2d2a6e9d..efbcc9558 100644 --- a/src/mesh/PhoneAPI.cpp +++ b/src/mesh/PhoneAPI.cpp @@ -430,6 +430,8 @@ bool PhoneAPI::available() auto nextNode = nodeDB->readNextMeshNode(readIndex); if (nextNode) { nodeInfoForPhone = TypeConversions::ConvertToNodeInfo(nextNode); + nodeInfoForPhone.is_favorite = + nodeInfoForPhone.is_favorite || nodeInfoForPhone.num == nodeDB->getNodeNum(); // Our node is always a favorite } } return true; // Always say we have something, because we might need to advance our state machine From f1a1834ee2c5572dc6ae97997d401567138ef875 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sat, 13 Apr 2024 16:14:15 -0500 Subject: [PATCH 439/472] Update portduino to include SPI and setSetial fixes (#3611) --- arch/portduino/portduino.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index 3c996741c..07151c4a3 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -1,6 +1,6 @@ ; The Portduino based sim environment on top of any host OS, all hardware will be simulated [portduino_base] -platform = https://github.com/meshtastic/platform-native.git#117acc5e7fcc2047e9ba1dc11789daea26fc36d2 +platform = https://github.com/meshtastic/platform-native.git#c95616208ffff4c8a36d48df810a3f072cce3521 framework = arduino build_src_filter = From 0a246bfe9b93de6e7bd644ea8613b5af482de420 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 14 Apr 2024 00:29:42 -0500 Subject: [PATCH 440/472] Add more useful error output in radio interfaces (#3615) * Add more useful error output in radio interfaces * trunk --- src/mesh/RF95Interface.cpp | 12 ++++++++++++ src/mesh/SX126xInterface.cpp | 17 +++++++++++++---- src/mesh/SX128xInterface.cpp | 15 +++++++++++---- 3 files changed, 36 insertions(+), 8 deletions(-) diff --git a/src/mesh/RF95Interface.cpp b/src/mesh/RF95Interface.cpp index adc512ae2..b658a8ff6 100644 --- a/src/mesh/RF95Interface.cpp +++ b/src/mesh/RF95Interface.cpp @@ -128,12 +128,18 @@ bool RF95Interface::reconfigure() RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING); err = lora->setSyncWord(syncWord); + if (err != RADIOLIB_ERR_NONE) + LOG_ERROR("Radiolib error %d when attempting RF95 setSyncWord!\n", err); assert(err == RADIOLIB_ERR_NONE); err = lora->setCurrentLimit(currentLimit); + if (err != RADIOLIB_ERR_NONE) + LOG_ERROR("Radiolib error %d when attempting RF95 setCurrentLimit!\n", err); assert(err == RADIOLIB_ERR_NONE); err = lora->setPreambleLength(preambleLength); + if (err != RADIOLIB_ERR_NONE) + LOG_ERROR("Radiolib error %d when attempting RF95 setPreambleLength!\n", err); assert(err == RADIOLIB_ERR_NONE); err = lora->setFrequency(getFreq()); @@ -164,6 +170,8 @@ void RF95Interface::addReceiveMetadata(meshtastic_MeshPacket *mp) void RF95Interface::setStandby() { int err = lora->standby(); + if (err != RADIOLIB_ERR_NONE) + LOG_ERROR("Radiolib error %d when attempting RF95 standby!\n", err); assert(err == RADIOLIB_ERR_NONE); isReceiving = false; // If we were receiving, not any more @@ -185,6 +193,8 @@ void RF95Interface::startReceive() setTransmitEnable(false); setStandby(); int err = lora->startReceive(); + if (err != RADIOLIB_ERR_NONE) + LOG_ERROR("Radiolib error %d when attempting RF95 startReceive!\n", err); assert(err == RADIOLIB_ERR_NONE); isReceiving = true; @@ -205,6 +215,8 @@ bool RF95Interface::isChannelActive() // LOG_DEBUG("Channel is busy!\n"); return true; } + if (result != RADIOLIB_ERR_WRONG_MODEM) + LOG_ERROR("Radiolib error %d when attempting RF95 isChannelActive!\n", result); assert(result != RADIOLIB_ERR_WRONG_MODEM); // LOG_DEBUG("Channel is free!\n"); diff --git a/src/mesh/SX126xInterface.cpp b/src/mesh/SX126xInterface.cpp index 104d0a5ed..0690f9e96 100644 --- a/src/mesh/SX126xInterface.cpp +++ b/src/mesh/SX126xInterface.cpp @@ -181,12 +181,18 @@ template bool SX126xInterface::reconfigure() RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING); err = lora.setSyncWord(syncWord); + if (err != RADIOLIB_ERR_NONE) + LOG_ERROR("Radiolib error %d when attempting SX126X setSyncWord!\n", err); assert(err == RADIOLIB_ERR_NONE); err = lora.setCurrentLimit(currentLimit); + if (err != RADIOLIB_ERR_NONE) + LOG_ERROR("Radiolib error %d when attempting SX126X setCurrentLimit!\n", err); assert(err == RADIOLIB_ERR_NONE); err = lora.setPreambleLength(preambleLength); + if (err != RADIOLIB_ERR_NONE) + LOG_ERROR("Radiolib error %d when attempting SX126X setPreambleLength!\n", err); assert(err == RADIOLIB_ERR_NONE); err = lora.setFrequency(getFreq()); @@ -197,6 +203,8 @@ template bool SX126xInterface::reconfigure() power = SX126X_MAX_POWER; err = lora.setOutputPower(power); + if (err != RADIOLIB_ERR_NONE) + LOG_ERROR("Radiolib error %d when attempting SX126X setOutputPower!\n", err); assert(err == RADIOLIB_ERR_NONE); startReceive(); // restart receiving @@ -215,10 +223,8 @@ template void SX126xInterface::setStandby() int err = lora.standby(); - if (err != RADIOLIB_ERR_NONE) { + if (err != RADIOLIB_ERR_NONE) LOG_DEBUG("SX126x standby failed with error %d\n", err); - } - assert(err == RADIOLIB_ERR_NONE); isReceiving = false; // If we were receiving, not any more @@ -260,6 +266,8 @@ template void SX126xInterface::startReceive() int err = lora.startReceiveDutyCycleAuto(preambleLength, 8, RADIOLIB_SX126X_IRQ_RX_DEFAULT | RADIOLIB_SX126X_IRQ_PREAMBLE_DETECTED | RADIOLIB_SX126X_IRQ_HEADER_VALID); + if (err != RADIOLIB_ERR_NONE) + LOG_ERROR("Radiolib error %d when attempting SX126X startReceiveDutyCycleAuto!\n", err); assert(err == RADIOLIB_ERR_NONE); isReceiving = true; @@ -279,7 +287,8 @@ template bool SX126xInterface::isChannelActive() result = lora.scanChannel(); if (result == RADIOLIB_LORA_DETECTED) return true; - + if (result != RADIOLIB_ERR_WRONG_MODEM) + LOG_ERROR("Radiolib error %d when attempting SX126X scanChannel!\n", result); assert(result != RADIOLIB_ERR_WRONG_MODEM); return false; diff --git a/src/mesh/SX128xInterface.cpp b/src/mesh/SX128xInterface.cpp index 45325f339..564b80494 100644 --- a/src/mesh/SX128xInterface.cpp +++ b/src/mesh/SX128xInterface.cpp @@ -126,9 +126,13 @@ template bool SX128xInterface::reconfigure() RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING); err = lora.setSyncWord(syncWord); + if (err != RADIOLIB_ERR_NONE) + LOG_ERROR("Radiolib error %d when attempting SX128X setSyncWord!\n", err); assert(err == RADIOLIB_ERR_NONE); err = lora.setPreambleLength(preambleLength); + if (err != RADIOLIB_ERR_NONE) + LOG_ERROR("Radiolib error %d when attempting SX128X setPreambleLength!\n", err); assert(err == RADIOLIB_ERR_NONE); err = lora.setFrequency(getFreq()); @@ -139,6 +143,8 @@ template bool SX128xInterface::reconfigure() power = SX128X_MAX_POWER; err = lora.setOutputPower(power); + if (err != RADIOLIB_ERR_NONE) + LOG_ERROR("Radiolib error %d when attempting SX128X setOutputPower!\n", err); assert(err == RADIOLIB_ERR_NONE); startReceive(); // restart receiving @@ -162,10 +168,8 @@ template void SX128xInterface::setStandby() int err = lora.standby(); - if (err != RADIOLIB_ERR_NONE) { + if (err != RADIOLIB_ERR_NONE) LOG_ERROR("SX128x standby failed with error %d\n", err); - } - assert(err == RADIOLIB_ERR_NONE); #if ARCH_PORTDUINO if (settingsMap[rxen] != RADIOLIB_NC) { @@ -255,6 +259,8 @@ template void SX128xInterface::startReceive() lora.startReceive(RADIOLIB_SX128X_RX_TIMEOUT_INF, RADIOLIB_SX128X_IRQ_RX_DEFAULT | RADIOLIB_SX128X_IRQ_PREAMBLE_DETECTED | RADIOLIB_SX128X_IRQ_HEADER_VALID); + if (err != RADIOLIB_ERR_NONE) + LOG_ERROR("Radiolib error %d when attempting SX128X startReceive!\n", err); assert(err == RADIOLIB_ERR_NONE); isReceiving = true; @@ -274,7 +280,8 @@ template bool SX128xInterface::isChannelActive() result = lora.scanChannel(); if (result == RADIOLIB_LORA_DETECTED) return true; - + if (result != RADIOLIB_ERR_WRONG_MODEM) + LOG_ERROR("Radiolib error %d when attempting SX128X scanChannel!\n", result); assert(result != RADIOLIB_ERR_WRONG_MODEM); return false; From ec3971bce5a3b65a5c2593dae8c8ab5b25d0f451 Mon Sep 17 00:00:00 2001 From: Manuel <71137295+mverch67@users.noreply.github.com> Date: Sun, 14 Apr 2024 15:11:22 +0200 Subject: [PATCH 441/472] fix upDown ISR (#3612) --- src/input/UpDownInterruptBase.cpp | 49 +++++++++++++++++++++---------- src/input/UpDownInterruptBase.h | 9 +++++- 2 files changed, 41 insertions(+), 17 deletions(-) diff --git a/src/input/UpDownInterruptBase.cpp b/src/input/UpDownInterruptBase.cpp index ecc3b944a..b1f83c56b 100644 --- a/src/input/UpDownInterruptBase.cpp +++ b/src/input/UpDownInterruptBase.cpp @@ -1,7 +1,7 @@ #include "UpDownInterruptBase.h" #include "configuration.h" -UpDownInterruptBase::UpDownInterruptBase(const char *name) +UpDownInterruptBase::UpDownInterruptBase(const char *name) : concurrency::OSThread(name) { this->_originName = name; } @@ -24,31 +24,48 @@ void UpDownInterruptBase::init(uint8_t pinDown, uint8_t pinUp, uint8_t pinPress, attachInterrupt(this->_pinUp, onIntUp, RISING); LOG_DEBUG("Up/down/press GPIO initialized (%d, %d, %d)\n", this->_pinUp, this->_pinDown, pinPress); + + this->setInterval(100); +} + +int32_t UpDownInterruptBase::runOnce() +{ + InputEvent e; + e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE; + + if (this->action == UPDOWN_ACTION_PRESSED) { + LOG_DEBUG("GPIO event Press\n"); + e.inputEvent = this->_eventPressed; + } else if (this->action == UPDOWN_ACTION_UP) { + LOG_DEBUG("GPIO event Up\n"); + e.inputEvent = this->_eventUp; + } else if (this->action == UPDOWN_ACTION_DOWN) { + LOG_DEBUG("GPIO event Down\n"); + e.inputEvent = this->_eventDown; + } + + if (e.inputEvent != meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE) { + e.source = this->_originName; + e.kbchar = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE; + this->notifyObservers(&e); + } + + this->action = UPDOWN_ACTION_NONE; + + return 100; } void UpDownInterruptBase::intPressHandler() { - InputEvent e; - e.source = this->_originName; - LOG_DEBUG("GPIO event Press\n"); - e.inputEvent = this->_eventPressed; - this->notifyObservers(&e); + this->action = UPDOWN_ACTION_PRESSED; } void UpDownInterruptBase::intDownHandler() { - InputEvent e; - e.source = this->_originName; - LOG_DEBUG("GPIO event Down\n"); - e.inputEvent = this->_eventDown; - this->notifyObservers(&e); + this->action = UPDOWN_ACTION_DOWN; } void UpDownInterruptBase::intUpHandler() { - InputEvent e; - e.source = this->_originName; - LOG_DEBUG("GPIO event Up\n"); - e.inputEvent = this->_eventUp; - this->notifyObservers(&e); + this->action = UPDOWN_ACTION_UP; } diff --git a/src/input/UpDownInterruptBase.h b/src/input/UpDownInterruptBase.h index afa64d28d..7060a0d80 100644 --- a/src/input/UpDownInterruptBase.h +++ b/src/input/UpDownInterruptBase.h @@ -3,7 +3,7 @@ #include "InputBroker.h" #include "mesh/NodeDB.h" -class UpDownInterruptBase : public Observable +class UpDownInterruptBase : public Observable, public concurrency::OSThread { public: explicit UpDownInterruptBase(const char *name); @@ -13,6 +13,13 @@ class UpDownInterruptBase : public Observable void intDownHandler(); void intUpHandler(); + int32_t runOnce() override; + + protected: + enum UpDownInterruptBaseActionType { UPDOWN_ACTION_NONE, UPDOWN_ACTION_PRESSED, UPDOWN_ACTION_UP, UPDOWN_ACTION_DOWN }; + + volatile UpDownInterruptBaseActionType action = UPDOWN_ACTION_NONE; + private: uint8_t _pinDown = 0; uint8_t _pinUp = 0; From 5047468d9fee8aad3913514369f904ce6ef6fa85 Mon Sep 17 00:00:00 2001 From: Manuel <71137295+mverch67@users.noreply.github.com> Date: Sun, 14 Apr 2024 16:11:27 +0200 Subject: [PATCH 442/472] fix/enhancement: TFT device powersave (part 3) (#3600) * fix: device TFT powersave (part 3) * trunk fmt * trunk fmt * undo bluetooth deinit from #3596 * revert code for heltec tracker --------- Co-authored-by: Ben Meadors --- src/PowerFSM.cpp | 6 +++++- src/graphics/TFTDisplay.cpp | 13 +++++++++---- src/mesh/NodeDB.cpp | 6 ++++++ src/nimble/NimbleBluetooth.cpp | 4 ++-- src/sleep.cpp | 7 +++++++ variants/t-deck/variant.h | 2 ++ variants/t-watch-s3/platformio.ini | 2 -- variants/t-watch-s3/variant.h | 2 ++ 8 files changed, 33 insertions(+), 9 deletions(-) diff --git a/src/PowerFSM.cpp b/src/PowerFSM.cpp index a6b2aea27..ac48e664c 100644 --- a/src/PowerFSM.cpp +++ b/src/PowerFSM.cpp @@ -17,6 +17,10 @@ #include "sleep.h" #include "target_specific.h" +#ifndef SLEEP_TIME +#define SLEEP_TIME 30 +#endif + /// Should we behave as if we have AC power now? static bool isPowered() { @@ -81,7 +85,7 @@ static void lsIdle() // If some other service would stall sleep, don't let sleep happen yet if (doPreflightSleep()) { // Briefly come out of sleep long enough to blink the led once every few seconds - uint32_t sleepTime = 30; + uint32_t sleepTime = SLEEP_TIME; setLed(false); // Never leave led on while in light sleep esp_sleep_source_t wakeCause2 = doLightSleep(sleepTime * 1000LL); diff --git a/src/graphics/TFTDisplay.cpp b/src/graphics/TFTDisplay.cpp index 8de415185..fb64553ef 100644 --- a/src/graphics/TFTDisplay.cpp +++ b/src/graphics/TFTDisplay.cpp @@ -561,8 +561,10 @@ void TFTDisplay::sendCommand(uint8_t com) #elif defined(ST7735_BL_V05) pinMode(ST7735_BL_V05, OUTPUT); digitalWrite(ST7735_BL_V05, TFT_BACKLIGHT_ON); -#endif -#if defined(TFT_BL) && defined(TFT_BACKLIGHT_ON) +#elif !defined(RAK14014) && !defined(M5STACK) && !defined(UNPHONE) + tft->wakeup(); + tft->powerSaveOff(); +#elif defined(TFT_BL) && defined(TFT_BACKLIGHT_ON) digitalWrite(TFT_BL, TFT_BACKLIGHT_ON); #endif @@ -596,10 +598,13 @@ void TFTDisplay::sendCommand(uint8_t com) #elif defined(ST7735_BL_V05) pinMode(ST7735_BL_V05, OUTPUT); digitalWrite(ST7735_BL_V05, !TFT_BACKLIGHT_ON); -#endif -#if defined(TFT_BL) && defined(TFT_BACKLIGHT_ON) +#elif !defined(RAK14014) && !defined(M5STACK) && !defined(UNPHONE) + tft->sleep(); + tft->powerSaveOn(); +#elif defined(TFT_BL) && defined(TFT_BACKLIGHT_ON) digitalWrite(TFT_BL, !TFT_BACKLIGHT_ON); #endif + #ifdef VTFT_CTRL_V03 digitalWrite(VTFT_CTRL_V03, HIGH); #endif diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index ea0a27992..921935593 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -311,6 +311,12 @@ void NodeDB::initConfigIntervals() config.power.wait_bluetooth_secs = default_wait_bluetooth_secs; config.display.screen_on_secs = default_screen_on_secs; + +#if defined(T_WATCH_S3) || defined(T_DECK) + config.power.is_power_saving = true; + config.display.screen_on_secs = 30; + config.power.wait_bluetooth_secs = 30; +#endif } void NodeDB::installDefaultModuleConfig() diff --git a/src/nimble/NimbleBluetooth.cpp b/src/nimble/NimbleBluetooth.cpp index 42b296e45..0b91bf44f 100644 --- a/src/nimble/NimbleBluetooth.cpp +++ b/src/nimble/NimbleBluetooth.cpp @@ -113,8 +113,8 @@ void NimbleBluetooth::shutdown() pAdvertising->reset(); pAdvertising->stop(); -#if defined(ARCH_ESP32) - // Saving of ~1mA for esp32-s3 and 0.1mA for esp32 +#if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0) + // Saving of ~1mA // Probably applicable to other ESP32 boards - unverified NimBLEDevice::deinit(); #endif diff --git a/src/sleep.cpp b/src/sleep.cpp index fdfaf5e35..6abe535d7 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -352,6 +352,9 @@ esp_sleep_wakeup_cause_t doLightSleep(uint64_t sleepMsec) // FIXME, use a more r gpio_wakeup_enable(pin, GPIO_INTR_LOW_LEVEL); esp_sleep_enable_gpio_wakeup(); +#endif +#ifdef T_WATCH_S3 + gpio_wakeup_enable((gpio_num_t)SCREEN_TOUCH_INT, GPIO_INTR_LOW_LEVEL); #endif enableLoraInterrupt(); #ifdef PMU_IRQ @@ -385,6 +388,10 @@ esp_sleep_wakeup_cause_t doLightSleep(uint64_t sleepMsec) // FIXME, use a more r buttonThread->attachButtonInterrupts(); #endif +#ifdef T_WATCH_S3 + gpio_wakeup_disable((gpio_num_t)SCREEN_TOUCH_INT); +#endif + #if !defined(SOC_PM_SUPPORT_EXT_WAKEUP) && defined(LORA_DIO1) && (LORA_DIO1 != RADIOLIB_NC) if (radioType != RF95_RADIO) { gpio_wakeup_disable((gpio_num_t)LORA_DIO1); diff --git a/variants/t-deck/variant.h b/variants/t-deck/variant.h index 62ac0a373..09db198ec 100644 --- a/variants/t-deck/variant.h +++ b/variants/t-deck/variant.h @@ -24,6 +24,8 @@ #define TOUCH_I2C_PORT 0 #define TOUCH_SLAVE_ADDRESS 0x5D // GT911 +#define SLEEP_TIME 120 + #define BUTTON_PIN 0 // #define BUTTON_NEED_PULLUP diff --git a/variants/t-watch-s3/platformio.ini b/variants/t-watch-s3/platformio.ini index d03273ed4..5d5904b30 100644 --- a/variants/t-watch-s3/platformio.ini +++ b/variants/t-watch-s3/platformio.ini @@ -3,8 +3,6 @@ extends = esp32s3_base board = t-watch-s3 upload_protocol = esptool -upload_speed = 115200 -upload_port = /dev/tty.usbmodem3485188D636C1 build_flags = ${esp32_base.build_flags} -DT_WATCH_S3 diff --git a/variants/t-watch-s3/variant.h b/variants/t-watch-s3/variant.h index c66fac5ef..ad7e6b56b 100644 --- a/variants/t-watch-s3/variant.h +++ b/variants/t-watch-s3/variant.h @@ -25,6 +25,8 @@ #define TOUCH_I2C_PORT 1 #define TOUCH_SLAVE_ADDRESS 0x38 +#define SLEEP_TIME 180 + #define I2C_SDA1 39 // Used for capacitive touch #define I2C_SCL1 40 // Used for capacitive touch From 4f205718f01b9de456388a9fe84d80668de65a6a Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 14 Apr 2024 10:27:01 -0500 Subject: [PATCH 443/472] Device telemetry uptime in seconds (#3614) --- src/modules/Telemetry/DeviceTelemetry.cpp | 21 +++++++++------------ src/modules/Telemetry/DeviceTelemetry.h | 21 +++++++++++++++++++++ 2 files changed, 30 insertions(+), 12 deletions(-) diff --git a/src/modules/Telemetry/DeviceTelemetry.cpp b/src/modules/Telemetry/DeviceTelemetry.cpp index 2ae904b89..3529267cb 100644 --- a/src/modules/Telemetry/DeviceTelemetry.cpp +++ b/src/modules/Telemetry/DeviceTelemetry.cpp @@ -15,14 +15,14 @@ int32_t DeviceTelemetryModule::runOnce() { - uint32_t now = millis(); + refreshUptime(); if (((lastSentToMesh == 0) || - ((now - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.device_update_interval))) && + ((uptimeLastMs - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.device_update_interval))) && airTime->isTxAllowedChannelUtil(config.device.role != meshtastic_Config_DeviceConfig_Role_SENSOR) && airTime->isTxAllowedAirUtil() && config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER && config.device.role != meshtastic_Config_DeviceConfig_Role_CLIENT_HIDDEN) { sendTelemetry(); - lastSentToMesh = now; + lastSentToMesh = uptimeLastMs; } else if (service.isToPhoneQueueEmpty()) { // Just send to phone when it's not our time to send to mesh yet // Only send while queue is empty (phone assumed connected) @@ -68,16 +68,12 @@ meshtastic_Telemetry DeviceTelemetryModule::getDeviceTelemetry() t.time = getTime(); t.which_variant = meshtastic_Telemetry_device_metrics_tag; - t.variant.device_metrics.air_util_tx = airTime->utilizationTXPercent(); - if (powerStatus->getIsCharging()) { - t.variant.device_metrics.battery_level = MAGIC_USB_BATTERY_LEVEL; - } else { - t.variant.device_metrics.battery_level = powerStatus->getBatteryChargePercent(); - } - + t.variant.device_metrics.battery_level = + powerStatus->getIsCharging() ? MAGIC_USB_BATTERY_LEVEL : powerStatus->getBatteryChargePercent(); t.variant.device_metrics.channel_utilization = airTime->channelUtilizationPercent(); t.variant.device_metrics.voltage = powerStatus->getBatteryVoltageMv() / 1000.0; + t.variant.device_metrics.uptime_seconds = getUptimeSeconds(); return t; } @@ -85,9 +81,10 @@ meshtastic_Telemetry DeviceTelemetryModule::getDeviceTelemetry() bool DeviceTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly) { meshtastic_Telemetry telemetry = getDeviceTelemetry(); - LOG_INFO("(Sending): air_util_tx=%f, channel_utilization=%f, battery_level=%i, voltage=%f\n", + LOG_INFO("(Sending): air_util_tx=%f, channel_utilization=%f, battery_level=%i, voltage=%f, uptime=%i\n", telemetry.variant.device_metrics.air_util_tx, telemetry.variant.device_metrics.channel_utilization, - telemetry.variant.device_metrics.battery_level, telemetry.variant.device_metrics.voltage); + telemetry.variant.device_metrics.battery_level, telemetry.variant.device_metrics.voltage, + telemetry.variant.device_metrics.uptime_seconds); meshtastic_MeshPacket *p = allocDataProtobuf(telemetry); p->to = dest; diff --git a/src/modules/Telemetry/DeviceTelemetry.h b/src/modules/Telemetry/DeviceTelemetry.h index 81f83ce0a..5f4e761f9 100644 --- a/src/modules/Telemetry/DeviceTelemetry.h +++ b/src/modules/Telemetry/DeviceTelemetry.h @@ -12,6 +12,8 @@ class DeviceTelemetryModule : private concurrency::OSThread, public ProtobufModu : concurrency::OSThread("DeviceTelemetryModule"), ProtobufModule("DeviceTelemetry", meshtastic_PortNum_TELEMETRY_APP, &meshtastic_Telemetry_msg) { + uptimeWrapCount = 0; + uptimeLastMs = millis(); setIntervalFromNow(45 * 1000); // Wait until NodeInfo is sent } virtual bool wantUIFrame() { return false; } @@ -28,8 +30,27 @@ class DeviceTelemetryModule : private concurrency::OSThread, public ProtobufModu */ bool sendTelemetry(NodeNum dest = NODENUM_BROADCAST, bool phoneOnly = false); + /** + * Get the uptime in seconds + * Loses some accuracy after 49 days, but that's fine + */ + uint32_t getUptimeSeconds() { return (0xFFFFFFFF / 1000) * uptimeWrapCount + (uptimeLastMs / 1000); } + private: meshtastic_Telemetry getDeviceTelemetry(); uint32_t sendToPhoneIntervalMs = SECONDS_IN_MINUTE * 1000; // Send to phone every minute uint32_t lastSentToMesh = 0; + + void refreshUptime() + { + auto now = millis(); + // If we wrapped around (~49 days), increment the wrap count + if (now < uptimeLastMs) + uptimeWrapCount++; + + uptimeLastMs = now; + } + + uint32_t uptimeWrapCount; + uint32_t uptimeLastMs; }; From 1447148811ff49119dc01e588d60380c4c6809f4 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 14 Apr 2024 14:15:06 -0500 Subject: [PATCH 444/472] Make sure settingsStrings get initialized --- src/platform/portduino/PortduinoGlue.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index 72b2a3bc7..f686ef3dc 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -77,6 +77,10 @@ void portduinoSetup() gpioInit(); std::string gpioChipName = "gpiochip"; + settingsStrings[i2cdev] = ""; + settingsStrings[keyboardDevice] = ""; + settingsStrings[webserverrootpath] = ""; + settingsStrings[spidev] = ""; YAML::Node yamlConfig; @@ -280,4 +284,4 @@ int initGPIOPin(int pinNum, std::string gpioChipName) std::cout << "Warning, cannot claim pin " << gpio_name << (p ? p.__cxa_exception_type()->name() : "null") << std::endl; return ERRNO_DISABLED; } -} \ No newline at end of file +} From 00d4c011c7d901dea144ae452f0d419312bda164 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 14 Apr 2024 14:36:11 -0500 Subject: [PATCH 445/472] Fix sx126x error log logic --- src/mesh/SX126xInterface.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/mesh/SX126xInterface.cpp b/src/mesh/SX126xInterface.cpp index 0690f9e96..afaa13b7f 100644 --- a/src/mesh/SX126xInterface.cpp +++ b/src/mesh/SX126xInterface.cpp @@ -287,7 +287,7 @@ template bool SX126xInterface::isChannelActive() result = lora.scanChannel(); if (result == RADIOLIB_LORA_DETECTED) return true; - if (result != RADIOLIB_ERR_WRONG_MODEM) + if (result != RADIOLIB_CHANNEL_FREE) LOG_ERROR("Radiolib error %d when attempting SX126X scanChannel!\n", result); assert(result != RADIOLIB_ERR_WRONG_MODEM); From 5b52c31a76762eda5c1e7d61221e39c59cecdccc Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Sun, 14 Apr 2024 14:36:39 -0500 Subject: [PATCH 446/472] Fix HAS_WIRE logic in main --- src/main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main.cpp b/src/main.cpp index 32ac91412..587bcb56e 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -387,7 +387,7 @@ void setup() // We need to scan here to decide if we have a screen for nodeDB.init() and because power has been applied to // accessories auto i2cScanner = std::unique_ptr(new ScanI2CTwoWire()); -#ifdef HAS_WIRE +#if HAS_WIRE LOG_INFO("Scanning for i2c devices...\n"); #endif From 1d9754404163b9bed92d79da92d6019053f91127 Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Mon, 15 Apr 2024 23:50:42 +1200 Subject: [PATCH 447/472] Wireless Paper: Fix BLE after Lightsleep (#3629) * NimBLE deinit for deep-sleep only * Optionally disable blink during light-sleep * Advised to revert "blink disable" This reverts commit 66347ce19bb7e6ade64827a01b0ba834bff1e361. --- src/nimble/NimbleBluetooth.cpp | 8 ++++---- src/nimble/NimbleBluetooth.h | 1 + src/sleep.cpp | 6 ++++++ variants/heltec_wireless_paper/variant.h | 3 +++ variants/heltec_wireless_paper_v1/variant.h | 3 +++ 5 files changed, 17 insertions(+), 4 deletions(-) diff --git a/src/nimble/NimbleBluetooth.cpp b/src/nimble/NimbleBluetooth.cpp index 0b91bf44f..092aef470 100644 --- a/src/nimble/NimbleBluetooth.cpp +++ b/src/nimble/NimbleBluetooth.cpp @@ -112,12 +112,12 @@ void NimbleBluetooth::shutdown() NimBLEAdvertising *pAdvertising = NimBLEDevice::getAdvertising(); pAdvertising->reset(); pAdvertising->stop(); +} -#if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0) - // Saving of ~1mA - // Probably applicable to other ESP32 boards - unverified +// Extra power-saving on some devices +void NimbleBluetooth::deinit() +{ NimBLEDevice::deinit(); -#endif } bool NimbleBluetooth::isActive() diff --git a/src/nimble/NimbleBluetooth.h b/src/nimble/NimbleBluetooth.h index df2d3e45a..d1e347830 100644 --- a/src/nimble/NimbleBluetooth.h +++ b/src/nimble/NimbleBluetooth.h @@ -6,6 +6,7 @@ class NimbleBluetooth : BluetoothApi public: void setup(); void shutdown(); + void deinit(); void clearBonds(); bool isActive(); bool isConnected(); diff --git a/src/sleep.cpp b/src/sleep.cpp index 6abe535d7..860a676df 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -206,6 +206,12 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) // not using wifi yet, but once we are this is needed to shutoff the radio hw // esp_wifi_stop(); waitEnterSleep(skipPreflight); + +#ifdef NIMBLE_DEINIT_FOR_DEEPSLEEP + // Extra power saving on some devices + nimbleBluetooth->deinit(); +#endif + #ifdef ARCH_ESP32 if (shouldLoraWake(msecToWake)) { notifySleep.notifyObservers(NULL); diff --git a/variants/heltec_wireless_paper/variant.h b/variants/heltec_wireless_paper/variant.h index 29b8bbbd1..466925a2e 100644 --- a/variants/heltec_wireless_paper/variant.h +++ b/variants/heltec_wireless_paper/variant.h @@ -55,3 +55,6 @@ #define SX126X_DIO2_AS_RF_SWITCH #define SX126X_DIO3_TCXO_VOLTAGE 1.8 + +// Power management +#define NIMBLE_DEINIT_FOR_DEEPSLEEP // Required to reach manufacturers claim of 18uA diff --git a/variants/heltec_wireless_paper_v1/variant.h b/variants/heltec_wireless_paper_v1/variant.h index 29b8bbbd1..466925a2e 100644 --- a/variants/heltec_wireless_paper_v1/variant.h +++ b/variants/heltec_wireless_paper_v1/variant.h @@ -55,3 +55,6 @@ #define SX126X_DIO2_AS_RF_SWITCH #define SX126X_DIO3_TCXO_VOLTAGE 1.8 + +// Power management +#define NIMBLE_DEINIT_FOR_DEEPSLEEP // Required to reach manufacturers claim of 18uA From 2803fa964e337b58da26fec4f29f62c7338481a1 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Mon, 15 Apr 2024 07:22:05 -0500 Subject: [PATCH 448/472] Add LoadFileState to differentiate types of success / failures (#3625) --- src/mesh/NodeDB.cpp | 49 +++++++++++++--------- src/mesh/NodeDB.h | 16 ++++++- src/modules/CannedMessageModule.cpp | 6 +-- src/modules/ExternalNotificationModule.cpp | 4 +- src/modules/NeighborInfoModule.cpp | 4 +- 5 files changed, 52 insertions(+), 27 deletions(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 921935593..dce7e47af 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -551,12 +551,17 @@ static const char *moduleConfigFileName = "/prefs/module.proto"; static const char *channelFileName = "/prefs/channels.proto"; static const char *oemConfigFile = "/oem/oem.proto"; -/** Load a protobuf from a file, return true for success */ -bool NodeDB::loadProto(const char *filename, size_t protoSize, size_t objSize, const pb_msgdesc_t *fields, void *dest_struct) +/** Load a protobuf from a file, return LoadFileResult */ +LoadFileResult NodeDB::loadProto(const char *filename, size_t protoSize, size_t objSize, const pb_msgdesc_t *fields, + void *dest_struct) { - bool okay = false; + LoadFileResult state = LoadFileResult::OTHER_FAILURE; #ifdef FSCom - // static DeviceState scratch; We no longer read into a tempbuf because this structure is 15KB of valuable RAM + + if (!FSCom.exists(filename)) { + LOG_INFO("File %s not found\n", filename); + return LoadFileResult::NOT_FOUND; + } auto f = FSCom.open(filename, FILE_O_READ); @@ -564,30 +569,32 @@ bool NodeDB::loadProto(const char *filename, size_t protoSize, size_t objSize, c LOG_INFO("Loading %s\n", filename); pb_istream_t stream = {&readcb, &f, protoSize}; - // LOG_DEBUG("Preload channel name=%s\n", channelSettings.name); - memset(dest_struct, 0, objSize); if (!pb_decode(&stream, fields, dest_struct)) { LOG_ERROR("Error: can't decode protobuf %s\n", PB_GET_ERROR(&stream)); + state = LoadFileResult::DECODE_FAILED; } else { - okay = true; + LOG_INFO("Loaded %s successfully\n", filename); + state = LoadFileResult::SUCCESS; } - f.close(); } else { - LOG_INFO("No %s preferences found\n", filename); + LOG_ERROR("Could not open / read %s\n", filename); } #else LOG_ERROR("ERROR: Filesystem not implemented\n"); + state = LoadFileState::NO_FILESYSTEM; #endif - return okay; + return state; } void NodeDB::loadFromDisk() { // static DeviceState scratch; We no longer read into a tempbuf because this structure is 15KB of valuable RAM - if (!loadProto(prefFileName, sizeof(meshtastic_DeviceState) + MAX_NUM_NODES * sizeof(meshtastic_NodeInfo), - sizeof(meshtastic_DeviceState), &meshtastic_DeviceState_msg, &devicestate)) { + auto state = loadProto(prefFileName, sizeof(meshtastic_DeviceState) + MAX_NUM_NODES * sizeof(meshtastic_NodeInfo), + sizeof(meshtastic_DeviceState), &meshtastic_DeviceState_msg, &devicestate); + + if (state != LoadFileResult::SUCCESS) { installDefaultDeviceState(); // Our in RAM copy might now be corrupt } else { if (devicestate.version < DEVICESTATE_MIN_VER) { @@ -602,8 +609,9 @@ void NodeDB::loadFromDisk() } meshNodes->resize(MAX_NUM_NODES); - if (!loadProto(configFileName, meshtastic_LocalConfig_size, sizeof(meshtastic_LocalConfig), &meshtastic_LocalConfig_msg, - &config)) { + state = loadProto(configFileName, meshtastic_LocalConfig_size, sizeof(meshtastic_LocalConfig), &meshtastic_LocalConfig_msg, + &config); + if (state != LoadFileResult::SUCCESS) { installDefaultConfig(); // Our in RAM copy might now be corrupt } else { if (config.version < DEVICESTATE_MIN_VER) { @@ -614,8 +622,9 @@ void NodeDB::loadFromDisk() } } - if (!loadProto(moduleConfigFileName, meshtastic_LocalModuleConfig_size, sizeof(meshtastic_LocalModuleConfig), - &meshtastic_LocalModuleConfig_msg, &moduleConfig)) { + state = loadProto(moduleConfigFileName, meshtastic_LocalModuleConfig_size, sizeof(meshtastic_LocalModuleConfig), + &meshtastic_LocalModuleConfig_msg, &moduleConfig); + if (state != LoadFileResult::SUCCESS) { installDefaultModuleConfig(); // Our in RAM copy might now be corrupt } else { if (moduleConfig.version < DEVICESTATE_MIN_VER) { @@ -626,8 +635,9 @@ void NodeDB::loadFromDisk() } } - if (!loadProto(channelFileName, meshtastic_ChannelFile_size, sizeof(meshtastic_ChannelFile), &meshtastic_ChannelFile_msg, - &channelFile)) { + state = loadProto(channelFileName, meshtastic_ChannelFile_size, sizeof(meshtastic_ChannelFile), &meshtastic_ChannelFile_msg, + &channelFile); + if (state != LoadFileResult::SUCCESS) { installDefaultChannels(); // Our in RAM copy might now be corrupt } else { if (channelFile.version < DEVICESTATE_MIN_VER) { @@ -638,7 +648,8 @@ void NodeDB::loadFromDisk() } } - if (loadProto(oemConfigFile, meshtastic_OEMStore_size, sizeof(meshtastic_OEMStore), &meshtastic_OEMStore_msg, &oemStore)) { + state = loadProto(oemConfigFile, meshtastic_OEMStore_size, sizeof(meshtastic_OEMStore), &meshtastic_OEMStore_msg, &oemStore); + if (state == LoadFileResult::SUCCESS) { LOG_INFO("Loaded OEMStore\n"); } } diff --git a/src/mesh/NodeDB.h b/src/mesh/NodeDB.h index 4d24d7225..1c1736f78 100644 --- a/src/mesh/NodeDB.h +++ b/src/mesh/NodeDB.h @@ -38,6 +38,19 @@ uint32_t sinceLastSeen(const meshtastic_NodeInfoLite *n); /// Given a packet, return how many seconds in the past (vs now) it was received uint32_t sinceReceived(const meshtastic_MeshPacket *p); +enum LoadFileResult { + // Successfully opened the file + SUCCESS = 1, + // File does not exist + NOT_FOUND = 2, + // Device does not have a filesystem + NO_FILESYSTEM = 3, + // File exists, but could not decode protobufs + DECODE_FAILED = 4, + // File exists, but open failed for some reason + OTHER_FAILURE = 5 +}; + class NodeDB { // NodeNum provisionalNodeNum; // if we are trying to find a node num this is our current attempt @@ -115,7 +128,8 @@ class NodeDB bool factoryReset(); - bool loadProto(const char *filename, size_t protoSize, size_t objSize, const pb_msgdesc_t *fields, void *dest_struct); + LoadFileResult loadProto(const char *filename, size_t protoSize, size_t objSize, const pb_msgdesc_t *fields, + void *dest_struct); bool saveProto(const char *filename, size_t protoSize, const pb_msgdesc_t *fields, const void *dest_struct); void installRoleDefaults(meshtastic_Config_DeviceConfig_Role role); diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index c1cf90325..cbd6fee72 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -664,9 +664,9 @@ ProcessMessage CannedMessageModule::handleReceived(const meshtastic_MeshPacket & void CannedMessageModule::loadProtoForModule() { - if (!nodeDB->loadProto(cannedMessagesConfigFile, meshtastic_CannedMessageModuleConfig_size, - sizeof(meshtastic_CannedMessageModuleConfig), &meshtastic_CannedMessageModuleConfig_msg, - &cannedMessageModuleConfig)) { + if (nodeDB->loadProto(cannedMessagesConfigFile, meshtastic_CannedMessageModuleConfig_size, + sizeof(meshtastic_CannedMessageModuleConfig), &meshtastic_CannedMessageModuleConfig_msg, + &cannedMessageModuleConfig) != LoadFileResult::SUCCESS) { installDefaultCannedMessageModuleConfig(); } } diff --git a/src/modules/ExternalNotificationModule.cpp b/src/modules/ExternalNotificationModule.cpp index 617796544..a38b231af 100644 --- a/src/modules/ExternalNotificationModule.cpp +++ b/src/modules/ExternalNotificationModule.cpp @@ -284,8 +284,8 @@ ExternalNotificationModule::ExternalNotificationModule() // moduleConfig.external_notification.alert_message_buzzer = true; if (moduleConfig.external_notification.enabled) { - if (!nodeDB->loadProto(rtttlConfigFile, meshtastic_RTTTLConfig_size, sizeof(meshtastic_RTTTLConfig), - &meshtastic_RTTTLConfig_msg, &rtttlConfig)) { + if (nodeDB->loadProto(rtttlConfigFile, meshtastic_RTTTLConfig_size, sizeof(meshtastic_RTTTLConfig), + &meshtastic_RTTTLConfig_msg, &rtttlConfig) != LoadFileResult::SUCCESS) { memset(rtttlConfig.ringtone, 0, sizeof(rtttlConfig.ringtone)); strncpy(rtttlConfig.ringtone, "24:d=32,o=5,b=565:f6,p,f6,4p,p,f6,p,f6,2p,p,b6,p,b6,p,b6,p,b6,p,b,p,b,p,b,p,b,p,b,p,b,p,b,p,b,1p.,2p.,p", diff --git a/src/modules/NeighborInfoModule.cpp b/src/modules/NeighborInfoModule.cpp index 92395ffc5..470234047 100644 --- a/src/modules/NeighborInfoModule.cpp +++ b/src/modules/NeighborInfoModule.cpp @@ -233,8 +233,8 @@ meshtastic_Neighbor *NeighborInfoModule::getOrCreateNeighbor(NodeNum originalSen void NeighborInfoModule::loadProtoForModule() { - if (!nodeDB->loadProto(neighborInfoConfigFile, meshtastic_NeighborInfo_size, sizeof(meshtastic_NeighborInfo), - &meshtastic_NeighborInfo_msg, &neighborState)) { + if (nodeDB->loadProto(neighborInfoConfigFile, meshtastic_NeighborInfo_size, sizeof(meshtastic_NeighborInfo), + &meshtastic_NeighborInfo_msg, &neighborState) != LoadFileResult::SUCCESS) { neighborState = meshtastic_NeighborInfo_init_zero; } } From 1291da746b1e052793327105b7d0e6d46d37ce19 Mon Sep 17 00:00:00 2001 From: Gareth Coleman <30833824+garethhcoleman@users.noreply.github.com> Date: Mon, 15 Apr 2024 13:30:45 +0100 Subject: [PATCH 449/472] Support for alt I2C address for LSM6DS3 sensor, identification of TCA9555 IO Expander, resolve serial hang issue (#3622) * basic identification of TCA9555 * recognise LSM6DS3 on alt address * keep variant.h changes out of this PR * 2nd attempt to keep variant.h changes out of this PR --------- Co-authored-by: Ben Meadors --- src/configuration.h | 6 +++++- src/detect/ScanI2C.h | 1 + src/detect/ScanI2CTwoWire.cpp | 9 ++++++++- variants/unphone/platformio.ini | 5 ++++- 4 files changed, 18 insertions(+), 3 deletions(-) diff --git a/src/configuration.h b/src/configuration.h index 66ec607ff..37b67f666 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -138,9 +138,13 @@ along with this program. If not, see . // ----------------------------------------------------------------------------- // Security // ----------------------------------------------------------------------------- - #define ATECC608B_ADDR 0x35 +// ----------------------------------------------------------------------------- +// IO Expander +// ----------------------------------------------------------------------------- +#define TCA9555_ADDR 0x26 + // ----------------------------------------------------------------------------- // GPS // ----------------------------------------------------------------------------- diff --git a/src/detect/ScanI2C.h b/src/detect/ScanI2C.h index e87ede0a4..c8fcfee10 100644 --- a/src/detect/ScanI2C.h +++ b/src/detect/ScanI2C.h @@ -40,6 +40,7 @@ class ScanI2C BMA423, BQ24295, LSM6DS3, + TCA9555, #ifdef HAS_NCP5623 NCP5623, #endif diff --git a/src/detect/ScanI2CTwoWire.cpp b/src/detect/ScanI2CTwoWire.cpp index 335892131..13c2f4609 100644 --- a/src/detect/ScanI2CTwoWire.cpp +++ b/src/detect/ScanI2CTwoWire.cpp @@ -299,6 +299,12 @@ void ScanI2CTwoWire::scanPort(I2CPort port) if (registerValue == 0xC0) { type = BQ24295; LOG_INFO("BQ24295 PMU found\n"); + break; + } + registerValue = getRegisterValue(ScanI2CTwoWire::RegisterLocation(addr, 0x0F), 1); // get ID + if (registerValue == 0x6A) { + type = LSM6DS3; + LOG_INFO("LSM6DS3 accelerometer found at address 0x%x\n", (uint8_t)addr.address); } else { type = QMI8658; LOG_INFO("QMI8658 Highrate 6-Axis inertial measurement sensor found\n"); @@ -310,7 +316,8 @@ void ScanI2CTwoWire::scanPort(I2CPort port) SCAN_SIMPLE_CASE(PMSA0031_ADDR, PMSA0031, "PMSA0031 air quality sensor found\n") SCAN_SIMPLE_CASE(MPU6050_ADDR, MPU6050, "MPU6050 accelerometer found\n"); SCAN_SIMPLE_CASE(BMA423_ADDR, BMA423, "BMA423 accelerometer found\n"); - SCAN_SIMPLE_CASE(LSM6DS3_ADDR, LSM6DS3, "LSM6DS3 accelerometer found\n"); + SCAN_SIMPLE_CASE(LSM6DS3_ADDR, LSM6DS3, "LSM6DS3 accelerometer found at address 0x%x\n", (uint8_t)addr.address); + SCAN_SIMPLE_CASE(TCA9555_ADDR, TCA9555, "TCA9555 I2C expander found\n"); default: LOG_INFO("Device found at address 0x%x was not able to be enumerated\n", addr.address); diff --git a/variants/unphone/platformio.ini b/variants/unphone/platformio.ini index 9a4a63807..06314eaa3 100644 --- a/variants/unphone/platformio.ini +++ b/variants/unphone/platformio.ini @@ -7,10 +7,13 @@ upload_speed = 921600 monitor_speed = 115200 monitor_filters = esp32_exception_decoder +build_unflags = + -D ARDUINO_USB_MODE + build_flags = ${esp32_base.build_flags} -D UNPHONE - -D BOARD_HAS_PSRAM -I variants/unphone + -D ARDUINO_USB_MODE=0 lib_deps = ${esp32s3_base.lib_deps} lovyan03/LovyanGFX@^1.1.8 \ No newline at end of file From 27ae4399bc3f8c0049d3061fe454981e5e27fa73 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Mon, 15 Apr 2024 16:35:52 -0500 Subject: [PATCH 450/472] Zero hop always for connected node (#3634) --- src/mesh/PhoneAPI.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/mesh/PhoneAPI.cpp b/src/mesh/PhoneAPI.cpp index efbcc9558..2a69d6d56 100644 --- a/src/mesh/PhoneAPI.cpp +++ b/src/mesh/PhoneAPI.cpp @@ -430,6 +430,7 @@ bool PhoneAPI::available() auto nextNode = nodeDB->readNextMeshNode(readIndex); if (nextNode) { nodeInfoForPhone = TypeConversions::ConvertToNodeInfo(nextNode); + nodeInfoForPhone.hops_away = nodeInfoForPhone.num == nodeDB->getNodeNum() ? 0 : nodeInfoForPhone.hops_away; nodeInfoForPhone.is_favorite = nodeInfoForPhone.is_favorite || nodeInfoForPhone.num == nodeDB->getNodeNum(); // Our node is always a favorite } From 2f9b68e08b2ff5fd4c6aa40b9c84041d2f3351ac Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Mon, 15 Apr 2024 16:36:22 -0500 Subject: [PATCH 451/472] File management changes (Part 2 - Reboot instead of reformat NRF52 after two failed file saves) (#3630) * Add LoadFileState to differentiate types of success / failures * Try rebooting NRF52s with multiple failed saves * Trunkate --- src/mesh/NodeDB.cpp | 17 ++++++++++++++--- 1 file changed, 14 insertions(+), 3 deletions(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index dce7e47af..73aa29bbf 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -688,9 +688,13 @@ bool NodeDB::saveProto(const char *filename, size_t protoSize, const pb_msgdesc_ static uint8_t failedCounter = 0; failedCounter++; if (failedCounter >= 2) { - FSCom.format(); - // After formatting, the device needs to be restarted - nodeDB->resetRadioConfig(true); + LOG_ERROR("Failed to save file twice. Rebooting...\n"); + delay(100); + NVIC_SystemReset(); + // We used to blow away the filesystem here, but that's a bit extreme + // FSCom.format(); + // // After formatting, the device needs to be restarted + // nodeDB->resetRadioConfig(true); } #endif } @@ -734,6 +738,7 @@ void NodeDB::saveToDisk(int saveWhat) config.has_power = true; config.has_network = true; config.has_bluetooth = true; + saveProto(configFileName, meshtastic_LocalConfig_size, &meshtastic_LocalConfig_msg, &config); } @@ -745,6 +750,12 @@ void NodeDB::saveToDisk(int saveWhat) moduleConfig.has_serial = true; moduleConfig.has_store_forward = true; moduleConfig.has_telemetry = true; + moduleConfig.has_neighbor_info = true; + moduleConfig.has_detection_sensor = true; + moduleConfig.has_ambient_lighting = true; + moduleConfig.has_audio = true; + moduleConfig.has_paxcounter = true; + saveProto(moduleConfigFileName, meshtastic_LocalModuleConfig_size, &meshtastic_LocalModuleConfig_msg, &moduleConfig); } From 441638c2eba017e842ab5b96b18f6f05dbcc2828 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Mon, 15 Apr 2024 20:23:49 -0500 Subject: [PATCH 452/472] [create-pull-request] automated change (#3636) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 6aedf1e72..f5ad818a2 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 3 -build = 5 +build = 6 From 7d3175dc833f19d78754075c8fae2d3afb3686b5 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Tue, 16 Apr 2024 07:22:31 -0500 Subject: [PATCH 453/472] More useful default input device for Pi 400 (#3639) --- bin/config-dist.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bin/config-dist.yaml b/bin/config-dist.yaml index 5a8e658cb..d8cb5a9dd 100644 --- a/bin/config-dist.yaml +++ b/bin/config-dist.yaml @@ -112,7 +112,7 @@ Touchscreen: ### Configure device for direct keyboard input Input: -# KeyboardDevice: /dev/input/event0 +# KeyboardDevice: /dev/input/by-id/usb-_Raspberry_Pi_Internal_Keyboard-event-kbd ### From 3413b9da412fb0f197096d34de2b3fd4b90ff5ee Mon Sep 17 00:00:00 2001 From: Gareth Coleman <30833824+garethhcoleman@users.noreply.github.com> Date: Tue, 16 Apr 2024 13:29:08 +0100 Subject: [PATCH 454/472] Fixed XPT2046 syntax and using unPhone library to clean up support (#3631) * Fixed XPT2046 syntax and using unPhone library to clean up main and TFTDisplay. * strange extra edits removed wtf --- src/graphics/TFTDisplay.cpp | 33 ++++++++++++--------------------- src/main.cpp | 16 +--------------- variants/unphone/platformio.ini | 15 +++++++++++++-- variants/unphone/variant.cpp | 20 ++++++++++++++++++++ variants/unphone/variant.h | 14 +++++++++++--- 5 files changed, 57 insertions(+), 41 deletions(-) create mode 100644 variants/unphone/variant.cpp diff --git a/src/graphics/TFTDisplay.cpp b/src/graphics/TFTDisplay.cpp index fb64553ef..b561f3b56 100644 --- a/src/graphics/TFTDisplay.cpp +++ b/src/graphics/TFTDisplay.cpp @@ -411,8 +411,7 @@ class LGFX : public lgfx::LGFX_Device lgfx::Panel_HX8357D _panel_instance; lgfx::Bus_SPI _bus_instance; #if defined(USE_XPT2046) - lgfx::ITouch *_touch_instance; -// lgfx::Touch_XPT2046 _touch_instance; + lgfx::Touch_XPT2046 _touch_instance; #endif public: @@ -466,8 +465,7 @@ class LGFX : public lgfx::LGFX_Device #if defined(USE_XPT2046) { // Configure settings for touch control. - _touch_instance = new lgfx::Touch_XPT2046; - auto touch_cfg = _touch_instance->config(); + auto touch_cfg = _touch_instance.config(); touch_cfg.pin_cs = TOUCH_CS; touch_cfg.x_min = 0; @@ -478,8 +476,8 @@ class LGFX : public lgfx::LGFX_Device touch_cfg.bus_shared = true; touch_cfg.offset_rotation = 1; - _touch_instance->config(touch_cfg); - //_panel_instance->setTouch(_touch_instance); + _touch_instance.config(touch_cfg); + _panel_instance.setTouch(&_touch_instance); } #endif setPanel(&_panel_instance); @@ -496,6 +494,11 @@ static LGFX *tft = nullptr; #include "TFTDisplay.h" #include +#ifdef UNPHONE +#include "unPhone.h" +extern unPhone unphone; +#endif + TFTDisplay::TFTDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY geometry, HW_I2C i2cBus) { LOG_DEBUG("TFTDisplay!\n"); @@ -576,11 +579,7 @@ void TFTDisplay::sendCommand(uint8_t com) digitalWrite(VTFT_CTRL, LOW); #endif #ifdef UNPHONE - Wire.beginTransmission(0x26); - Wire.write(0x02); - Wire.write(0x04); // Backlight on - Wire.write(0x22); // G&B LEDs off - Wire.endTransmission(); + unphone.backlight(true); // using unPhone library #endif #ifdef RAK14014 #elif !defined(M5STACK) @@ -612,11 +611,7 @@ void TFTDisplay::sendCommand(uint8_t com) digitalWrite(VTFT_CTRL, HIGH); #endif #ifdef UNPHONE - Wire.beginTransmission(0x26); - Wire.write(0x02); - Wire.write(0x00); // Backlight off - Wire.write(0x22); // G&B LEDs off - Wire.endTransmission(); + unphone.backlight(false); // using unPhone library #endif #ifdef RAK14014 #elif !defined(M5STACK) @@ -690,11 +685,7 @@ bool TFTDisplay::connect() digitalWrite(ST7735_BL_V05, TFT_BACKLIGHT_ON); #endif #ifdef UNPHONE - Wire.beginTransmission(0x26); - Wire.write(0x02); - Wire.write(0x04); // Backlight on - Wire.write(0x22); // G&B LEDs off - Wire.endTransmission(); + unphone.backlight(true); // using unPhone library LOG_INFO("Power to TFT Backlight\n"); #endif diff --git a/src/main.cpp b/src/main.cpp index 587bcb56e..744fda4de 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -590,20 +590,6 @@ void setup() if (config.display.oled != meshtastic_Config_DisplayConfig_OledType_OLED_AUTO) screen_model = config.display.oled; -#ifdef UNPHONE - // initialise IO expander with pinmodes - Wire.beginTransmission(0x26); - Wire.write(0x06); - Wire.write(0x7A); - Wire.write(0xDD); - Wire.endTransmission(); - Wire.beginTransmission(0x26); - Wire.write(0x02); - Wire.write(0x04); // Backlight on - Wire.write(0x22); // G&B LEDs off - Wire.endTransmission(); -#endif - #if defined(USE_SH1107) screen_model = meshtastic_Config_DisplayConfig_OledType_OLED_SH1107; // set dimension of 128x128 display_geometry = GEOMETRY_128_128; @@ -1017,4 +1003,4 @@ void loop() mainDelay.delay(delayMsec); } // if (didWake) LOG_DEBUG("wake!\n"); -} +} \ No newline at end of file diff --git a/variants/unphone/platformio.ini b/variants/unphone/platformio.ini index 06314eaa3..dad9a7177 100644 --- a/variants/unphone/platformio.ini +++ b/variants/unphone/platformio.ini @@ -1,5 +1,7 @@ +; platformio.ini for unphone meshtastic + [env:unphone] -;build_type = debug ; to make it possible to step through our jtag debugger + extends = esp32s3_base board_level = extra board = unphone9 @@ -14,6 +16,15 @@ build_flags = ${esp32_base.build_flags} -D UNPHONE -I variants/unphone -D ARDUINO_USB_MODE=0 + -D UNPHONE_ACCEL=0 + -D UNPHONE_TOUCHS=0 + -D UNPHONE_SDCARD=0 + -D UNPHONE_UI0=0 + -D UNPHONE_LORA=0 + -D UNPHONE_FACTORY_MODE=0 + +build_src_filter = ${esp32_base.build_src_filter} +<../variants/unphone> lib_deps = ${esp32s3_base.lib_deps} - lovyan03/LovyanGFX@^1.1.8 \ No newline at end of file + lovyan03/LovyanGFX @ ^1.1.8 + https://gitlab.com/hamishcunningham/unphonelibrary#meshtastic @ ^9.0.0 \ No newline at end of file diff --git a/variants/unphone/variant.cpp b/variants/unphone/variant.cpp new file mode 100644 index 000000000..3f6d1c54d --- /dev/null +++ b/variants/unphone/variant.cpp @@ -0,0 +1,20 @@ +// meshtastic/firmware/variants/unphone/variant.cpp + +#include "unPhone.h" +unPhone unphone = unPhone("meshtastic_unphone"); + +void initVariant() +{ + unphone.begin(); // initialise hardware etc. + unphone.store(unphone.buildTime); + unphone.printWakeupReason(); // what woke us up? (stored, not printed :|) + unphone.checkPowerSwitch(); // if power switch is off, shutdown + unphone.backlight(false); // setup backlight and make sure its off + + for (int i = 0; i < 3; i++) { // buzz a bit + unphone.vibe(true); + delay(150); + unphone.vibe(false); + delay(150); + } +} \ No newline at end of file diff --git a/variants/unphone/variant.h b/variants/unphone/variant.h index 9306537f2..180fdfe2c 100644 --- a/variants/unphone/variant.h +++ b/variants/unphone/variant.h @@ -1,3 +1,7 @@ +// meshtastic/firmware/variants/unphone/variant.h + +#pragma once + #define SPI_SCK 39 #define SPI_MOSI 40 #define SPI_MISO 41 @@ -28,7 +32,7 @@ #define TFT_WIDTH 320 #define TFT_OFFSET_X 0 #define TFT_OFFSET_Y 0 -#define TFT_OFFSET_ROTATION 6 // the unPhone's screen is wired unusually, 0 is typical value here +#define TFT_OFFSET_ROTATION 6 // unPhone's screen wired unusually, 0 typical #define TFT_INVERT false #define SCREEN_ROTATE true #define SCREEN_TRANSITION_FRAMERATE 5 @@ -37,7 +41,10 @@ #define USE_XPT2046 1 #define TOUCH_CS 38 -#define HAS_GPS 0 // the unphone doesn't have a gps module +#define HAS_GPS \ + 0 // the unphone doesn't have a gps module by default (though + // GPS featherwing -- https://www.adafruit.com/product/3133 + // -- can be added) #undef GPS_RX_PIN #undef GPS_TX_PIN @@ -49,6 +56,7 @@ #define BUTTON_PIN 21 // Button 3 - square - top button in landscape mode #define BUTTON_NEED_PULLUP // we do need a helping hand up +#define BUTTON_PIN_ALT 45 // Button 1 - triangle - bottom button in landscape mode #define I2C_SDA 3 // I2C pins for this board #define I2C_SCL 4 @@ -58,6 +66,6 @@ // ratio of voltage divider = 3.20 (R1=100k, R2=220k) // #define ADC_MULTIPLIER 3.2 -// #define BATTERY_PIN 13 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage +// #define BATTERY_PIN 13 // battery V measurement pin; vbat divider is here // #define ADC_CHANNEL ADC2_GPIO13_CHANNEL // #define BAT_MEASURE_ADC_UNIT 2 \ No newline at end of file From a01069a549584937ced04ab741f57cd35c110837 Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Wed, 17 Apr 2024 00:36:14 +1200 Subject: [PATCH 455/472] No more printing power-state changes to screen (#3640) --- src/PowerFSM.cpp | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/src/PowerFSM.cpp b/src/PowerFSM.cpp index ac48e664c..4f42b36b5 100644 --- a/src/PowerFSM.cpp +++ b/src/PowerFSM.cpp @@ -185,10 +185,12 @@ static void powerEnter() screen->setOn(true); setBluetoothEnable(true); // within enter() the function getState() returns the state we came from - if (strcmp(powerFSM.getState()->name, "BOOT") != 0 && strcmp(powerFSM.getState()->name, "POWER") != 0 && + + // Mothballed: print change of power-state to device screen + /* if (strcmp(powerFSM.getState()->name, "BOOT") != 0 && strcmp(powerFSM.getState()->name, "POWER") != 0 && strcmp(powerFSM.getState()->name, "DARK") != 0) { screen->print("Powered...\n"); - } + }*/ } } @@ -205,8 +207,10 @@ static void powerExit() { screen->setOn(true); setBluetoothEnable(true); - if (!isPowered()) - screen->print("Unpowered...\n"); + + // Mothballed: print change of power-state to device screen + /*if (!isPowered()) + screen->print("Unpowered...\n");*/ } static void onEnter() From 699ea7467299c8c5e19711111f0ad98f1c14b894 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Tue, 16 Apr 2024 08:01:32 -0500 Subject: [PATCH 456/472] [create-pull-request] automated change (#3642) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/mesh.pb.h | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/protobufs b/protobufs index f92900c5f..ecf105f66 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit f92900c5f884b04388fb7abf61d4df66783015e4 +Subproject commit ecf105f66d182531423b73f4408c53701313c4eb diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index e674e28bb..67b2edd15 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -146,6 +146,8 @@ typedef enum _meshtastic_HardwareModel { /* Teledatics TD-LORAC NRF52840 based M.2 LoRA module Compatible with the TD-WRLS development board */ meshtastic_HardwareModel_TD_LORAC = 60, + /* CDEBYTE EoRa-S3 board using their own MM modules, clone of LILYGO T3S3 */ + meshtastic_HardwareModel_CDEBYTE_EORA_S3 = 61, /* ------------------------------------------------------------------------------------------------------------------------------------------ Reserved ID For developing private Ports. These will show up in live traffic sparsely, so we can use a high number. Keep it within 8 bits. ------------------------------------------------------------------------------------------------------------------------------------------ */ From e813703bf5298b60eb5357608b6e5009ebd87def Mon Sep 17 00:00:00 2001 From: S5NC <145265251+S5NC@users.noreply.github.com> Date: Tue, 16 Apr 2024 15:00:16 +0100 Subject: [PATCH 457/472] Add support for CDEBYTE_EoRa-S3 (#3613) * Create CDEBYTE_EoRa-S3.json * Update CDEBYTE_EoRa-S3.json * Update architecture.h * Create variant.h * Create platformio.ini * Create pins_arduino.h * Update variant.h * Update variant.h * Update variant.h * Trunk format * update variant.h --------- Co-authored-by: Ben Meadors Co-authored-by: S5NC <> --- boards/CDEBYTE_EoRa-S3.json | 38 +++++++++++++++ src/platform/esp32/architecture.h | 2 + variants/CDEBYTE_EoRa-S3/pins_arduino.h | 37 +++++++++++++++ variants/CDEBYTE_EoRa-S3/platformio.ini | 8 ++++ variants/CDEBYTE_EoRa-S3/variant.h | 63 +++++++++++++++++++++++++ 5 files changed, 148 insertions(+) create mode 100644 boards/CDEBYTE_EoRa-S3.json create mode 100644 variants/CDEBYTE_EoRa-S3/pins_arduino.h create mode 100644 variants/CDEBYTE_EoRa-S3/platformio.ini create mode 100644 variants/CDEBYTE_EoRa-S3/variant.h diff --git a/boards/CDEBYTE_EoRa-S3.json b/boards/CDEBYTE_EoRa-S3.json new file mode 100644 index 000000000..9ecee3c9f --- /dev/null +++ b/boards/CDEBYTE_EoRa-S3.json @@ -0,0 +1,38 @@ +{ + "build": { + "arduino": { + "ldscript": "esp32s3_out.ld" + }, + "core": "esp32", + "extra_flags": [ + "-D CDEBYTE_EORA_S3", + "-D ARDUINO_USB_CDC_ON_BOOT=1", + "-D ARDUINO_USB_MODE=0", + "-D ARDUINO_RUNNING_CORE=1", + "-D ARDUINO_EVENT_RUNNING_CORE=1", + "-D BOARD_HAS_PSRAM" + ], + "f_cpu": "240000000L", + "f_flash": "80000000L", + "flash_mode": "dio", + "hwids": [["0x303A", "0x1001"]], + "mcu": "esp32s3", + "variant": "CDEBYTE_EoRa-S3" + }, + "connectivity": ["wifi"], + "debug": { + "openocd_target": "esp32s3.cfg" + }, + "frameworks": ["arduino", "espidf"], + "name": "CDEBYTE EoRa-S3", + "upload": { + "flash_size": "4MB", + "maximum_ram_size": 327680, + "maximum_size": 4194304, + "wait_for_upload_port": true, + "require_upload_port": true, + "speed": 921600 + }, + "url": "https://www.cdebyte.com/Module-Testkits-EoRaPI", + "vendor": "CDEBYTE" +} diff --git a/src/platform/esp32/architecture.h b/src/platform/esp32/architecture.h index 6855265ac..15e437bb5 100644 --- a/src/platform/esp32/architecture.h +++ b/src/platform/esp32/architecture.h @@ -117,6 +117,8 @@ #define HW_VENDOR meshtastic_HardwareModel_HELTEC_WIRELESS_PAPER #elif defined(TLORA_T3S3_V1) #define HW_VENDOR meshtastic_HardwareModel_TLORA_T3_S3 +#elif defined(CDEBYTE_ELORA_S3) +#define HW_VENDOR meshtastic_HardwareModel_CDEBYTE_ELORA_S3 #elif defined(BETAFPV_2400_TX) #define HW_VENDOR meshtastic_HardwareModel_BETAFPV_2400_TX #elif defined(NANO_G1_EXPLORER) diff --git a/variants/CDEBYTE_EoRa-S3/pins_arduino.h b/variants/CDEBYTE_EoRa-S3/pins_arduino.h new file mode 100644 index 000000000..38a9103f0 --- /dev/null +++ b/variants/CDEBYTE_EoRa-S3/pins_arduino.h @@ -0,0 +1,37 @@ +// Need this file for ESP32-S3 +// No need to modify this file, changes to pins imported from variant.h +// Most is similar to https://github.com/espressif/arduino-esp32/blob/master/variants/esp32s3/pins_arduino.h + +#ifndef Pins_Arduino_h +#define Pins_Arduino_h + +#include +#include + +#define USB_VID 0x303a +#define USB_PID 0x1001 + +#define EXTERNAL_NUM_INTERRUPTS 46 +#define NUM_DIGITAL_PINS 48 +#define NUM_ANALOG_INPUTS 20 + +#define analogInputToDigitalPin(p) (((p) < 20) ? (analogChannelToDigitalPin(p)) : -1) +#define digitalPinToInterrupt(p) \ + (((p) < 48) ? (p) : -1) // Maybe it should be <= 48 but this is from a trustworthy source so it is likely correct +#define digitalPinHasPWM(p) (p < 46) + +// Serial +static const uint8_t TX = UART_TX; +static const uint8_t RX = UART_RX; + +// Default SPI will be mapped to Radio +static const uint8_t SS = LORA_CS; +static const uint8_t SCK = LORA_SCK; +static const uint8_t MOSI = LORA_MOSI; +static const uint8_t MISO = LORA_MISO; + +// The default Wire will be mapped to PMU and RTC +static const uint8_t SCL = I2C_SCL; +static const uint8_t SDA = I2C_SDA; + +#endif /* Pins_Arduino_h */ diff --git a/variants/CDEBYTE_EoRa-S3/platformio.ini b/variants/CDEBYTE_EoRa-S3/platformio.ini new file mode 100644 index 000000000..1ff54de88 --- /dev/null +++ b/variants/CDEBYTE_EoRa-S3/platformio.ini @@ -0,0 +1,8 @@ +[env:CDEBYTE_EoRa-S3] +extends = esp32s3_base +board = CDEBYTE_EoRa-S3 +build_flags = + ${esp32s3_base.build_flags} + -D CDEBYTE_EORA_S3 + -I variants/CDEBYTE_EoRa-S3 + -D GPS_POWER_TOGGLE diff --git a/variants/CDEBYTE_EoRa-S3/variant.h b/variants/CDEBYTE_EoRa-S3/variant.h new file mode 100644 index 000000000..5da99667b --- /dev/null +++ b/variants/CDEBYTE_EoRa-S3/variant.h @@ -0,0 +1,63 @@ +// LED - status indication +#define LED_PIN 37 + +// Button - user interface +#define BUTTON_PIN 0 // This is the BOOT button, and it has its own pull-up resistor + +// SD card - TODO: test, currently untested, copied from T3S3 variant +#define HAS_SDCARD +#define SDCARD_USE_SPI1 +// TODO: rename this to make this SD-card specific +#define SPI_CS 13 +#define SPI_SCK 14 +#define SPI_MOSI 11 +#define SPI_MISO 2 +// FIXME: there are two other SPI pins that are not defined here +// Compatibility +#define SDCARD_CS SPI_CS + +// Battery voltage monitoring - TODO: test, currently untested, copied from T3S3 variant +#define BATTERY_PIN 1 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage +#define ADC_CHANNEL ADC1_GPIO1_CHANNEL +#define ADC_MULTIPLIER \ + 2.11 // ratio of voltage divider = 2.0 (R10=1M, R13=1M), plus some undervoltage correction - TODO: this was carried over from + // the T3S3, test to see if the undervoltage correction is needed. + +// Display - OLED connected via I2C by the default hardware configuration +#define HAS_SCREEN 1 +#define USE_SSD1306 +#define I2C_SCL 17 +#define I2C_SDA 18 + +// UART - The 1mm JST SH connector closest to the USB-C port +#define UART_TX 43 +#define UART_RX 44 + +// Peripheral I2C - The 1mm JST SH connector furthest from the USB-C port which follows Adafruit connection standard. There are no +// pull-up resistors on these lines, the downstream device needs to include them. TODO: test, currently untested +#define I2C_SCL1 21 +#define I2C_SDA1 10 + +// Radio +#define USE_SX1262 // CDEBYTE EoRa-S3-900TB <- CDEBYTE E22-900MM22S <- Semtech SX1262 +#define USE_SX1268 // CDEBYTE EoRa-S3-400TB <- CDEBYTE E22-400MM22S <- Semtech SX1268 + +#define SX126X_CS 7 +#define LORA_SCK 5 +#define LORA_MOSI 6 +#define LORA_MISO 3 +#define SX126X_RESET 8 +#define SX126X_BUSY 34 +#define SX126X_DIO1 33 + +#define SX126X_DIO2_AS_RF_SWITCH // All switching is performed with DIO2, it is automatically inverted using circuitry. +// CDEBYTE EoRa-S3 uses an XTAL, thus we do not need DIO3 as TCXO voltage reference. Don't define SX126X_DIO3_TCXO_VOLTAGE for +// simplicity rather than defining it as 0. +#define SX126X_MAX_POWER \ + 22 // E22-900MM22S and E22-400MM22S have a raw SX1262 or SX1268 respsectively, they are rated to output up and including 22 + // dBm out of their SX126x IC. + +// Compatibility with old variant.h file structure - FIXME: this should be done in the respective radio interface modules to clean +// up all variants. +#define LORA_CS SX126X_CS +#define LORA_DIO1 SX126X_DIO1 \ No newline at end of file From 9599549477d015a747ae1a828ea75ee73bc6eb77 Mon Sep 17 00:00:00 2001 From: Andrew Yong Date: Tue, 16 Apr 2024 22:03:36 +0800 Subject: [PATCH 458/472] Add configuration option for LoRa Region Code override for region-locked builds/variants (#3540) The main use case for this will be to create a custom Heltec WiFi LoRa 32 V3 SG_923 variant, which will be pre-flashed and sent for regulatory approval for retail sale. Signed-off-by: Andrew Yong Co-authored-by: Ben Meadors --- src/configuration.h | 7 +++++++ src/mesh/RadioInterface.cpp | 8 +++++++- 2 files changed, 14 insertions(+), 1 deletion(-) diff --git a/src/configuration.h b/src/configuration.h index 37b67f666..701e07a32 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -74,6 +74,13 @@ along with this program. If not, see . #define RTC_DATA_ATTR #endif +// ----------------------------------------------------------------------------- +// Regulatory overrides for producing regional builds +// ----------------------------------------------------------------------------- + +// Define if region should override user saved region +// #define LORA_REGIONCODE meshtastic_Config_LoRaConfig_RegionCode_SG_923 + // ----------------------------------------------------------------------------- // Feature toggles // ----------------------------------------------------------------------------- diff --git a/src/mesh/RadioInterface.cpp b/src/mesh/RadioInterface.cpp index 3aac9dfce..63912a03e 100644 --- a/src/mesh/RadioInterface.cpp +++ b/src/mesh/RadioInterface.cpp @@ -151,10 +151,16 @@ static uint8_t bytes[MAX_RHPACKETLEN]; void initRegion() { const RegionInfo *r = regions; +#ifdef LORA_REGIONCODE + for (; r->code != meshtastic_Config_LoRaConfig_RegionCode_UNSET && r->code != LORA_REGIONCODE; r++) + ; + LOG_INFO("Wanted region %d, regulatory override to %s\n", config.lora.region, r->name); +#else for (; r->code != meshtastic_Config_LoRaConfig_RegionCode_UNSET && r->code != config.lora.region; r++) ; - myRegion = r; LOG_INFO("Wanted region %d, using %s\n", config.lora.region, r->name); +#endif + myRegion = r; } /** From 55c9c3b29843a3301c5982ad6a46561d80d0fd94 Mon Sep 17 00:00:00 2001 From: David Ellefsen <93522+titan098@users.noreply.github.com> Date: Tue, 16 Apr 2024 16:03:51 +0200 Subject: [PATCH 459/472] Support for the ATGM336H series of GPS modules (#3610) Co-authored-by: Ben Meadors --- src/RedirectablePrint.cpp | 8 +- src/gps/GPS.cpp | 163 +++++++++++++++++++++++++++++++++++++- src/gps/GPS.h | 18 ++++- src/gps/cas.h | 63 +++++++++++++++ 4 files changed, 246 insertions(+), 6 deletions(-) create mode 100644 src/gps/cas.h diff --git a/src/RedirectablePrint.cpp b/src/RedirectablePrint.cpp index 16906e2e0..e09e5fe30 100644 --- a/src/RedirectablePrint.cpp +++ b/src/RedirectablePrint.cpp @@ -182,11 +182,11 @@ size_t RedirectablePrint::log(const char *logLevel, const char *format, ...) void RedirectablePrint::hexDump(const char *logLevel, unsigned char *buf, uint16_t len) { const char alphabet[17] = "0123456789abcdef"; - log(logLevel, " +------------------------------------------------+ +----------------+\n"); - log(logLevel, " |.0 .1 .2 .3 .4 .5 .6 .7 .8 .9 .a .b .c .d .e .f | | ASCII |\n"); + log(logLevel, " +------------------------------------------------+ +----------------+\n"); + log(logLevel, " |.0 .1 .2 .3 .4 .5 .6 .7 .8 .9 .a .b .c .d .e .f | | ASCII |\n"); for (uint16_t i = 0; i < len; i += 16) { if (i % 128 == 0) - log(logLevel, " +------------------------------------------------+ +----------------+\n"); + log(logLevel, " +------------------------------------------------+ +----------------+\n"); char s[] = "| | | |\n"; uint8_t ix = 1, iy = 52; for (uint8_t j = 0; j < 16; j++) { @@ -208,7 +208,7 @@ void RedirectablePrint::hexDump(const char *logLevel, unsigned char *buf, uint16 log(logLevel, "."); log(logLevel, s); } - log(logLevel, " +------------------------------------------------+ +----------------+\n"); + log(logLevel, " +------------------------------------------------+ +----------------+\n"); } std::string RedirectablePrint::mt_sprintf(const std::string fmt_str, ...) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 6a0e3e44a..0d0bfd9a2 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -7,6 +7,8 @@ #include "main.h" // pmu_found #include "sleep.h" + +#include "cas.h" #include "ubx.h" #ifdef ARCH_PORTDUINO @@ -51,6 +53,28 @@ void GPS::UBXChecksum(uint8_t *message, size_t length) message[length - 1] = CK_B; } +// Calculate the checksum for a CAS packet +void GPS::CASChecksum(uint8_t *message, size_t length) +{ + uint32_t cksum = ((uint32_t)message[5] << 24); // Message ID + cksum += ((uint32_t)message[4]) << 16; // Class + cksum += message[2]; // Payload Len + + // Iterate over the payload as a series of uint32_t's and + // accumulate the cksum + uint32_t *payload = (uint32_t *)(message + 6); + for (size_t i = 0; i < (length - 10) / 4; i++) { + uint32_t p = payload[i]; + cksum += p; + } + + // Place the checksum values in the message + message[length - 4] = (cksum & 0xFF); + message[length - 3] = (cksum & (0xFF << 8)) >> 8; + message[length - 2] = (cksum & (0xFF << 16)) >> 16; + message[length - 1] = (cksum & (0xFF << 24)) >> 24; +} + // Function to create a ublox packet for editing in memory uint8_t GPS::makeUBXPacket(uint8_t class_id, uint8_t msg_id, uint8_t payload_size, const uint8_t *msg) { @@ -72,6 +96,41 @@ uint8_t GPS::makeUBXPacket(uint8_t class_id, uint8_t msg_id, uint8_t payload_siz return (payload_size + 8); } +// Function to create a CAS packet for editing in memory +uint8_t GPS::makeCASPacket(uint8_t class_id, uint8_t msg_id, uint8_t payload_size, const uint8_t *msg) +{ + // General CAS structure + // | H1 | H2 | payload_len | cls | msg | Payload ... | Checksum | + // Size: | 1 | 1 | 2 | 1 | 1 | payload_len | 4 | + // Pos: | 0 | 1 | 2 | 3 | 4 | 5 | 6 | 7 ... | 6 + payload_len ... | + // |------|------|-------------|------|------|------|--------------|---------------------------| + // | 0xBA | 0xCE | 0xXX | 0xXX | 0xXX | 0xXX | 0xXX | 0xXX ... | 0xXX | 0xXX | 0xXX | 0xXX | + + // Construct the CAS packet + UBXscratch[0] = 0xBA; // header 1 (0xBA) + UBXscratch[1] = 0xCE; // header 2 (0xCE) + UBXscratch[2] = payload_size; // length 1 + UBXscratch[3] = 0; // length 2 + UBXscratch[4] = class_id; // class + UBXscratch[5] = msg_id; // id + + UBXscratch[6 + payload_size] = 0x00; // Checksum + UBXscratch[7 + payload_size] = 0x00; + UBXscratch[8 + payload_size] = 0x00; + UBXscratch[9 + payload_size] = 0x00; + + for (int i = 0; i < payload_size; i++) { + UBXscratch[6 + i] = pgm_read_byte(&msg[i]); + } + CASChecksum(UBXscratch, (payload_size + 10)); + +#if defined(GPS_DEBUG) && defined(DEBUG_PORT) + LOG_DEBUG("Constructed CAS packet: \n"); + DEBUG_PORT.hexDump(MESHTASTIC_LOG_LEVEL_DEBUG, UBXscratch, payload_size + 10); +#endif + return (payload_size + 10); +} + GPS_RESPONSE GPS::getACK(const char *message, uint32_t waitMillis) { uint8_t buffer[768] = {0}; @@ -81,6 +140,7 @@ GPS_RESPONSE GPS::getACK(const char *message, uint32_t waitMillis) while (millis() < startTimeout) { if (_serial_gps->available()) { b = _serial_gps->read(); + #ifdef GPS_DEBUG LOG_DEBUG("%02X", (char *)buffer); #endif @@ -104,6 +164,67 @@ GPS_RESPONSE GPS::getACK(const char *message, uint32_t waitMillis) return GNSS_RESPONSE_NONE; } +GPS_RESPONSE GPS::getACKCas(uint8_t class_id, uint8_t msg_id, uint32_t waitMillis) +{ + uint32_t startTime = millis(); + uint8_t buffer[CAS_ACK_NACK_MSG_SIZE] = {0}; + uint8_t bufferPos = 0; + + // CAS-ACK-(N)ACK structure + // | H1 | H2 | Payload Len | cls | msg | Payload | Checksum (4) | + // | | | | | | Cls | Msg | Reserved | | + // |------|------|-------------|------|------|------|------|-------------|---------------------------| + // ACK-NACK| 0xBA | 0xCE | 0x04 | 0x00 | 0x05 | 0x00 | 0xXX | 0xXX | 0x00 | 0x00 | 0xXX | 0xXX | 0xXX | 0xXX | + // ACK-ACK | 0xBA | 0xCE | 0x04 | 0x00 | 0x05 | 0x01 | 0xXX | 0xXX | 0x00 | 0x00 | 0xXX | 0xXX | 0xXX | 0xXX | + + while (millis() - startTime < waitMillis) { + if (_serial_gps->available()) { + buffer[bufferPos++] = _serial_gps->read(); + + // keep looking at the first two bytes of buffer until + // we have found the CAS frame header (0xBA, 0xCE), if not + // keep reading bytes until we find a frame header or we run + // out of time. + if ((bufferPos == 2) && !(buffer[0] == 0xBA && buffer[1] == 0xCE)) { + buffer[0] = buffer[1]; + buffer[1] = 0; + bufferPos = 1; + } + } + + // we have read all the bytes required for the Ack/Nack (14-bytes) + // and we must have found a frame to get this far + if (bufferPos == sizeof(buffer) - 1) { + uint8_t msg_cls = buffer[4]; // message class should be 0x05 + uint8_t msg_msg_id = buffer[5]; // message id should be 0x00 or 0x01 + uint8_t payload_cls = buffer[6]; // payload class id + uint8_t payload_msg = buffer[7]; // payload message id + + // Check for an ACK-ACK for the specified class and message id + if ((msg_cls == 0x05) && (msg_msg_id == 0x01) && payload_cls == class_id && payload_msg == msg_id) { +#ifdef GPS_DEBUG + LOG_INFO("Got ACK for class %02X message %02X in %d millis.\n", class_id, msg_id, millis() - startTime); +#endif + return GNSS_RESPONSE_OK; + } + + // Check for an ACK-NACK for the specified class and message id + if ((msg_cls == 0x05) && (msg_msg_id == 0x00) && payload_cls == class_id && payload_msg == msg_id) { +#ifdef GPS_DEBUG + LOG_WARN("Got NACK for class %02X message %02X in %d millis.\n", class_id, msg_id, millis() - startTime); +#endif + return GNSS_RESPONSE_NAK; + } + + // This isn't the frame we are looking for, clear the buffer + // and try again until we run out of time. + memset(buffer, 0x0, sizeof(buffer)); + bufferPos = 0; + } + } + return GNSS_RESPONSE_NONE; +} + GPS_RESPONSE GPS::getACK(uint8_t class_id, uint8_t msg_id, uint32_t waitMillis) { uint8_t b; @@ -313,6 +434,33 @@ bool GPS::setup() // Switch to Fitness Mode, for running and walking purpose with low speed (<5 m/s) _serial_gps->write("$PMTK886,1*29\r\n"); delay(250); + } else if (gnssModel == GNSS_MODEL_ATGM336H) { + // Set the intial configuration of the device - these _should_ work for most AT6558 devices + msglen = makeCASPacket(0x06, 0x07, sizeof(_message_CAS_CFG_NAVX_CONF), _message_CAS_CFG_NAVX_CONF); + _serial_gps->write(UBXscratch, msglen); + if (getACKCas(0x06, 0x07, 250) != GNSS_RESPONSE_OK) { + LOG_WARN("ATGM336H - Could not set Configuration"); + } + + // Set the update frequence to 1Hz + msglen = makeCASPacket(0x06, 0x04, sizeof(_message_CAS_CFG_RATE_1HZ), _message_CAS_CFG_RATE_1HZ); + _serial_gps->write(UBXscratch, msglen); + if (getACKCas(0x06, 0x04, 250) != GNSS_RESPONSE_OK) { + LOG_WARN("ATGM336H - Could not set Update Frequency"); + } + + // Set the NEMA output messages + // Ask for only RMC and GGA + uint8_t fields[] = {CAS_NEMA_RMC, CAS_NEMA_GGA}; + for (int i = 0; i < sizeof(fields); i++) { + // Construct a CAS-CFG-MSG packet + uint8_t cas_cfg_msg_packet[] = {0x4e, fields[i], 0x01, 0x00}; + msglen = makeCASPacket(0x06, 0x01, sizeof(cas_cfg_msg_packet), cas_cfg_msg_packet); + _serial_gps->write(UBXscratch, msglen); + if (getACKCas(0x06, 0x01, 250) != GNSS_RESPONSE_OK) { + LOG_WARN("ATGM336H - Could not enable NMEA MSG: %d\n", fields[i]); + } + } } else if (gnssModel == GNSS_MODEL_UC6580) { // The Unicore UC6580 can use a lot of sat systems, enable it to // use GPS L1 & L5 + BDS B1I & B2a + GLONASS L1 + GALILEO E1 & E5a + SBAS @@ -948,10 +1096,18 @@ GnssModel_t GPS::probe(int serialSpeed) uint8_t buffer[768] = {0}; delay(100); - // Close all NMEA sentences , Only valid for L76K MTK platform + // Close all NMEA sentences, valid for L76K, ATGM336H (and likely other AT6558 devices) _serial_gps->write("$PCAS03,0,0,0,0,0,0,0,0,0,0,,,0,0*02\r\n"); delay(20); + // Get version information + clearBuffer(); + _serial_gps->write("$PCAS06,1*1A\r\n"); + if (getACK("$GPTXT,01,01,02,HW=ATGM336H", 500) == GNSS_RESPONSE_OK) { + LOG_INFO("ATGM336H GNSS init succeeded, using ATGM336H Module\n"); + return GNSS_MODEL_ATGM336H; + } + // Get version information clearBuffer(); _serial_gps->write("$PCAS06,0*1B\r\n"); @@ -1216,6 +1372,11 @@ bool GPS::factoryReset() LOG_INFO("GNSS Factory Reset via PCAS10,3\n"); _serial_gps->write("$PCAS10,3*1F\r\n"); delay(100); + } else if (gnssModel == GNSS_MODEL_ATGM336H) { + LOG_INFO("Factory Reset via CAS-CFG-RST\n"); + uint8_t msglen = makeCASPacket(0x06, 0x02, sizeof(_message_CAS_CFG_RST_FACTORY), _message_CAS_CFG_RST_FACTORY); + _serial_gps->write(UBXscratch, msglen); + delay(100); } else { // fire this for good measure, if we have an L76B - won't harm other devices. _serial_gps->write("$PMTK104*37\r\n"); diff --git a/src/gps/GPS.h b/src/gps/GPS.h index 49f27e29f..77c6c0269 100644 --- a/src/gps/GPS.h +++ b/src/gps/GPS.h @@ -22,7 +22,14 @@ struct uBloxGnssModelInfo { char extension[10][30]; }; -typedef enum { GNSS_MODEL_MTK, GNSS_MODEL_UBLOX, GNSS_MODEL_UC6580, GNSS_MODEL_UNKNOWN, GNSS_MODEL_MTK_L76B } GnssModel_t; +typedef enum { + GNSS_MODEL_ATGM336H, + GNSS_MODEL_MTK, + GNSS_MODEL_UBLOX, + GNSS_MODEL_UC6580, + GNSS_MODEL_UNKNOWN, + GNSS_MODEL_MTK_L76B +} GnssModel_t; typedef enum { GNSS_RESPONSE_NONE, @@ -133,6 +140,11 @@ class GPS : private concurrency::OSThread static const uint8_t _message_VALSET_DISABLE_SBAS_RAM[]; static const uint8_t _message_VALSET_DISABLE_SBAS_BBR[]; + // CASIC commands for ATGM336H + static const uint8_t _message_CAS_CFG_RST_FACTORY[]; + static const uint8_t _message_CAS_CFG_NAVX_CONF[]; + static const uint8_t _message_CAS_CFG_RATE_1HZ[]; + meshtastic_Position p = meshtastic_Position_init_default; GPS() : concurrency::OSThread("GPS") {} @@ -174,6 +186,7 @@ class GPS : private concurrency::OSThread // Create a ublox packet for editing in memory uint8_t makeUBXPacket(uint8_t class_id, uint8_t msg_id, uint8_t payload_size, const uint8_t *msg); + uint8_t makeCASPacket(uint8_t class_id, uint8_t msg_id, uint8_t payload_size, const uint8_t *msg); // scratch space for creating ublox packets uint8_t UBXscratch[250] = {0}; @@ -184,6 +197,8 @@ class GPS : private concurrency::OSThread GPS_RESPONSE getACK(uint8_t c, uint8_t i, uint32_t waitMillis); GPS_RESPONSE getACK(const char *message, uint32_t waitMillis); + GPS_RESPONSE getACKCas(uint8_t class_id, uint8_t msg_id, uint32_t waitMillis); + /** * Switch the GPS into a mode where we are actively looking for a lock, or alternatively switch GPS into a low power mode * @@ -243,6 +258,7 @@ class GPS : private concurrency::OSThread // Calculate checksum void UBXChecksum(uint8_t *message, size_t length); + void CASChecksum(uint8_t *message, size_t length); /** Get how long we should stay looking for each aquisition */ diff --git a/src/gps/cas.h b/src/gps/cas.h new file mode 100644 index 000000000..53d75cda9 --- /dev/null +++ b/src/gps/cas.h @@ -0,0 +1,63 @@ +#pragma once + +// CASIC binary message definitions +// Reference: https://www.icofchina.com/d/file/xiazai/2020-09-22/20f1b42b3a11ac52089caf3603b43fb5.pdf +// ATGM33H-5N: https://www.icofchina.com/pro/mokuai/2016-08-01/4.html +// (https://www.icofchina.com/d/file/xiazai/2016-12-05/b5c57074f4b1fcc62ba8c7868548d18a.pdf) + +// NEMA (Class ID - 0x4e) message IDs +#define CAS_NEMA_GGA 0x00 +#define CAS_NEMA_GLL 0x01 +#define CAS_NEMA_GSA 0x02 +#define CAS_NEMA_GSV 0x03 +#define CAS_NEMA_RMC 0x04 +#define CAS_NEMA_VTG 0x05 +#define CAS_NEMA_GST 0x07 +#define CAS_NEMA_ZDA 0x08 +#define CAS_NEMA_DHV 0x0D + +// Size of a CAS-ACK-(N)ACK message (14 bytes) +#define CAS_ACK_NACK_MSG_SIZE 0x0E + +// CFG-RST (0x06, 0x02) +// Factory reset +const uint8_t GPS::_message_CAS_CFG_RST_FACTORY[] = { + 0xFF, 0x03, // Fields to clear + 0x01, // Reset Mode: Controlled Software reset + 0x03 // Startup Mode: Factory +}; + +// CFG_RATE (0x06, 0x01) +// 1HZ update rate, this should always be the case after +// factory reset but update it regardless +const uint8_t GPS::_message_CAS_CFG_RATE_1HZ[] = { + 0xE8, 0x03, // Update Rate: 0x03E8 = 1000ms + 0x00, 0x00 // Reserved +}; + +// CFG-NAVX (0x06, 0x07) +// Initial ATGM33H-5N configuration, Updates for Dynamic Mode, Fix Mode, and SV system +// Qwirk: The ATGM33H-5N-31 should only support GPS+BDS, however it will happily enable +// and use GPS+BDS+GLONASS iff the correct CFG_NAVX command is used. +const uint8_t GPS::_message_CAS_CFG_NAVX_CONF[] = { + 0x03, 0x01, 0x00, 0x00, // Update Mask: Dynamic Mode, Fix Mode, Nav Settings + 0x03, // Dynamic Mode: Automotive + 0x03, // Fix Mode: Auto 2D/3D + 0x00, // Min SV + 0x00, // Max SVs + 0x00, // Min CNO + 0x00, // Reserved1 + 0x00, // Init 3D fix + 0x00, // Min Elevation + 0x00, // Dr Limit + 0x07, // Nav System: 2^0 = GPS, 2^1 = BDS 2^2 = GLONASS: 2^3 + // 3=GPS+BDS, 7=GPS+BDS+GLONASS + 0x00, 0x00, // Rollover Week + 0x00, 0x00, 0x00, 0x00, // Fix Altitude + 0x00, 0x00, 0x00, 0x00, // Fix Height Error + 0x00, 0x00, 0x00, 0x00, // PDOP Maximum + 0x00, 0x00, 0x00, 0x00, // TDOP Maximum + 0x00, 0x00, 0x00, 0x00, // Position Accuracy Max + 0x00, 0x00, 0x00, 0x00, // Time Accuracy Max + 0x00, 0x00, 0x00, 0x00 // Static Hold Threshold +}; \ No newline at end of file From c34956e9d8912f28c6ae65137298804d81d669ec Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Wed, 17 Apr 2024 00:47:56 +0200 Subject: [PATCH 460/472] =?UTF-8?q?Cosmetics:=20rename=20remaining=20plugi?= =?UTF-8?q?ns=20=E2=86=92=20modules=20and=20less=20errors=20(#3645)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- src/mesh/MeshModule.cpp | 11 ++++++----- src/mesh/MeshModule.h | 6 +++--- src/mesh/RF95Interface.cpp | 2 +- src/mesh/Router.cpp | 4 ++-- src/mesh/SX128xInterface.cpp | 2 +- src/modules/AdminModule.cpp | 2 +- 6 files changed, 14 insertions(+), 13 deletions(-) diff --git a/src/mesh/MeshModule.cpp b/src/mesh/MeshModule.cpp index c8dd7f3d1..2ef46e4db 100644 --- a/src/mesh/MeshModule.cpp +++ b/src/mesh/MeshModule.cpp @@ -12,7 +12,7 @@ const meshtastic_MeshPacket *MeshModule::currentRequest; /** * If any of the current chain of modules has already sent a reply, it will be here. This is useful to allow - * the RoutingPlugin to avoid sending redundant acks + * the RoutingModule to avoid sending redundant acks */ meshtastic_MeshPacket *MeshModule::currentReply; @@ -40,7 +40,7 @@ meshtastic_MeshPacket *MeshModule::allocAckNak(meshtastic_Routing_Error err, Nod c.error_reason = err; c.which_variant = meshtastic_Routing_error_reason_tag; - // Now that we have moded sendAckNak up one level into the class hierarchy we can no longer assume we are a RoutingPlugin + // Now that we have moded sendAckNak up one level into the class hierarchy we can no longer assume we are a RoutingModule // So we manually call pb_encode_to_bytes and specify routing port number // auto p = allocDataProtobuf(c); meshtastic_MeshPacket *p = router->allocForSending(); @@ -54,7 +54,8 @@ meshtastic_MeshPacket *MeshModule::allocAckNak(meshtastic_Routing_Error err, Nod p->to = to; p->decoded.request_id = idFrom; p->channel = chIndex; - LOG_ERROR("Alloc an err=%d,to=0x%x,idFrom=0x%x,id=0x%x\n", err, to, idFrom, p->id); + if (err != meshtastic_Routing_Error_NONE) + LOG_ERROR("Alloc an err=%d,to=0x%x,idFrom=0x%x,id=0x%x\n", err, to, idFrom, p->id); return p; } @@ -68,7 +69,7 @@ meshtastic_MeshPacket *MeshModule::allocErrorResponse(meshtastic_Routing_Error e return r; } -void MeshModule::callPlugins(meshtastic_MeshPacket &mp, RxSource src) +void MeshModule::callModules(meshtastic_MeshPacket &mp, RxSource src) { // LOG_DEBUG("In call modules\n"); bool moduleFound = false; @@ -258,7 +259,7 @@ void MeshModule::observeUIEvents(Observer *observer) } } -AdminMessageHandleResult MeshModule::handleAdminMessageForAllPlugins(const meshtastic_MeshPacket &mp, +AdminMessageHandleResult MeshModule::handleAdminMessageForAllModules(const meshtastic_MeshPacket &mp, meshtastic_AdminMessage *request, meshtastic_AdminMessage *response) { diff --git a/src/mesh/MeshModule.h b/src/mesh/MeshModule.h index 6c431adb4..2e2af33e0 100644 --- a/src/mesh/MeshModule.h +++ b/src/mesh/MeshModule.h @@ -64,11 +64,11 @@ class MeshModule /** For use only by MeshService */ - static void callPlugins(meshtastic_MeshPacket &mp, RxSource src = RX_SRC_RADIO); + static void callModules(meshtastic_MeshPacket &mp, RxSource src = RX_SRC_RADIO); static std::vector GetMeshModulesWithUIFrames(); static void observeUIEvents(Observer *observer); - static AdminMessageHandleResult handleAdminMessageForAllPlugins(const meshtastic_MeshPacket &mp, + static AdminMessageHandleResult handleAdminMessageForAllModules(const meshtastic_MeshPacket &mp, meshtastic_AdminMessage *request, meshtastic_AdminMessage *response); #if HAS_SCREEN @@ -195,4 +195,4 @@ class MeshModule /** set the destination and packet parameters of packet p intended as a reply to a particular "to" packet * This ensures that if the request packet was sent reliably, the reply is sent that way as well. */ -void setReplyTo(meshtastic_MeshPacket *p, const meshtastic_MeshPacket &to); +void setReplyTo(meshtastic_MeshPacket *p, const meshtastic_MeshPacket &to); \ No newline at end of file diff --git a/src/mesh/RF95Interface.cpp b/src/mesh/RF95Interface.cpp index b658a8ff6..8c6c349fd 100644 --- a/src/mesh/RF95Interface.cpp +++ b/src/mesh/RF95Interface.cpp @@ -215,7 +215,7 @@ bool RF95Interface::isChannelActive() // LOG_DEBUG("Channel is busy!\n"); return true; } - if (result != RADIOLIB_ERR_WRONG_MODEM) + if (result != RADIOLIB_CHANNEL_FREE) LOG_ERROR("Radiolib error %d when attempting RF95 isChannelActive!\n", result); assert(result != RADIOLIB_ERR_WRONG_MODEM); diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp index 3fa933bb1..e4d67f019 100644 --- a/src/mesh/Router.cpp +++ b/src/mesh/Router.cpp @@ -479,7 +479,7 @@ void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src) // call modules here if (!skipHandle) - MeshModule::callPlugins(*p, src); + MeshModule::callModules(*p, src); } void Router::perhapsHandleReceived(meshtastic_MeshPacket *p) @@ -499,4 +499,4 @@ void Router::perhapsHandleReceived(meshtastic_MeshPacket *p) handleReceived(p); packetPool.release(p); -} +} \ No newline at end of file diff --git a/src/mesh/SX128xInterface.cpp b/src/mesh/SX128xInterface.cpp index 564b80494..9e4fbfa77 100644 --- a/src/mesh/SX128xInterface.cpp +++ b/src/mesh/SX128xInterface.cpp @@ -280,7 +280,7 @@ template bool SX128xInterface::isChannelActive() result = lora.scanChannel(); if (result == RADIOLIB_LORA_DETECTED) return true; - if (result != RADIOLIB_ERR_WRONG_MODEM) + if (result != RADIOLIB_CHANNEL_FREE) LOG_ERROR("Radiolib error %d when attempting SX128X scanChannel!\n", result); assert(result != RADIOLIB_ERR_WRONG_MODEM); diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index b40633af0..54eb577f7 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -256,7 +256,7 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta default: meshtastic_AdminMessage res = meshtastic_AdminMessage_init_default; - AdminMessageHandleResult handleResult = MeshModule::handleAdminMessageForAllPlugins(mp, r, &res); + AdminMessageHandleResult handleResult = MeshModule::handleAdminMessageForAllModules(mp, r, &res); if (handleResult == AdminMessageHandleResult::HANDLED_WITH_RESPONSE) { myReply = allocDataProtobuf(res); From 2450031b1bfd189c7e9723432922f5f6dd9d7245 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 17 Apr 2024 07:00:18 -0500 Subject: [PATCH 461/472] Add device metrics uptime to MQTT JSON (#3643) * Add device metrics uptime to MQTT JSON * Cast a spell --- src/mqtt/MQTT.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 05d5486b2..da1c204b8 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -656,6 +656,7 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp) msgPayload["voltage"] = new JSONValue(decoded->variant.device_metrics.voltage); msgPayload["channel_utilization"] = new JSONValue(decoded->variant.device_metrics.channel_utilization); msgPayload["air_util_tx"] = new JSONValue(decoded->variant.device_metrics.air_util_tx); + msgPayload["uptime_seconds"] = new JSONValue((uint)decoded->variant.device_metrics.uptime_seconds); } else if (decoded->which_variant == meshtastic_Telemetry_environment_metrics_tag) { msgPayload["temperature"] = new JSONValue(decoded->variant.environment_metrics.temperature); msgPayload["relative_humidity"] = new JSONValue(decoded->variant.environment_metrics.relative_humidity); From bc085ab840af3ab00dca88eb34b30db74e83d61e Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Wed, 17 Apr 2024 14:07:40 +0200 Subject: [PATCH 462/472] Fix #3641: Always set MAC when picking new NodeNum (#3651) Co-authored-by: Ben Meadors --- src/mesh/NodeDB.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 73aa29bbf..710b21593 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -527,8 +527,8 @@ void NodeDB::installDefaultDeviceState() void NodeDB::pickNewNodeNum() { NodeNum nodeNum = myNodeInfo.my_node_num; + getMacAddr(ourMacAddr); // Make sure ourMacAddr is set if (nodeNum == 0) { - getMacAddr(ourMacAddr); // Make sure ourMacAddr is set // Pick an initial nodenum based on the macaddr nodeNum = (ourMacAddr[2] << 24) | (ourMacAddr[3] << 16) | (ourMacAddr[4] << 8) | ourMacAddr[5]; } From d47e9bed196ae05c4dc1a2abd3bc783b9cbb965c Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Wed, 17 Apr 2024 14:25:52 -0500 Subject: [PATCH 463/472] Add multiple SPI devices for Radio, Display, and Touchscreen (#3638) This changeset gives us the ability to specify a separate SPI device for the LoRa, Display, and Touchscreen. The changes in Portduino also add support for specifying a new SPI speed for each transaction. All together, this means that we can let the Linux OS manage the CS lines, and also get much faster SPI speeds, leading to better framerates. * Add multiple SPI devices to put Radio, Display, and Touchscreen on each their own --------- Co-authored-by: Ben Meadors --- arch/portduino/portduino.ini | 2 +- bin/config-dist.yaml | 4 +- src/graphics/TFTDisplay.cpp | 4 +- src/graphics/mesh_bus_spi.cpp | 188 +++++++++++++++++++++++ src/graphics/mesh_bus_spi.h | 100 ++++++++++++ src/input/TouchScreenImpl1.cpp | 2 +- src/main.cpp | 12 +- src/main.h | 5 + src/platform/portduino/PortduinoGlue.cpp | 29 ++++ src/platform/portduino/PortduinoGlue.h | 6 +- 10 files changed, 340 insertions(+), 12 deletions(-) create mode 100644 src/graphics/mesh_bus_spi.cpp create mode 100644 src/graphics/mesh_bus_spi.h diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index 07151c4a3..53f06c9f3 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -1,6 +1,6 @@ ; The Portduino based sim environment on top of any host OS, all hardware will be simulated [portduino_base] -platform = https://github.com/meshtastic/platform-native.git#c95616208ffff4c8a36d48df810a3f072cce3521 +platform = https://github.com/meshtastic/platform-native.git#6fb39b6f94ece9c042141edb4afb91aca94dcaab framework = arduino build_src_filter = diff --git a/bin/config-dist.yaml b/bin/config-dist.yaml index d8cb5a9dd..f729f1ac7 100644 --- a/bin/config-dist.yaml +++ b/bin/config-dist.yaml @@ -101,11 +101,13 @@ Display: # Height: 240 Touchscreen: +### Note, at least for now, the touchscreen must have a CS pin defined, even if you let Linux manage the CS switching. + # Module: STMPE610 # CS: 7 # IRQ: 24 -# Module: XPT2046 +# Module: XPT2046 # Waveshare 2.8inch # CS: 7 # IRQ: 17 diff --git a/src/graphics/TFTDisplay.cpp b/src/graphics/TFTDisplay.cpp index b561f3b56..12e549424 100644 --- a/src/graphics/TFTDisplay.cpp +++ b/src/graphics/TFTDisplay.cpp @@ -1,6 +1,7 @@ #include "configuration.h" #include "main.h" #if ARCH_PORTDUINO +#include "mesh_bus_spi.h" #include "platform/portduino/PortduinoGlue.h" #endif @@ -339,7 +340,7 @@ static TFT_eSPI *tft = nullptr; // Invoke library, pins defined in User_Setup.h class LGFX : public lgfx::LGFX_Device { lgfx::Panel_LCD *_panel_instance; - lgfx::Bus_SPI _bus_instance; + lgfx::Mesh_Bus_SPI _bus_instance; lgfx::ITouch *_touch_instance; @@ -356,6 +357,7 @@ class LGFX : public lgfx::LGFX_Device _panel_instance = new lgfx::Panel_ILI9341; auto buscfg = _bus_instance.config(); buscfg.spi_mode = 0; + _bus_instance.spi_device(DisplaySPI, settingsStrings[displayspidev]); buscfg.pin_dc = settingsMap[displayDC]; // Set SPI DC pin number (-1 = disable) diff --git a/src/graphics/mesh_bus_spi.cpp b/src/graphics/mesh_bus_spi.cpp new file mode 100644 index 000000000..a9536d490 --- /dev/null +++ b/src/graphics/mesh_bus_spi.cpp @@ -0,0 +1,188 @@ +// This code has been copied from LovyanGFX to make the SPI device selectable for touchscreens. +// Ideally this could eventually be an inherited class from BUS_SPI, +// but currently too many internal objects are set private. + +#include "configuration.h" +#if ARCH_PORTDUINO +#include "lgfx/v1/misc/pixelcopy.hpp" +#include "main.h" +#include "mesh_bus_spi.h" +#include +#include + +namespace lgfx +{ +inline namespace v1 +{ +//---------------------------------------------------------------------------- + +void Mesh_Bus_SPI::config(const config_t &config) +{ + _cfg = config; + + if (_cfg.pin_dc >= 0) { + pinMode(_cfg.pin_dc, pin_mode_t::output); + gpio_hi(_cfg.pin_dc); + } +} + +bool Mesh_Bus_SPI::init(void) +{ + dc_h(); + pinMode(_cfg.pin_dc, pin_mode_t::output); + if (SPIName != "") + PrivateSPI->begin(SPIName.c_str()); + else + PrivateSPI->begin(); + return true; +} + +void Mesh_Bus_SPI::release(void) +{ + PrivateSPI->end(); +} + +void Mesh_Bus_SPI::spi_device(HardwareSPI *newSPI, std::string newSPIName) +{ + PrivateSPI = newSPI; + SPIName = newSPIName; +} +void Mesh_Bus_SPI::beginTransaction(void) +{ + dc_h(); + SPISettings setting(_cfg.freq_write, MSBFIRST, _cfg.spi_mode); + PrivateSPI->beginTransaction(setting); +} + +void Mesh_Bus_SPI::endTransaction(void) +{ + PrivateSPI->endTransaction(); + dc_h(); +} + +void Mesh_Bus_SPI::beginRead(void) +{ + PrivateSPI->endTransaction(); + // SPISettings setting(_cfg.freq_read, BitOrder::MSBFIRST, _cfg.spi_mode, false); + SPISettings setting(_cfg.freq_read, MSBFIRST, _cfg.spi_mode); + PrivateSPI->beginTransaction(setting); +} + +void Mesh_Bus_SPI::endRead(void) +{ + PrivateSPI->endTransaction(); + beginTransaction(); +} + +void Mesh_Bus_SPI::wait(void) {} + +bool Mesh_Bus_SPI::busy(void) const +{ + return false; +} + +bool Mesh_Bus_SPI::writeCommand(uint32_t data, uint_fast8_t bit_length) +{ + dc_l(); + PrivateSPI->transfer((uint8_t *)&data, bit_length >> 3); + dc_h(); + return true; +} + +void Mesh_Bus_SPI::writeData(uint32_t data, uint_fast8_t bit_length) +{ + PrivateSPI->transfer((uint8_t *)&data, bit_length >> 3); +} + +void Mesh_Bus_SPI::writeDataRepeat(uint32_t data, uint_fast8_t bit_length, uint32_t length) +{ + const uint8_t dst_bytes = bit_length >> 3; + uint32_t limit = (dst_bytes == 3) ? 12 : 16; + auto buf = _flip_buffer.getBuffer(512); + size_t fillpos = 0; + reinterpret_cast(buf)[0] = data; + fillpos += dst_bytes; + uint32_t len; + do { + len = ((length - 1) % limit) + 1; + if (limit <= 64) + limit <<= 1; + + while (fillpos < len * dst_bytes) { + memcpy(&buf[fillpos], buf, fillpos); + fillpos += fillpos; + } + + PrivateSPI->transfer(buf, len * dst_bytes); + } while (length -= len); +} + +void Mesh_Bus_SPI::writePixels(pixelcopy_t *param, uint32_t length) +{ + const uint8_t dst_bytes = param->dst_bits >> 3; + uint32_t limit = (dst_bytes == 3) ? 12 : 16; + uint32_t len; + do { + len = ((length - 1) % limit) + 1; + if (limit <= 32) + limit <<= 1; + auto buf = _flip_buffer.getBuffer(len * dst_bytes); + param->fp_copy(buf, 0, len, param); + PrivateSPI->transfer(buf, len * dst_bytes); + } while (length -= len); +} + +void Mesh_Bus_SPI::writeBytes(const uint8_t *data, uint32_t length, bool dc, bool use_dma) +{ + if (dc) + dc_h(); + else + dc_l(); + PrivateSPI->transfer(const_cast(data), length); + if (!dc) + dc_h(); +} + +uint32_t Mesh_Bus_SPI::readData(uint_fast8_t bit_length) +{ + uint32_t res = 0; + bit_length >>= 3; + if (!bit_length) + return res; + int idx = 0; + do { + res |= PrivateSPI->transfer(0) << idx; + idx += 8; + } while (--bit_length); + return res; +} + +bool Mesh_Bus_SPI::readBytes(uint8_t *dst, uint32_t length, bool use_dma) +{ + do { + dst[0] = PrivateSPI->transfer(0); + ++dst; + } while (--length); + return true; +} + +void Mesh_Bus_SPI::readPixels(void *dst, pixelcopy_t *param, uint32_t length) +{ + uint32_t bytes = param->src_bits >> 3; + uint32_t dstindex = 0; + uint32_t len = 4; + uint8_t buf[24]; + param->src_data = buf; + do { + if (len > length) + len = length; + readBytes((uint8_t *)buf, len * bytes, true); + param->src_x = 0; + dstindex = param->fp_copy(dst, dstindex, dstindex + len, param); + length -= len; + } while (length); +} + +} // namespace v1 +} // namespace lgfx +#endif \ No newline at end of file diff --git a/src/graphics/mesh_bus_spi.h b/src/graphics/mesh_bus_spi.h new file mode 100644 index 000000000..903f7ad9d --- /dev/null +++ b/src/graphics/mesh_bus_spi.h @@ -0,0 +1,100 @@ +#if ARCH_PORTDUINO +/*----------------------------------------------------------------------------/ + Lovyan GFX - Graphics library for embedded devices. + +Original Source: + https://github.com/lovyan03/LovyanGFX/ + +Licence: + [FreeBSD](https://github.com/lovyan03/LovyanGFX/blob/master/license.txt) + +Author: + [lovyan03](https://twitter.com/lovyan03) + +Contributors: + [ciniml](https://github.com/ciniml) + [mongonta0716](https://github.com/mongonta0716) + [tobozo](https://github.com/tobozo) +/----------------------------------------------------------------------------*/ +#pragma once + +#include + +#include "lgfx/v1/Bus.hpp" +#include "lgfx/v1/platforms/common.hpp" + +namespace lgfx +{ +inline namespace v1 +{ +//---------------------------------------------------------------------------- + +class Mesh_Bus_SPI : public IBus +{ + public: + struct config_t { + uint32_t freq_write = 16000000; + uint32_t freq_read = 8000000; + // bool spi_3wire = true; + // bool use_lock = true; + int16_t pin_sclk = -1; + int16_t pin_miso = -1; + int16_t pin_mosi = -1; + int16_t pin_dc = -1; + uint8_t spi_mode = 0; + }; + + const config_t &config(void) const { return _cfg; } + + void config(const config_t &config); + + bus_type_t busType(void) const override { return bus_type_t::bus_spi; } + + bool init(void) override; + void release(void) override; + void spi_device(HardwareSPI *newSPI, std::string newSPIName); + + void beginTransaction(void) override; + void endTransaction(void) override; + void wait(void) override; + bool busy(void) const override; + + bool writeCommand(uint32_t data, uint_fast8_t bit_length) override; + void writeData(uint32_t data, uint_fast8_t bit_length) override; + void writeDataRepeat(uint32_t data, uint_fast8_t bit_length, uint32_t count) override; + void writePixels(pixelcopy_t *param, uint32_t length) override; + void writeBytes(const uint8_t *data, uint32_t length, bool dc, bool use_dma) override; + + void initDMA(void) {} + void flush(void) {} + void addDMAQueue(const uint8_t *data, uint32_t length) override { writeBytes(data, length, true, true); } + void execDMAQueue(void) {} + uint8_t *getDMABuffer(uint32_t length) override { return _flip_buffer.getBuffer(length); } + + void beginRead(void) override; + void endRead(void) override; + uint32_t readData(uint_fast8_t bit_length) override; + bool readBytes(uint8_t *dst, uint32_t length, bool use_dma) override; + void readPixels(void *dst, pixelcopy_t *param, uint32_t length) override; + + private: + HardwareSPI *PrivateSPI; + std::string SPIName; + __attribute__((always_inline)) inline void dc_h(void) { gpio_hi(_cfg.pin_dc); } + __attribute__((always_inline)) inline void dc_l(void) { gpio_lo(_cfg.pin_dc); } + + config_t _cfg; + FlipBuffer _flip_buffer; + bool _need_wait; + uint32_t _mask_reg_dc; + uint32_t _last_apb_freq = -1; + uint32_t _clkdiv_write; + uint32_t _clkdiv_read; + volatile uint32_t *_gpio_reg_dc_h; + volatile uint32_t *_gpio_reg_dc_l; +}; + +//---------------------------------------------------------------------------- +} // namespace v1 +} // namespace lgfx +#endif \ No newline at end of file diff --git a/src/input/TouchScreenImpl1.cpp b/src/input/TouchScreenImpl1.cpp index 3e4ed4163..c863ead69 100644 --- a/src/input/TouchScreenImpl1.cpp +++ b/src/input/TouchScreenImpl1.cpp @@ -4,7 +4,7 @@ #include "configuration.h" #include "modules/ExternalNotificationModule.h" -#ifdef ARCH_PORTDUINO +#if ARCH_PORTDUINO #include "platform/portduino/PortduinoGlue.h" #endif diff --git a/src/main.cpp b/src/main.cpp index 744fda4de..b1a15634f 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -630,14 +630,12 @@ void setup() pinMode(LORA_CS, OUTPUT); digitalWrite(LORA_CS, HIGH); SPI1.begin(false); -#else // HW_SPI1_DEVICE +#else // HW_SPI1_DEVICE SPI.setSCK(LORA_SCK); SPI.setTX(LORA_MOSI); SPI.setRX(LORA_MISO); SPI.begin(false); -#endif // HW_SPI1_DEVICE -#elif ARCH_PORTDUINO - SPI.begin(settingsStrings[spidev].c_str()); +#endif // HW_SPI1_DEVICE #elif !defined(ARCH_ESP32) // ARCH_RP2040 SPI.begin(); #else @@ -724,7 +722,7 @@ void setup() if (settingsMap[use_sx1262]) { if (!rIf) { LOG_DEBUG("Attempting to activate sx1262 radio on SPI port %s\n", settingsStrings[spidev].c_str()); - LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(SPI, spiSettings); + LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(*LoraSPI, spiSettings); rIf = new SX1262Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset], settingsMap[busy]); if (!rIf->init()) { @@ -738,7 +736,7 @@ void setup() } else if (settingsMap[use_rf95]) { if (!rIf) { LOG_DEBUG("Attempting to activate rf95 radio on SPI port %s\n", settingsStrings[spidev].c_str()); - LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(SPI, spiSettings); + LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(*LoraSPI, spiSettings); rIf = new RF95Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset], settingsMap[busy]); if (!rIf->init()) { @@ -753,7 +751,7 @@ void setup() } else if (settingsMap[use_sx1280]) { if (!rIf) { LOG_DEBUG("Attempting to activate sx1280 radio on SPI port %s\n", settingsStrings[spidev].c_str()); - LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(SPI, spiSettings); + LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(*LoraSPI, spiSettings); rIf = new SX1280Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset], settingsMap[busy]); if (!rIf->init()) { diff --git a/src/main.h b/src/main.h index 132fd190b..bb812b7b6 100644 --- a/src/main.h +++ b/src/main.h @@ -22,6 +22,11 @@ extern NimbleBluetooth *nimbleBluetooth; extern NRF52Bluetooth *nrf52Bluetooth; #endif +#if ARCH_PORTDUINO +extern HardwareSPI *DisplaySPI; +extern HardwareSPI *LoraSPI; + +#endif extern ScanI2C::DeviceAddress screen_found; extern ScanI2C::DeviceAddress cardkb_found; extern uint8_t kb_model; diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index f686ef3dc..f3415aaee 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -15,6 +15,8 @@ #include #include +HardwareSPI *DisplaySPI; +HardwareSPI *LoraSPI; std::map settingsMap; std::map settingsStrings; char *configPath = nullptr; @@ -81,6 +83,7 @@ void portduinoSetup() settingsStrings[keyboardDevice] = ""; settingsStrings[webserverrootpath] = ""; settingsStrings[spidev] = ""; + settingsStrings[displayspidev] = ""; YAML::Node yamlConfig; @@ -187,6 +190,9 @@ void portduinoSetup() settingsMap[displayOffsetY] = yamlConfig["Display"]["OffsetY"].as(0); settingsMap[displayRotate] = yamlConfig["Display"]["Rotate"].as(false); settingsMap[displayInvert] = yamlConfig["Display"]["Invert"].as(false); + if (yamlConfig["Display"]["spidev"]) { + settingsStrings[displayspidev] = "/dev/" + yamlConfig["Display"]["spidev"].as("spidev0.1"); + } } settingsMap[touchscreenModule] = no_touchscreen; if (yamlConfig["Touchscreen"]) { @@ -196,6 +202,9 @@ void portduinoSetup() settingsMap[touchscreenModule] = stmpe610; settingsMap[touchscreenCS] = yamlConfig["Touchscreen"]["CS"].as(-1); settingsMap[touchscreenIRQ] = yamlConfig["Touchscreen"]["IRQ"].as(-1); + if (yamlConfig["Touchscreen"]["spidev"]) { + settingsStrings[touchscreenspidev] = "/dev/" + yamlConfig["Touchscreen"]["spidev"].as(""); + } } if (yamlConfig["Input"]) { settingsStrings[keyboardDevice] = (yamlConfig["Input"]["KeyboardDevice"]).as(""); @@ -267,6 +276,26 @@ void portduinoSetup() initGPIOPin(settingsMap[touchscreenIRQ], gpioChipName); } + // if we specify a touchscreen dev, that is SPI. + // else if we specify a screen dev, that is SPI + // else if we specify a LoRa dev, that is SPI. + if (settingsStrings[touchscreenspidev] != "") { + SPI.begin(settingsStrings[touchscreenspidev].c_str()); + DisplaySPI = new HardwareSPI; + DisplaySPI->begin(settingsStrings[displayspidev].c_str()); + LoraSPI = new HardwareSPI; + LoraSPI->begin(settingsStrings[spidev].c_str()); + } else if (settingsStrings[displayspidev] != "") { + SPI.begin(settingsStrings[displayspidev].c_str()); + DisplaySPI = &SPI; + LoraSPI = new HardwareSPI; + LoraSPI->begin(settingsStrings[spidev].c_str()); + } else { + SPI.begin(settingsStrings[spidev].c_str()); + LoraSPI = &SPI; + DisplaySPI = &SPI; + } + return; } diff --git a/src/platform/portduino/PortduinoGlue.h b/src/platform/portduino/PortduinoGlue.h index 505c436d6..980fc63b8 100644 --- a/src/platform/portduino/PortduinoGlue.h +++ b/src/platform/portduino/PortduinoGlue.h @@ -21,6 +21,8 @@ enum configNames { touchscreenModule, touchscreenCS, touchscreenIRQ, + touchscreenspidev, + displayspidev, displayPanel, displayWidth, displayHeight, @@ -45,4 +47,6 @@ enum { level_error, level_warn, level_info, level_debug }; extern std::map settingsMap; extern std::map settingsStrings; -int initGPIOPin(int pinNum, std::string gpioChipname); \ No newline at end of file +int initGPIOPin(int pinNum, std::string gpioChipname); +extern HardwareSPI *DisplaySPI; +extern HardwareSPI *LoraSPI; \ No newline at end of file From 2e14234b77ed98ec63368fb5fb5b8cf6192f7018 Mon Sep 17 00:00:00 2001 From: Oliver Seiler Date: Thu, 18 Apr 2024 09:55:47 +1200 Subject: [PATCH 464/472] don't enable the CDC interface already at boot (#3652) Co-authored-by: Ben Meadors --- boards/tbeam-s3-core.json | 1 - 1 file changed, 1 deletion(-) diff --git a/boards/tbeam-s3-core.json b/boards/tbeam-s3-core.json index 8d2c3eed6..4c82a2789 100644 --- a/boards/tbeam-s3-core.json +++ b/boards/tbeam-s3-core.json @@ -7,7 +7,6 @@ "extra_flags": [ "-DBOARD_HAS_PSRAM", "-DLILYGO_TBEAM_S3_CORE", - "-DARDUINO_USB_CDC_ON_BOOT=1", "-DARDUINO_USB_MODE=1", "-DARDUINO_RUNNING_CORE=1", "-DARDUINO_EVENT_RUNNING_CORE=1" From 747c713ba925fd77f6f4a8bb000db3cedd9d45ab Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Fri, 19 Apr 2024 00:27:18 +1200 Subject: [PATCH 465/472] (ESP32) Fix bluetooth after light-sleep; de-init for deep sleep (#3655) --- src/nimble/NimbleBluetooth.cpp | 10 ++++++++-- src/platform/esp32/main-esp32.cpp | 5 +++-- src/sleep.cpp | 4 ++-- variants/heltec_wireless_paper/variant.h | 3 --- variants/heltec_wireless_paper_v1/variant.h | 3 --- 5 files changed, 13 insertions(+), 12 deletions(-) diff --git a/src/nimble/NimbleBluetooth.cpp b/src/nimble/NimbleBluetooth.cpp index 092aef470..8f7e00461 100644 --- a/src/nimble/NimbleBluetooth.cpp +++ b/src/nimble/NimbleBluetooth.cpp @@ -106,20 +106,26 @@ static NimbleBluetoothFromRadioCallback *fromRadioCallbacks; void NimbleBluetooth::shutdown() { + // No measurable power saving for ESP32 during light-sleep(?) +#ifndef ARCH_ESP32 // Shutdown bluetooth for minimum power draw LOG_INFO("Disable bluetooth\n"); - // Bluefruit.Advertising.stop(); NimBLEAdvertising *pAdvertising = NimBLEDevice::getAdvertising(); pAdvertising->reset(); pAdvertising->stop(); +#endif } -// Extra power-saving on some devices +// Proper shutdown for ESP32. Needs reboot to reverse. void NimbleBluetooth::deinit() { +#ifdef ARCH_ESP32 + LOG_INFO("Disable bluetooth until reboot\n"); NimBLEDevice::deinit(); +#endif } +// Has initial setup been completed bool NimbleBluetooth::isActive() { return bleServer; diff --git a/src/platform/esp32/main-esp32.cpp b/src/platform/esp32/main-esp32.cpp index 3fb6e7774..2894a49fc 100644 --- a/src/platform/esp32/main-esp32.cpp +++ b/src/platform/esp32/main-esp32.cpp @@ -30,9 +30,10 @@ void setBluetoothEnable(bool enable) } if (enable && !nimbleBluetooth->isActive()) { nimbleBluetooth->setup(); - } else if (!enable) { - nimbleBluetooth->shutdown(); } + // For ESP32, no way to recover from bluetooth shutdown without reboot + // BLE advertising automatically stops when MCU enters light-sleep(?) + // For deep-sleep, shutdown hardware with nimbleBluetooth->deinit(). Requires reboot to reverse } } #else diff --git a/src/sleep.cpp b/src/sleep.cpp index 860a676df..a2a221d79 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -207,8 +207,8 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) // esp_wifi_stop(); waitEnterSleep(skipPreflight); -#ifdef NIMBLE_DEINIT_FOR_DEEPSLEEP - // Extra power saving on some devices +#ifdef ARCH_ESP32 + // Full shutdown of bluetooth hardware nimbleBluetooth->deinit(); #endif diff --git a/variants/heltec_wireless_paper/variant.h b/variants/heltec_wireless_paper/variant.h index 466925a2e..29b8bbbd1 100644 --- a/variants/heltec_wireless_paper/variant.h +++ b/variants/heltec_wireless_paper/variant.h @@ -55,6 +55,3 @@ #define SX126X_DIO2_AS_RF_SWITCH #define SX126X_DIO3_TCXO_VOLTAGE 1.8 - -// Power management -#define NIMBLE_DEINIT_FOR_DEEPSLEEP // Required to reach manufacturers claim of 18uA diff --git a/variants/heltec_wireless_paper_v1/variant.h b/variants/heltec_wireless_paper_v1/variant.h index 466925a2e..29b8bbbd1 100644 --- a/variants/heltec_wireless_paper_v1/variant.h +++ b/variants/heltec_wireless_paper_v1/variant.h @@ -55,6 +55,3 @@ #define SX126X_DIO2_AS_RF_SWITCH #define SX126X_DIO3_TCXO_VOLTAGE 1.8 - -// Power management -#define NIMBLE_DEINIT_FOR_DEEPSLEEP // Required to reach manufacturers claim of 18uA From 425a71599595b1d4937f5d9030886a0f7e5c98fd Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Thu, 18 Apr 2024 14:20:39 -0500 Subject: [PATCH 466/472] Added one minute throttling to NodeDB save to disk (#3648) * Added one minute throttling to NodeDB * Derp --- src/mesh/Default.h | 3 ++- src/mesh/NodeDB.cpp | 7 +++++-- src/mesh/NodeDB.h | 3 ++- src/mesh/Throttle.cpp | 27 +++++++++++++++++++++++++++ src/mesh/Throttle.h | 9 +++++++++ 5 files changed, 45 insertions(+), 4 deletions(-) create mode 100644 src/mesh/Throttle.cpp create mode 100644 src/mesh/Throttle.h diff --git a/src/mesh/Default.h b/src/mesh/Default.h index 734cdf519..95723744b 100644 --- a/src/mesh/Default.h +++ b/src/mesh/Default.h @@ -2,6 +2,7 @@ #include #include #define ONE_DAY 24 * 60 * 60 +#define ONE_MINUTE_MS 60 * 1000 #define default_gps_update_interval IF_ROUTER(ONE_DAY, 2 * 60) #define default_broadcast_interval_secs IF_ROUTER(ONE_DAY / 2, 15 * 60) @@ -27,4 +28,4 @@ class Default static uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval); static uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t defaultInterval); static uint32_t getConfiguredOrDefault(uint32_t configured, uint32_t defaultValue); -}; +}; \ No newline at end of file diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 710b21593..39422b454 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -813,6 +813,7 @@ size_t NodeDB::getNumOnlineMeshNodes(bool localOnly) } #include "MeshModule.h" +#include "Throttle.h" /** Update position info for this node based on received position data */ @@ -907,8 +908,10 @@ bool NodeDB::updateUser(uint32_t nodeId, const meshtastic_User &p, uint8_t chann powerFSM.trigger(EVENT_NODEDB_UPDATED); notifyObservers(true); // Force an update whether or not our node counts have changed - // We just changed something important about the user, store our DB - saveToDisk(SEGMENT_DEVICESTATE); + // We just changed something about the user, store our DB + Throttle::execute( + &lastNodeDbSave, ONE_MINUTE_MS, []() { nodeDB->saveToDisk(SEGMENT_DEVICESTATE); }, + []() { LOG_DEBUG("Deferring NodeDB saveToDisk for now, since we saved less than a minute ago\n"); }); } return changed; diff --git a/src/mesh/NodeDB.h b/src/mesh/NodeDB.h index 1c1736f78..57040fbd6 100644 --- a/src/mesh/NodeDB.h +++ b/src/mesh/NodeDB.h @@ -160,6 +160,7 @@ class NodeDB } private: + uint32_t lastNodeDbSave = 0; // when we last saved our db to flash /// Find a node in our DB, create an empty NodeInfoLite if missing meshtastic_NodeInfoLite *getOrCreateMeshNode(NodeNum n); @@ -229,4 +230,4 @@ extern uint32_t error_address; ModuleConfig_RangeTestConfig_size + ModuleConfig_SerialConfig_size + ModuleConfig_StoreForwardConfig_size + \ ModuleConfig_TelemetryConfig_size + ModuleConfig_size) -// Please do not remove this comment, it makes trunk and compiler happy at the same time. +// Please do not remove this comment, it makes trunk and compiler happy at the same time. \ No newline at end of file diff --git a/src/mesh/Throttle.cpp b/src/mesh/Throttle.cpp new file mode 100644 index 000000000..d8f23f9dc --- /dev/null +++ b/src/mesh/Throttle.cpp @@ -0,0 +1,27 @@ +#include "Throttle.h" +#include + +/// @brief Execute a function throttled to a minimum interval +/// @param lastExecutionMs Pointer to the last execution time in milliseconds +/// @param minumumIntervalMs Minimum execution interval in milliseconds +/// @param throttleFunc Function to execute if the execution is not deferred +/// @param onDefer Default to NULL, execute the function if the execution is deferred +/// @return true if the function was executed, false if it was deferred +bool Throttle::execute(uint32_t *lastExecutionMs, uint32_t minumumIntervalMs, void (*throttleFunc)(void), void (*onDefer)(void)) +{ + if (*lastExecutionMs == 0) { + *lastExecutionMs = millis(); + throttleFunc(); + return true; + } + uint32_t now = millis(); + + if ((now - *lastExecutionMs) >= minumumIntervalMs) { + throttleFunc(); + *lastExecutionMs = now; + return true; + } else if (onDefer != NULL) { + onDefer(); + } + return false; +} \ No newline at end of file diff --git a/src/mesh/Throttle.h b/src/mesh/Throttle.h new file mode 100644 index 000000000..8115595a4 --- /dev/null +++ b/src/mesh/Throttle.h @@ -0,0 +1,9 @@ +#pragma once +#include +#include + +class Throttle +{ + public: + static bool execute(uint32_t *lastExecutionMs, uint32_t minumumIntervalMs, void (*func)(void), void (*onDefer)(void) = NULL); +}; \ No newline at end of file From 4c0b7ea409a9ea372e202ca95bff1463ee13717c Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Thu, 18 Apr 2024 21:28:11 +0200 Subject: [PATCH 467/472] StoreForward: Remove assert when receiving unhandled case (#3661) --- src/modules/esp32/StoreForwardModule.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/esp32/StoreForwardModule.cpp b/src/modules/esp32/StoreForwardModule.cpp index a60065e56..12cddc520 100644 --- a/src/modules/esp32/StoreForwardModule.cpp +++ b/src/modules/esp32/StoreForwardModule.cpp @@ -506,7 +506,7 @@ bool StoreForwardModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, break; default: - assert(0); // unexpected state + break; // no need to do anything } return true; // There's no need for others to look at this message. } From e4b5f2ce14fe118eb1455a38e7768871490b75fe Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Thu, 18 Apr 2024 23:16:50 +0200 Subject: [PATCH 468/472] NeighborInfo: Only keep neighbors in RAM (#3660) * NeighborInfo: Only keep neighbors in RAM It fills up quickly when nodes are running >=2.3 * Defer first transmission as it's usually empty --------- Co-authored-by: Ben Meadors --- src/modules/NeighborInfoModule.cpp | 144 +++++++++-------------------- src/modules/NeighborInfoModule.h | 27 +----- 2 files changed, 50 insertions(+), 121 deletions(-) diff --git a/src/modules/NeighborInfoModule.cpp b/src/modules/NeighborInfoModule.cpp index 470234047..8c8135deb 100644 --- a/src/modules/NeighborInfoModule.cpp +++ b/src/modules/NeighborInfoModule.cpp @@ -4,11 +4,8 @@ #include "NodeDB.h" #include "RTC.h" -#define MAX_NUM_NEIGHBORS 10 // also defined in NeighborInfo protobuf options NeighborInfoModule *neighborInfoModule; -static const char *neighborInfoConfigFile = "/prefs/neighbors.proto"; - /* Prints a single neighbor info packet and associated neighbors Uses LOG_DEBUG, which equates to Console.log @@ -30,26 +27,23 @@ NOTE: for debugging only */ void NeighborInfoModule::printNodeDBNeighbors() { - int num_neighbors = getNumNeighbors(); - LOG_DEBUG("Our NodeDB contains %d neighbors\n", num_neighbors); - for (int i = 0; i < num_neighbors; i++) { - const meshtastic_Neighbor *dbEntry = getNeighborByIndex(i); - LOG_DEBUG(" Node %d: node_id=0x%x, snr=%.2f\n", i, dbEntry->node_id, dbEntry->snr); + LOG_DEBUG("Our NodeDB contains %d neighbors\n", neighbors.size()); + for (size_t i = 0; i < neighbors.size(); i++) { + LOG_DEBUG("Node %d: node_id=0x%x, snr=%.2f\n", i, neighbors[i].node_id, neighbors[i].snr); } } /* Send our initial owner announcement 35 seconds after we start (to give network time to setup) */ NeighborInfoModule::NeighborInfoModule() : ProtobufModule("neighborinfo", meshtastic_PortNum_NEIGHBORINFO_APP, &meshtastic_NeighborInfo_msg), - concurrency::OSThread("NeighborInfoModule"), neighbors(neighborState.neighbors), - numNeighbors(&neighborState.neighbors_count) + concurrency::OSThread("NeighborInfoModule") { ourPortNum = meshtastic_PortNum_NEIGHBORINFO_APP; if (moduleConfig.neighbor_info.enabled) { isPromiscuous = true; // Update neighbors from all packets - this->loadProtoForModule(); - setIntervalFromNow(35 * 1000); + setIntervalFromNow( + Default::getConfiguredOrDefaultMs(moduleConfig.neighbor_info.update_interval, default_broadcast_interval_secs)); } else { LOG_DEBUG("NeighborInfoModule is disabled\n"); disable(); @@ -63,18 +57,17 @@ Assumes that the neighborInfo packet has been allocated */ uint32_t NeighborInfoModule::collectNeighborInfo(meshtastic_NeighborInfo *neighborInfo) { - uint my_node_id = nodeDB->getNodeNum(); + NodeNum my_node_id = nodeDB->getNodeNum(); neighborInfo->node_id = my_node_id; neighborInfo->last_sent_by_id = my_node_id; neighborInfo->node_broadcast_interval_secs = moduleConfig.neighbor_info.update_interval; - int num_neighbors = cleanUpNeighbors(); + cleanUpNeighbors(); - for (int i = 0; i < num_neighbors; i++) { - const meshtastic_Neighbor *dbEntry = getNeighborByIndex(i); - if ((neighborInfo->neighbors_count < MAX_NUM_NEIGHBORS) && (dbEntry->node_id != my_node_id)) { - neighborInfo->neighbors[neighborInfo->neighbors_count].node_id = dbEntry->node_id; - neighborInfo->neighbors[neighborInfo->neighbors_count].snr = dbEntry->snr; + for (auto nbr : neighbors) { + if ((neighborInfo->neighbors_count < MAX_NUM_NEIGHBORS) && (nbr.node_id != my_node_id)) { + neighborInfo->neighbors[neighborInfo->neighbors_count].node_id = nbr.node_id; + neighborInfo->neighbors[neighborInfo->neighbors_count].snr = nbr.snr; // Note: we don't set the last_rx_time and node_broadcast_intervals_secs here, because we don't want to send this over // the mesh neighborInfo->neighbors_count++; @@ -85,41 +78,22 @@ uint32_t NeighborInfoModule::collectNeighborInfo(meshtastic_NeighborInfo *neighb } /* -Remove neighbors from the database that we haven't heard from in a while -@returns new number of neighbors + Remove neighbors from the database that we haven't heard from in a while */ -size_t NeighborInfoModule::cleanUpNeighbors() +void NeighborInfoModule::cleanUpNeighbors() { uint32_t now = getTime(); - int num_neighbors = getNumNeighbors(); NodeNum my_node_id = nodeDB->getNodeNum(); - - // Find neighbors to remove - std::vector indices_to_remove; - for (int i = 0; i < num_neighbors; i++) { - const meshtastic_Neighbor *dbEntry = getNeighborByIndex(i); + for (auto it = neighbors.rbegin(); it != neighbors.rend();) { // We will remove a neighbor if we haven't heard from them in twice the broadcast interval - if ((now - dbEntry->last_rx_time > dbEntry->node_broadcast_interval_secs * 2) && (dbEntry->node_id != my_node_id)) { - indices_to_remove.push_back(i); + if ((now - it->last_rx_time > it->node_broadcast_interval_secs * 2) && (it->node_id != my_node_id)) { + LOG_DEBUG("Removing neighbor with node ID 0x%x\n", it->node_id); + it = std::vector::reverse_iterator( + neighbors.erase(std::next(it).base())); // Erase the element and update the iterator + } else { + ++it; } } - - // Update the neighbor list - for (uint i = 0; i < indices_to_remove.size(); i++) { - int index = indices_to_remove[i]; - LOG_DEBUG("Removing neighbor with node ID 0x%x\n", neighbors[index].node_id); - for (int j = index; j < num_neighbors - 1; j++) { - neighbors[j] = neighbors[j + 1]; - } - (*numNeighbors)--; - } - - // Save the neighbor list if we removed any neighbors or neighbors were already updated upon receiving a packet - if (indices_to_remove.size() > 0 || shouldSave) { - saveProtoForModule(); - } - - return *numNeighbors; } /* Send neighbor info to the mesh */ @@ -143,7 +117,9 @@ Will be used for broadcast. int32_t NeighborInfoModule::runOnce() { bool requestReplies = false; - sendNeighborInfo(NODENUM_BROADCAST, requestReplies); + if (airTime->isTxAllowedChannelUtil(true) && airTime->isTxAllowedAirUtil()) { + sendNeighborInfo(NODENUM_BROADCAST, requestReplies); + } return Default::getConfiguredOrDefaultMs(moduleConfig.neighbor_info.update_interval, default_broadcast_interval_secs); } @@ -178,10 +154,7 @@ void NeighborInfoModule::alterReceivedProtobuf(meshtastic_MeshPacket &p, meshtas void NeighborInfoModule::resetNeighbors() { - *numNeighbors = 0; - neighborState.neighbors_count = 0; - memset(neighborState.neighbors, 0, sizeof(neighborState.neighbors)); - saveProtoForModule(); + neighbors.clear(); } void NeighborInfoModule::updateNeighbors(const meshtastic_MeshPacket &mp, const meshtastic_NeighborInfo *np) @@ -201,61 +174,36 @@ meshtastic_Neighbor *NeighborInfoModule::getOrCreateNeighbor(NodeNum originalSen n = nodeDB->getNodeNum(); } // look for one in the existing list - for (int i = 0; i < (*numNeighbors); i++) { - meshtastic_Neighbor *nbr = &neighbors[i]; - if (nbr->node_id == n) { + for (size_t i = 0; i < neighbors.size(); i++) { + if (neighbors[i].node_id == n) { // if found, update it - nbr->snr = snr; - nbr->last_rx_time = getTime(); + neighbors[i].snr = snr; + neighbors[i].last_rx_time = getTime(); // Only if this is the original sender, the broadcast interval corresponds to it if (originalSender == n && node_broadcast_interval_secs != 0) - nbr->node_broadcast_interval_secs = node_broadcast_interval_secs; - return nbr; + neighbors[i].node_broadcast_interval_secs = node_broadcast_interval_secs; + return &neighbors[i]; } } // otherwise, allocate one and assign data to it - // TODO: max memory for the database should take neighbors into account, but currently doesn't - if (*numNeighbors < MAX_NUM_NEIGHBORS) { - (*numNeighbors)++; - } - meshtastic_Neighbor *new_nbr = &neighbors[((*numNeighbors) - 1)]; - new_nbr->node_id = n; - new_nbr->snr = snr; - new_nbr->last_rx_time = getTime(); + + meshtastic_Neighbor new_nbr = meshtastic_Neighbor_init_zero; + new_nbr.node_id = n; + new_nbr.snr = snr; + new_nbr.last_rx_time = getTime(); // Only if this is the original sender, the broadcast interval corresponds to it if (originalSender == n && node_broadcast_interval_secs != 0) - new_nbr->node_broadcast_interval_secs = node_broadcast_interval_secs; + new_nbr.node_broadcast_interval_secs = node_broadcast_interval_secs; else // Assume the same broadcast interval as us for the neighbor if we don't know it - new_nbr->node_broadcast_interval_secs = moduleConfig.neighbor_info.update_interval; - shouldSave = true; // Save the new neighbor upon next cleanup - return new_nbr; -} + new_nbr.node_broadcast_interval_secs = moduleConfig.neighbor_info.update_interval; -void NeighborInfoModule::loadProtoForModule() -{ - if (nodeDB->loadProto(neighborInfoConfigFile, meshtastic_NeighborInfo_size, sizeof(meshtastic_NeighborInfo), - &meshtastic_NeighborInfo_msg, &neighborState) != LoadFileResult::SUCCESS) { - neighborState = meshtastic_NeighborInfo_init_zero; + if (neighbors.size() < MAX_NUM_NEIGHBORS) { + neighbors.push_back(new_nbr); + } else { + // If we have too many neighbors, replace the oldest one + LOG_WARN("Neighbor DB is full, replacing oldest neighbor\n"); + neighbors.erase(neighbors.begin()); + neighbors.push_back(new_nbr); } -} - -/** - * @brief Save the module config to file. - * - * @return true On success. - * @return false On error. - */ -bool NeighborInfoModule::saveProtoForModule() -{ - bool okay = true; - -#ifdef FS - FS.mkdir("/prefs"); -#endif - - okay &= nodeDB->saveProto(neighborInfoConfigFile, meshtastic_NeighborInfo_size, &meshtastic_NeighborInfo_msg, &neighborState); - if (okay) - shouldSave = false; - - return okay; + return &neighbors.back(); } \ No newline at end of file diff --git a/src/modules/NeighborInfoModule.h b/src/modules/NeighborInfoModule.h index d47004981..496fdece5 100644 --- a/src/modules/NeighborInfoModule.h +++ b/src/modules/NeighborInfoModule.h @@ -1,13 +1,13 @@ #pragma once #include "ProtobufModule.h" +#define MAX_NUM_NEIGHBORS 10 // also defined in NeighborInfo protobuf options /* * Neighborinfo module for sending info on each node's 0-hop neighbors to the mesh */ class NeighborInfoModule : public ProtobufModule, private concurrency::OSThread { - meshtastic_Neighbor *neighbors; - pb_size_t *numNeighbors; + std::vector neighbors; public: /* @@ -18,15 +18,7 @@ class NeighborInfoModule : public ProtobufModule, priva /* Reset neighbor info after clearing nodeDB*/ void resetNeighbors(); - bool saveProtoForModule(); - - private: - bool shouldSave = false; // Whether we should save the neighbor info to flash - protected: - // Note: this holds our local info. - meshtastic_NeighborInfo neighborState; - /* * Called to handle a particular incoming message * @return true if you've guaranteed you've handled this message and no other handlers should be considered for it @@ -40,10 +32,9 @@ class NeighborInfoModule : public ProtobufModule, priva uint32_t collectNeighborInfo(meshtastic_NeighborInfo *neighborInfo); /* - Remove neighbors from the database that we haven't heard from in a while - @returns new number of neighbors + Remove neighbors from the database that we haven't heard from in a while */ - size_t cleanUpNeighbors(); + void cleanUpNeighbors(); /* Allocate a new NeighborInfo packet */ meshtastic_NeighborInfo *allocateNeighborInfoPacket(); @@ -56,22 +47,12 @@ class NeighborInfoModule : public ProtobufModule, priva */ void sendNeighborInfo(NodeNum dest = NODENUM_BROADCAST, bool wantReplies = false); - size_t getNumNeighbors() { return *numNeighbors; } - - meshtastic_Neighbor *getNeighborByIndex(size_t x) - { - assert(x < *numNeighbors); - return &neighbors[x]; - } - /* update neighbors with subpacket sniffed from network */ void updateNeighbors(const meshtastic_MeshPacket &mp, const meshtastic_NeighborInfo *np); /* update a NeighborInfo packet with our NodeNum as last_sent_by_id */ void alterReceivedProtobuf(meshtastic_MeshPacket &p, meshtastic_NeighborInfo *n) override; - void loadProtoForModule(); - /* Does our periodic broadcast */ int32_t runOnce() override; From 64edfb76e0ad1d7d434df27a9d9edac1e7003533 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Fri, 19 Apr 2024 00:44:13 +0200 Subject: [PATCH 469/472] Uplink to MQTT after potentially altering content (#3646) Mainly for traceroute module now Co-authored-by: Ben Meadors --- src/mesh/Router.cpp | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp index e4d67f019..4189bca66 100644 --- a/src/mesh/Router.cpp +++ b/src/mesh/Router.cpp @@ -465,21 +465,22 @@ void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src) cancelSending(p->from, p->id); skipHandle = true; } -#if !MESHTASTIC_EXCLUDE_MQTT - // Publish received message to MQTT if we're not the original transmitter of the packet - if (!skipHandle && moduleConfig.mqtt.enabled && getFrom(p) != nodeDB->getNodeNum() && mqtt) - mqtt->onSend(*p_encrypted, *p, p->channel); -#endif - } else { printPacket("packet decoding failed or skipped (no PSK?)", p); } - packetPool.release(p_encrypted); // Release the encrypted packet - // call modules here - if (!skipHandle) + if (!skipHandle) { MeshModule::callModules(*p, src); + +#if !MESHTASTIC_EXCLUDE_MQTT + // After potentially altering it, publish received message to MQTT if we're not the original transmitter of the packet + if (decoded && moduleConfig.mqtt.enabled && getFrom(p) != nodeDB->getNodeNum() && mqtt) + mqtt->onSend(*p_encrypted, *p, p->channel); +#endif + } + + packetPool.release(p_encrypted); // Release the encrypted packet } void Router::perhapsHandleReceived(meshtastic_MeshPacket *p) From 7a3570aecf119825dba67784ecedb0338e1285bb Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 18 Apr 2024 18:29:50 -0500 Subject: [PATCH 470/472] [create-pull-request] automated change (#3662) Co-authored-by: thebentern --- protobufs | 2 +- src/mesh/generated/meshtastic/config.pb.h | 29 ++++++++++------------- 2 files changed, 13 insertions(+), 18 deletions(-) diff --git a/protobufs b/protobufs index ecf105f66..0d08acd9c 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit ecf105f66d182531423b73f4408c53701313c4eb +Subproject commit 0d08acd9c51c4e5575f3ea42368834ec990b2278 diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index fd040c57f..2abe040a6 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -324,35 +324,30 @@ typedef struct _meshtastic_Config_PositionConfig { /* Power Config\ See [Power Config](/docs/settings/config/power) for additional power config details. */ typedef struct _meshtastic_Config_PowerConfig { - /* If set, we are powered from a low-current source (i.e. solar), so even if it looks like we have power flowing in - we should try to minimize power consumption as much as possible. - YOU DO NOT NEED TO SET THIS IF YOU'VE set is_router (it is implied in that case). - Advanced Option */ + /* Description: Will sleep everything as much as possible, for the tracker and sensor role this will also include the lora radio. + Don't use this setting if you want to use your device with the phone apps or are using a device without a user button. + Technical Details: Works for ESP32 devices and NRF52 devices in the Sensor or Tracker roles */ bool is_power_saving; - /* If non-zero, the device will fully power off this many seconds after external power is removed. */ + /* Description: If non-zero, the device will fully power off this many seconds after external power is removed. */ uint32_t on_battery_shutdown_after_secs; /* Ratio of voltage divider for battery pin eg. 3.20 (R1=100k, R2=220k) Overrides the ADC_MULTIPLIER defined in variant for battery voltage calculation. - Should be set to floating point value between 2 and 4 - Fixes issues on Heltec v2 */ + https://meshtastic.org/docs/configuration/radio/power/#adc-multiplier-override + Should be set to floating point value between 2 and 6 */ float adc_multiplier_override; - /* Wait Bluetooth Seconds - The number of seconds for to wait before turning off BLE in No Bluetooth states - 0 for default of 1 minute */ + /* Description: The number of seconds for to wait before turning off BLE in No Bluetooth states + Technical Details: ESP32 Only 0 for default of 1 minute */ uint32_t wait_bluetooth_secs; /* Super Deep Sleep Seconds While in Light Sleep if mesh_sds_timeout_secs is exceeded we will lower into super deep sleep for this value (default 1 year) or a button press 0 for default of one year */ uint32_t sds_secs; - /* Light Sleep Seconds - In light sleep the CPU is suspended, LoRa radio is on, BLE is off an GPS is on - ESP32 Only - 0 for default of 300 */ + /* Description: In light sleep the CPU is suspended, LoRa radio is on, BLE is off an GPS is on + Technical Details: ESP32 Only 0 for default of 300 */ uint32_t ls_secs; - /* Minimum Wake Seconds - While in light sleep when we receive packets on the LoRa radio we will wake and handle them and stay awake in no BLE mode for this value - 0 for default of 10 seconds */ + /* Description: While in light sleep when we receive packets on the LoRa radio we will wake and handle them and stay awake in no BLE mode for this value + Technical Details: ESP32 Only 0 for default of 10 seconds */ uint32_t min_wake_secs; /* I2C address of INA_2XX to use for reading device battery voltage */ uint8_t device_battery_ina_address; From 65bde8538fae649939273d2f93a526acc6aa37f2 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 18 Apr 2024 20:33:23 -0500 Subject: [PATCH 471/472] [create-pull-request] automated change (#3663) Co-authored-by: thebentern --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index f5ad818a2..485f55130 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 3 -build = 6 +build = 7 From 44aa248099fdcf2a27ae06285ceabc29d6479fd8 Mon Sep 17 00:00:00 2001 From: Manuel <71137295+mverch67@users.noreply.github.com> Date: Sat, 20 Apr 2024 02:27:13 +0200 Subject: [PATCH 472/472] added new display parameters (#3670) --- src/platform/portduino/PortduinoGlue.cpp | 19 +++++++++++++++++++ src/platform/portduino/PortduinoGlue.h | 11 +++++++++-- 2 files changed, 28 insertions(+), 2 deletions(-) diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index f3415aaee..a04c9c12c 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -178,18 +178,31 @@ void portduinoSetup() settingsMap[displayPanel] = st7735; else if (yamlConfig["Display"]["Panel"].as("") == "ST7735S") settingsMap[displayPanel] = st7735s; + else if (yamlConfig["Display"]["Panel"].as("") == "ST7796") + settingsMap[displayPanel] = st7796; else if (yamlConfig["Display"]["Panel"].as("") == "ILI9341") settingsMap[displayPanel] = ili9341; + else if (yamlConfig["Display"]["Panel"].as("") == "ILI9488") + settingsMap[displayPanel] = ili9488; + else if (yamlConfig["Display"]["Panel"].as("") == "HX8357D") + settingsMap[displayPanel] = hx8357d; + else if (yamlConfig["Display"]["Panel"].as("") == "X11") + settingsMap[displayPanel] = x11; settingsMap[displayHeight] = yamlConfig["Display"]["Height"].as(0); settingsMap[displayWidth] = yamlConfig["Display"]["Width"].as(0); settingsMap[displayDC] = yamlConfig["Display"]["DC"].as(-1); settingsMap[displayCS] = yamlConfig["Display"]["CS"].as(-1); + settingsMap[displayRGBOrder] = yamlConfig["Display"]["RGBOrder"].as(false); settingsMap[displayBacklight] = yamlConfig["Display"]["Backlight"].as(-1); + settingsMap[displayBacklightInvert] = yamlConfig["Display"]["BacklightInvert"].as(false); + settingsMap[displayBacklightPWMChannel] = yamlConfig["Display"]["BacklightPWMChannel"].as(-1); settingsMap[displayReset] = yamlConfig["Display"]["Reset"].as(-1); settingsMap[displayOffsetX] = yamlConfig["Display"]["OffsetX"].as(0); settingsMap[displayOffsetY] = yamlConfig["Display"]["OffsetY"].as(0); settingsMap[displayRotate] = yamlConfig["Display"]["Rotate"].as(false); + settingsMap[displayOffsetRotate] = yamlConfig["Display"]["OffsetRotate"].as(1); settingsMap[displayInvert] = yamlConfig["Display"]["Invert"].as(false); + settingsMap[displayBusFrequency] = yamlConfig["Display"]["BusFrequency"].as(40000000); if (yamlConfig["Display"]["spidev"]) { settingsStrings[displayspidev] = "/dev/" + yamlConfig["Display"]["spidev"].as("spidev0.1"); } @@ -200,8 +213,14 @@ void portduinoSetup() settingsMap[touchscreenModule] = xpt2046; else if (yamlConfig["Touchscreen"]["Module"].as("") == "STMPE610") settingsMap[touchscreenModule] = stmpe610; + else if (yamlConfig["Touchscreen"]["Module"].as("") == "GT911") + settingsMap[touchscreenModule] = gt911; + else if (yamlConfig["Touchscreen"]["Module"].as("") == "FT5x06") + settingsMap[touchscreenModule] = ft5x06; settingsMap[touchscreenCS] = yamlConfig["Touchscreen"]["CS"].as(-1); settingsMap[touchscreenIRQ] = yamlConfig["Touchscreen"]["IRQ"].as(-1); + settingsMap[touchscreenBusFrequency] = yamlConfig["Touchscreen"]["BusFrequency"].as(1000000); + settingsMap[touchscreenRotate] = yamlConfig["Touchscreen"]["Rotate"].as(-1); if (yamlConfig["Touchscreen"]["spidev"]) { settingsStrings[touchscreenspidev] = "/dev/" + yamlConfig["Touchscreen"]["spidev"].as(""); } diff --git a/src/platform/portduino/PortduinoGlue.h b/src/platform/portduino/PortduinoGlue.h index 980fc63b8..ed2954eef 100644 --- a/src/platform/portduino/PortduinoGlue.h +++ b/src/platform/portduino/PortduinoGlue.h @@ -21,16 +21,23 @@ enum configNames { touchscreenModule, touchscreenCS, touchscreenIRQ, + touchscreenBusFrequency, + touchscreenRotate, touchscreenspidev, displayspidev, + displayBusFrequency, displayPanel, displayWidth, displayHeight, displayCS, displayDC, + displayRGBOrder, displayBacklight, + displayBacklightPWMChannel, + displayBacklightInvert, displayReset, displayRotate, + displayOffsetRotate, displayOffsetX, displayOffsetY, displayInvert, @@ -41,8 +48,8 @@ enum configNames { webserverrootpath, maxnodes }; -enum { no_screen, st7789, st7735, st7735s, ili9341 }; -enum { no_touchscreen, xpt2046, stmpe610 }; +enum { no_screen, x11, st7789, st7735, st7735s, st7796, ili9341, ili9488, hx8357d }; +enum { no_touchscreen, xpt2046, stmpe610, gt911, ft5x06 }; enum { level_error, level_warn, level_info, level_debug }; extern std::map settingsMap;