Compare commits

...

12 Commits

Author SHA1 Message Date
Michael
31b9bd5729
Merge c461038d5a into 655c6b51fe 2025-09-02 12:28:16 -04:00
Ben Meadors
655c6b51fe
Try-fix Cardkb detection (#7825)
* Try-fix: CardKB detection regression

* Correct macro
2025-09-02 09:50:15 -05:00
Chloe Bethel
0bd4cefad3 Make ExternalNotification show up in excluded_modules, more STM32 modules (#7797)
* Show ExternalNotification as excluded if it is

* Enable ExternalNotification, SerialModule and RangeTest on STM32WL

* Misc fixes for #7797 - ARCH_STM32 -> ARCH_STM32WL, use less flash by dropping weather station support for serialmodule, set tx/rx pins before begin

* Enable Serial1 on RAK3172, make SerialModule use it (console is on LPUART1)

* Fix SerialModule on RAK3172, fix board definition of RAK3172 to include the right pin mapping.
2025-09-02 07:09:15 -05:00
github-actions[bot]
9b1fb795d7
Upgrade trunk (#7822)
Co-authored-by: vidplace7 <1779290+vidplace7@users.noreply.github.com>
2025-09-02 06:41:48 -05:00
Tom Fifield
3040e5a7bb Fix GPS that hard code 2080 as the start time. (#7803)
* Fix GPS that hard code 2080 as the start time.

Some GPS chips, such as the AG3335 in T1000e and L96 have a hardcoded
time of 2080-01-05 when they start up.

To fix that in a way that seems permanent, let's ignore times that
are more than 40 years since the firmware was built. We should followup
in late 2039 to see if any changes are needed.

Reported-By: @b8b8

* Update src/gps/RTC.cpp

Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com>

* Put FORTY_YEARS in header and use in both places.

* Restore Ben's nicer log lines.

---------

Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com>
2025-09-02 06:41:26 -05:00
Ben Meadors
3b82d55176
Revert "Add gat562_mesh_tracker_pro device. (#7815)" (#7824)
This reverts commit 7d1300ab66.
2025-09-02 06:17:01 -05:00
Tom Fifield
a6b8202cd4 Hold for 20s after GPS lock (#7801)
* Hold for >20s after GPS lock

GPS chips are designed to stay locked for a while to download some data and save it.
This data is important for speeding up future locks, and making them higher quality.
Our present configuration could make every lock perform similar to first lock.

This patch sets a hold of between 20s and 10% of the lock search time after lock
is acquired. This should allow the GPS to finish its work before we turn it off.

Fixes https://github.com/meshtastic/firmware/issues/7466

* Remove T1000E-specific GPS holds

The new code does the same thing, for all devices.

* Fix publishing settings

* Cleanups, removing unused variables.

* ifdef log line with GPS_DEBUG

* fixQual is not a bool.
2025-09-02 06:06:06 -05:00
Jason P
cfc1bf10c9 If usePreset is False, show value as Custom (#7812) 2025-09-02 06:05:55 -05:00
Wilson
7d1300ab66
Add gat562_mesh_tracker_pro device. (#7815)
Some checks are pending
CI / build-rp2040 (push) Blocked by required conditions
CI / build-rp2350 (push) Blocked by required conditions
CI / build-stm32 (push) Blocked by required conditions
CI / build-debian-src (push) Waiting to run
CI / package-pio-deps-native-tft (push) Waiting to run
CI / test-native (push) Waiting to run
CI / docker-deb-amd64 (push) Waiting to run
CI / docker-deb-amd64-tft (push) Waiting to run
CI / docker-alp-amd64 (push) Waiting to run
CI / docker-alp-amd64-tft (push) Waiting to run
CI / docker-deb-arm64 (push) Waiting to run
CI / docker-deb-armv7 (push) Waiting to run
CI / gather-artifacts (esp32) (push) Blocked by required conditions
CI / gather-artifacts (esp32c3) (push) Blocked by required conditions
CI / gather-artifacts (esp32c6) (push) Blocked by required conditions
CI / gather-artifacts (esp32s3) (push) Blocked by required conditions
CI / gather-artifacts (nrf52840) (push) Blocked by required conditions
CI / gather-artifacts (rp2040) (push) Blocked by required conditions
CI / gather-artifacts (rp2350) (push) Blocked by required conditions
CI / gather-artifacts (stm32) (push) Blocked by required conditions
CI / release-artifacts (push) Blocked by required conditions
CI / release-firmware (esp32) (push) Blocked by required conditions
CI / release-firmware (esp32c3) (push) Blocked by required conditions
CI / release-firmware (esp32c6) (push) Blocked by required conditions
CI / release-firmware (esp32s3) (push) Blocked by required conditions
CI / release-firmware (nrf52840) (push) Blocked by required conditions
CI / release-firmware (rp2040) (push) Blocked by required conditions
CI / release-firmware (rp2350) (push) Blocked by required conditions
CI / release-firmware (stm32) (push) Blocked by required conditions
CI / publish-firmware (push) Blocked by required conditions
2025-09-02 13:06:24 +08:00
Michael
c461038d5a
Merge branch 'master' into fix/t-echo-backlight-touch-button 2025-08-28 08:18:41 +02:00
Michael
176a463d85
Merge branch 'master' into fix/t-echo-backlight-touch-button 2025-08-20 22:49:23 +02:00
Michael Overhorst
9b2fff2f70 Add TEchoBacklight support for T-Echo variant
Introduces TEchoBacklight class to manage the backlight on the T-Echo device (BaseUI only)
2025-08-20 22:46:36 +02:00
24 changed files with 330 additions and 89 deletions

View File

@ -9,7 +9,7 @@ plugins:
lint: lint:
enabled: enabled:
- checkov@3.2.467 - checkov@3.2.467
- renovate@41.90.1 - renovate@41.91.3
- prettier@3.6.2 - prettier@3.6.2
- trufflehog@3.90.5 - trufflehog@3.90.5
- yamllint@1.37.1 - yamllint@1.37.1

View File

@ -5,7 +5,7 @@
}, },
"core": "stm32", "core": "stm32",
"cpu": "cortex-m4", "cpu": "cortex-m4",
"extra_flags": "-DSTM32WLxx -DSTM32WLE5xx -DARDUINO_GENERIC_WLE5CCUX", "extra_flags": "-DSTM32WLxx -DSTM32WLE5xx -DARDUINO_RAK3172_MODULE",
"f_cpu": "48000000L", "f_cpu": "48000000L",
"mcu": "stm32wle5ccu", "mcu": "stm32wle5ccu",
"variant": "STM32WLxx/WL54CCU_WL55CCU_WLE4C(8-B-C)U_WLE5C(8-B-C)U", "variant": "STM32WLxx/WL54CCU_WL55CCU_WLE4C(8-B-C)U_WLE5C(8-B-C)U",

View File

@ -1,7 +1,14 @@
#include "DisplayFormatters.h" #include "DisplayFormatters.h"
const char *DisplayFormatters::getModemPresetDisplayName(meshtastic_Config_LoRaConfig_ModemPreset preset, bool useShortName) const char *DisplayFormatters::getModemPresetDisplayName(meshtastic_Config_LoRaConfig_ModemPreset preset, bool useShortName,
bool usePreset)
{ {
// If use_preset is false, always return "Custom"
if (!usePreset) {
return "Custom";
}
switch (preset) { switch (preset) {
case meshtastic_Config_LoRaConfig_ModemPreset_SHORT_TURBO: case meshtastic_Config_LoRaConfig_ModemPreset_SHORT_TURBO:
return useShortName ? "ShortT" : "ShortTurbo"; return useShortName ? "ShortT" : "ShortTurbo";

View File

@ -4,5 +4,6 @@
class DisplayFormatters class DisplayFormatters
{ {
public: public:
static const char *getModemPresetDisplayName(meshtastic_Config_LoRaConfig_ModemPreset preset, bool useShortName); static const char *getModemPresetDisplayName(meshtastic_Config_LoRaConfig_ModemPreset preset, bool useShortName,
bool usePreset);
}; };

View File

@ -843,9 +843,6 @@ void GPS::setPowerState(GPSPowerState newState, uint32_t sleepTime)
setPowerPMU(true); // Power (PMU): on setPowerPMU(true); // Power (PMU): on
writePinStandby(false); // Standby (pin): awake (not standby) writePinStandby(false); // Standby (pin): awake (not standby)
setPowerUBLOX(true); // Standby (UBLOX): awake setPowerUBLOX(true); // Standby (UBLOX): awake
#ifdef GNSS_AIROHA
lastFixStartMsec = 0;
#endif
break; break;
case GPS_SOFTSLEEP: case GPS_SOFTSLEEP:
@ -863,9 +860,7 @@ void GPS::setPowerState(GPSPowerState newState, uint32_t sleepTime)
writePinStandby(true); // Standby (pin): asleep (not awake) writePinStandby(true); // Standby (pin): asleep (not awake)
setPowerUBLOX(false, sleepTime); // Standby (UBLOX): asleep, timed setPowerUBLOX(false, sleepTime); // Standby (UBLOX): asleep, timed
#ifdef GNSS_AIROHA #ifdef GNSS_AIROHA
if (config.position.gps_update_interval * 1000 >= GPS_FIX_HOLD_TIME * 2) {
digitalWrite(PIN_GPS_EN, LOW); digitalWrite(PIN_GPS_EN, LOW);
}
#endif #endif
break; break;
@ -877,9 +872,7 @@ void GPS::setPowerState(GPSPowerState newState, uint32_t sleepTime)
writePinStandby(true); // Standby (pin): asleep writePinStandby(true); // Standby (pin): asleep
setPowerUBLOX(false, 0); // Standby (UBLOX): asleep, indefinitely setPowerUBLOX(false, 0); // Standby (UBLOX): asleep, indefinitely
#ifdef GNSS_AIROHA #ifdef GNSS_AIROHA
if (config.position.gps_update_interval * 1000 >= GPS_FIX_HOLD_TIME * 2) {
digitalWrite(PIN_GPS_EN, LOW); digitalWrite(PIN_GPS_EN, LOW);
}
#endif #endif
break; break;
} }
@ -1062,6 +1055,8 @@ void GPS::down()
} }
// If update interval long enough (or softsleep unsupported): hardsleep instead // If update interval long enough (or softsleep unsupported): hardsleep instead
setPowerState(GPS_HARDSLEEP, sleepTime); setPowerState(GPS_HARDSLEEP, sleepTime);
// Reset the fix quality to 0, since we're off.
fixQual = 0;
} }
} }
@ -1121,11 +1116,19 @@ int32_t GPS::runOnce()
shouldPublish = true; shouldPublish = true;
} }
uint8_t prev_fixQual = fixQual;
bool gotLoc = lookForLocation(); bool gotLoc = lookForLocation();
if (gotLoc && !hasValidLocation) { // declare that we have location ASAP if (gotLoc && !hasValidLocation) { // declare that we have location ASAP
LOG_DEBUG("hasValidLocation RISING EDGE"); LOG_DEBUG("hasValidLocation RISING EDGE");
hasValidLocation = true; hasValidLocation = true;
shouldPublish = true; shouldPublish = true;
// Hold for 20secs after getting a lock to download ephemeris etc
fixHoldEnds = millis() + 20000;
}
if (gotLoc && prev_fixQual == 0) { // just got a lock after turning back on.
fixHoldEnds = millis() + 20000;
shouldPublish = true; // Publish immediately, since next publish is at end of hold
} }
bool tooLong = scheduling.searchedTooLong(); bool tooLong = scheduling.searchedTooLong();
@ -1134,8 +1137,7 @@ int32_t GPS::runOnce()
// Once we get a location we no longer desperately want an update // Once we get a location we no longer desperately want an update
if ((gotLoc && gotTime) || tooLong) { if ((gotLoc && gotTime) || tooLong) {
if (tooLong && !gotLoc) {
if (tooLong) {
// we didn't get a location during this ack window, therefore declare loss of lock // we didn't get a location during this ack window, therefore declare loss of lock
if (hasValidLocation) { if (hasValidLocation) {
LOG_DEBUG("hasValidLocation FALLING EDGE"); LOG_DEBUG("hasValidLocation FALLING EDGE");
@ -1143,9 +1145,15 @@ int32_t GPS::runOnce()
p = meshtastic_Position_init_default; p = meshtastic_Position_init_default;
hasValidLocation = false; hasValidLocation = false;
} }
if (millis() > fixHoldEnds) {
shouldPublish = true; // publish our update at the end of the lock hold
publishUpdate();
down(); down();
shouldPublish = true; // publish our update for this just finished acquisition window #ifdef GPS_DEBUG
} else {
LOG_DEBUG("Holding for GPS data download: %d ms (numSats=%d)", fixHoldEnds - millis(), p.sats_in_view);
#endif
}
} }
// If state has changed do a publish // If state has changed do a publish
@ -1508,24 +1516,6 @@ static int32_t toDegInt(RawDegrees d)
*/ */
bool GPS::lookForTime() bool GPS::lookForTime()
{ {
#ifdef GNSS_AIROHA
uint8_t fix = reader.fixQuality();
if (fix >= 1 && fix <= 5) {
if (lastFixStartMsec > 0) {
if (Throttle::isWithinTimespanMs(lastFixStartMsec, GPS_FIX_HOLD_TIME)) {
return false;
} else {
clearBuffer();
}
} else {
lastFixStartMsec = millis();
return false;
}
} else {
return false;
}
#endif
auto ti = reader.time; auto ti = reader.time;
auto d = reader.date; auto d = reader.date;
if (ti.isValid() && d.isValid()) { // Note: we don't check for updated, because we'll only be called if needed if (ti.isValid() && d.isValid()) { // Note: we don't check for updated, because we'll only be called if needed
@ -1564,25 +1554,6 @@ The Unix epoch (or Unix time or POSIX time or Unix timestamp) is the number of s
*/ */
bool GPS::lookForLocation() bool GPS::lookForLocation()
{ {
#ifdef GNSS_AIROHA
if ((config.position.gps_update_interval * 1000) >= (GPS_FIX_HOLD_TIME * 2)) {
uint8_t fix = reader.fixQuality();
if (fix >= 1 && fix <= 5) {
if (lastFixStartMsec > 0) {
if (Throttle::isWithinTimespanMs(lastFixStartMsec, GPS_FIX_HOLD_TIME)) {
return false;
} else {
clearBuffer();
}
} else {
lastFixStartMsec = millis();
return false;
}
} else {
return false;
}
}
#endif
// By default, TinyGPS++ does not parse GPGSA lines, which give us // By default, TinyGPS++ does not parse GPGSA lines, which give us
// the 2D/3D fixType (see NMEAGPS.h) // the 2D/3D fixType (see NMEAGPS.h)
// At a minimum, use the fixQuality indicator in GPGGA (FIXME?) // At a minimum, use the fixQuality indicator in GPGGA (FIXME?)

View File

@ -159,7 +159,7 @@ class GPS : private concurrency::OSThread
uint8_t fixType = 0; // fix type from GPGSA uint8_t fixType = 0; // fix type from GPGSA
#endif #endif
uint32_t lastWakeStartMsec = 0, lastSleepStartMsec = 0, lastFixStartMsec = 0; uint32_t fixHoldEnds = 0;
uint32_t rx_gpio = 0; uint32_t rx_gpio = 0;
uint32_t tx_gpio = 0; uint32_t tx_gpio = 0;

View File

@ -132,6 +132,10 @@ RTCSetResult perhapsSetRTC(RTCQuality q, const struct timeval *tv, bool forceUpd
if (tv->tv_sec < BUILD_EPOCH) { if (tv->tv_sec < BUILD_EPOCH) {
LOG_WARN("Ignore time (%ld) before build epoch (%ld)!", printableEpoch, BUILD_EPOCH); LOG_WARN("Ignore time (%ld) before build epoch (%ld)!", printableEpoch, BUILD_EPOCH);
return RTCSetResultInvalidTime; return RTCSetResultInvalidTime;
} else if (tv->tv_sec > (BUILD_EPOCH + FORTY_YEARS)) {
LOG_WARN("Ignore time (%ld) too far in the future (build epoch: %ld, max allowed: %ld)!", printableEpoch, BUILD_EPOCH,
BUILD_EPOCH + FORTY_YEARS);
return RTCSetResultInvalidTime;
} }
#endif #endif
@ -250,6 +254,10 @@ RTCSetResult perhapsSetRTC(RTCQuality q, struct tm &t)
if (tv.tv_sec < BUILD_EPOCH) { if (tv.tv_sec < BUILD_EPOCH) {
LOG_WARN("Ignore time (%ld) before build epoch (%ld)!", printableEpoch, BUILD_EPOCH); LOG_WARN("Ignore time (%ld) before build epoch (%ld)!", printableEpoch, BUILD_EPOCH);
return RTCSetResultInvalidTime; return RTCSetResultInvalidTime;
} else if (tv.tv_sec > (BUILD_EPOCH + FORTY_YEARS)) {
LOG_WARN("Ignore time (%ld) too far in the future (build epoch: %ld, max allowed: %ld)!", printableEpoch, BUILD_EPOCH,
BUILD_EPOCH + FORTY_YEARS);
return RTCSetResultInvalidTime;
} }
#endif #endif

View File

@ -55,3 +55,6 @@ time_t gm_mktime(struct tm *tm);
#define SEC_PER_DAY 86400 #define SEC_PER_DAY 86400
#define SEC_PER_HOUR 3600 #define SEC_PER_HOUR 3600
#define SEC_PER_MIN 60 #define SEC_PER_MIN 60
#ifdef BUILD_EPOCH
#define FORTY_YEARS (40UL * 365 * SEC_PER_DAY) // probably time to update your firmware
#endif

View File

@ -263,12 +263,6 @@ void drawFrameSettings(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t
display->drawString(x + 1, y, "USB"); display->drawString(x + 1, y, "USB");
} }
// auto mode = DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, true);
// display->drawString(x + SCREEN_WIDTH - display->getStringWidth(mode), y, mode);
// if (config.display.heading_bold)
// display->drawString(x + SCREEN_WIDTH - display->getStringWidth(mode) - 1, y, mode);
uint32_t currentMillis = millis(); uint32_t currentMillis = millis();
uint32_t seconds = currentMillis / 1000; uint32_t seconds = currentMillis / 1000;
uint32_t minutes = seconds / 60; uint32_t minutes = seconds / 60;
@ -398,7 +392,7 @@ void drawLoRaFocused(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x,
display->drawString(nameX, getTextPositions(display)[line++], shortnameble); display->drawString(nameX, getTextPositions(display)[line++], shortnameble);
// === Second Row: Radio Preset === // === Second Row: Radio Preset ===
auto mode = DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false); auto mode = DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false, config.lora.use_preset);
char regionradiopreset[25]; char regionradiopreset[25];
const char *region = myRegion ? myRegion->name : NULL; const char *region = myRegion ? myRegion->name : NULL;
if (region != nullptr) { if (region != nullptr) {

View File

@ -13,7 +13,11 @@ void CardKbI2cImpl::init()
if (cardkb_found.address == 0x00) { if (cardkb_found.address == 0x00) {
LOG_DEBUG("Rescan for I2C keyboard"); LOG_DEBUG("Rescan for I2C keyboard");
uint8_t i2caddr_scan[] = {CARDKB_ADDR, TDECK_KB_ADDR, BBQ10_KB_ADDR, MPR121_KB_ADDR, TCA8418_KB_ADDR}; uint8_t i2caddr_scan[] = {CARDKB_ADDR, TDECK_KB_ADDR, BBQ10_KB_ADDR, MPR121_KB_ADDR, TCA8418_KB_ADDR};
#if defined(T_LORA_PAGER)
uint8_t i2caddr_asize = sizeof(i2caddr_scan) / sizeof(i2caddr_scan[0]); uint8_t i2caddr_asize = sizeof(i2caddr_scan) / sizeof(i2caddr_scan[0]);
#else
uint8_t i2caddr_asize = 5;
#endif
auto i2cScanner = std::unique_ptr<ScanI2CTwoWire>(new ScanI2CTwoWire()); auto i2cScanner = std::unique_ptr<ScanI2CTwoWire>(new ScanI2CTwoWire());
#if WIRE_INTERFACES_COUNT == 2 #if WIRE_INTERFACES_COUNT == 2

View File

@ -108,6 +108,10 @@ NRF52Bluetooth *nrf52Bluetooth = nullptr;
ButtonThread *TouchButtonThread = nullptr; ButtonThread *TouchButtonThread = nullptr;
#endif #endif
#if defined(TTGO_T_ECHO) && !defined(MESHTASTIC_INCLUDE_NICHE_GRAPHICS)
#include "../variants/nrf52840/t-echo/TEchoBacklight.h"
#endif
#if defined(BUTTON_PIN) || defined(ARCH_PORTDUINO) #if defined(BUTTON_PIN) || defined(ARCH_PORTDUINO)
ButtonThread *UserButtonThread = nullptr; ButtonThread *UserButtonThread = nullptr;
#endif #endif
@ -1016,8 +1020,13 @@ void setup()
BaseType_t higherWake = 0; BaseType_t higherWake = 0;
mainDelay.interruptFromISR(&higherWake); mainDelay.interruptFromISR(&higherWake);
}; };
#if defined(TTGO_T_ECHO) && !defined(MESHTASTIC_INCLUDE_NICHE_GRAPHICS)
touchConfig.singlePress = INPUT_BROKER_NONE;
touchConfig.longPress = INPUT_BROKER_NONE;
#else
touchConfig.singlePress = INPUT_BROKER_NONE; touchConfig.singlePress = INPUT_BROKER_NONE;
touchConfig.longPress = INPUT_BROKER_BACK; touchConfig.longPress = INPUT_BROKER_BACK;
#endif
TouchButtonThread->initButton(touchConfig); TouchButtonThread->initButton(touchConfig);
#endif #endif
@ -1491,6 +1500,14 @@ void setup()
// We manually run this to update the NodeStatus // We manually run this to update the NodeStatus
nodeDB->notifyObservers(true); nodeDB->notifyObservers(true);
#if defined(TTGO_T_ECHO) && !defined(MESHTASTIC_INCLUDE_NICHE_GRAPHICS)
if (!tEchoBacklight) {
tEchoBacklight = new TEchoBacklight();
tEchoBacklight->setPin(PIN_EINK_EN);
tEchoBacklight->start();
}
#endif
} }
#endif #endif
@ -1525,7 +1542,7 @@ extern meshtastic_DeviceMetadata getDeviceMetadata()
#if ((!HAS_SCREEN || NO_EXT_GPIO) || MESHTASTIC_EXCLUDE_CANNEDMESSAGES) && !defined(MESHTASTIC_INCLUDE_NICHE_GRAPHICS) #if ((!HAS_SCREEN || NO_EXT_GPIO) || MESHTASTIC_EXCLUDE_CANNEDMESSAGES) && !defined(MESHTASTIC_INCLUDE_NICHE_GRAPHICS)
deviceMetadata.excluded_modules |= meshtastic_ExcludedModules_CANNEDMSG_CONFIG; deviceMetadata.excluded_modules |= meshtastic_ExcludedModules_CANNEDMSG_CONFIG;
#endif #endif
#if NO_EXT_GPIO #if NO_EXT_GPIO || MESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION
deviceMetadata.excluded_modules |= meshtastic_ExcludedModules_EXTNOTIF_CONFIG; deviceMetadata.excluded_modules |= meshtastic_ExcludedModules_EXTNOTIF_CONFIG;
#endif #endif
// Only edge case here is if we apply this a device with built in Accelerometer and want to detect interrupts // Only edge case here is if we apply this a device with built in Accelerometer and want to detect interrupts

View File

@ -368,7 +368,7 @@ const char *Channels::getName(size_t chIndex)
// Per mesh.proto spec, if bandwidth is specified we must ignore modemPreset enum, we assume that in that case // Per mesh.proto spec, if bandwidth is specified we must ignore modemPreset enum, we assume that in that case
// the app effed up and forgot to set channelSettings.name // the app effed up and forgot to set channelSettings.name
if (config.lora.use_preset) { if (config.lora.use_preset) {
channelName = DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false); channelName = DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false, config.lora.use_preset);
} else { } else {
channelName = "Custom"; channelName = "Custom";
} }
@ -382,7 +382,8 @@ bool Channels::isDefaultChannel(ChannelIndex chIndex)
const auto &ch = getByIndex(chIndex); const auto &ch = getByIndex(chIndex);
if (ch.settings.psk.size == 1 && ch.settings.psk.bytes[0] == 1) { if (ch.settings.psk.size == 1 && ch.settings.psk.bytes[0] == 1) {
const char *name = getName(chIndex); const char *name = getName(chIndex);
const char *presetName = DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false); const char *presetName =
DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false, config.lora.use_preset);
// Check if the name is the default derived from the modem preset // Check if the name is the default derived from the modem preset
if (strcmp(name, presetName) == 0) if (strcmp(name, presetName) == 0)
return true; return true;

View File

@ -586,7 +586,8 @@ void RadioInterface::applyModemConfig()
// Check if we use the default frequency slot // Check if we use the default frequency slot
RadioInterface::uses_default_frequency_slot = RadioInterface::uses_default_frequency_slot =
channel_num == hash(DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false)) % numChannels; channel_num ==
hash(DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false, config.lora.use_preset)) % numChannels;
// Old frequency selection formula // Old frequency selection formula
// float freq = myRegion->freqStart + ((((myRegion->freqEnd - myRegion->freqStart) / numChannels) / 2) * channel_num); // float freq = myRegion->freqStart + ((((myRegion->freqEnd - myRegion->freqStart) / numChannels) / 2) * channel_num);

View File

@ -364,9 +364,10 @@ ExternalNotificationModule::ExternalNotificationModule()
// moduleConfig.external_notification.alert_message_buzzer = true; // moduleConfig.external_notification.alert_message_buzzer = true;
if (moduleConfig.external_notification.enabled) { if (moduleConfig.external_notification.enabled) {
#if !defined(MESHTASTIC_EXCLUDE_INPUTBROKER)
if (inputBroker) // put our callback in the inputObserver list if (inputBroker) // put our callback in the inputObserver list
inputObserver.observe(inputBroker); inputObserver.observe(inputBroker);
#endif
if (nodeDB->loadProto(rtttlConfigFile, meshtastic_RTTTLConfig_size, sizeof(meshtastic_RTTTLConfig), if (nodeDB->loadProto(rtttlConfigFile, meshtastic_RTTTLConfig_size, sizeof(meshtastic_RTTTLConfig),
&meshtastic_RTTTLConfig_msg, &rtttlConfig) != LoadFileResult::LOAD_SUCCESS) { &meshtastic_RTTTLConfig_msg, &rtttlConfig) != LoadFileResult::LOAD_SUCCESS) {
memset(rtttlConfig.ringtone, 0, sizeof(rtttlConfig.ringtone)); memset(rtttlConfig.ringtone, 0, sizeof(rtttlConfig.ringtone));

View File

@ -88,7 +88,7 @@
#include "modules/StoreForwardModule.h" #include "modules/StoreForwardModule.h"
#endif #endif
#endif #endif
#if defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040) || defined(ARCH_PORTDUINO)
#if !MESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION #if !MESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION
#include "modules/ExternalNotificationModule.h" #include "modules/ExternalNotificationModule.h"
#endif #endif
@ -98,7 +98,6 @@
#if !defined(CONFIG_IDF_TARGET_ESP32S2) && !MESHTASTIC_EXCLUDE_SERIAL #if !defined(CONFIG_IDF_TARGET_ESP32S2) && !MESHTASTIC_EXCLUDE_SERIAL
#include "modules/SerialModule.h" #include "modules/SerialModule.h"
#endif #endif
#endif
#if !MESHTASTIC_EXCLUDE_DROPZONE #if !MESHTASTIC_EXCLUDE_DROPZONE
#include "modules/DropzoneModule.h" #include "modules/DropzoneModule.h"
@ -246,8 +245,8 @@ void setupModules()
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_POWER_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR #if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_POWER_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
new PowerTelemetryModule(); new PowerTelemetryModule();
#endif #endif
#if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)) && !defined(CONFIG_IDF_TARGET_ESP32S2) && \ #if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040) || defined(ARCH_STM32WL)) && \
!defined(CONFIG_IDF_TARGET_ESP32C3) !defined(CONFIG_IDF_TARGET_ESP32S2) && !defined(CONFIG_IDF_TARGET_ESP32C3)
#if !MESHTASTIC_EXCLUDE_SERIAL #if !MESHTASTIC_EXCLUDE_SERIAL
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_COLOR) { if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_COLOR) {
new SerialModule(); new SerialModule();
@ -268,13 +267,11 @@ void setupModules()
storeForwardModule = new StoreForwardModule(); storeForwardModule = new StoreForwardModule();
#endif #endif
#endif #endif
#if defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040) || defined(ARCH_PORTDUINO)
#if !MESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION #if !MESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION
externalNotificationModule = new ExternalNotificationModule(); externalNotificationModule = new ExternalNotificationModule();
#endif #endif
#if !MESHTASTIC_EXCLUDE_RANGETEST && !MESHTASTIC_EXCLUDE_GPS #if !MESHTASTIC_EXCLUDE_RANGETEST && !MESHTASTIC_EXCLUDE_GPS
new RangeTestModule(); new RangeTestModule();
#endif
#endif #endif
} else { } else {
#if !MESHTASTIC_EXCLUDE_ADMIN #if !MESHTASTIC_EXCLUDE_ADMIN

View File

@ -31,7 +31,7 @@ uint32_t packetSequence = 0;
int32_t RangeTestModule::runOnce() int32_t RangeTestModule::runOnce()
{ {
#if defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_PORTDUINO) #if defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_STM32WL) || defined(ARCH_PORTDUINO)
/* /*
Uncomment the preferences below if you want to use the module Uncomment the preferences below if you want to use the module
@ -130,7 +130,7 @@ void RangeTestModuleRadio::sendPayload(NodeNum dest, bool wantReplies)
ProcessMessage RangeTestModuleRadio::handleReceived(const meshtastic_MeshPacket &mp) ProcessMessage RangeTestModuleRadio::handleReceived(const meshtastic_MeshPacket &mp)
{ {
#if defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_PORTDUINO) #if defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_STM32WL) || defined(ARCH_PORTDUINO)
if (moduleConfig.range_test.enabled) { if (moduleConfig.range_test.enabled) {

View File

@ -49,8 +49,8 @@
#include "meshSolarApp.h" #include "meshSolarApp.h"
#endif #endif
#if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)) && !defined(CONFIG_IDF_TARGET_ESP32S2) && \ #if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040) || defined(ARCH_STM32WL)) && \
!defined(CONFIG_IDF_TARGET_ESP32C3) !defined(CONFIG_IDF_TARGET_ESP32S2) && !defined(CONFIG_IDF_TARGET_ESP32C3)
#define RX_BUFFER 256 #define RX_BUFFER 256
#define TIMEOUT 250 #define TIMEOUT 250
@ -67,7 +67,7 @@ SerialModuleRadio *serialModuleRadio;
defined(ELECROW_ThinkNode_M5) || defined(HELTEC_MESH_SOLAR) || defined(T_ECHO_LITE) defined(ELECROW_ThinkNode_M5) || defined(HELTEC_MESH_SOLAR) || defined(T_ECHO_LITE)
SerialModule::SerialModule() : StreamAPI(&Serial), concurrency::OSThread("Serial") {} SerialModule::SerialModule() : StreamAPI(&Serial), concurrency::OSThread("Serial") {}
static Print *serialPrint = &Serial; static Print *serialPrint = &Serial;
#elif defined(CONFIG_IDF_TARGET_ESP32C6) #elif defined(CONFIG_IDF_TARGET_ESP32C6) || defined(RAK3172)
SerialModule::SerialModule() : StreamAPI(&Serial1), concurrency::OSThread("Serial") {} SerialModule::SerialModule() : StreamAPI(&Serial1), concurrency::OSThread("Serial") {}
static Print *serialPrint = &Serial1; static Print *serialPrint = &Serial1;
#else #else
@ -173,7 +173,18 @@ int32_t SerialModule::runOnce()
Serial.begin(baud); Serial.begin(baud);
Serial.setTimeout(moduleConfig.serial.timeout > 0 ? moduleConfig.serial.timeout : TIMEOUT); Serial.setTimeout(moduleConfig.serial.timeout > 0 ? moduleConfig.serial.timeout : TIMEOUT);
} }
#elif defined(ARCH_STM32WL)
#ifndef RAK3172
HardwareSerial *serialInstance = &Serial2;
#else
HardwareSerial *serialInstance = &Serial1;
#endif
if (moduleConfig.serial.rxd && moduleConfig.serial.txd) {
serialInstance->setTx(moduleConfig.serial.txd);
serialInstance->setRx(moduleConfig.serial.rxd);
}
serialInstance->begin(baud);
serialInstance->setTimeout(moduleConfig.serial.timeout > 0 ? moduleConfig.serial.timeout : TIMEOUT);
#elif defined(ARCH_ESP32) #elif defined(ARCH_ESP32)
if (moduleConfig.serial.rxd && moduleConfig.serial.txd) { if (moduleConfig.serial.rxd && moduleConfig.serial.txd) {
@ -260,8 +271,13 @@ int32_t SerialModule::runOnce()
while (Serial1.available()) { while (Serial1.available()) {
serialPayloadSize = Serial1.readBytes(serialBytes, meshtastic_Constants_DATA_PAYLOAD_LEN); serialPayloadSize = Serial1.readBytes(serialBytes, meshtastic_Constants_DATA_PAYLOAD_LEN);
#else #else
while (Serial2.available()) { #ifndef RAK3172
serialPayloadSize = Serial2.readBytes(serialBytes, meshtastic_Constants_DATA_PAYLOAD_LEN); HardwareSerial *serialInstance = &Serial2;
#else
HardwareSerial *serialInstance = &Serial1;
#endif
while (serialInstance->available()) {
serialPayloadSize = serialInstance->readBytes(serialBytes, meshtastic_Constants_DATA_PAYLOAD_LEN);
#endif #endif
serialModuleRadio->sendPayload(); serialModuleRadio->sendPayload();
} }
@ -511,7 +527,7 @@ ParsedLine parseLine(const char *line)
void SerialModule::processWXSerial() void SerialModule::processWXSerial()
{ {
#if !defined(TTGO_T_ECHO) && !defined(T_ECHO_LITE) && !defined(CANARYONE) && !defined(CONFIG_IDF_TARGET_ESP32C6) && \ #if !defined(TTGO_T_ECHO) && !defined(T_ECHO_LITE) && !defined(CANARYONE) && !defined(CONFIG_IDF_TARGET_ESP32C6) && \
!defined(MESHLINK) && !defined(ELECROW_ThinkNode_M1) && !defined(ELECROW_ThinkNode_M5) !defined(MESHLINK) && !defined(ELECROW_ThinkNode_M1) && !defined(ELECROW_ThinkNode_M5) && !defined(ARCH_STM32WL)
static unsigned int lastAveraged = 0; static unsigned int lastAveraged = 0;
static unsigned int averageIntervalMillis = 300000; // 5 minutes hard coded. static unsigned int averageIntervalMillis = 300000; // 5 minutes hard coded.
static double dir_sum_sin = 0; static double dir_sum_sin = 0;

View File

@ -8,8 +8,8 @@
#include <Arduino.h> #include <Arduino.h>
#include <functional> #include <functional>
#if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)) && !defined(CONFIG_IDF_TARGET_ESP32S2) && \ #if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040) || defined(ARCH_STM32WL)) && \
!defined(CONFIG_IDF_TARGET_ESP32C3) !defined(CONFIG_IDF_TARGET_ESP32S2) && !defined(CONFIG_IDF_TARGET_ESP32C3)
class SerialModule : public StreamAPI, private concurrency::OSThread class SerialModule : public StreamAPI, private concurrency::OSThread
{ {

View File

@ -0,0 +1,174 @@
#include "TEchoBacklight.h"
#if defined(TTGO_T_ECHO) && !defined(MESHTASTIC_INCLUDE_NICHE_GRAPHICS)
#include "RadioLibInterface.h"
#include "configuration.h"
TEchoBacklight *tEchoBacklight = nullptr;
TEchoBacklight::TEchoBacklight() : OSThread("TEchoBacklight")
{
setInterval(POLL_INTERVAL_MS);
OSThread::disable();
}
void TEchoBacklight::setPin(uint8_t pin)
{
pinMode(pin, OUTPUT);
off();
}
void TEchoBacklight::start()
{
pinMode(PIN_BUTTON_TOUCH, INPUT_PULLUP);
attachInterrupt(PIN_BUTTON_TOUCH, touchISR, FALLING);
}
int32_t TEchoBacklight::runOnce()
{
bool awaitingRelease = false;
switch (state) {
case REST:
break;
case IRQ:
if (!RadioLibInterface::instance || RadioLibInterface::instance->isSending()) {
LOG_INFO("TEchoBacklight: Touch ignored - radio transmitting");
state = REST;
break;
}
LOG_INFO("TEchoBacklight: Touch detected - peek()");
peek();
state = POLLING_UNFIRED;
awaitingRelease = true;
break;
case POLLING_UNFIRED: {
uint32_t length = millis() - irqAtMillis;
if (!isTouchPressed()) {
state = REST;
if (length > DEBOUNCE_MS && length < LATCH_TIME_MS) {
LOG_INFO("TEchoBacklight: Short press (%lums) - off()", length);
off();
} else {
LOG_INFO("TEchoBacklight: Touch released too quick (%lums) - debounced", length);
}
} else {
awaitingRelease = true;
if (length >= LATCH_TIME_MS) {
LOG_INFO("TEchoBacklight: Long press (%lums) - starting latch blink", length);
state = BLINKING;
blinkStartTime = millis();
blinkStep = 0;
setBacklight(false);
}
}
break;
}
case BLINKING: {
uint32_t elapsed = millis() - blinkStartTime;
if (elapsed >= BLINK_DELAY_MS) {
blinkStep++;
blinkStartTime = millis();
setBacklight(blinkStep % 2 == 1);
if (blinkStep == BLINK_STEPS) {
backlightLatched = true;
state = POLLING_FIRED;
LOG_INFO("TEchoBacklight: Blink complete - latched ON");
}
}
awaitingRelease = true;
break;
}
case POLLING_FIRED:
if (!isTouchPressed()) {
LOG_INFO("TEchoBacklight: Long press released");
state = REST;
} else {
awaitingRelease = true;
}
break;
}
if (!awaitingRelease) {
stopThread();
}
return POLL_INTERVAL_MS;
}
void TEchoBacklight::setBacklight(bool on)
{
digitalWrite(PIN_EINK_EN, on ? HIGH : LOW);
}
bool TEchoBacklight::isTouchPressed()
{
return digitalRead(PIN_BUTTON_TOUCH) == LOW;
}
void TEchoBacklight::peek()
{
setBacklight(true);
backlightLatched = false;
}
void TEchoBacklight::latch()
{
if (backlightLatched) {
LOG_INFO("TEchoBacklight: latch() - turning OFF");
backlightLatched = false;
setBacklight(false);
} else {
LOG_INFO("TEchoBacklight: latch() - turning ON");
backlightLatched = true;
setBacklight(true);
}
}
void TEchoBacklight::off()
{
backlightLatched = false;
setBacklight(false);
}
void TEchoBacklight::touchISR()
{
static volatile bool isrRunning = false;
if (!isrRunning && tEchoBacklight) {
isrRunning = true;
if (tEchoBacklight->state == REST) {
tEchoBacklight->state = IRQ;
tEchoBacklight->irqAtMillis = millis();
tEchoBacklight->startThread();
LOG_INFO("TEchoBacklight: ISR triggered - starting thread");
}
isrRunning = false;
}
}
void TEchoBacklight::startThread()
{
if (!OSThread::enabled) {
OSThread::setInterval(POLL_INTERVAL_MS);
OSThread::enabled = true;
}
}
void TEchoBacklight::stopThread()
{
if (OSThread::enabled) {
OSThread::disable();
}
state = REST;
}
#endif

View File

@ -0,0 +1,43 @@
#pragma once
#include "configuration.h"
#if defined(TTGO_T_ECHO) && !defined(MESHTASTIC_INCLUDE_NICHE_GRAPHICS)
#include "concurrency/OSThread.h"
class TEchoBacklight : public concurrency::OSThread
{
public:
TEchoBacklight();
int32_t runOnce() override;
void setPin(uint8_t pin);
void start();
void peek();
void latch();
void off();
private:
static constexpr uint32_t LATCH_TIME_MS = 5000;
static constexpr uint32_t POLL_INTERVAL_MS = 10;
static constexpr uint32_t DEBOUNCE_MS = 50;
static constexpr uint32_t BLINK_DELAY_MS = 25;
static constexpr uint8_t BLINK_STEPS = 3;
enum State { REST, IRQ, POLLING_UNFIRED, POLLING_FIRED, BLINKING };
bool backlightLatched = false;
uint32_t irqAtMillis = 0;
State state = REST;
uint32_t blinkStartTime = 0;
uint8_t blinkStep = 0;
void setBacklight(bool on);
bool isTouchPressed();
static void touchISR();
void startThread();
void stopThread();
};
extern TEchoBacklight *tEchoBacklight;
#endif

View File

@ -22,6 +22,7 @@
#include "nrf.h" #include "nrf.h"
#include "wiring_constants.h" #include "wiring_constants.h"
#include "wiring_digital.h" #include "wiring_digital.h"
#include "TEchoBacklight.h"
const uint32_t g_ADigitalPinMap[] = { const uint32_t g_ADigitalPinMap[] = {
// P0 - pins 0 and 1 are hardwired for xtal and should never be enabled // P0 - pins 0 and 1 are hardwired for xtal and should never be enabled

View File

@ -124,7 +124,6 @@ extern "C" {
#define GPS_RTC_INT (0 + 15) // P0.15, normal is LOW, wake by HIGH #define GPS_RTC_INT (0 + 15) // P0.15, normal is LOW, wake by HIGH
#define GPS_RESETB_OUT (32 + 14) // P1.14, always input pull_up #define GPS_RESETB_OUT (32 + 14) // P1.14, always input pull_up
#define GPS_FIX_HOLD_TIME 15000 // ms
#define BATTERY_PIN 2 // P0.02/AIN0, BAT_ADC #define BATTERY_PIN 2 // P0.02/AIN0, BAT_ADC
#define BATTERY_IMMUTABLE #define BATTERY_IMMUTABLE
#define ADC_MULTIPLIER (2.0F) #define ADC_MULTIPLIER (2.0F)

View File

@ -123,7 +123,6 @@ extern "C" {
#define GPS_RESETB_OUT (32 + 14) // P1.14, awlays input pull_up #define GPS_RESETB_OUT (32 + 14) // P1.14, awlays input pull_up
// #define GPS_THREAD_INTERVAL 50 // #define GPS_THREAD_INTERVAL 50
#define GPS_FIX_HOLD_TIME 15000 // ms
#define BATTERY_PIN 2 #define BATTERY_PIN 2
// #define ADC_CHANNEL ADC1_GPIO2_CHANNEL // #define ADC_CHANNEL ADC1_GPIO2_CHANNEL

View File

@ -6,6 +6,10 @@ board_upload.maximum_size = 233472 ; reserve the last 28KB for filesystem
build_flags = build_flags =
${stm32_base.build_flags} ${stm32_base.build_flags}
-Ivariants/stm32/rak3172 -Ivariants/stm32/rak3172
-DRAK3172
-DENABLE_HWSERIAL1
-DPIN_SERIAL1_RX=PB7
-DPIN_SERIAL1_TX=PB6
-DPIN_WIRE_SDA=PA11 -DPIN_WIRE_SDA=PA11
-DPIN_WIRE_SCL=PA12 -DPIN_WIRE_SCL=PA12
-DMESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR=1 -DMESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR=1