Compare commits

...

36 Commits

Author SHA1 Message Date
Ben Meadors
2f9b68e08b 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
2024-04-15 16:36:22 -05:00
Ben Meadors
27ae4399bc Zero hop always for connected node (#3634) 2024-04-15 16:35:52 -05:00
Gareth Coleman
1291da746b 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 <benmmeadors@gmail.com>
2024-04-15 07:30:45 -05:00
Ben Meadors
2803fa964e Add LoadFileState to differentiate types of success / failures (#3625) 2024-04-15 07:22:05 -05:00
todd-herbert
1d97544041 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 66347ce19b.
2024-04-15 06:50:42 -05:00
Jonathan Bennett
5b52c31a76 Fix HAS_WIRE logic in main 2024-04-14 16:44:28 -05:00
Jonathan Bennett
00d4c011c7 Fix sx126x error log logic 2024-04-14 16:44:28 -05:00
Jonathan Bennett
1447148811 Make sure settingsStrings get initialized 2024-04-14 16:44:28 -05:00
Ben Meadors
4f205718f0 Device telemetry uptime in seconds (#3614) 2024-04-14 10:27:01 -05:00
Manuel
5047468d9f 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 <benmmeadors@gmail.com>
2024-04-14 09:11:27 -05:00
Manuel
ec3971bce5 fix upDown ISR (#3612) 2024-04-14 08:11:22 -05:00
Jonathan Bennett
0a246bfe9b Add more useful error output in radio interfaces (#3615)
* Add more useful error output in radio interfaces

* trunk
2024-04-14 00:29:42 -05:00
Jonathan Bennett
f1a1834ee2 Update portduino to include SPI and setSetial fixes (#3611) 2024-04-13 16:14:15 -05:00
Ben Meadors
2a6e26620e Auto-favorite our node (#3609) 2024-04-12 20:17:25 -05:00
Jonathan Bennett
3f45c2d4f0 Fix another LOG_DEBUG message that should be LOG_ERROR (#3607) 2024-04-12 14:14:56 -05:00
Jonathan Bennett
11adfe05ce Drop unishox2 functions from Router (#3606) 2024-04-12 14:06:05 -05:00
Ben Meadors
b4009f9f2f New fixed copy-pasted more corrector hash 2024-04-12 11:49:35 -05:00
Jonathan Bennett
917b739e62 Update TinyGPS version to un-derped commit 2024-04-12 11:29:08 -05:00
Ben Meadors
2c4db16336 TinyGPSAltitude support for negative altitude (#3605) 2024-04-12 10:49:14 -05:00
Manuel
4c9646f7d9 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 <benmmeadors@gmail.com>
2024-04-12 10:01:24 -05:00
Oliver Seiler
8fd32f3452 enable USB CDC (#3597) 2024-04-12 07:19:48 -05:00
todd-herbert
178877f2d9 Enable T-Echo touch button by default (#3604)
Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
2024-04-12 07:18:36 -05:00
Jonathan Bennett
6de0363eea Pin RadioLib to 6.5.x (#3601) 2024-04-12 07:17:43 -05:00
Gareth Coleman
f4a2023dba 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 <hamish@gate.ac.uk>
Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
2024-04-11 19:40:14 -05:00
Manuel
927d07e2c6 fix: device PMU shutdown (part 2) (#3596)
* fix: device PMU shutdown (part 2)

* fix error + enable nimble deinit
2024-04-11 19:39:07 -05:00
github-actions[bot]
a4a8556aa2 [create-pull-request] automated change (#3595)
Co-authored-by: thebentern <thebentern@users.noreply.github.com>
2024-04-11 07:41:37 -05:00
todd-herbert
8e29efcb50 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>
2024-04-11 07:02:50 -05:00
GUVWAF
3bee6ce9c3 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
2024-04-10 11:29:29 -05:00
Thomas Göttgens
fcab20fb3b Merge pull request #3580 from meshtastic/add-iaq
add BME680 IAQ reading
2024-04-09 21:55:42 +02:00
Thomas Göttgens
2d81c97b98 fix #2586 (lower IAQ quality for saving to 2 and rework save logic) 2024-04-09 21:20:36 +02:00
Thomas Göttgens
cfd98b2c91 add BME680 IAQ reading. Range is from 0 (clean) - 500 (extremely polluted) 2024-04-09 21:20:36 +02:00
rcarteraz
6e7405e56b add unphone (#3584) 2024-04-09 12:26:03 -05:00
rcarteraz
77082e35f5 Add unPhone to S3 build scripts (#3583)
* add unphone to s3 devices

* add unphone
2024-04-09 11:37:38 -05:00
github-actions[bot]
daa64b055a [create-pull-request] automated change (#3579)
Co-authored-by: caveman99 <caveman99@users.noreply.github.com>
2024-04-09 08:00:19 -05:00
Thomas Göttgens
ec74fba2bd 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
2024-04-09 07:40:55 -05:00
github-actions[bot]
e89575bfd1 [create-pull-request] automated change (#3577)
Co-authored-by: thebentern <thebentern@users.noreply.github.com>
2024-04-08 18:43:10 -05:00
91 changed files with 575 additions and 267 deletions

View File

@@ -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 }}

View File

@@ -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: |

View File

@@ -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 =

View File

@@ -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 (

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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"
],

View File

@@ -74,11 +74,11 @@ 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
https://github.com/meshtastic/TinyGPSPlus.git#f9f4fef2183514aa52be91d714c1455dd6f26e45
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,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

View File

@@ -5,6 +5,7 @@
#include "power.h"
#include <Adafruit_LIS3DH.h>
#include <Adafruit_LSM6DS3TRC.h>
#include <Adafruit_MPU6050.h>
#include <Arduino.h>
#include <SensorBMA423.hpp>
@@ -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

View File

@@ -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

View File

@@ -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;

View File

@@ -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

View File

@@ -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);
@@ -102,18 +106,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 {

View File

@@ -128,6 +128,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#define MPU6050_ADDR 0x68
#define LIS3DH_ADR 0x18
#define BMA423_ADDR 0x19
#define LSM6DS3_ADDR 0x6A
// -----------------------------------------------------------------------------
// LED
@@ -137,9 +138,13 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
// -----------------------------------------------------------------------------
// Security
// -----------------------------------------------------------------------------
#define ATECC608B_ADDR 0x35
// -----------------------------------------------------------------------------
// IO Expander
// -----------------------------------------------------------------------------
#define TCA9555_ADDR 0x26
// -----------------------------------------------------------------------------
// GPS
// -----------------------------------------------------------------------------
@@ -280,4 +285,4 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#ifdef MESHTASTIC_EXCLUDE_SCREEN
#undef HAS_SCREEN
#define HAS_SCREEN 0
#endif
#endif

View File

@@ -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;

View File

@@ -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

View File

@@ -39,6 +39,8 @@ class ScanI2C
LIS3DH,
BMA423,
BQ24295,
LSM6DS3,
TCA9555,
#ifdef HAS_NCP5623
NCP5623,
#endif

View File

@@ -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,6 +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 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);

View File

@@ -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

View File

@@ -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;
}

View File

@@ -3,7 +3,7 @@
#include "InputBroker.h"
#include "mesh/NodeDB.h"
class UpDownInterruptBase : public Observable<const InputEvent *>
class UpDownInterruptBase : public Observable<const InputEvent *>, public concurrency::OSThread
{
public:
explicit UpDownInterruptBase(const char *name);
@@ -13,6 +13,13 @@ class UpDownInterruptBase : public Observable<const InputEvent *>
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;

View File

@@ -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;
@@ -188,9 +192,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);
@@ -386,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<ScanI2CTwoWire>(new ScanI2CTwoWire());
#ifdef HAS_WIRE
#if HAS_WIRE
LOG_INFO("Scanning for i2c devices...\n");
#endif
@@ -796,6 +797,7 @@ void setup()
rIf = NULL;
} else {
LOG_INFO("STM32WL Radio init succeeded, using STM32WL radio\n");
radioType = STM32WLx_RADIO;
}
}
#endif
@@ -809,6 +811,7 @@ void setup()
rIf = NULL;
} else {
LOG_INFO("Using SIMULATED radio!\n");
radioType = SIM_RADIO;
}
}
#endif
@@ -822,6 +825,7 @@ void setup()
rIf = NULL;
} else {
LOG_INFO("RF95 Radio init succeeded, using RF95 radio\n");
radioType = RF95_RADIO;
}
}
#endif
@@ -835,6 +839,7 @@ void setup()
rIf = NULL;
} else {
LOG_INFO("SX1262 Radio init succeeded, using SX1262 radio\n");
radioType = SX1262_RADIO;
}
}
#endif
@@ -848,6 +853,7 @@ void setup()
rIf = NULL;
} else {
LOG_INFO("SX1268 Radio init succeeded, using SX1268 radio\n");
radioType = SX1268_RADIO;
}
}
#endif
@@ -861,6 +867,7 @@ void setup()
rIf = NULL;
} else {
LOG_INFO("LLCC68 Radio init succeeded, using LLCC68 radio\n");
radioType = LLCC68_RADIO;
}
}
#endif
@@ -874,6 +881,7 @@ void setup()
rIf = NULL;
} else {
LOG_INFO("SX1280 Radio init succeeded, using SX1280 radio\n");
radioType = SX1280_RADIO;
}
}
#endif

View File

@@ -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()
@@ -346,6 +352,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;
@@ -517,11 +526,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) ||
@@ -541,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);
@@ -554,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) {
@@ -592,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) {
@@ -604,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) {
@@ -616,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) {
@@ -628,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");
}
}
@@ -667,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
}
@@ -713,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);
}
@@ -724,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);
}

View File

@@ -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);

View File

@@ -430,6 +430,9 @@ 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
}
}
return true; // Always say we have something, because we might need to advance our state machine

View File

@@ -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");

View File

@@ -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);
}
}
}

View File

@@ -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);
}
}

View File

@@ -181,12 +181,18 @@ template <typename T> bool SX126xInterface<T>::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 <typename T> bool SX126xInterface<T>::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 <typename T> void SX126xInterface<T>::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 <typename T> void SX126xInterface<T>::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 <typename T> bool SX126xInterface<T>::isChannelActive()
result = lora.scanChannel();
if (result == RADIOLIB_LORA_DETECTED)
return true;
if (result != RADIOLIB_CHANNEL_FREE)
LOG_ERROR("Radiolib error %d when attempting SX126X scanChannel!\n", result);
assert(result != RADIOLIB_ERR_WRONG_MODEM);
return false;

View File

@@ -126,9 +126,13 @@ template <typename T> bool SX128xInterface<T>::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 <typename T> bool SX128xInterface<T>::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 <typename T> void SX128xInterface<T>::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 <typename T> void SX128xInterface<T>::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 <typename T> bool SX128xInterface<T>::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;

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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,8 +305,9 @@ 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_NodeInfoLite_size 166
#define meshtastic_OEMStore_size 3344
#define meshtastic_PositionLite_size 28

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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
@@ -1383,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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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
@@ -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 */
@@ -73,6 +75,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) */
@@ -153,13 +158,13 @@ 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_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_EnvironmentMetrics_init_zero {0, 0, 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}
#define meshtastic_Telemetry_init_zero {0, 0, {meshtastic_DeviceMetrics_init_zero}}
@@ -169,12 +174,14 @@ 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
#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
@@ -204,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
@@ -214,7 +222,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 +280,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_DeviceMetrics_size 27
#define meshtastic_EnvironmentMetrics_size 34
#define meshtastic_PowerMetrics_size 30
#define meshtastic_Telemetry_size 79

View File

@@ -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

View File

@@ -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

View File

@@ -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();
}
}

View File

@@ -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",

View File

@@ -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;
}
}

View File

@@ -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;

View File

@@ -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;
};

View File

@@ -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)

View File

@@ -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;
}
@@ -85,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++;
}
@@ -103,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);
}

View File

@@ -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()

View File

@@ -6,6 +6,7 @@ class NimbleBluetooth : BluetoothApi
public:
void setup();
void shutdown();
void deinit();
void clearBonds();
bool isActive();
bool isConnected();

View File

@@ -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;
}
}
}

View File

@@ -4,9 +4,11 @@
#include "GPS.h"
#endif
#include "ButtonThread.h"
#include "MeshRadio.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "detect/LoRaRadioType.h"
#include "error.h"
#include "main.h"
#include "sleep.h"
@@ -152,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);
}
@@ -204,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);
@@ -244,6 +252,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.
@@ -256,6 +280,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) {
@@ -270,25 +295,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);
}
@@ -337,9 +352,15 @@ 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
#ifdef T_WATCH_S3
gpio_wakeup_enable((gpio_num_t)SCREEN_TOUCH_INT, GPIO_INTR_LOW_LEVEL);
#endif
enableLoraInterrupt();
#ifdef PMU_IRQ
@@ -349,24 +370,43 @@ 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);
}
assert(res == ESP_OK);
res = esp_light_sleep_start();
if (res != ESP_OK) {
LOG_DEBUG("esp_light_sleep_start 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_ERROR("esp_light_sleep_start result %d\n", res);
}
// 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
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
#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);
}
#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();
@@ -374,8 +414,11 @@ esp_sleep_wakeup_cause_t doLightSleep(uint64_t sleepMsec) // FIXME, use a more r
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;
}
@@ -417,20 +460,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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -1,4 +1,4 @@
[VERSION]
major = 2
minor = 3
build = 4
build = 5