Compare commits

...

138 Commits

Author SHA1 Message Date
Ben Meadors
4fa7f5a748 Fix devicestate persistence bug 2024-03-19 10:31:31 -05:00
Manuel
a6625998f5 fix compiler warnings in NodeDB.h (#3439)
* fix warnings on arm

* make trunk+compiler happy
2024-03-19 06:22:45 -05:00
Manuel
711b85cfe8 fix WLAN crash (#3435)
* fix WLAN crash

* link to commit in arduinothread

* revert usb mode
2024-03-18 15:42:44 -05:00
github-actions[bot]
b98176e73e [create-pull-request] automated change (#3434)
Co-authored-by: thebentern <thebentern@users.noreply.github.com>
2024-03-18 07:33:01 -05:00
Ben Meadors
aae49f5ecf Remove confusing channel suffix (#3432)
* Remove confusing channel suffix

* Missed it
2024-03-17 08:38:49 -05:00
Ben Meadors
0d1d79b6d1 Extract default intervals and coalesce methods into their own file / static class methods (#3425)
* Extract default intervals and coalesce methods into their own file / static class methods

* Missed pax

* Still managed to miss one
2024-03-17 08:18:30 -05:00
Ben Meadors
bb57ccfc9e Remove devicestate no_save (#3424) 2024-03-17 08:16:22 -05:00
Ben Meadors
e27f029d09 Bump minimum NodeInfo send to 5 minutes (#3423)
* Bump minimum NodeInfo send to 3 minutes

* 5
2024-03-16 19:56:42 -05:00
Thomas Göttgens
13cc1b0252 (3/3) Add variant for pico with waveshare and GPS hat (#3412)
* (3/3) Add variant for pico with waveshare and GPS hat, utilizing slow clock.

* Not everybody has Serial2

* Trunk

* Push it real gud

* No init

---------

Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
2024-03-16 10:01:43 -05:00
github-actions[bot]
54a2a4bcc6 [create-pull-request] automated change (#3422)
Co-authored-by: thebentern <thebentern@users.noreply.github.com>
2024-03-16 07:39:28 -05:00
David Ellefsen
611f291d4d Factory reset GNSS_MODEL_MTK GPS modules with PCAS10,3 (#3388)
Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
2024-03-15 19:19:50 -05:00
Ben Meadors
9586606229 Handle for heartbeat toradio packets (#3420) 2024-03-15 18:40:48 -05:00
github-actions[bot]
0de36fbfb0 [create-pull-request] automated change (#3419)
Co-authored-by: thebentern <thebentern@users.noreply.github.com>
2024-03-15 17:12:45 -05:00
Andre K
0dda20bc35 fix for I2C scan getting stuck (#3375)
* refactor: add delay for T-Echo peripherals setup

* comment out `PIN_POWER_EN1`
2024-03-15 17:12:30 -05:00
Ben Meadors
52cfec29fc More comprehensive client proxy queue guards (#3414)
* More comprehensive MQTT thread and queue guards

* Consolidate logic

* Remove channel check

* Check for map_reporting_enabled as well

* Update message

* Remove channel check from here as well

* One liner

* Start the mqtt thread back up when channels change and we want mqtt
2024-03-15 16:17:47 -05:00
Thomas Göttgens
4d0d82f7e7 Merge pull request #3411 from meshtastic/rp2040-slowclock
(2/3) Add Slow Clock Support for RP2040 platform.
2024-03-15 20:56:50 +01:00
Thomas Göttgens
34bc22f94d (2/3) Add Slow Clock Support for RP2040 platform. This will disable USB Softserial. 2024-03-15 20:16:36 +01:00
Thomas Göttgens
cb3740708b Merge pull request #3410 from meshtastic/gnss-l76b
(1/3) Support L76B GNSS chip found on pico waveshare shield.
2024-03-15 20:16:06 +01:00
Thomas Göttgens
e8ec167854 Merge branch 'gnss-l76b' of github.com:meshtastic/firmware into gnss-l76b 2024-03-15 19:48:19 +01:00
Thomas Göttgens
b900415218 that should work now 2024-03-15 19:47:47 +01:00
Thomas Göttgens
2eb78fec53 Merge branch 'master' into gnss-l76b 2024-03-15 19:39:47 +01:00
Thomas Göttgens
da7cd5fc7f new Accelerometer lib (#3413)
* new Accelerometer lib

* Use our fork till upstreasm merges changes.

* that PR escalated quickly

* resurrect display flip
2024-03-15 10:45:14 -05:00
Thomas Göttgens
b06c77d46f don't fix this to a hardware model. 2024-03-15 16:43:39 +01:00
Thomas Göttgens
cbc0aa16c5 fix compilation 2024-03-15 16:37:47 +01:00
github-actions[bot]
876a0520a9 [create-pull-request] automated change (#3418)
Co-authored-by: thebentern <thebentern@users.noreply.github.com>
2024-03-15 08:09:48 -05:00
Thomas Göttgens
50cc4cfcf1 We don't use Lorawan (#3417)
#warning "Persistent storage not supported!" [-Wcpp]
2024-03-15 08:07:54 -05:00
Ben Meadors
ec6bdeed81 NodeInfo broadcast ensure default on 0 and enforce 1 hour minimum (#3415)
* NodeInfo broadcasts ensure defaults on 0 and enforce 1 hour minumum

* Doh!

* Hey that's not on config!
2024-03-15 07:12:03 -05:00
Ben Meadors
a085c3ddb3 Try-fix router missed messages (#3405) 2024-03-14 17:00:57 -05:00
Thomas Göttgens
58cdf360f8 (1/3) Support L76B GNSS chip found on pico waveshare shield. Original work by @Mictronics 2024-03-14 16:18:33 +01:00
Ben Meadors
9c37e57e75 Only allow phone to set time for fixed positions (#3403) 2024-03-13 20:27:26 -05:00
Andre K
9d2fcbe1e1 use decoded packets in public MQTT range test/detection sensor filter (#3404)
Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
2024-03-13 18:24:49 -05:00
Ben Meadors
3995e2f708 Remove bunk code 2024-03-13 15:06:52 -05:00
github-actions[bot]
216f85ff22 [create-pull-request] automated change (#3397)
Co-authored-by: thebentern <thebentern@users.noreply.github.com>
2024-03-13 09:02:48 -05:00
Ben Meadors
2efe436102 Update nrf52 platform and consolidate Adafruit Bus IO (#3393) 2024-03-13 07:20:51 -05:00
Thomas Göttgens
fb16390205 Merge pull request #3395 from tavdog/patch_buzzer_no_turnoff_off_by_one_error
fix off by one error
2024-03-13 09:23:14 +01:00
Tavis
333c3c1c9e fix off by one error
buzzer is index 2, but loop was 0-1 so buzzer never got turned off.
2024-03-12 21:42:08 -10:00
GUVWAF
724fa38a55 Fix T-LoRa V2.1-6 with TCXO init (#3392) 2024-03-12 16:42:34 -05:00
Wolfgang Nagele
38ea681433 Fix LTO discharge curve (#3385)
* Fix LTO discharge curve

* Remove duplicate info
2024-03-12 16:42:21 -05:00
Wolfgang Nagele
ee685b4ed7 Check AQ_SET_PIN instead of EINK dependency (#3387) 2024-03-12 13:03:04 -05:00
Thomas Herrmann
cf11807f97 use priority background for low priority messages (#3381) 2024-03-12 12:21:09 -05:00
Wolfgang Nagele
7f063fbf81 Support external charge detection (#3386)
* Support external charge detection

* trunk fmt
2024-03-12 11:55:31 -05:00
Thomas Göttgens
6215495ccc Merge pull request #3379 from meshtastic/create-pull-request/patch
Changes by create-pull-request action
2024-03-12 10:26:17 +01:00
GUVWAF
045dda64e7 Merge pull request #3383 from AeroXuk/patch-1
Fix for incorrect mapTopic mqtt path
2024-03-12 08:39:30 +01:00
AeroXuk
affbd7f2b9 Update MQTT.cpp
Bug fix for #3382
2024-03-12 02:13:52 +00:00
thebentern
f9bf9e2dcc [create-pull-request] automated change 2024-03-11 21:43:46 +00:00
GUVWAF
5f47ca1f32 Don't spam logs if no position with map reporting (#3378) 2024-03-11 15:58:45 -05:00
Thomas Göttgens
6a27e62bcf Merge pull request #3356 from todd-herbert/eink-special-frames
Handle "special-frames" with EInkDynamicDisplay
2024-03-11 21:43:39 +01:00
Ben Meadors
2d5a6c1a20 Merge branch 'master' into eink-special-frames 2024-03-11 13:32:42 -05:00
Manuel
c7839b469b fix of tryfix SHT31 sensor (#3377) 2024-03-11 12:51:14 -05:00
Ben Meadors
95967a01b8 Merge branch 'master' into eink-special-frames 2024-03-11 12:46:32 -05:00
Manuel
e16689a0d6 fix heap use after delete (#3373) 2024-03-11 12:45:59 -05:00
Andre K
c80098f517 refactor: remove ACKs in range tests so zero hops is honored (#3374) 2024-03-11 11:49:46 -05:00
Todd Herbert
1f766a04aa purge unused enum val 2024-03-12 04:04:28 +13:00
Todd Herbert
1d31be939f Swap Wireless Paper V1.0 dependency to meshtastic/GxEPD2 2024-03-12 03:06:01 +13:00
Thomas Göttgens
4b4bd07d5c Merge branch 'master' into eink-special-frames 2024-03-11 14:10:19 +01:00
todd-herbert
cf4753f7fd Async full-refresh for EInkDynamicDisplay (#3339)
* Move Wireless Paper V1.1 custom hibernate behavior to GxEPD2

* Async full-refresh for EInkDynamicDisplay

* initial config for T-Echo

* formatting
responds to https://github.com/meshtastic/firmware/pull/3339#discussion_r1518175434

* increase fast-refresh limit for T-Echo
https://github.com/meshtastic/firmware/pull/3339#issuecomment-1986245727

* change dependency from private repo to meshtastic/GxEPD2

---------

Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
2024-03-11 07:56:55 -05:00
Thomas Göttgens
892223a297 fix typos and add 2 missing modules to the equasion (#3370) 2024-03-11 07:52:46 -05:00
Thomas Göttgens
658ed6fd28 tryfix SHT31 sensor on secondary bus 2024-03-11 13:51:26 +01:00
David Ellefsen
3a8f623f8a Change '! -z' to '-n' to addresss shellcheck/SC2236 2024-03-11 12:09:00 +01:00
David Ellefsen
f09e5c96fc Add permission: read-all to silence CKV_GHA_1 check 2024-03-11 12:09:00 +01:00
David Ellefsen
a493ab526f Trunk fmt to correct failing PR check for device-install.sh 2024-03-11 12:09:00 +01:00
David Ellefsen
b3ec3c20fb Update device-install.sh files to account for bleota-c3.bin file 2024-03-11 12:09:00 +01:00
David Ellefsen
b65b9e5d65 Include esp32c3 build step 2024-03-11 12:09:00 +01:00
Kevin Cai
766beefbc5 Update AccelerometerThread.h to work with T-Watch S3 2024-03-11 10:58:25 +01:00
Thomas Göttgens
eb372c190e Merge pull request #3365 from GUVWAF/mapReport
Periodic reporting of device information to a map via MQTT
2024-03-10 20:55:31 +01:00
Thomas Göttgens
70df36b5db Merge branch 'master' into mapReport 2024-03-10 20:54:48 +01:00
Thomas Göttgens
e33d014257 Merge pull request #3351 from thoherr/refactor-paxcounter
Refactor paxcounter
2024-03-10 18:49:16 +01:00
Thomas Herrmann
26691c0be7 include requested change and suggestions on PR from @caveman99 2024-03-10 16:08:26 +01:00
Thomas Herrmann
09e08e0091 add some documentation, cleanup 2024-03-10 16:08:26 +01:00
Thomas Herrmann
73c77b663c fix typo 2024-03-10 16:08:26 +01:00
Thomas Herrmann
fb4faf790b split query of paxcounter data from sending funcionality; don't cummulate (count mode != 1); use flag to signal changed count data 2024-03-10 16:08:26 +01:00
GUVWAF
cb7407e06b Don't need to check all channels if not using default frequency slot 2024-03-10 16:04:59 +01:00
GUVWAF
b45a912409 Use dedicated map topic 2024-03-10 15:56:00 +01:00
Thomas Göttgens
c7d5698dbc Merge branch 'master' into mapReport 2024-03-10 15:40:22 +01:00
Thomas Göttgens
d1a25947e3 Merge pull request #3366 from meshtastic/create-pull-request/patch
Changes by create-pull-request action
2024-03-10 15:40:05 +01:00
caveman99
69dcc948b9 [create-pull-request] automated change 2024-03-10 14:39:40 +00:00
GUVWAF
084b01715e Merge remote-tracking branch 'origin/master' into mapReport 2024-03-10 14:54:41 +01:00
GUVWAF
af9d14c370 Periodic reporting of device information to a map via MQTT 2024-03-10 14:52:37 +01:00
Todd Herbert
1032e16ea4 reorder determineMode() checks 2024-03-11 01:02:03 +13:00
Andre K
3da1b74a10 refactor: always send range tests with zero hops 2024-03-10 10:50:02 +01:00
Todd Herbert
c0a3b20aa3 while drafting, build from todd-herbert/meshtastic-GxEPD2#async 2024-03-10 13:45:35 +13:00
Todd Herbert
3daae24d29 fix fallback behavior for unmodified GxEPD2
Issues exposed by https://github.com/meshtastic/firmware/pull/3356#issuecomment-1986950317
2024-03-10 13:43:57 +13:00
Jonathan Bennett
dced888492 Add precision_bit sto json 2024-03-09 15:34:01 -06:00
Ben Meadors
7167f1e04f Add parens to macro (#3361) 2024-03-09 15:25:16 -06:00
Ben Meadors
dfbb4cd913 Merge branch 'master' into eink-special-frames 2024-03-09 14:10:09 -06:00
GUVWAF
3da7c0dba7 Add hops_away to JSON output (#3357) 2024-03-09 11:32:49 -06:00
Todd Herbert
7b70324435 handle special frames in Screen.cpp 2024-03-10 05:00:51 +13:00
Todd Herbert
94eb837ee8 function macro for tidier addFramFlag() calls 2024-03-10 04:14:45 +13:00
Todd Herbert
a9c07a4c01 add frameFlags to LOG_DEBUG() messages 2024-03-10 04:07:51 +13:00
Todd Herbert
e232e3462c add BLOCKING modifier to frameFlagTypes 2024-03-10 03:48:59 +13:00
Todd Herbert
94794edd43 add init code as a determineMode() check 2024-03-10 03:43:07 +13:00
Todd Herbert
95b6f27d2a change order of determineMode() checks 2024-03-10 03:38:39 +13:00
Todd Herbert
efd818fe90 move storeAndReset() to end of update() 2024-03-10 03:07:13 +13:00
Todd Herbert
576f582cd9 rename setFrameFlag() method 2024-03-10 02:30:16 +13:00
Todd Herbert
d5c11d1892 change dependency from private repo to meshtastic/GxEPD2 2024-03-10 02:11:49 +13:00
Ben Meadors
aaa5d61162 Merge branch 'master' into eink-async 2024-03-09 07:06:04 -06:00
Ben Meadors
3efd606ea7 Bump to 2.3.0 2024-03-09 07:01:46 -06:00
Ben Meadors
42286edc81 Merge branch 'master' into eink-async 2024-03-09 06:59:56 -06:00
Mark Trevor Birss
29335a18f5 Update variant.h (#3354) 2024-03-09 06:55:02 -06:00
Andre K
51df4fc775 fix: turn off T-Echo peripherals on deep sleep (#3162)
Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
2024-03-08 20:15:37 -06:00
Ben Meadors
0f1bc98305 Update MQTT topic to match (#3353) 2024-03-08 20:15:00 -06:00
Todd Herbert
23926210d1 increase fast-refresh limit for T-Echo
https://github.com/meshtastic/firmware/pull/3339#issuecomment-1986245727
2024-03-09 09:57:30 +13:00
Todd Herbert
7275c21f6b formatting
responds to https://github.com/meshtastic/firmware/pull/3339#discussion_r1518175434
2024-03-09 09:34:53 +13:00
Todd Herbert
ac89bb3387 initial config for T-Echo 2024-03-09 09:30:34 +13:00
Todd Herbert
07da130586 Async full-refresh for EInkDynamicDisplay 2024-03-09 09:30:34 +13:00
Todd Herbert
5d4d91f775 Move Wireless Paper V1.1 custom hibernate behavior to GxEPD2 2024-03-09 09:30:34 +13:00
Ben Meadors
7da1153c2c Fix known_only panic by short circuiting for NULL before checking has_user (#3352) 2024-03-08 08:31:49 -06:00
GUVWAF
585805c3b9 Add original hop limit to header to determine hops used (#3321)
* Set `hop_start` in header to determine how many hops each packet traveled

* Set hopLimit of response according to hops used by request

* Identify neighbors based on `hopStart` and `hopLimit`

* NeighborInfo: get all packets and assume a default broadcast interval

* Add fail-safe in case node in between is running modified firmware

* Add `viaMQTT` and `hopsAway` to NodeInfo

* Replace `HOP_RELIABLE` with hopStart for repeated packet

---------

Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
2024-03-08 07:13:57 -06:00
Thomas Göttgens
a4830e0ab1 Merge pull request #3347 from thoherr/add-bmp085_180-sensor
add BMP085 (and BMP180) sensor (temperature and air pressure)
2024-03-08 12:02:43 +01:00
Thomas Herrmann
763ae9f2e2 add BMP085 (and BMP180) sensor (temperature and air pressure) 2024-03-07 23:58:04 +01:00
Ben Meadors
7f12505716 Update trunk 2024-03-07 15:52:08 -06:00
Ben Meadors
b4940b476d Trunk 2024-03-07 15:51:28 -06:00
Steven Osborn
c860493e68 Add delay so GPS and Radio have time to power up (#3334)
* Add delay so GPS and Radio have time to power up

* reduce the delay a bit

* make delay more generic / configurable

* remove whitespace changes
2024-03-07 07:11:25 -06:00
github-actions[bot]
2dd751e339 [create-pull-request] automated change (#3346)
Co-authored-by: thebentern <thebentern@users.noreply.github.com>
2024-03-07 07:06:47 -06:00
Jonathan Bennett
bfce3938d2 Add openssl as dependency to meshtasticd .deb 2024-03-06 18:54:09 -06:00
Jonathan Bennett
46ad623785 Add webroot to .deb 2024-03-06 17:43:04 -06:00
Jonathan Bennett
e174328de3 Native Webserver (#3343)
* Added WebServer/WebServices for Native Linux Meshtastic and web gui

* Fix bug in login functionality

* Added customized config of portdunio.ini with LovyannGFX from marelab repro

* Compile Problem resolved with developer version of LovyanGFX.git

* Compile against dev version

* Fixes to fit into main branch

* Update variant.h, main.cpp, .gitignore, WebServer.cpp, esp32s2.ini, WebServer.h, ContentHandler.cpp, rp2040.ini, nrf52.ini, ContentHelper.cpp, Dockerfile, ContentHandler.h, esp32.ini, stm32wl5e.ini

* Added linux pi std /usr/include dir

* Adding /usr/innclude for Linux compile against native libs that are not hadled by platformio

* Review log level changes & translation

* Update Dockerfile

* Fix Typo & VFS ref. Part1

* Fix Typo & VFS ref.

* Dev Version for ulfius web lib

* Update platformio.ini

* Free VFS path string

* Remove unintended changes

* More unintentional changes

* Make the HTTP server optional on native

* Tune-up for Native web defaults

* Don't modify build system yet

* Remove more unneeded changes

---------

Co-authored-by: marc hammermann <marchammermann@googlemail.com>
Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
Co-authored-by: Thomas Göttgens <tgoettgens@gmail.com>
2024-03-06 16:23:04 -06:00
Jonathan Bennett
9d37a8d17f Stop Fiddling with Newlines! (#3341) 2024-03-06 13:09:46 -06:00
Thomas Göttgens
f5ff77c2b9 Turn off certain modules not wanted in custom builds (#3337) 2024-03-05 07:50:52 -06:00
Ben Meadors
72050530f1 NRF52 bluetooth cleanup and fix (#3328)
* NRF52 bluetooth cleanup. Fixes BLE not returning after serial PhoneAPI connection

* Use new var name in esp32 arch
2024-03-03 13:56:55 -06:00
Ken McGuire
e5bf07d4fb Fix for issue #3310 (#3327)
* Portduino multiple logging levels

* Fixes based on GPSFan work

* Fix derped logic

* Correct size field for AID message

* Reformat to add comments, beginning of GPS rework

* Update PM2 message for Neo-6

* Correct ECO mode logic as ECO mode is only for Neo-6

* Cleanup ubx.h add a few more comments

* GPS rework, changes for M8 and stub for M10

* Add VALSET commands for u-blox M10 receivers

* Add VALSET commands for u-blox M10 receivers
tweak M8 commands
add comments for VALSET configuration commands

* Add commands to init M10 receivers,
tweak the M8 init sequence, this is a WIP as there are still some issues during init.
Add M10 version of PMREQ.

* Add wakeup source of uartrx to PMREQ_10
The M10 does not respond to commands when asleep,
may need to do this for the M8 as well

* Enable NMEA messages on USB port.
Normally, it is a good idea to disable messages on unused ports.
Native Linux needs to be able to use GNSS modules connected via
via either serial or USB.
In the future I2C connections may be required, but are not enabled for now.

* Save the config for all u-blox receiver types.
The M10 supports this command in addition to saving using
the VALSET commands for the RAM & BBR layers.

---------

Co-authored-by: Jonathan Bennett <jbennett@incomsystems.biz>
Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
2024-03-03 13:08:47 -06:00
Jonathan Bennett
7ab9a94edb just off the coast of NULL Island isn't OK either. 2024-03-03 11:50:07 -06:00
Ben Meadors
3c3d391044 Remove rangetest file on factory reset (#3322) 2024-03-03 10:33:30 -06:00
Ben Meadors
e3063a2785 Turns out bluefruit uses some of these macros even though "we" don't :-/ 2024-03-03 09:46:36 -06:00
Ben Meadors
6dbb6583ef Put these back 2024-03-03 09:33:18 -06:00
Ben Meadors
9b3e519487 Revert "Fix LED pinout for T-Echo board marked v1.0" (#3304)
* Revert "Fix LED pinout for T-Echo board marked v1.0, date 2021-6-28 (#3051)"

This reverts commit c2afa879b8.

* Remove / comment out unused LED pins
2024-03-03 08:55:52 -06:00
Ben Meadors
495840c777 Filter out neighborinfo if we don't have the module enabled (#3314)
* Filter out neighborinfo if we don't have the module enabled

* Handlereceived instead

* Add debug message
2024-03-03 08:36:36 -06:00
todd-herbert
5865add857 E-Ink: fast refresh for Wireless Paper V1.1 (#3320) 2024-03-03 07:13:56 -06:00
todd-herbert
c659292836 Reimplement "Dynamic E-Ink" as a derived class (#3316)
Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
2024-03-02 20:07:29 -06:00
Ben Meadors
905718e2ac Remove problematic IO2 3V3 toggling (again) as GPS EN pin (#3317)
* Remove problematic IO2 3V3 toggling (again) as GPS EN pin

* Comment

* Trunk
2024-03-02 15:45:59 -06:00
Ben Meadors
a58348369d Update protos and add new fields to type conversions (#3315) 2024-03-02 10:20:27 -06:00
Ben Meadors
d20fa6e927 Comment out ReplyModule registration, but leave it in as example (#3312) 2024-03-02 07:21:53 -06:00
Ben Meadors
bf88773b6b Don't send anybody to null island ever (#3308) 2024-02-28 13:44:15 -06:00
todd-herbert
6acc63729b Refactor EInkDisplay (#3299)
* Refactor EInkDisplay
A lot of variant specific code is merged, with the macros pushed to the respective variant.h files.
"Dynamic Partial" code has been purged, pending a rewrite.

* fix: declare class only if USE_EINK, init all members

* refactor: move macros to platformio.ini
Responds to https://github.com/meshtastic/firmware/pull/3299#issuecomment-1966425926

* fix: EInkDisplay::connect() references old macros
Usage was in a block of variant-specific code, which had been intentionally left untouched.

* fix: remove duplicate macros from variant.h

---------

Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
2024-02-28 09:45:15 -06:00
todd-herbert
7aee014f5e Add Heltec Wireless Paper V1.0 to the build matrix (#3306) 2024-02-28 09:20:20 -06:00
Ben Meadors
2786db499d Missing include 2024-02-28 08:01:59 -06:00
Thomas Herrmann
4ffb906fe8 move duplicate #define for screen to unified header file (#3302) 2024-02-27 12:49:46 -06:00
github-actions[bot]
f7758b4e44 [create-pull-request] automated change (#3298)
Co-authored-by: thebentern <thebentern@users.noreply.github.com>
2024-02-26 21:32:49 -06:00
139 changed files with 2879 additions and 1228 deletions

View File

@@ -35,6 +35,7 @@ jobs:
sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32.ini
sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32s2.ini
sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32s3.ini
sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32c3.ini
- name: Build ESP32
run: bin/build-esp32.sh ${{ inputs.board }}

62
.github/workflows/build_esp32_c3.yml vendored Normal file
View File

@@ -0,0 +1,62 @@
name: Build ESP32-C3
on:
workflow_call:
inputs:
board:
required: true
type: string
permissions: read-all
jobs:
build-esp32-c3:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v3
- name: Build base
id: base
uses: ./.github/actions/setup-base
- name: Pull web ui
uses: dsaltares/fetch-gh-release-asset@a40c8b4a0471f9ab81bdf73a010f74cc51476ad4
with:
repo: meshtastic/web
file: build.tar
target: build.tar
token: ${{ secrets.GITHUB_TOKEN }}
- name: Unpack web ui
run: |
tar -xf build.tar -C data/static
rm build.tar
- name: Remove debug flags for release
if: ${{ github.event_name == 'workflow_dispatch' }}
run: |
sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32.ini
sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32s2.ini
sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32s3.ini
sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32c3.ini
- name: Build ESP32
run: bin/build-esp32.sh ${{ inputs.board }}
- name: Pull OTA Firmware
uses: dsaltares/fetch-gh-release-asset@a40c8b4a0471f9ab81bdf73a010f74cc51476ad4
with:
repo: meshtastic/firmware-ota
file: firmware-c3.bin
target: release/bleota-c3.bin
token: ${{ secrets.GITHUB_TOKEN }}
- name: Get release version string
shell: bash
run: echo "version=$(./bin/buildinfo.py long)" >> $GITHUB_OUTPUT
id: version
- name: Store binaries as an artifact
uses: actions/upload-artifact@v3
with:
name: firmware-${{ inputs.board }}-${{ steps.version.outputs.version }}.zip
path: |
release/*.bin
release/*.elf

View File

@@ -34,6 +34,7 @@ jobs:
sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32.ini
sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32s2.ini
sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32s3.ini
sed -i '/DDEBUG_HEAP/d' ./arch/esp32/esp32c3.ini
- name: Build ESP32
run: bin/build-esp32.sh ${{ inputs.board }}

View File

@@ -67,7 +67,6 @@ jobs:
- board: tlora-v2-1-1_6-tcxo
- board: tlora-v2-1-1_8
- board: tbeam
- board: heltec-ht62-esp32c3-sx1262
- board: heltec-v2_0
- board: heltec-v2_1
- board: tbeam0_7
@@ -93,7 +92,8 @@ jobs:
- board: heltec-wsl-v3
- board: heltec-wireless-tracker
- board: heltec-wireless-tracker-V1-0
- board: heltec-wireless-paper
- board: heltec-wireless-paper-v1_0
- board: heltec-wireless-paper #v1.1
- board: tbeam-s3-core
- board: tlora-t3s3-v1
- board: t-watch-s3
@@ -104,6 +104,16 @@ jobs:
with:
board: ${{ matrix.board }}
build-esp32-c3:
strategy:
fail-fast: false
matrix:
include:
- board: heltec-ht62-esp32c3-sx1262
uses: ./.github/workflows/build_esp32_c3.yml
with:
board: ${{ matrix.board }}
build-nrf52:
strategy:
fail-fast: false
@@ -225,6 +235,7 @@ jobs:
[
build-esp32,
build-esp32-s3,
build-esp32-c3,
build-nrf52,
build-raspbian,
build-native,
@@ -250,7 +261,7 @@ jobs:
id: version
- name: Move files up
run: mv -b -t ./ ./*tbeam-2*/littlefs*.bin ./*tbeam-2*/bleota.bin ./*tbeam-s3*/bleota-s3.bin ./**/firmware*.bin ./*t-echo*/Meshtastic_nRF52_factory_erase_v2.uf2 ./**/firmware-*.uf2 ./**/firmware-*-ota.zip ./**/*.elf ./*native*/*device-*.sh ./*native*/*device-*.bat ./firmware-raspbian-*/release/meshtasticd_linux_aarch64 ./firmware-raspbian-*/bin/config-dist.yaml
run: mv -b -t ./ ./*tbeam-2*/littlefs*.bin ./*tbeam-2*/bleota.bin ./*tbeam-s3*/bleota-s3.bin ./*esp32c3*/bleota-c3.bin ./**/firmware*.bin ./*t-echo*/Meshtastic_nRF52_factory_erase_v2.uf2 ./**/firmware-*.uf2 ./**/firmware-*-ota.zip ./**/*.elf ./*native*/*device-*.sh ./*native*/*device-*.bat ./firmware-raspbian-*/release/meshtasticd_linux_aarch64 ./firmware-raspbian-*/bin/config-dist.yaml
- name: Repackage in single firmware zip
uses: actions/upload-artifact@v3

View File

@@ -23,6 +23,14 @@ jobs:
ref: ${{github.event.pull_request.head.ref}}
repository: ${{github.event.pull_request.head.repo.full_name}}
- name: Pull web ui
uses: dsaltares/fetch-gh-release-asset@a40c8b4a0471f9ab81bdf73a010f74cc51476ad4
with:
repo: meshtastic/web
file: build.tar
target: build.tar
token: ${{ secrets.GITHUB_TOKEN }}
- name: Get release version string
run: echo "version=$(./bin/buildinfo.py long)" >> $GITHUB_OUTPUT
id: version
@@ -37,9 +45,12 @@ jobs:
- name: build .debpkg
run: |
mkdir -p .debpkg/usr/share/doc/meshtasticd/web
mkdir -p .debpkg/usr/sbin
mkdir -p .debpkg/etc/meshtasticd
mkdir -p .debpkg/usr/lib/systemd/system/
tar -xf build.tar -C .debpkg/usr/share/doc/meshtasticd/web
gunzip .debpkg/usr/share/doc/meshtasticd/web/*.gz
cp release/meshtasticd_linux_aarch64 .debpkg/usr/sbin/meshtasticd
cp bin/config-dist.yaml .debpkg/etc/meshtasticd/config.yaml
chmod +x .debpkg/usr/sbin/meshtasticd
@@ -52,7 +63,7 @@ jobs:
maintainer: Jonathan Bennett
version: ${{ steps.version.outputs.version }} # refs/tags/v*.*.*
arch: arm64
depends: libyaml-cpp0.7
depends: libyaml-cpp0.7, openssl
desc: Native Linux Meshtastic binary.
- uses: actions/upload-artifact@v3

2
.gitignore vendored
View File

@@ -31,3 +31,5 @@ venv/
release/
.vscode/extensions.json
/compile_commands.json
src/mesh/raspihttp/certificate.pem
src/mesh/raspihttp/private_key.pem

View File

@@ -4,19 +4,19 @@ cli:
plugins:
sources:
- id: trunk
ref: v1.4.3
ref: v1.4.4
uri: https://github.com/trunk-io/plugins
lint:
enabled:
- trufflehog@3.68.2
- trufflehog@3.68.5
- yamllint@1.35.1
- bandit@1.7.7
- checkov@3.2.26
- terrascan@1.18.11
- checkov@3.2.32
- terrascan@1.19.1
- trivy@0.49.1
#- trufflehog@3.63.2-rc0
- taplo@0.8.1
- ruff@0.2.2
- ruff@0.3.1
- isort@5.13.2
- markdownlint@0.39.0
- oxipng@9.0.0

View File

@@ -1,5 +1,7 @@
{
"editor.formatOnSave": true,
"editor.defaultFormatter": "trunk.io",
"trunk.enableWindows": true
"trunk.enableWindows": true,
"files.insertFinalNewline": false,
"files.trimFinalNewlines": false
}

View File

@@ -4,7 +4,7 @@ extends = arduino_base
platform = platformio/espressif32@6.3.2 # This is a temporary fix to the S3-based devices bluetooth issues until we can determine what within ESP-IDF changed and can develop a suitable patch.
build_src_filter =
${arduino_base.build_src_filter} -<platform/nrf52/> -<platform/stm32wl> -<platform/rp2040> -<mesh/eth/>
${arduino_base.build_src_filter} -<platform/nrf52/> -<platform/stm32wl> -<platform/rp2040> -<mesh/eth/> -<mesh/raspihttp>
upload_speed = 921600
debug_init_break = tbreak setup

View File

@@ -2,7 +2,7 @@
extends = esp32_base
build_src_filter =
${esp32_base.build_src_filter} -<nimble/>
${esp32_base.build_src_filter} -<nimble/> -<mesh/raspihttp>
monitor_speed = 115200
@@ -12,5 +12,4 @@ build_flags =
lib_ignore =
${esp32_base.lib_ignore}
NimBLE-Arduino
NimBLE-Arduino

View File

@@ -1,6 +1,6 @@
[nrf52_base]
; Instead of the standard nordicnrf52 platform, we use our fork which has our added variant files
platform = platformio/nordicnrf52@^10.1.0
platform = platformio/nordicnrf52@^10.4.0
extends = arduino_base
build_type = debug ; I'm debugging with ICE a lot now
@@ -11,7 +11,7 @@ build_flags =
-Isrc/platform/nrf52
build_src_filter =
${arduino_base.build_src_filter} -<platform/esp32/> -<platform/stm32wl> -<nimble/> -<mesh/wifi/> -<mesh/api/> -<mesh/http/> -<modules/esp32> -<platform/rp2040> -<mesh/eth/>
${arduino_base.build_src_filter} -<platform/esp32/> -<platform/stm32wl> -<nimble/> -<mesh/wifi/> -<mesh/api/> -<mesh/http/> -<modules/esp32> -<platform/rp2040> -<mesh/eth/> -<mesh/raspihttp>
lib_deps=
${arduino_base.lib_deps}

View File

@@ -12,6 +12,7 @@ build_src_filter =
-<platform/rp2040>
-<mesh/wifi/>
-<mesh/http/>
+<mesh/raspihttp/>
-<mesh/eth/>
-<modules/esp32>
-<modules/Telemetry/EnvironmentTelemetry.cpp>

View File

@@ -1,8 +1,8 @@
; Common settings for rp2040 Processor based targets
[rp2040_base]
platform = https://github.com/maxgerhardt/platform-raspberrypi.git#612de5399d68b359053f1307ed223d400aea975c
platform = https://github.com/maxgerhardt/platform-raspberrypi.git#60d6ae81fcc73c34b1493ca9e261695e471bc0c2
extends = arduino_base
platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#3.6.2
platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#3.7.2
board_build.core = earlephilhower
board_build.filesystem_size = 0.5m
@@ -12,7 +12,7 @@ build_flags =
-D__PLAT_RP2040__
# -D _POSIX_THREADS
build_src_filter =
${arduino_base.build_src_filter} -<platform/esp32/> -<nimble/> -<modules/esp32> -<platform/nrf52/> -<platform/stm32wl> -<mesh/eth/> -<mesh/wifi/> -<mesh/http/>
${arduino_base.build_src_filter} -<platform/esp32/> -<nimble/> -<modules/esp32> -<platform/nrf52/> -<platform/stm32wl> -<mesh/eth/> -<mesh/wifi/> -<mesh/http/> -<mesh/raspihttp>
lib_ignore =
BluetoothOTA

View File

@@ -13,7 +13,7 @@ build_flags =
-DVECT_TAB_OFFSET=0x08000000
build_src_filter =
${arduino_base.build_src_filter} -<platform/esp32/> -<nimble/> -<mesh/api/> -<mesh/wifi/> -<mesh/http/> -<modules/esp32> -<mesh/eth/> -<input> -<buzz> -<modules/Telemetry> -<platform/nrf52> -<platform/portduino> -<platform/rp2040>
${arduino_base.build_src_filter} -<platform/esp32/> -<nimble/> -<mesh/api/> -<mesh/wifi/> -<mesh/http/> -<modules/esp32> -<mesh/eth/> -<input> -<buzz> -<modules/Telemetry> -<platform/nrf52> -<platform/portduino> -<platform/rp2040> -<mesh/raspihttp>
board_upload.offset_address = 0x08000000
upload_protocol = stlink

View File

@@ -117,3 +117,7 @@ Input:
Logging:
LogLevel: info # debug, info, warn, error
Webserver:
# Port: 443 # Port for Webserver & Webservices
# RootPath: /usr/share/doc/meshtasticd/web # Root Dir of WebServer

View File

@@ -31,9 +31,13 @@ IF EXIST %FILENAME% IF x%FILENAME:update=%==x%FILENAME% (
%PYTHON% -m esptool --baud 115200 erase_flash
%PYTHON% -m esptool --baud 115200 write_flash 0x00 %FILENAME%
@REM Account for S3 board's different OTA partition
@REM Account for S3 and C3 board's different OTA partition
IF x%FILENAME:s3=%==x%FILENAME% IF x%FILENAME:v3=%==x%FILENAME% IF x%FILENAME:t-deck=%==x%FILENAME% IF x%FILENAME:wireless-paper=%==x%FILENAME% IF x%FILENAME:wireless-tracker=%==x%FILENAME% (
%PYTHON% -m esptool --baud 115200 write_flash 0x260000 bleota.bin
IF x%FILENAME:esp32c3=%==x%FILENAME% (
%PYTHON% -m esptool --baud 115200 write_flash 0x260000 bleota.bin
) else (
%PYTHON% -m esptool --baud 115200 write_flash 0x260000 bleota-c3.bin
)
) else (
%PYTHON% -m esptool --baud 115200 write_flash 0x260000 bleota-s3.bin
)

View File

@@ -1,12 +1,12 @@
#!/bin/sh
PYTHON=${PYTHON:-$(which python3 python|head -n 1)}
PYTHON=${PYTHON:-$(which python3 python | head -n 1)}
set -e
# Usage info
show_help() {
cat << EOF
cat <<EOF
Usage: $(basename $0) [-h] [-p ESPTOOL_PORT] [-P PYTHON] [-f FILENAME|FILENAME]
Flash image file to device, but first erasing and writing system information"
@@ -18,44 +18,50 @@ Flash image file to device, but first erasing and writing system information"
EOF
}
while getopts ":hp:P:f:" opt; do
case "${opt}" in
h)
show_help
exit 0
;;
p) export ESPTOOL_PORT=${OPTARG}
;;
P) PYTHON=${OPTARG}
;;
f) FILENAME=${OPTARG}
;;
*)
echo "Invalid flag."
show_help >&2
exit 1
;;
esac
case "${opt}" in
h)
show_help
exit 0
;;
p)
export ESPTOOL_PORT=${OPTARG}
;;
P)
PYTHON=${OPTARG}
;;
f)
FILENAME=${OPTARG}
;;
*)
echo "Invalid flag."
show_help >&2
exit 1
;;
esac
done
shift "$((OPTIND-1))"
shift "$((OPTIND - 1))"
[ -z "$FILENAME" -a -n "$1" ] && {
FILENAME=$1
shift
FILENAME=$1
shift
}
if [ -f "${FILENAME}" ] && [ ! -z "${FILENAME##*"update"*}" ]; then
if [ -f "${FILENAME}" ] && [ -n "${FILENAME##*"update"*}" ]; then
echo "Trying to flash ${FILENAME}, but first erasing and writing system information"
"$PYTHON" -m esptool erase_flash
"$PYTHON" -m esptool write_flash 0x00 ${FILENAME}
"$PYTHON" -m esptool erase_flash
"$PYTHON" -m esptool write_flash 0x00 ${FILENAME}
# Account for S3 board's different OTA partition
if [ ! -z "${FILENAME##*"s3"*}" ] && [ ! -z "${FILENAME##*"-v3"*}" ] && [ ! -z "${FILENAME##*"t-deck"*}" ] && [ ! -z "${FILENAME##*"wireless-paper"*}" ] && [ ! -z "${FILENAME##*"wireless-tracker"*}" ]; then
"$PYTHON" -m esptool write_flash 0x260000 bleota.bin
if [ -n "${FILENAME##*"s3"*}" ] && [ -n "${FILENAME##*"-v3"*}" ] && [ -n "${FILENAME##*"t-deck"*}" ] && [ -n "${FILENAME##*"wireless-paper"*}" ] && [ -n "${FILENAME##*"wireless-tracker"*}" ]; then
if [ -n "${FILENAME##*"esp32c3"*}" ]; then
"$PYTHON" -m esptool write_flash 0x260000 bleota.bin
else
"$PYTHON" -m esptool write_flash 0x260000 bleota-c3.bin
fi
else
"$PYTHON" -m esptool write_flash 0x260000 bleota-s3.bin
"$PYTHON" -m esptool write_flash 0x260000 bleota-s3.bin
fi
"$PYTHON" -m esptool write_flash 0x300000 littlefs-*.bin
"$PYTHON" -m esptool write_flash 0x300000 littlefs-*.bin
else
show_help

View File

@@ -7,7 +7,10 @@
"cpu": "cortex-m4",
"extra_flags": "-DARDUINO_NRF52840_CANARY -DNRF52840_XXAA",
"f_cpu": "64000000L",
"hwids": [["0x239A", "0x4405"]],
"hwids": [
["0x239A", "0x4405"],
["0x239A", "0x009F"]
],
"usb_product": "CanaryOne",
"mcu": "nrf52840",
"variant": "canaryone",

View File

@@ -69,6 +69,7 @@ build_flags = -Wno-missing-field-initializers
-DRADIOLIB_EXCLUDE_PAGER
-DRADIOLIB_EXCLUDE_FSK4
-DRADIOLIB_EXCLUDE_APRS
-DRADIOLIB_EXCLUDE_LORAWAN
monitor_speed = 115200
@@ -77,8 +78,8 @@ lib_deps =
https://github.com/meshtastic/esp8266-oled-ssd1306.git#ee628ee6c9588d4c56c9e3da35f0fc9448ad54a8 ; ESP8266_SSD1306
mathertel/OneButton@^2.5.0 ; OneButton library for non-blocking button debounce
https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159
https://github.com/meshtastic/TinyGPSPlus.git#2044b2c51e91ab4cd8cc93b15e40658cd808dd06
https://github.com/meshtastic/ArduinoThread.git#72921ac222eed6f526ba1682023cee290d9aa1b3
https://github.com/meshtastic/TinyGPSPlus.git#f9f4fef2183514aa52be91d714c1455dd6f26e45
https://github.com/meshtastic/ArduinoThread.git#1ae8778c85d0a2a729f989e0b1e7d7c4dc84eef0
nanopb/Nanopb@^0.4.7
erriez/ErriezCRC32@^1.0.1
@@ -113,9 +114,10 @@ lib_deps =
; (not included in native / portduino)
[environmental_base]
lib_deps =
adafruit/Adafruit BusIO@^1.11.4
adafruit/Adafruit BusIO@^1.15.0
adafruit/Adafruit Unified Sensor@^1.1.11
adafruit/Adafruit BMP280 Library@^2.6.8
adafruit/Adafruit BMP085 Library@^1.2.4
adafruit/Adafruit BME280 Library@^2.2.2
https://github.com/boschsensortec/Bosch-BSEC2-Library#v1.5.2400
boschsensortec/BME68x Sensor Library@^1.1.40407
@@ -129,4 +131,4 @@ lib_deps =
adafruit/Adafruit PM25 AQI Sensor@^1.0.6
adafruit/Adafruit MPU6050@^2.2.4
adafruit/Adafruit LIS3DH@^1.2.4
https://github.com/lewisxhe/BMA423_Library@^0.0.1
https://github.com/lewisxhe/SensorLib#27fd0f721e20cd09e1f81383f0ba58a54fe84a17

View File

@@ -7,16 +7,16 @@
#include <Adafruit_LIS3DH.h>
#include <Adafruit_MPU6050.h>
#include <Arduino.h>
#include <SensorBMA423.hpp>
#include <Wire.h>
#include <bma.h>
BMA423 bmaSensor;
SensorBMA423 bmaSensor;
bool BMA_IRQ = false;
#define ACCELEROMETER_CHECK_INTERVAL_MS 100
#define ACCELEROMETER_CLICK_THRESHOLD 40
uint16_t readRegister(uint8_t address, uint8_t reg, uint8_t *data, uint16_t len)
int readRegister(uint8_t address, uint8_t reg, uint8_t *data, uint8_t len)
{
Wire.beginTransmission(address);
Wire.write(reg);
@@ -29,7 +29,7 @@ uint16_t readRegister(uint8_t address, uint8_t reg, uint8_t *data, uint16_t len)
return 0; // Pass
}
uint16_t writeRegister(uint8_t address, uint8_t reg, uint8_t *data, uint16_t len)
int writeRegister(uint8_t address, uint8_t reg, uint8_t *data, uint8_t len)
{
Wire.beginTransmission(address);
Wire.write(reg);
@@ -72,24 +72,14 @@ class AccelerometerThread : public concurrency::OSThread
lis.setRange(LIS3DH_RANGE_2_G);
// Adjust threshold, higher numbers are less sensitive
lis.setClick(config.device.double_tap_as_button_press ? 2 : 1, ACCELEROMETER_CLICK_THRESHOLD);
} else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 && bmaSensor.begin(readRegister, writeRegister, delay)) {
} else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 &&
bmaSensor.begin(accelerometer_found.address, &readRegister, &writeRegister)) {
LOG_DEBUG("BMA423 initializing\n");
Acfg cfg;
cfg.odr = BMA4_OUTPUT_DATA_RATE_100HZ;
cfg.range = BMA4_ACCEL_RANGE_2G;
cfg.bandwidth = BMA4_ACCEL_NORMAL_AVG4;
cfg.perf_mode = BMA4_CONTINUOUS_MODE;
bmaSensor.setAccelConfig(cfg);
bmaSensor.enableAccel();
struct bma4_int_pin_config pin_config;
pin_config.edge_ctrl = BMA4_LEVEL_TRIGGER;
pin_config.lvl = BMA4_ACTIVE_HIGH;
pin_config.od = BMA4_PUSH_PULL;
pin_config.output_en = BMA4_OUTPUT_ENABLE;
pin_config.input_en = BMA4_INPUT_DISABLE;
// The correct trigger interrupt needs to be configured as needed
bmaSensor.setINTPinConfig(pin_config, BMA4_INTR1_MAP);
bmaSensor.configAccelerometer(bmaSensor.RANGE_2G, bmaSensor.ODR_100HZ, bmaSensor.BW_NORMAL_AVG4,
bmaSensor.PERF_CONTINUOUS_MODE);
bmaSensor.enableAccelerometer();
bmaSensor.configInterrupt(BMA4_LEVEL_TRIGGER, BMA4_ACTIVE_HIGH, BMA4_PUSH_PULL, BMA4_OUTPUT_ENABLE,
BMA4_INPUT_DISABLE);
#ifdef BMA423_INT
pinMode(BMA4XX_INT, INPUT);
@@ -102,25 +92,22 @@ class AccelerometerThread : public concurrency::OSThread
RISING); // Select the interrupt mode according to the actual circuit
#endif
struct bma423_axes_remap remap_data;
remap_data.x_axis = 0;
remap_data.x_axis_sign = 1;
remap_data.y_axis = 1;
remap_data.y_axis_sign = 0;
remap_data.z_axis = 2;
remap_data.z_axis_sign = 1;
#ifdef T_WATCH_S3
// Need to raise the wrist function, need to set the correct axis
bmaSensor.setRemapAxes(&remap_data);
// sensor.enableFeature(BMA423_STEP_CNTR, true);
bmaSensor.enableFeature(BMA423_TILT, true);
bmaSensor.enableFeature(BMA423_WAKEUP, true);
// sensor.resetStepCounter();
bmaSensor.setReampAxes(bmaSensor.REMAP_TOP_LAYER_RIGHT_CORNER);
#else
bmaSensor.setReampAxes(bmaSensor.REMAP_BOTTOM_LAYER_BOTTOM_LEFT_CORNER);
#endif
// bmaSensor.enableFeature(bmaSensor.FEATURE_STEP_CNTR, true);
bmaSensor.enableFeature(bmaSensor.FEATURE_TILT, true);
bmaSensor.enableFeature(bmaSensor.FEATURE_WAKEUP, true);
// bmaSensor.resetPedometer();
// Turn on feature interrupt
bmaSensor.enableStepCountInterrupt();
bmaSensor.enableTiltInterrupt();
bmaSensor.enablePedometerIRQ();
bmaSensor.enableTiltIRQ();
// It corresponds to isDoubleClick interrupt
bmaSensor.enableWakeupInterrupt();
bmaSensor.enableWakeupIRQ();
}
}
@@ -141,8 +128,8 @@ class AccelerometerThread : public concurrency::OSThread
buttonPress();
return 500;
}
} else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 && bmaSensor.getINT()) {
if (bmaSensor.isTilt() || bmaSensor.isDoubleClick()) {
} else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 && bmaSensor.readIrqStatus() != DEV_WIRE_NONE) {
if (bmaSensor.isTilt() || bmaSensor.isDoubleTap()) {
wakeScreen();
return 500;
}
@@ -171,4 +158,4 @@ class AccelerometerThread : public concurrency::OSThread
Adafruit_LIS3DH lis;
};
} // namespace concurrency
} // namespace concurrency

View File

@@ -54,6 +54,19 @@ static const adc_atten_t atten = ADC_ATTENUATION;
#endif
#endif // BATTERY_PIN && ARCH_ESP32
#ifdef EXT_CHRG_DETECT
#ifndef EXT_CHRG_DETECT_MODE
static const uint8_t ext_chrg_detect_mode = INPUT;
#else
static const uint8_t ext_chrg_detect_mode = EXT_CHRG_DETECT_MODE;
#endif
#ifndef EXT_CHRG_DETECT_VALUE
static const uint8_t ext_chrg_detect_value = HIGH;
#else
static const uint8_t ext_chrg_detect_value = EXT_CHRG_DETECT_VALUE;
#endif
#endif
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO)
INA260Sensor ina260Sensor;
INA219Sensor ina219Sensor;
@@ -322,7 +335,14 @@ class AnalogBatteryLevel : public HasBatteryLevel
/// Assume charging if we have a battery and external power is connected.
/// we can't be smart enough to say 'full'?
virtual bool isCharging() override { return isBatteryConnect() && isVbusIn(); }
virtual bool isCharging() override
{
#ifdef EXT_CHRG_DETECT
return digitalRead(EXT_CHRG_DETECT) == ext_chrg_detect_value;
#else
return isBatteryConnect() && isVbusIn();
#endif
}
private:
/// If we see a battery voltage higher than physics allows - assume charger is pumping
@@ -389,6 +409,9 @@ bool Power::analogInit()
#ifdef EXT_PWR_DETECT
pinMode(EXT_PWR_DETECT, INPUT);
#endif
#ifdef EXT_CHRG_DETECT
pinMode(EXT_CHRG_DETECT, ext_chrg_detect_mode);
#endif
#ifdef BATTERY_PIN
LOG_DEBUG("Using analog input %d for battery level\n", BATTERY_PIN);
@@ -473,11 +496,6 @@ bool Power::setup()
void Power::shutdown()
{
screen->setOn(false);
#if defined(USE_EINK) && defined(PIN_EINK_EN)
digitalWrite(PIN_EINK_EN, LOW); // power off backlight first
#endif
LOG_INFO("Shutting down\n");
#ifdef HAS_PMU

View File

@@ -8,6 +8,7 @@
* actions to be taken upon entering or exiting each state.
*/
#include "PowerFSM.h"
#include "Default.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "configuration.h"
@@ -45,7 +46,7 @@ static void sdsEnter()
{
LOG_DEBUG("Enter state: SDS\n");
// FIXME - make sure GPS and LORA radio are off first - because we want close to zero current draw
doDeepSleep(getConfiguredOrDefaultMs(config.power.sds_secs), false);
doDeepSleep(Default::getConfiguredOrDefaultMs(config.power.sds_secs), false);
}
extern Power *power;
@@ -343,13 +344,13 @@ void PowerFSM_setup()
powerFSM.add_transition(&stateDARK, &stateDARK, EVENT_CONTACT_FROM_PHONE, NULL, "Contact from phone");
powerFSM.add_timed_transition(&stateON, &stateDARK,
getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL,
Default::getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL,
"Screen-on timeout");
powerFSM.add_timed_transition(&statePOWER, &stateDARK,
getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL,
Default::getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL,
"Screen-on timeout");
powerFSM.add_timed_transition(&stateDARK, &stateDARK,
getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL,
Default::getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL,
"Screen-on timeout");
// We never enter light-sleep or NB states on NRF52 (because the CPU uses so little power normally)
@@ -358,12 +359,13 @@ void PowerFSM_setup()
// Don't add power saving transitions if we are a power saving tracker or sensor. Sleep will be initiatiated through the
// modules
if ((isRouter || config.power.is_power_saving) && !isTrackerOrSensor) {
powerFSM.add_timed_transition(&stateNB, isInfrastructureRole ? &stateSDS : &stateLS,
getConfiguredOrDefaultMs(config.power.min_wake_secs, default_min_wake_secs), NULL,
powerFSM.add_timed_transition(&stateNB, &stateLS,
Default::getConfiguredOrDefaultMs(config.power.min_wake_secs, default_min_wake_secs), NULL,
"Min wake timeout");
powerFSM.add_timed_transition(&stateDARK, isInfrastructureRole ? &stateSDS : &stateLS,
getConfiguredOrDefaultMs(config.power.wait_bluetooth_secs, default_wait_bluetooth_secs),
NULL, "Bluetooth timeout");
powerFSM.add_timed_transition(
&stateDARK, &stateLS,
Default::getConfiguredOrDefaultMs(config.power.wait_bluetooth_secs, default_wait_bluetooth_secs), NULL,
"Bluetooth timeout");
}
#endif

View File

@@ -1,3 +1,4 @@
#include "Default.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "concurrency/OSThread.h"
@@ -28,7 +29,7 @@ class PowerFSMThread : public OSThread
timeLastPowered = millis();
} else if (config.power.on_battery_shutdown_after_secs > 0 && config.power.on_battery_shutdown_after_secs != UINT32_MAX &&
millis() > (timeLastPowered +
getConfiguredOrDefaultMs(
Default::getConfiguredOrDefaultMs(
config.power.on_battery_shutdown_after_secs))) { // shutdown after 30 minutes unpowered
powerFSM.trigger(EVENT_SHUTDOWN);
}

View File

@@ -3,7 +3,11 @@
#include "PowerFSM.h"
#include "configuration.h"
#ifdef RP2040_SLOW_CLOCK
#define Port Serial2
#else
#define Port Serial
#endif
// Defaulting to the formerly removed phone_timeout_secs value of 15 minutes
#define SERIAL_CONNECTION_TIMEOUT (15 * 60) * 1000UL
@@ -31,6 +35,10 @@ SerialConsole::SerialConsole() : StreamAPI(&Port), RedirectablePrint(&Port), con
canWrite = false; // We don't send packets to our port until it has talked to us first
// setDestination(&noopPrint); for testing, try turning off 'all' debug output and see what leaks
#ifdef RP2040_SLOW_CLOCK
Port.setTX(SERIAL2_TX);
Port.setRX(SERIAL2_RX);
#endif
Port.begin(SERIAL_BAUD);
#if defined(ARCH_NRF52) || defined(CONFIG_IDF_TARGET_ESP32S2) || defined(CONFIG_IDF_TARGET_ESP32S3) || defined(ARCH_RP2040)
time_t timeout = millis();
@@ -64,7 +72,7 @@ bool SerialConsole::checkIsConnected()
/**
* we override this to notice when we've received a protobuf over the serial
* stream. Then we shunt off debug serial output.
* stream. Then we shut off debug serial output.
*/
bool SerialConsole::handleToRadio(const uint8_t *buf, size_t len)
{

View File

@@ -111,6 +111,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#define MCP9808_ADDR 0x18
#define INA_ADDR 0x40
#define INA_ADDR_ALTERNATE 0x41
#define INA_ADDR_WAVESHARE_UPS 0x43
#define INA3221_ADDR 0x42
#define QMC6310_ADDR 0x1C
#define QMI8658_ADDR 0x6B
@@ -221,4 +222,24 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#ifndef HW_VENDOR
#error HW_VENDOR must be defined
#endif
#endif
// global switch to turn off all optional modules for a minimzed build
#ifdef MESHTASTIC_EXCLUDE_MODULES
#define MESHTASTIC_EXCLUDE_AUDIO 1
#define MESHTASTIC_EXCLUDE_DETECTIONSENSOR 1
#define MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR 1
#define MESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION 1
#define MESHTASTIC_EXCLUDE_PAXCOUNTER 1
#define MESHTASTIC_EXCLUDE_POWER_TELEMETRY 1
#define MESHTASTIC_EXCLUDE_RANGETEST 1
#define MESHTASTIC_EXCLUDE_REMOTEHARDWARE 1
#define MESHTASTIC_EXCLUDE_STOREFORWARD 1
#define MESHTASTIC_EXCLUDE_ATAK 1
#define MESHTASTIC_EXCLUDE_CANNEDMESSAGES 1
#define MESHTASTIC_EXCLUDE_NEIGHBORINFO 1
#define MESHTASTIC_EXCLUDE_TRACEROUTE 1
#define MESHTASTIC_EXCLUDE_WAYPOINT 1
#define MESHTASTIC_EXCLUDE_INPUTBROKER 1
#define MESHTASTIC_EXCLUDE_SERIAL 1
#endif

View File

@@ -23,6 +23,7 @@ class ScanI2C
BME_680,
BME_280,
BMP_280,
BMP_085,
INA260,
INA219,
INA3221,

View File

@@ -183,8 +183,13 @@ void ScanI2CTwoWire::scanPort(I2CPort port)
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
case ATECC608B_ADDR:
type = ATECC608B;
if (atecc.begin(addr.address) == true) {
#ifdef RP2040_SLOW_CLOCK
if (atecc.begin(addr.address, Wire, Serial2) == true)
#else
if (atecc.begin(addr.address) == true)
#endif
{
LOG_INFO("ATECC608B initialized\n");
} else {
LOG_WARN("ATECC608B initialization failed\n");
@@ -242,6 +247,10 @@ void ScanI2CTwoWire::scanPort(I2CPort port)
LOG_INFO("BME-280 sensor found at address 0x%x\n", (uint8_t)addr.address);
type = BME_280;
break;
case 0x55:
LOG_INFO("BMP-085 or BMP-180 sensor found at address 0x%x\n", (uint8_t)addr.address);
type = BMP_085;
break;
default:
LOG_INFO("BMP-280 sensor found at address 0x%x\n", (uint8_t)addr.address);
type = BMP_280;
@@ -250,6 +259,7 @@ void ScanI2CTwoWire::scanPort(I2CPort port)
case INA_ADDR:
case INA_ADDR_ALTERNATE:
case INA_ADDR_WAVESHARE_UPS:
registerValue = getRegisterValue(ScanI2CTwoWire::RegisterLocation(addr, 0xFE), 2);
LOG_DEBUG("Register MFG_UID: 0x%x\n", registerValue);
if (registerValue == 0x5449) {

View File

@@ -1,4 +1,5 @@
#include "GPS.h"
#include "Default.h"
#include "NodeDB.h"
#include "RTC.h"
#include "configuration.h"
@@ -255,19 +256,6 @@ bool GPS::setup()
if (!didSerialInit) {
#if !defined(GPS_UC6580)
#if defined(RAK4630) && defined(PIN_3V3_EN)
// If we are using the RAK4630 and we have no other peripherals on the I2C bus or module interest in 3V3_S,
// then we can safely set en_gpio turn off power to 3V3 (IO2) to hard sleep the GPS
if (rtc_found.port == ScanI2C::DeviceType::NONE && rgb_found.type == ScanI2C::DeviceType::NONE &&
accelerometer_found.port == ScanI2C::DeviceType::NONE && !moduleConfig.detection_sensor.enabled &&
!moduleConfig.telemetry.air_quality_enabled && !moduleConfig.telemetry.environment_measurement_enabled &&
config.power.device_battery_ina_address == 0 && en_gpio == 0) {
LOG_DEBUG("Since no problematic peripherals or interested modules were found, setting power save GPS_EN to pin %i\n",
PIN_3V3_EN);
en_gpio = PIN_3V3_EN;
}
#endif
if (tx_gpio && gnssModel == GNSS_MODEL_UNKNOWN) {
LOG_DEBUG("Probing for GPS at %d \n", serialSpeeds[speedSelect]);
gnssModel = probe(serialSpeeds[speedSelect]);
@@ -303,6 +291,26 @@ bool GPS::setup()
// Switch to Vehicle Mode, since SoftRF enables Aviation < 2g
_serial_gps->write("$PCAS11,3*1E\r\n");
delay(250);
} else if (gnssModel == GNSS_MODEL_MTK_L76B) {
// Waveshare Pico-GPS hat uses the L76B with 9600 baud
// Initialize the L76B Chip, use GPS + GLONASS
// See note in L76_Series_GNSS_Protocol_Specification, chapter 3.29
_serial_gps->write("$PMTK353,1,1,0,0,0*2B\r\n");
// Above command will reset the GPS and takes longer before it will accept new commands
delay(1000);
// only ask for RMC and GGA (GNRMC and GNGGA)
// See note in L76_Series_GNSS_Protocol_Specification, chapter 2.1
_serial_gps->write("$PMTK314,0,1,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*28\r\n");
delay(250);
// Enable SBAS
_serial_gps->write("$PMTK301,2*2E\r\n");
delay(250);
// Enable PPS for 2D/3D fix only
_serial_gps->write("$PMTK285,3,100*3F\r\n");
delay(250);
// Switch to Fitness Mode, for running and walking purpose with low speed (<5 m/s)
_serial_gps->write("$PMTK886,1*29\r\n");
delay(250);
} else if (gnssModel == GNSS_MODEL_UC6580) {
// The Unicore UC6580 can use a lot of sat systems, enable it to
// use GPS L1 & L5 + BDS B1I & B2a + GLONASS L1 + GALILEO E1 & E5a + SBAS
@@ -488,14 +496,6 @@ bool GPS::setup()
}
}
}
msglen = makeUBXPacket(0x06, 0x09, sizeof(_message_SAVE), _message_SAVE);
_serial_gps->write(UBXscratch, msglen);
if (getACK(0x06, 0x09, 2000) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to save GNSS module configuration.\n");
} else {
LOG_INFO("GNSS module configuration saved!\n");
}
} else {
// LOG_INFO("u-blox M10 hardware found.\n");
delay(1000);
@@ -588,6 +588,13 @@ bool GPS::setup()
// BBR will survive a restart, and power off for a while, but modules with small backup
// batteries or super caps will not retain the config for a long power off time.
}
msglen = makeUBXPacket(0x06, 0x09, sizeof(_message_SAVE), _message_SAVE);
_serial_gps->write(UBXscratch, msglen);
if (getACK(0x06, 0x09, 2000) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to save GNSS module configuration.\n");
} else {
LOG_INFO("GNSS module configuration saved!\n");
}
}
didSerialInit = true;
}
@@ -638,17 +645,27 @@ void GPS::setGPSPower(bool on, bool standbyOnly, uint32_t sleepTime)
return;
}
#endif
#ifdef PIN_GPS_STANDBY // Specifically the standby pin for L76K and clones
#ifdef PIN_GPS_STANDBY // Specifically the standby pin for L76B, L76K and clones
if (on) {
LOG_INFO("Waking GPS\n");
pinMode(PIN_GPS_STANDBY, OUTPUT);
// Some PCB's use an inverse logic due to a transistor driver
// Example for this is the Pico-Waveshare Lora+GPS HAT
#ifdef PIN_GPS_STANDBY_INVERTED
digitalWrite(PIN_GPS_STANDBY, 0);
#else
digitalWrite(PIN_GPS_STANDBY, 1);
#endif
return;
} else {
LOG_INFO("GPS entering sleep\n");
// notifyGPSSleep.notifyObservers(NULL);
pinMode(PIN_GPS_STANDBY, OUTPUT);
#ifdef PIN_GPS_STANDBY_INVERTED
digitalWrite(PIN_GPS_STANDBY, 1);
#else
digitalWrite(PIN_GPS_STANDBY, 0);
#endif
return;
}
#endif
@@ -742,7 +759,7 @@ uint32_t GPS::getWakeTime() const
if (t == UINT32_MAX)
return t; // already maxint
return getConfiguredOrDefaultMs(t, default_broadcast_interval_secs);
return Default::Default::getConfiguredOrDefaultMs(t, default_broadcast_interval_secs);
}
/** Get how long we should sleep between aqusition attempts in msecs
@@ -929,7 +946,7 @@ GnssModel_t GPS::probe(int serialSpeed)
uint8_t buffer[768] = {0};
delay(100);
// Close all NMEA sentences , Only valid for MTK platform
// Close all NMEA sentences , Only valid for L76K MTK platform
_serial_gps->write("$PCAS03,0,0,0,0,0,0,0,0,0,0,,,0,0*02\r\n");
delay(20);
@@ -941,6 +958,18 @@ GnssModel_t GPS::probe(int serialSpeed)
return GNSS_MODEL_MTK;
}
// Close all NMEA sentences, valid for L76B MTK platform (Waveshare Pico GPS)
_serial_gps->write("$PMTK514,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*2E\r\n");
delay(20);
// Get version information
clearBuffer();
_serial_gps->write("$PMTK605*31\r\n");
if (getACK("Quectel-L76B", 500) == GNSS_RESPONSE_OK) {
LOG_INFO("L76B GNSS init succeeded, using L76B GNSS Module\n");
return GNSS_MODEL_MTK_L76B;
}
uint8_t cfg_rate[] = {0xB5, 0x62, 0x06, 0x08, 0x00, 0x00, 0x00, 0x00};
UBXChecksum(cfg_rate, sizeof(cfg_rate));
clearBuffer();
@@ -1122,7 +1151,6 @@ GPS *GPS::createGps()
LOG_DEBUG("Using GPIO%d for GPS RX\n", new_gps->rx_gpio);
LOG_DEBUG("Using GPIO%d for GPS TX\n", new_gps->tx_gpio);
_serial_gps->begin(GPS_BAUDRATE, SERIAL_8N1, new_gps->rx_gpio, new_gps->tx_gpio);
#else
_serial_gps->begin(GPS_BAUDRATE);
#endif
@@ -1181,7 +1209,16 @@ bool GPS::factoryReset()
// byte _message_CFG_RST_COLDSTART[] = {0xB5, 0x62, 0x06, 0x04, 0x04, 0x00, 0xFF, 0xB9, 0x00, 0x00, 0xC6, 0x8B};
// _serial_gps->write(_message_CFG_RST_COLDSTART, sizeof(_message_CFG_RST_COLDSTART));
// delay(1000);
} else if (gnssModel == GNSS_MODEL_MTK) {
// send the CAS10 to perform a factory restart of the device (and other device that support PCAS statements)
LOG_INFO("GNSS Factory Reset via PCAS10,3\n");
_serial_gps->write("$PCAS10,3*1F\r\n");
delay(100);
} else {
// fire this for good measure, if we have an L76B - won't harm other devices.
_serial_gps->write("$PMTK104*37\r\n");
// No PMTK_ACK for this command.
delay(100);
// send the UBLOX Factory Reset Command regardless of detect state, something is very wrong, just assume it's UBLOX.
// Factory Reset
byte _message_reset[] = {0xB5, 0x62, 0x06, 0x09, 0x0D, 0x00, 0xFF, 0xFB, 0x00, 0x00, 0x00,

View File

@@ -20,12 +20,7 @@ struct uBloxGnssModelInfo {
char extension[10][30];
};
typedef enum {
GNSS_MODEL_MTK,
GNSS_MODEL_UBLOX,
GNSS_MODEL_UC6580,
GNSS_MODEL_UNKNOWN,
} GnssModel_t;
typedef enum { GNSS_MODEL_MTK, GNSS_MODEL_UBLOX, GNSS_MODEL_UC6580, GNSS_MODEL_UNKNOWN, GNSS_MODEL_MTK_L76B } GnssModel_t;
typedef enum {
GNSS_RESPONSE_NONE,
@@ -92,8 +87,11 @@ class GPS : private concurrency::OSThread
public:
/** If !NULL we will use this serial port to construct our GPS */
#if defined(RPI_PICO_WAVESHARE)
static SerialUART *_serial_gps;
#else
static HardwareSerial *_serial_gps;
#endif
static uint8_t _message_PMREQ[];
static uint8_t _message_PMREQ_10[];
static const uint8_t _message_CFG_RXM_PSM[];

View File

@@ -11,7 +11,7 @@
#define PI 3.1415926535897932384626433832795
#define OLC_CODE_LEN 11
#define DEG_CONVERT 180 / PI
#define DEG_CONVERT (180 / PI)
// Helper functions
// Raises a number to an exponent, handling negative exponents.

View File

@@ -2,127 +2,49 @@
#ifdef USE_EINK
#include "EInkDisplay2.h"
#include "GxEPD2_BW.h"
#include "SPILock.h"
#include "main.h"
#include <SPI.h>
#if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0)
SPIClass *hspi = NULL;
#endif
/*
The macros EINK_DISPLAY_MODEL, EINK_WIDTH, and EINK_HEIGHT are defined as build_flags in a variant's platformio.ini
Previously, these macros were defined at the top of this file.
#define COLORED GxEPD_BLACK
#define UNCOLORED GxEPD_WHITE
For archival reasons, note that the following configurations had also been tested during this period:
* ifdef RAK4631
- 4.2 inch
EINK_DISPLAY_MODEL: GxEPD2_420_M01
EINK_WIDTH: 300
EINK_WIDTH: 400
#if defined(TTGO_T_ECHO)
#define TECHO_DISPLAY_MODEL GxEPD2_154_D67
#elif defined(RAK4630)
- 2.9 inch
EINK_DISPLAY_MODEL: GxEPD2_290_T5D
EINK_WIDTH: 296
EINK_HEIGHT: 128
// GxEPD2_213_BN - RAK14000 2.13 inch b/w 250x122 - changed from GxEPD2_213_B74 - which was not going to give fast refresh
// support
#define TECHO_DISPLAY_MODEL GxEPD2_213_BN
// 4.2 inch 300x400 - GxEPD2_420_M01
// #define TECHO_DISPLAY_MODEL GxEPD2_420_M01
// 2.9 inch 296x128 - GxEPD2_290_T5D
// #define TECHO_DISPLAY_MODEL GxEPD2_290_T5D
// 1.54 inch 200x200 - GxEPD2_154_M09
// #define TECHO_DISPLAY_MODEL GxEPD2_154_M09
#elif defined(MAKERPYTHON)
// 2.9 inch 296x128 - GxEPD2_290_T5D
#define TECHO_DISPLAY_MODEL GxEPD2_290_T5D
#elif defined(PCA10059)
// 4.2 inch 300x400 - GxEPD2_420_M01
#define TECHO_DISPLAY_MODEL GxEPD2_420_M01
#elif defined(M5_COREINK)
// M5Stack CoreInk
// 1.54 inch 200x200 - GxEPD2_154_M09
#define TECHO_DISPLAY_MODEL GxEPD2_154_M09
#elif defined(HELTEC_WIRELESS_PAPER)
// #define TECHO_DISPLAY_MODEL GxEPD2_213_T5D
#define TECHO_DISPLAY_MODEL GxEPD2_213_FC1
#elif defined(HELTEC_WIRELESS_PAPER_V1_0)
// 2.13" 122x250 - DEPG0213BNS800
#define TECHO_DISPLAY_MODEL GxEPD2_213_BN
#endif
GxEPD2_BW<TECHO_DISPLAY_MODEL, TECHO_DISPLAY_MODEL::HEIGHT> *adafruitDisplay;
- 1.54 inch
EINK_DISPLAY_MODEL: GxEPD2_154_M09
EINK_WIDTH: 200
EINK_HEIGHT: 200
*/
// Constructor
EInkDisplay::EInkDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY geometry, HW_I2C i2cBus)
{
#if defined(TTGO_T_ECHO)
setGeometry(GEOMETRY_RAWMODE, 200, 200);
#elif defined(RAK4630)
// GxEPD2_213_BN - RAK14000 2.13 inch b/w 250x122
setGeometry(GEOMETRY_RAWMODE, 250, 122);
this->displayBufferSize = 250 * (128 / 8);
// GxEPD2_420_M01
// setGeometry(GEOMETRY_RAWMODE, 300, 400);
// GxEPD2_290_T5D
// setGeometry(GEOMETRY_RAWMODE, 296, 128);
// GxEPD2_154_M09
// setGeometry(GEOMETRY_RAWMODE, 200, 200);
#elif defined(HELTEC_WIRELESS_PAPER_V1_0)
// The display's memory is actually 128px x 250px
// Setting the buffersize manually prevents 122/8 truncating to a 15 byte width
// (Or something like that..)
// Set dimensions in OLEDDisplay base class
this->geometry = GEOMETRY_RAWMODE;
this->displayWidth = 250;
this->displayHeight = 122;
this->displayBufferSize = 250 * (128 / 8);
this->displayWidth = EINK_WIDTH;
this->displayHeight = EINK_HEIGHT;
#elif defined(HELTEC_WIRELESS_PAPER)
// GxEPD2_213_BN - 2.13 inch b/w 250x122
setGeometry(GEOMETRY_RAWMODE, 250, 122);
#elif defined(MAKERPYTHON)
// GxEPD2_290_T5D
setGeometry(GEOMETRY_RAWMODE, 296, 128);
// Round shortest side up to nearest byte, to prevent truncation causing an undersized buffer
uint16_t shortSide = min(EINK_WIDTH, EINK_HEIGHT);
uint16_t longSide = max(EINK_WIDTH, EINK_HEIGHT);
if (shortSide % 8 != 0)
shortSide = (shortSide | 7) + 1;
#elif defined(PCA10059)
// GxEPD2_420_M01
setGeometry(GEOMETRY_RAWMODE, 300, 400);
#elif defined(M5_COREINK)
// M5Stack_CoreInk 200x200
// 1.54 inch 200x200 - GxEPD2_154_M09
setGeometry(GEOMETRY_RAWMODE, EPD_HEIGHT, EPD_WIDTH);
#elif defined(my)
// GxEPD2_290_T5D
setGeometry(GEOMETRY_RAWMODE, 296, 128);
LOG_DEBUG("GEOMETRY_RAWMODE, 296, 128\n");
#elif defined(ESP32_S3_PICO)
// GxEPD2_290_T94_V2
setGeometry(GEOMETRY_RAWMODE, EPD_WIDTH, EPD_HEIGHT);
LOG_DEBUG("GEOMETRY_RAWMODE, 296, 128\n");
#endif
// setGeometry(GEOMETRY_RAWMODE, 128, 64); // old resolution
// setGeometry(GEOMETRY_128_64); // We originally used this because I wasn't sure if rawmode worked - it does
this->displayBufferSize = longSide * (shortSide / 8);
}
// FIXME quick hack to limit drawing to a very slow rate
uint32_t lastDrawMsec;
/**
* Force a display update if we haven't drawn within the specified msecLimit
*/
@@ -131,13 +53,6 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit)
// No need to grab this lock because we are on our own SPI bus
// concurrency::LockGuard g(spiLock);
#if defined(USE_EINK_DYNAMIC_REFRESH)
// Decide between full refresh, fast refresh, or skipping the update
bool continueUpdate = determineRefreshMode();
if (!continueUpdate)
return false;
#else
uint32_t now = millis();
uint32_t sinceLast = now - lastDrawMsec;
@@ -146,56 +61,34 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit)
else
return false;
#endif
// FIXME - only draw bits have changed (use backbuf similar to the other displays)
// tft.drawBitmap(0, 0, buffer, 128, 64, TFT_YELLOW, TFT_BLACK);
for (uint32_t y = 0; y < displayHeight; y++) {
for (uint32_t x = 0; x < displayWidth; x++) {
// get src pixel in the page based ordering the OLED lib uses FIXME, super inefficient
auto b = buffer[x + (y / 8) * displayWidth];
auto isset = b & (1 << (y & 7));
adafruitDisplay->drawPixel(x, y, isset ? COLORED : UNCOLORED);
adafruitDisplay->drawPixel(x, y, isset ? GxEPD_BLACK : GxEPD_WHITE);
}
}
// Trigger the refresh in GxEPD2
LOG_DEBUG("Updating E-Paper... ");
#if defined(TTGO_T_ECHO)
adafruitDisplay->nextPage();
#elif defined(RAK4630) || defined(MAKERPYTHON)
// RAK14000 2.13 inch b/w 250x122 actually now does support fast refresh
// Full update mode (slow)
// adafruitDisplay->display(false); // FIXME, use fast refresh mode
// Only enable for e-Paper with support for fast updates and comment out above adafruitDisplay->display(false);
// 1.54 inch 200x200 - GxEPD2_154_M09
// 2.13 inch 250x122 - GxEPD2_213_BN
// 2.9 inch 296x128 - GxEPD2_290_T5D
// 4.2 inch 300x400 - GxEPD2_420_M01
adafruitDisplay->nextPage();
#elif defined(PCA10059) || defined(M5_COREINK)
adafruitDisplay->nextPage();
#elif defined(HELTEC_WIRELESS_PAPER_V1_0)
adafruitDisplay->nextPage();
#elif defined(HELTEC_WIRELESS_PAPER)
adafruitDisplay->nextPage();
#elif defined(ESP32_S3_PICO)
adafruitDisplay->nextPage();
#elif defined(PRIVATE_HW) || defined(my)
adafruitDisplay->nextPage();
#endif
// End the update process
endUpdate();
// Put screen to sleep to save power (possibly not necessary because we already did poweroff inside of display)
adafruitDisplay->hibernate();
LOG_DEBUG("done\n");
return true;
}
// End the update process - virtual method, overriden in derived class
void EInkDisplay::endUpdate()
{
// Power off display hardware, then deep-sleep (Except Wireless Paper V1.1, no deep-sleep)
adafruitDisplay->hibernate();
}
// Write the buffer to the display memory
void EInkDisplay::display(void)
{
@@ -203,15 +96,9 @@ void EInkDisplay::display(void)
// at least one forceDisplay() keyframe. This prevents flashing when we should the critical
// bootscreen (that we want to look nice)
#ifdef USE_EINK_DYNAMIC_REFRESH
lowPriority();
forceDisplay();
highPriority();
#else
if (lastDrawMsec) {
forceDisplay(slowUpdateMsec); // Show the first screen a few seconds after boot, then slower
}
#endif
}
// Send a command to the display (low level function)
@@ -226,16 +113,11 @@ void EInkDisplay::setDetected(uint8_t detected)
(void)detected;
}
// Connect to the display
// Connect to the display - variant specific
bool EInkDisplay::connect()
{
LOG_INFO("Doing EInk init\n");
#ifdef PIN_EINK_PWR_ON
pinMode(PIN_EINK_PWR_ON, OUTPUT);
digitalWrite(PIN_EINK_PWR_ON, HIGH); // If we need to assert a pin to power external peripherals
#endif
#ifdef PIN_EINK_EN
// backlight power, HIGH is backlight on, LOW is off
pinMode(PIN_EINK_EN, OUTPUT);
@@ -244,9 +126,9 @@ bool EInkDisplay::connect()
#if defined(TTGO_T_ECHO)
{
auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY, SPI1);
auto lowLevel = new EINK_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY, SPI1);
adafruitDisplay = new GxEPD2_BW<TECHO_DISPLAY_MODEL, TECHO_DISPLAY_MODEL::HEIGHT>(*lowLevel);
adafruitDisplay = new GxEPD2_BW<EINK_DISPLAY_MODEL, EINK_DISPLAY_MODEL::HEIGHT>(*lowLevel);
adafruitDisplay->init();
adafruitDisplay->setRotation(3);
adafruitDisplay->setPartialWindow(0, 0, displayWidth, displayHeight);
@@ -254,8 +136,8 @@ bool EInkDisplay::connect()
#elif defined(RAK4630) || defined(MAKERPYTHON)
{
if (eink_found) {
auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY);
adafruitDisplay = new GxEPD2_BW<TECHO_DISPLAY_MODEL, TECHO_DISPLAY_MODEL::HEIGHT>(*lowLevel);
auto lowLevel = new EINK_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY);
adafruitDisplay = new GxEPD2_BW<EINK_DISPLAY_MODEL, EINK_DISPLAY_MODEL::HEIGHT>(*lowLevel);
adafruitDisplay->init(115200, true, 10, false, SPI1, SPISettings(4000000, MSBFIRST, SPI_MODE0));
// RAK14000 2.13 inch b/w 250x122 does actually now support fast refresh
adafruitDisplay->setRotation(3);
@@ -267,7 +149,7 @@ bool EInkDisplay::connect()
}
}
#elif defined(HELTEC_WIRELESS_PAPER_V1_0)
#elif defined(HELTEC_WIRELESS_PAPER_V1_0) || defined(HELTEC_WIRELESS_PAPER)
{
// Is this a normal boot, or a wake from deep sleep?
esp_sleep_wakeup_cause_t wakeReason = esp_sleep_get_wakeup_cause();
@@ -296,243 +178,39 @@ bool EInkDisplay::connect()
delay(100);
// Create GxEPD2 objects
auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY, *hspi);
adafruitDisplay = new GxEPD2_BW<TECHO_DISPLAY_MODEL, TECHO_DISPLAY_MODEL::HEIGHT>(*lowLevel);
auto lowLevel = new EINK_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY, *hspi);
adafruitDisplay = new GxEPD2_BW<EINK_DISPLAY_MODEL, EINK_DISPLAY_MODEL::HEIGHT>(*lowLevel);
// Init GxEPD2
adafruitDisplay->init();
adafruitDisplay->setRotation(3);
}
#elif defined(HELTEC_WIRELESS_PAPER)
{
hspi = new SPIClass(HSPI);
hspi->begin(PIN_EINK_SCLK, -1, PIN_EINK_MOSI, PIN_EINK_CS); // SCLK, MISO, MOSI, SS
delay(100);
pinMode(Vext, OUTPUT);
digitalWrite(Vext, LOW);
delay(100);
auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY, *hspi);
adafruitDisplay = new GxEPD2_BW<TECHO_DISPLAY_MODEL, TECHO_DISPLAY_MODEL::HEIGHT>(*lowLevel);
adafruitDisplay->init();
adafruitDisplay->setRotation(3);
adafruitDisplay->clearScreen(); // Clearing now, so the boot logo will draw nice and smoothe (fast refresh)
}
#elif defined(PCA10059)
{
auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY);
adafruitDisplay = new GxEPD2_BW<TECHO_DISPLAY_MODEL, TECHO_DISPLAY_MODEL::HEIGHT>(*lowLevel);
auto lowLevel = new EINK_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY);
adafruitDisplay = new GxEPD2_BW<EINK_DISPLAY_MODEL, EINK_DISPLAY_MODEL::HEIGHT>(*lowLevel);
adafruitDisplay->init(115200, true, 10, false, SPI1, SPISettings(4000000, MSBFIRST, SPI_MODE0));
adafruitDisplay->setRotation(3);
adafruitDisplay->setPartialWindow(0, 0, displayWidth, displayHeight);
}
#elif defined(M5_COREINK)
auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY);
adafruitDisplay = new GxEPD2_BW<TECHO_DISPLAY_MODEL, TECHO_DISPLAY_MODEL::HEIGHT>(*lowLevel);
auto lowLevel = new EINK_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY);
adafruitDisplay = new GxEPD2_BW<EINK_DISPLAY_MODEL, EINK_DISPLAY_MODEL::HEIGHT>(*lowLevel);
adafruitDisplay->init(115200, true, 40, false, SPI, SPISettings(4000000, MSBFIRST, SPI_MODE0));
adafruitDisplay->setRotation(0);
adafruitDisplay->setPartialWindow(0, 0, EPD_WIDTH, EPD_HEIGHT);
adafruitDisplay->setPartialWindow(0, 0, EINK_WIDTH, EINK_HEIGHT);
#elif defined(my) || defined(ESP32_S3_PICO)
{
auto lowLevel = new TECHO_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY);
adafruitDisplay = new GxEPD2_BW<TECHO_DISPLAY_MODEL, TECHO_DISPLAY_MODEL::HEIGHT>(*lowLevel);
auto lowLevel = new EINK_DISPLAY_MODEL(PIN_EINK_CS, PIN_EINK_DC, PIN_EINK_RES, PIN_EINK_BUSY);
adafruitDisplay = new GxEPD2_BW<EINK_DISPLAY_MODEL, EINK_DISPLAY_MODEL::HEIGHT>(*lowLevel);
adafruitDisplay->init(115200, true, 40, false, SPI, SPISettings(4000000, MSBFIRST, SPI_MODE0));
adafruitDisplay->setRotation(1);
adafruitDisplay->setPartialWindow(0, 0, EPD_WIDTH, EPD_HEIGHT);
adafruitDisplay->setPartialWindow(0, 0, EINK_WIDTH, EINK_HEIGHT);
}
#endif
// adafruitDisplay->setFullWindow();
// adafruitDisplay->fillScreen(UNCOLORED);
// adafruitDisplay->drawCircle(100, 100, 20, COLORED);
// adafruitDisplay->display(false);
return true;
}
// Use a mix of full refresh, fast refresh, and update skipping, to balance urgency and display health
#if defined(USE_EINK_DYNAMIC_REFRESH)
// Suggest that subsequent updates should use fast-refresh
void EInkDisplay::highPriority()
{
isHighPriority = true;
}
// Suggest that subsequent updates should use full-refresh
void EInkDisplay::lowPriority()
{
isHighPriority = false;
}
// Full-refresh is explicitly requested for next one update - no skipping please
void EInkDisplay::demandFullRefresh()
{
demandingFull = true;
}
// configure display for fast-refresh
void EInkDisplay::configForFastRefresh()
{
// Display-specific code can go here
#if defined(PRIVATE_HW)
#else
// Otherwise:
adafruitDisplay->setPartialWindow(0, 0, adafruitDisplay->width(), adafruitDisplay->height());
#endif
}
// Configure display for full-refresh
void EInkDisplay::configForFullRefresh()
{
// Display-specific code can go here
#if defined(PRIVATE_HW)
#else
// Otherwise:
adafruitDisplay->setFullWindow();
#endif
}
#ifdef EINK_FASTREFRESH_ERASURE_LIMIT
// Count black pixels in an image. Used for "erasure tracking"
int32_t EInkDisplay::countBlackPixels()
{
int32_t blackCount = 0; // Signed, to avoid underflow when comparing
for (uint16_t b = 0; b < (displayWidth / 8) * displayHeight; b++) {
for (uint8_t i = 0; i < 7; i++) {
// Check if each bit is black or white
blackCount += (buffer[b] >> i) & 1;
}
}
return blackCount;
}
// Evaluate the (rough) amount of black->white pixel change since last full refresh
bool EInkDisplay::tooManyErasures()
{
// Ideally, we would compare the new and old buffers, to count *actual* white-to-black pixel changes
// but that would require substantially more "code tampering"
// Get the black pixel stats for this image
int32_t blackCount = countBlackPixels();
int32_t blackDifference = blackCount - prevBlackCount;
// Update the running total of "erasures" - black pixels which have become white, since last full-refresh
if (blackDifference < 0)
erasedSinceFull -= blackDifference;
// Store black pixel count for next time
prevBlackCount = blackCount;
// Log the running total - help devs setup new boards
LOG_DEBUG("Dynamic Refresh: erasedSinceFull=%hu, EINK_FASTREFRESH_ERASURE_LIMIT=%hu\n", erasedSinceFull,
EINK_FASTREFRESH_ERASURE_LIMIT);
// Check if too many pixels have been erased
if (erasedSinceFull > EINK_FASTREFRESH_ERASURE_LIMIT)
return true; // Too many
else
return false; // Still okay
}
#endif // ifdef EINK_FASTREFRESH_ERASURE_LIMIT
bool EInkDisplay::newImageMatchesOld()
{
uint32_t newImageHash = 0;
// Generate hash: sum all bytes in the image buffer
for (uint16_t b = 0; b < (displayWidth / 8) * displayHeight; b++) {
newImageHash += buffer[b];
}
// Compare hashes
bool hashMatches = (newImageHash == prevImageHash);
// Update the cached hash
prevImageHash = newImageHash;
// Return the comparison result
return hashMatches;
}
// Choose between, full-refresh, fast refresh, and update skipping, to balance urgency and display health.
bool EInkDisplay::determineRefreshMode()
{
uint32_t now = millis();
uint32_t sinceLast = now - lastUpdateMsec;
// If rate-limiting dropped a high-priority update:
// promote this update, so it runs ASAP
if (missedHighPriorityUpdate) {
isHighPriority = true;
missedHighPriorityUpdate = false;
}
// Abort: if too soon for a new frame (unless demanding full)
if (!demandingFull && isHighPriority && fastRefreshCount > 0 && sinceLast < highPriorityLimitMsec) {
LOG_DEBUG("Dynamic Refresh: update skipped. Exceeded EINK_HIGHPRIORITY_LIMIT_SECONDS\n");
missedHighPriorityUpdate = true;
return false;
}
if (!demandingFull && !isHighPriority && !demandingFull && sinceLast < lowPriorityLimitMsec) {
return false;
}
// If demanded full refresh: give it to them
if (demandingFull)
needsFull = true;
// Check if old image (fast-refresh) should be redrawn (as full), for image quality
if (fastRefreshCount > 0 && !isHighPriority)
needsFull = true;
// If too many fast updates, require a full-refresh (display health)
if (fastRefreshCount >= fastRefreshLimit)
needsFull = true;
#ifdef EINK_FASTREFRESH_ERASURE_LIMIT
// Some displays struggle with erasing black pixels to white, during fast-refresh
if (tooManyErasures())
needsFull = true;
#endif
// If image matches
// (Block must run, even if full already selected, to store hash for next time)
if (newImageMatchesOld()) {
// If low priority: limit rate
// otherwise, every loop() will run the hash method
if (!isHighPriority)
lastUpdateMsec = now;
// If update is *not* for display health or image quality, skip it
if (!needsFull)
return false;
}
// Conditions assessed - not skipping - load the appropriate config
// If options require a full refresh
if (!isHighPriority || needsFull) {
if (fastRefreshCount > 0)
configForFullRefresh();
LOG_DEBUG("Dynamic Refresh: conditions met for full-refresh\n");
fastRefreshCount = 0;
needsFull = false;
demandingFull = false;
erasedSinceFull = 0; // Reset the count for EINK_FASTREFRESH_ERASURE_LIMIT - tracks ghosting buildup
}
// If options allow a fast-refresh
else {
if (fastRefreshCount == 0)
configForFastRefresh();
LOG_DEBUG("Dynamic Refresh: conditions met for fast-refresh\n");
fastRefreshCount++;
}
lastUpdateMsec = now; // Mark time for rate limiting
return true; // Instruct calling method to continue with update
}
#endif // End USE_EINK_DYNAMIC_REFRESH
#endif

View File

@@ -1,8 +1,11 @@
#pragma once
#ifdef USE_EINK
#include "GxEPD2_BW.h"
#include <OLEDDisplay.h>
#if defined(HELTEC_WIRELESS_PAPER_V1_0)
#if defined(HELTEC_WIRELESS_PAPER_V1_0) || defined(HELTEC_WIRELESS_PAPER)
// Re-enable SPI after deep sleep: rtc_gpio_hold_dis()
#include "driver/rtc_io.h"
#endif
@@ -10,12 +13,15 @@
/**
* An adapter class that allows using the GxEPD2 library as if it was an OLEDDisplay implementation.
*
* Note: EInkDynamicDisplay derives from this class.
*
* Remaining TODO:
* optimize display() to only draw changed pixels (see other OLED subclasses for examples)
* implement displayOn/displayOff to turn off the TFT device (and backlight)
* Use the fast NRF52 SPI API rather than the slow standard arduino version
*
* turn radio back on - currently with both on spi bus is fucked? or are we leaving chip select asserted?
* Suggestion: perhaps similar to HELTEC_WIRELESS_PAPER issue, which resolved with rtc_gpio_hold_dis()
*/
class EInkDisplay : public OLEDDisplay
{
@@ -37,7 +43,14 @@ class EInkDisplay : public OLEDDisplay
*
* @return true if we did draw the screen
*/
bool forceDisplay(uint32_t msecLimit = 1000);
virtual bool forceDisplay(uint32_t msecLimit = 1000);
/**
* Run any code needed to complete an update, after the physical refresh has completed.
* Split from forceDisplay(), to enable async refresh in derived EInkDynamicDisplay class.
*
*/
virtual void endUpdate();
/**
* shim to make the abstraction happy
@@ -55,80 +68,17 @@ class EInkDisplay : public OLEDDisplay
// Connect to the display
virtual bool connect() override;
#if defined(USE_EINK_DYNAMIC_REFRESH)
// Full, fast, or skip: balance urgency with display health
// AdafruitGFX display object - instantiated in connect(), variant specific
GxEPD2_BW<EINK_DISPLAY_MODEL, EINK_DISPLAY_MODEL::HEIGHT> *adafruitDisplay = NULL;
// Use fast refresh if EITHER:
// * highPriority() was set
// * a highPriority() update was previously skipped, for rate-limiting - (EINK_HIGHPRIORITY_LIMIT_SECONDS)
// Use full refresh if EITHER:
// * lowPriority() was set
// * demandFullRefresh() was called - (single shot)
// * too many fast updates in a row: protect display - (EINK_FASTREFRESH_REPEAT_LIMIT)
// * no recent updates, and last update was fast: redraw for image quality (EINK_LOWPRIORITY_LIMIT_SECONDS)
// * (optional) too many "erasures" since full-refresh (black pixels cleared to white)
// Rate limit if:
// * lowPriority() - (EINK_LOWPRIORITY_LIMIT_SECONDS)
// * highPriority(), if multiple fast updates have run back-to-back - (EINK_HIGHPRIORITY_LIMIT_SECONDS)
// Skip update entirely if ALL criteria met:
// * new image matches old image
// * lowPriority()
// * no call to demandFullRefresh()
// * not redrawing for image quality
// * not refreshing for display health
// ------------------------------------
// To implement for your E-Ink display:
// * edit configForFastRefresh()
// * edit configForFullRefresh()
// * add macros to variant.h, and adjust to taste:
/*
#define USE_EINK_DYNAMIC_REFRESH
#define EINK_LOWPRIORITY_LIMIT_SECONDS 30
#define EINK_HIGHPRIORITY_LIMIT_SECONDS 1
#define EINK_FASTREFRESH_REPEAT_LIMIT 5
#define EINK_FASTREFRESH_ERASURE_LIMIT 300 // optional
*/
public:
void highPriority(); // Suggest fast refresh
void lowPriority(); // Suggest full refresh
void demandFullRefresh(); // For next update: explicitly request full refresh
protected:
void configForFastRefresh(); // Display specific code to select fast refresh mode
void configForFullRefresh(); // Display specific code to return to full refresh mode
bool newImageMatchesOld(); // Is the new update actually different to the last image?
bool determineRefreshMode(); // Called immediately before data written to display - choose refresh mode, or abort update
#ifdef EINK_FASTREFRESH_ERASURE_LIMIT
int32_t countBlackPixels(); // Calculate the number of black pixels in the new image
bool tooManyErasures(); // Has too much "ghosting" (black pixels erased to white) accumulated since last full-refresh?
// If display uses HSPI
#if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0)
SPIClass *hspi = NULL;
#endif
bool isHighPriority = true; // Does the method calling update believe that this is urgent?
bool needsFull = false; // Is a full refresh forced? (display health)
bool demandingFull = false; // Was full refresh specifically requested? (splash screens, etc)
bool missedHighPriorityUpdate = false; // Was a high priority update skipped for rate-limiting?
uint16_t fastRefreshCount = 0; // How many fast updates have occurred since last full refresh?
uint32_t lastUpdateMsec = 0; // When did the last update occur?
uint32_t prevImageHash = 0; // Used to check if update will change screen image (skippable or not)
int32_t prevBlackCount = 0; // How many black pixels were in the previous image
uint32_t erasedSinceFull = 0; // How many black pixels have been set back to white since last full-refresh? (roughly)
// Set in variant.h
const uint32_t lowPriorityLimitMsec = (uint32_t)1000 * EINK_LOWPRIORITY_LIMIT_SECONDS; // Max rate for fast refreshes
const uint32_t highPriorityLimitMsec = (uint32_t)1000 * EINK_HIGHPRIORITY_LIMIT_SECONDS; // Max rate for full refreshes
const uint32_t fastRefreshLimit = EINK_FASTREFRESH_REPEAT_LIMIT; // Max consecutive fast updates, before full is triggered
#else // !USE_EINK_DYNAMIC_REFRESH
// Tolerate calls to these methods anywhere, just to be safe
void highPriority() {}
void lowPriority() {}
void demandFullRefresh() {}
#endif
private:
// FIXME quick hack to limit drawing to a very slow rate
uint32_t lastDrawMsec = 0;
};
#endif

View File

@@ -0,0 +1,500 @@
#include "configuration.h"
#if defined(USE_EINK) && defined(USE_EINK_DYNAMICDISPLAY)
#include "EInkDynamicDisplay.h"
// Constructor
EInkDynamicDisplay::EInkDynamicDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY geometry, HW_I2C i2cBus)
: EInkDisplay(address, sda, scl, geometry, i2cBus)
{
// If tracking ghost pixels, grab memory
#ifdef EINK_LIMIT_GHOSTING_PX
dirtyPixels = new uint8_t[EInkDisplay::displayBufferSize](); // Init with zeros
#endif
}
// Destructor
EInkDynamicDisplay::~EInkDynamicDisplay()
{
// If we were tracking ghost pixels, free the memory
#ifdef EINK_LIMIT_GHOSTING_PX
delete[] dirtyPixels;
#endif
}
// Screen requests a BACKGROUND frame
void EInkDynamicDisplay::display()
{
addFrameFlag(BACKGROUND);
update();
}
// Screen requests a RESPONSIVE frame
bool EInkDynamicDisplay::forceDisplay(uint32_t msecLimit)
{
addFrameFlag(RESPONSIVE);
return update(); // (Unutilized) Base class promises to return true if update ran
}
// Add flag for the next frame
void EInkDynamicDisplay::addFrameFlag(frameFlagTypes flag)
{
// OR the new flag into the existing flags
this->frameFlags = (frameFlagTypes)(this->frameFlags | flag);
}
// GxEPD2 code to set fast refresh
void EInkDynamicDisplay::configForFastRefresh()
{
// Variant-specific code can go here
#if defined(PRIVATE_HW)
#else
// Otherwise:
adafruitDisplay->setPartialWindow(0, 0, adafruitDisplay->width(), adafruitDisplay->height());
#endif
}
// GxEPD2 code to set full refresh
void EInkDynamicDisplay::configForFullRefresh()
{
// Variant-specific code can go here
#if defined(PRIVATE_HW)
#else
// Otherwise:
adafruitDisplay->setFullWindow();
#endif
}
// Run any relevant GxEPD2 code, so next update will use correct refresh type
void EInkDynamicDisplay::applyRefreshMode()
{
// Change from FULL to FAST
if (currentConfig == FULL && refresh == FAST) {
configForFastRefresh();
currentConfig = FAST;
}
// Change from FAST back to FULL
else if (currentConfig == FAST && refresh == FULL) {
configForFullRefresh();
currentConfig = FULL;
}
}
// Update fastRefreshCount
void EInkDynamicDisplay::adjustRefreshCounters()
{
if (refresh == FAST)
fastRefreshCount++;
else if (refresh == FULL)
fastRefreshCount = 0;
}
// Trigger the display update by calling base class
bool EInkDynamicDisplay::update()
{
// Detemine the refresh mode to use, and start the update
bool refreshApproved = determineMode();
if (refreshApproved) {
EInkDisplay::forceDisplay(0); // Bypass base class' own rate-limiting system
storeAndReset(); // Store the result of this loop for next time. Note: call *before* endOrDetach()
endOrDetach(); // endUpdate() right now, or set the async refresh flag (if FULL and HAS_EINK_ASYNCFULL)
} else
storeAndReset(); // No update, no post-update code, just store the results
return refreshApproved; // (Unutilized) Base class promises to return true if update ran
}
// Figure out who runs the post-update code
void EInkDynamicDisplay::endOrDetach()
{
// If the GxEPD2 version reports that it has the async modifications
#ifdef HAS_EINK_ASYNCFULL
if (previousRefresh == FULL) {
asyncRefreshRunning = true; // Set the flag - picked up at start of determineMode(), next loop.
if (previousFrameFlags & BLOCKING)
awaitRefresh();
else
LOG_DEBUG("Async full-refresh begins\n");
}
// Fast Refresh
else if (previousRefresh == FAST)
EInkDisplay::endUpdate(); // Still block while updating, but EInkDisplay needs us to call endUpdate() ourselves.
// Fallback - If using an unmodified version of GxEPD2 for some reason
#else
if (previousRefresh == FULL || previousRefresh == FAST) { // If refresh wasn't skipped (on unspecified..)
LOG_WARN(
"GxEPD2 version has not been modified to support async refresh; using fallback behavior. Please update lib_deps in "
"variant's platformio.ini file\n");
EInkDisplay::endUpdate();
}
#endif
}
// Assess situation, pick a refresh type
bool EInkDynamicDisplay::determineMode()
{
checkInitialized();
checkForPromotion();
#if defined(HAS_EINK_ASYNCFULL)
checkAsyncFullRefresh();
#endif
checkRateLimiting();
// If too soon for a new frame, or display busy, abort early
if (refresh == SKIPPED)
return false; // No refresh
// -- New frame is due --
resetRateLimiting(); // Once determineMode() ends, will have to wait again
hashImage(); // Generate here, so we can still copy it to previousImageHash, even if we skip the comparison check
LOG_DEBUG("determineMode(): "); // Begin log entry
// Once mode determined, any remaining checks will bypass
checkCosmetic();
checkDemandingFast();
checkFrameMatchesPrevious();
checkConsecutiveFastRefreshes();
#ifdef EINK_LIMIT_GHOSTING_PX
checkExcessiveGhosting();
#endif
checkFastRequested();
if (refresh == UNSPECIFIED)
LOG_WARN("There was a flaw in the determineMode() logic.\n");
// -- Decision has been reached --
applyRefreshMode();
adjustRefreshCounters();
#ifdef EINK_LIMIT_GHOSTING_PX
// Full refresh clears any ghosting
if (refresh == FULL)
resetGhostPixelTracking();
#endif
// Return - call a refresh or not?
if (refresh == SKIPPED)
return false; // Don't trigger a refresh
else
return true; // Do trigger a refresh
}
// Is this the very first frame?
void EInkDynamicDisplay::checkInitialized()
{
if (!initialized) {
// Undo GxEPD2_BW::partialWindow(), if set by developer in EInkDisplay::connect()
configForFullRefresh();
// Clear any existing image, so we can draw logo with fast-refresh, but also to set GxEPD2_EPD::_initial_write
adafruitDisplay->clearScreen();
LOG_DEBUG("initialized, ");
initialized = true;
// Use a fast-refresh for the next frame; no skipping or else blank screen when waking from deep sleep
addFrameFlag(DEMAND_FAST);
}
}
// Was a frame skipped (rate, display busy) that should have been a FAST refresh?
void EInkDynamicDisplay::checkForPromotion()
{
// If a frame was skipped (rate, display busy), then promote a BACKGROUND frame
// Because we DID want a RESPONSIVE/COSMETIC/DEMAND_FULL frame last time, we just didn't get it
switch (previousReason) {
case ASYNC_REFRESH_BLOCKED_DEMANDFAST:
addFrameFlag(DEMAND_FAST);
break;
case ASYNC_REFRESH_BLOCKED_COSMETIC:
addFrameFlag(COSMETIC);
break;
case ASYNC_REFRESH_BLOCKED_RESPONSIVE:
case EXCEEDED_RATELIMIT_FAST:
addFrameFlag(RESPONSIVE);
break;
default:
break;
}
}
// Is it too soon for another frame of this type?
void EInkDynamicDisplay::checkRateLimiting()
{
uint32_t now = millis();
// Sanity check: millis() overflow - just let the update run..
if (previousRunMs > now)
return;
// Skip update: too soon for BACKGROUND
if (frameFlags == BACKGROUND) {
if (now - previousRunMs < EINK_LIMIT_RATE_BACKGROUND_SEC * 1000) {
refresh = SKIPPED;
reason = EXCEEDED_RATELIMIT_FULL;
return;
}
}
// No rate-limit for these special cases
if (frameFlags & COSMETIC || frameFlags & DEMAND_FAST)
return;
// Skip update: too soon for RESPONSIVE
if (frameFlags & RESPONSIVE) {
if (now - previousRunMs < EINK_LIMIT_RATE_RESPONSIVE_SEC * 1000) {
refresh = SKIPPED;
reason = EXCEEDED_RATELIMIT_FAST;
return;
}
}
}
// Is this frame COSMETIC (splash screens?)
void EInkDynamicDisplay::checkCosmetic()
{
// If a decision was already reached, don't run the check
if (refresh != UNSPECIFIED)
return;
// A full refresh is requested for cosmetic purposes: we have a decision
if (frameFlags & COSMETIC) {
refresh = FULL;
reason = FLAGGED_COSMETIC;
LOG_DEBUG("refresh=FULL, reason=FLAGGED_COSMETIC, frameFlags=0x%x\n", frameFlags);
}
}
// Is this a one-off special circumstance, where we REALLY want a fast refresh?
void EInkDynamicDisplay::checkDemandingFast()
{
// If a decision was already reached, don't run the check
if (refresh != UNSPECIFIED)
return;
// A fast refresh is demanded: we have a decision
if (frameFlags & DEMAND_FAST) {
refresh = FAST;
reason = FLAGGED_DEMAND_FAST;
LOG_DEBUG("refresh=FAST, reason=FLAGGED_DEMAND_FAST, frameFlags=0x%x\n", frameFlags);
}
}
// Does the new frame match the currently displayed image?
void EInkDynamicDisplay::checkFrameMatchesPrevious()
{
// If a decision was already reached, don't run the check
if (refresh != UNSPECIFIED)
return;
// If frame is *not* a duplicate, abort the check
if (imageHash != previousImageHash)
return;
#if !defined(EINK_BACKGROUND_USES_FAST)
// If BACKGROUND, and last update was FAST: redraw the same image in FULL (for display health + image quality)
if (frameFlags == BACKGROUND && fastRefreshCount > 0) {
refresh = FULL;
reason = REDRAW_WITH_FULL;
LOG_DEBUG("refresh=FULL, reason=REDRAW_WITH_FULL, frameFlags=0x%x\n", frameFlags);
return;
}
#endif
// Not redrawn, not COSMETIC, not DEMAND_FAST
refresh = SKIPPED;
reason = FRAME_MATCHED_PREVIOUS;
LOG_DEBUG("refresh=SKIPPED, reason=FRAME_MATCHED_PREVIOUS, frameFlags=0x%x\n", frameFlags);
}
// Have too many fast-refreshes occured consecutively, since last full refresh?
void EInkDynamicDisplay::checkConsecutiveFastRefreshes()
{
// If a decision was already reached, don't run the check
if (refresh != UNSPECIFIED)
return;
// If too many FAST refreshes consecutively - force a FULL refresh
if (fastRefreshCount >= EINK_LIMIT_FASTREFRESH) {
refresh = FULL;
reason = EXCEEDED_LIMIT_FASTREFRESH;
LOG_DEBUG("refresh=FULL, reason=EXCEEDED_LIMIT_FASTREFRESH, frameFlags=0x%x\n", frameFlags);
}
}
// No objections, we can perform fast-refresh, if desired
void EInkDynamicDisplay::checkFastRequested()
{
if (refresh != UNSPECIFIED)
return;
if (frameFlags == BACKGROUND) {
#ifdef EINK_BACKGROUND_USES_FAST
// If we want BACKGROUND to use fast. (FULL only when a limit is hit)
refresh = FAST;
reason = BACKGROUND_USES_FAST;
LOG_DEBUG("refresh=FAST, reason=BACKGROUND_USES_FAST, fastRefreshCount=%lu, frameFlags=0x%x\n", fastRefreshCount,
frameFlags);
#else
// If we do want to use FULL for BACKGROUND updates
refresh = FULL;
reason = FLAGGED_BACKGROUND;
LOG_DEBUG("refresh=FULL, reason=FLAGGED_BACKGROUND\n");
#endif
}
// Sanity: confirm that we did ask for a RESPONSIVE frame.
if (frameFlags & RESPONSIVE) {
refresh = FAST;
reason = NO_OBJECTIONS;
LOG_DEBUG("refresh=FAST, reason=NO_OBJECTIONS, fastRefreshCount=%lu, frameFlags=0x%x\n", fastRefreshCount, frameFlags);
}
}
// Reset the timer used for rate-limiting
void EInkDynamicDisplay::resetRateLimiting()
{
previousRunMs = millis();
}
// Generate a hash of this frame, to compare against previous update
void EInkDynamicDisplay::hashImage()
{
imageHash = 0;
// Sum all bytes of the image buffer together
for (uint16_t b = 0; b < (displayWidth / 8) * displayHeight; b++) {
imageHash += buffer[b];
}
}
// Store the results of determineMode() for future use, and reset for next call
void EInkDynamicDisplay::storeAndReset()
{
previousFrameFlags = frameFlags;
previousRefresh = refresh;
previousReason = reason;
// Only store image hash if the display will update
if (refresh != SKIPPED) {
previousImageHash = imageHash;
}
frameFlags = BACKGROUND;
refresh = UNSPECIFIED;
}
#ifdef EINK_LIMIT_GHOSTING_PX
// Count how many ghost pixels the new image will display
void EInkDynamicDisplay::countGhostPixels()
{
// If a decision was already reached, don't run the check
if (refresh != UNSPECIFIED)
return;
// Start a new count
ghostPixelCount = 0;
// Check new image, bit by bit, for any white pixels at locations marked "dirty"
for (uint16_t i = 0; i < displayBufferSize; i++) {
for (uint8_t bit = 0; bit < 7; bit++) {
const bool dirty = (dirtyPixels[i] >> bit) & 1; // Has pixel location been drawn to since full-refresh?
const bool shouldBeBlank = !((buffer[i] >> bit) & 1); // Is pixel location white in the new image?
// If pixel is (or has been) black since last full-refresh, and now is white: ghosting
if (dirty && shouldBeBlank)
ghostPixelCount++;
// Update the dirty status for this pixel - will this location become a ghost if set white in future?
if (!dirty && !shouldBeBlank)
dirtyPixels[i] |= (1 << bit);
}
}
LOG_DEBUG("ghostPixels=%hu, ", ghostPixelCount);
}
// Check if ghost pixel count exceeds the defined limit
void EInkDynamicDisplay::checkExcessiveGhosting()
{
// If a decision was already reached, don't run the check
if (refresh != UNSPECIFIED)
return;
countGhostPixels();
// If too many ghost pixels, select full refresh
if (ghostPixelCount > EINK_LIMIT_GHOSTING_PX) {
refresh = FULL;
reason = EXCEEDED_GHOSTINGLIMIT;
LOG_DEBUG("refresh=FULL, reason=EXCEEDED_GHOSTINGLIMIT, frameFlags=0x%x\n", frameFlags);
}
}
// Clear the dirty pixels array. Call when full-refresh cleans the display.
void EInkDynamicDisplay::resetGhostPixelTracking()
{
// Copy the current frame into dirtyPixels[] from the display buffer
memcpy(dirtyPixels, EInkDisplay::buffer, EInkDisplay::displayBufferSize);
}
#endif // EINK_LIMIT_GHOSTING_PX
#ifdef HAS_EINK_ASYNCFULL
// Check the status of an "async full-refresh", and run the finish-up code if the hardware is ready
void EInkDynamicDisplay::checkAsyncFullRefresh()
{
// No refresh taking place, continue with determineMode()
if (!asyncRefreshRunning)
return;
// Full refresh still running
if (adafruitDisplay->epd2.isBusy()) {
// No refresh
refresh = SKIPPED;
// Set the reason, marking what type of frame we're skipping
if (frameFlags & DEMAND_FAST)
reason = ASYNC_REFRESH_BLOCKED_DEMANDFAST;
else if (frameFlags & COSMETIC)
reason = ASYNC_REFRESH_BLOCKED_COSMETIC;
else if (frameFlags & RESPONSIVE)
reason = ASYNC_REFRESH_BLOCKED_RESPONSIVE;
else
reason = ASYNC_REFRESH_BLOCKED_BACKGROUND;
return;
}
// If we asyncRefreshRunning flag is still set, but display's BUSY pin reports the refresh is done
adafruitDisplay->endAsyncFull(); // Run the end of nextPage() code
EInkDisplay::endUpdate(); // Run base-class code to finish off update (NOT our derived class override)
asyncRefreshRunning = false; // Unset the flag
LOG_DEBUG("Async full-refresh complete\n");
// Note: this code only works because of a modification to meshtastic/GxEPD2.
// It is only equipped to intercept calls to nextPage()
}
// Hold control while an async refresh runs
void EInkDynamicDisplay::awaitRefresh()
{
// Continually poll the BUSY pin
while (adafruitDisplay->epd2.isBusy())
yield();
// End the full-refresh process
adafruitDisplay->endAsyncFull(); // Run the end of nextPage() code
EInkDisplay::endUpdate(); // Run base-class code to finish off update (NOT our derived class override)
asyncRefreshRunning = false; // Unset the flag
}
#endif // HAS_EINK_ASYNCFULL
#endif // USE_EINK_DYNAMICDISPLAY

View File

@@ -0,0 +1,127 @@
#pragma once
#include "configuration.h"
#if defined(USE_EINK) && defined(USE_EINK_DYNAMICDISPLAY)
#include "EInkDisplay2.h"
#include "GxEPD2_BW.h"
/*
Derives from the EInkDisplay adapter class.
Accepts suggestions from Screen class about frame type.
Determines which refresh type is most suitable.
(Full, Fast, Skip)
*/
class EInkDynamicDisplay : public EInkDisplay
{
public:
// Constructor
// ( Parameters unused, passed to EInkDisplay. Maintains compatibility OLEDDisplay class )
EInkDynamicDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY geometry, HW_I2C i2cBus);
~EInkDynamicDisplay();
// What kind of frame is this
enum frameFlagTypes : uint8_t {
BACKGROUND = (1 << 0), // For frames via display()
RESPONSIVE = (1 << 1), // For frames via forceDisplay()
COSMETIC = (1 << 2), // For splashes
DEMAND_FAST = (1 << 3), // Special case only
BLOCKING = (1 << 4), // Modifier - block while refresh runs
};
void addFrameFlag(frameFlagTypes flag);
// Set the correct frame flag, then call universal "update()" method
void display() override;
bool forceDisplay(uint32_t msecLimit) override; // Shadows base class. Parameter and return val unused.
protected:
enum refreshTypes : uint8_t { // Which refresh operation will be used
UNSPECIFIED,
FULL,
FAST,
SKIPPED,
};
enum reasonTypes : uint8_t { // How was the decision reached
NO_OBJECTIONS,
ASYNC_REFRESH_BLOCKED_DEMANDFAST,
ASYNC_REFRESH_BLOCKED_COSMETIC,
ASYNC_REFRESH_BLOCKED_RESPONSIVE,
ASYNC_REFRESH_BLOCKED_BACKGROUND,
EXCEEDED_RATELIMIT_FAST,
EXCEEDED_RATELIMIT_FULL,
FLAGGED_COSMETIC,
FLAGGED_DEMAND_FAST,
EXCEEDED_LIMIT_FASTREFRESH,
EXCEEDED_GHOSTINGLIMIT,
FRAME_MATCHED_PREVIOUS,
BACKGROUND_USES_FAST,
FLAGGED_BACKGROUND,
REDRAW_WITH_FULL,
};
void configForFastRefresh(); // GxEPD2 code to set fast-refresh
void configForFullRefresh(); // GxEPD2 code to set full-refresh
bool determineMode(); // Assess situation, pick a refresh type
void applyRefreshMode(); // Run any relevant GxEPD2 code, so next update will use correct refresh type
void adjustRefreshCounters(); // Update fastRefreshCount
bool update(); // Trigger the display update - determine mode, then call base class
void endOrDetach(); // Run the post-update code, or delegate it off to checkAsyncFullRefresh()
// Checks as part of determineMode()
void checkInitialized(); // Is this the very first frame?
void checkForPromotion(); // Was a frame skipped (rate, display busy) that should have been a FAST refresh?
void checkRateLimiting(); // Is this frame too soon?
void checkCosmetic(); // Was the COSMETIC flag set?
void checkDemandingFast(); // Was the DEMAND_FAST flag set?
void checkFrameMatchesPrevious(); // Does the new frame match the existing display image?
void checkConsecutiveFastRefreshes(); // Too many fast-refreshes consecutively?
void checkFastRequested(); // Was the flag set for RESPONSIVE, or only BACKGROUND?
void resetRateLimiting(); // Set previousRunMs - this now counts as an update, for rate-limiting
void hashImage(); // Generate a hashed version of this frame, to compare against previous update
void storeAndReset(); // Keep results of determineMode() for later, tidy-up for next call
// What we are determining for this frame
frameFlagTypes frameFlags = BACKGROUND; // Frame characteristics - determineMode() input
refreshTypes refresh = UNSPECIFIED; // Refresh type - determineMode() output
reasonTypes reason = NO_OBJECTIONS; // Reason - why was refresh type used
// What happened last time determineMode() ran
frameFlagTypes previousFrameFlags = BACKGROUND; // (Previous) Frame flags
refreshTypes previousRefresh = UNSPECIFIED; // (Previous) Outcome
reasonTypes previousReason = NO_OBJECTIONS; // (Previous) Reason
bool initialized = false; // Have we drawn at least one frame yet?
uint32_t previousRunMs = -1; // When did determineMode() last run (rather than rejecting for rate-limiting)
uint32_t imageHash = 0; // Hash of the current frame. Don't bother updating if nothing has changed!
uint32_t previousImageHash = 0; // Hash of the previous update's frame
uint32_t fastRefreshCount = 0; // How many fast-refreshes consecutively since last full refresh?
refreshTypes currentConfig = FULL; // Which refresh type is GxEPD2 currently configured for
// Optional - track ghosting, pixel by pixel
#ifdef EINK_LIMIT_GHOSTING_PX
void countGhostPixels(); // Count any pixels which have moved from black to white since last full-refresh
void checkExcessiveGhosting(); // Check if ghosting exceeds defined limit
void resetGhostPixelTracking(); // Clear the dirty pixels array. Call when full-refresh cleans the display.
uint8_t *dirtyPixels; // Any pixels that have been black since last full-refresh (dynamically allocated mem)
uint32_t ghostPixelCount = 0; // Number of pixels with problematic ghosting. Retained here for LOG_DEBUG use
#endif
// Conditional - async full refresh - only with modified meshtastic/GxEPD2
#if defined(HAS_EINK_ASYNCFULL)
void checkAsyncFullRefresh(); // Check the status of "async full-refresh"; run the post-update code if the hardware is ready
void awaitRefresh(); // Hold control while an async refresh runs
void endUpdate() override {} // Disable base-class behavior of running post-update immediately after forceDisplay()
bool asyncRefreshRunning = false; // Flag, checked by checkAsyncFullRefresh()
#endif
};
// Tidier calls to addFrameFlag() from outside class
#define EINK_ADD_FRAMEFLAG(display, flag) static_cast<EInkDynamicDisplay *>(display)->addFrameFlag(EInkDynamicDisplay::flag)
#else // !USE_EINK_DYNAMICDISPLAY
// Dummy-macro, removes the need for include guards
#define EINK_ADD_FRAMEFLAG(display, flag)
#endif

View File

@@ -31,6 +31,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#include "error.h"
#include "gps/GeoCoord.h"
#include "gps/RTC.h"
#include "graphics/ScreenFonts.h"
#include "graphics/images.h"
#include "input/TouchScreenImpl1.h"
#include "main.h"
@@ -56,14 +57,6 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#include "platform/portduino/PortduinoGlue.h"
#endif
#ifdef OLED_RU
#include "fonts/OLEDDisplayFontsRU.h"
#endif
#ifdef OLED_UA
#include "fonts/OLEDDisplayFontsUA.h"
#endif
using namespace meshtastic; /** @todo remove */
namespace graphics
@@ -111,31 +104,7 @@ static uint16_t displayWidth, displayHeight;
#define SCREEN_WIDTH displayWidth
#define SCREEN_HEIGHT displayHeight
#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \
!defined(DISPLAY_FORCE_SMALL_FONTS)
// The screen is bigger so use bigger fonts
#define FONT_SMALL ArialMT_Plain_16 // Height: 19
#define FONT_MEDIUM ArialMT_Plain_24 // Height: 28
#define FONT_LARGE ArialMT_Plain_24 // Height: 28
#else
#ifdef OLED_RU
#define FONT_SMALL ArialMT_Plain_10_RU
#else
#ifdef OLED_UA
#define FONT_SMALL ArialMT_Plain_10_UA
#else
#define FONT_SMALL ArialMT_Plain_10 // Height: 13
#endif
#endif
#define FONT_MEDIUM ArialMT_Plain_16 // Height: 19
#define FONT_LARGE ArialMT_Plain_24 // Height: 28
#endif
#define fontHeight(font) ((font)[1] + 1) // height is position 1
#define FONT_HEIGHT_SMALL fontHeight(FONT_SMALL)
#define FONT_HEIGHT_MEDIUM fontHeight(FONT_MEDIUM)
#define FONT_HEIGHT_LARGE fontHeight(FONT_LARGE)
#include "graphics/ScreenFonts.h"
#define getStringCenteredX(s) ((SCREEN_WIDTH - display->getStringWidth(s)) / 2)
@@ -291,6 +260,10 @@ static void drawWelcomeScreen(OLEDDisplay *display, OLEDDisplayUiState *state, i
/// Used on eink displays while in deep sleep
static void drawSleepScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
// Next frame should use full-refresh, and block while running, else device will sleep before async callback
EINK_ADD_FRAMEFLAG(display, COSMETIC);
EINK_ADD_FRAMEFLAG(display, BLOCKING);
drawIconScreen("Sleeping...", display, state, x, y);
}
#endif
@@ -929,9 +902,12 @@ Screen::Screen(ScanI2C::DeviceAddress address, meshtastic_Config_DisplayConfig_O
#elif defined(ST7735_CS) || defined(ILI9341_DRIVER) || defined(ST7789_CS) || defined(RAK14014)
dispdev = new TFTDisplay(address.address, -1, -1, geometry,
(address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE);
#elif defined(USE_EINK)
#elif defined(USE_EINK) && !defined(USE_EINK_DYNAMICDISPLAY)
dispdev = new EInkDisplay(address.address, -1, -1, geometry,
(address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE);
#elif defined(USE_EINK) && defined(USE_EINK_DYNAMICDISPLAY)
dispdev = new EInkDynamicDisplay(address.address, -1, -1, geometry,
(address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE);
#elif defined(USE_ST7567)
dispdev = new ST7567Wire(address.address, -1, -1, geometry,
(address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE);
@@ -966,6 +942,9 @@ void Screen::doDeepSleep()
static const int sleepFrameCount = sizeof(sleepFrames) / sizeof(sleepFrames[0]);
ui->setFrames(sleepFrames, sleepFrameCount);
ui->update();
#ifdef PIN_EINK_EN
digitalWrite(PIN_EINK_EN, LOW); // power off backlight
#endif
#endif
setOn(false);
}
@@ -1195,6 +1174,7 @@ int32_t Screen::runOnce()
break;
case Cmd::STOP_BLUETOOTH_PIN_SCREEN:
case Cmd::STOP_BOOT_SCREEN:
EINK_ADD_FRAMEFLAG(dispdev, COSMETIC); // E-Ink: Explicitly use full-refresh for next frame
setFrames();
break;
case Cmd::PRINT:
@@ -1375,6 +1355,7 @@ void Screen::handleStartBluetoothPinScreen(uint32_t pin)
{
LOG_DEBUG("showing bluetooth screen\n");
showingNormalScreen = false;
EINK_ADD_FRAMEFLAG(dispdev, DEMAND_FAST); // E-Ink: Explicitly use fast-refresh for next frame
static FrameCallback frames[] = {drawFrameBluetooth};
snprintf(btPIN, sizeof(btPIN), "%06u", pin);
@@ -1392,6 +1373,7 @@ void Screen::handleShutdownScreen()
{
LOG_DEBUG("showing shutdown screen\n");
showingNormalScreen = false;
EINK_ADD_FRAMEFLAG(dispdev, DEMAND_FAST); // E-Ink: Explicitly use fast-refresh for next frame
auto frame = [](OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) -> void {
drawFrameText(display, state, x, y, "Shutting down...");
@@ -1405,6 +1387,7 @@ void Screen::handleRebootScreen()
{
LOG_DEBUG("showing reboot screen\n");
showingNormalScreen = false;
EINK_ADD_FRAMEFLAG(dispdev, DEMAND_FAST); // E-Ink: Explicitly use fast-refresh for next frame
auto frame = [](OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) -> void {
drawFrameText(display, state, x, y, "Rebooting...");
@@ -1417,6 +1400,7 @@ void Screen::handleStartFirmwareUpdateScreen()
{
LOG_DEBUG("showing firmware screen\n");
showingNormalScreen = false;
EINK_ADD_FRAMEFLAG(dispdev, DEMAND_FAST); // E-Ink: Explicitly use fast-refresh for next frame
static FrameCallback frames[] = {drawFrameFirmware};
setFrameImmediateDraw(frames);
@@ -1529,8 +1513,7 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16
char channelStr[20];
{
concurrency::LockGuard guard(&lock);
auto chName = channels.getPrimaryName();
snprintf(channelStr, sizeof(channelStr), "%s", chName);
snprintf(channelStr, sizeof(channelStr), "#%s", channels.getName(channels.getPrimaryIndex()));
}
// Display power status

View File

@@ -47,6 +47,7 @@ class Screen
#endif
#include "EInkDisplay2.h"
#include "EInkDynamicDisplay.h"
#include "TFTDisplay.h"
#include "TypedQueue.h"
#include "commands.h"

View File

@@ -0,0 +1,35 @@
#pragma once
#ifdef OLED_RU
#include "graphics/fonts/OLEDDisplayFontsRU.h"
#endif
#ifdef OLED_UA
#include "graphics/fonts/OLEDDisplayFontsUA.h"
#endif
#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \
!defined(DISPLAY_FORCE_SMALL_FONTS)
// The screen is bigger so use bigger fonts
#define FONT_SMALL ArialMT_Plain_16 // Height: 19
#define FONT_MEDIUM ArialMT_Plain_24 // Height: 28
#define FONT_LARGE ArialMT_Plain_24 // Height: 28
#else
#ifdef OLED_RU
#define FONT_SMALL ArialMT_Plain_10_RU
#else
#ifdef OLED_UA
#define FONT_SMALL ArialMT_Plain_10_UA
#else
#define FONT_SMALL ArialMT_Plain_10 // Height: 13
#endif
#endif
#define FONT_MEDIUM ArialMT_Plain_16 // Height: 19
#define FONT_LARGE ArialMT_Plain_24 // Height: 28
#endif
#define fontHeight(font) ((font)[1] + 1) // height is position 1
#define FONT_HEIGHT_SMALL fontHeight(FONT_SMALL)
#define FONT_HEIGHT_MEDIUM fontHeight(FONT_MEDIUM)
#define FONT_HEIGHT_LARGE fontHeight(FONT_LARGE)

View File

@@ -68,6 +68,7 @@ NRF52Bluetooth *nrf52Bluetooth;
#ifdef ARCH_PORTDUINO
#include "linux/LinuxHardwareI2C.h"
#include "mesh/raspihttp/PiWebServer.h"
#include "platform/portduino/PortduinoGlue.h"
#include <fstream>
#include <iostream>
@@ -218,10 +219,16 @@ void setup()
initDeepSleep();
// Testing this fix für erratic T-Echo boot behaviour
#if defined(TTGO_T_ECHO) && defined(PIN_EINK_PWR_ON)
pinMode(PIN_EINK_PWR_ON, OUTPUT);
digitalWrite(PIN_EINK_PWR_ON, HIGH);
// power on peripherals
#if defined(TTGO_T_ECHO) && defined(PIN_POWER_EN)
pinMode(PIN_POWER_EN, OUTPUT);
digitalWrite(PIN_POWER_EN, HIGH);
// digitalWrite(PIN_POWER_EN1, INPUT);
#endif
#if defined(LORA_TCXO_GPIO)
pinMode(LORA_TCXO_GPIO, OUTPUT);
digitalWrite(LORA_TCXO_GPIO, HIGH);
#endif
#if defined(VEXT_ENABLE_V03)
@@ -340,7 +347,7 @@ void setup()
pinMode(PIN_3V3_EN, OUTPUT);
digitalWrite(PIN_3V3_EN, HIGH);
#endif
#ifndef USE_EINK
#ifdef AQ_SET_PIN
// RAK-12039 set pin for Air quality sensor
pinMode(AQ_SET_PIN, OUTPUT);
digitalWrite(AQ_SET_PIN, HIGH);
@@ -499,6 +506,7 @@ void setup()
SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::BME_680, meshtastic_TelemetrySensorType_BME680)
SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::BME_280, meshtastic_TelemetrySensorType_BME280)
SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::BMP_280, meshtastic_TelemetrySensorType_BMP280)
SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::BMP_085, meshtastic_TelemetrySensorType_BMP085)
SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::INA260, meshtastic_TelemetrySensorType_INA260)
SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::INA219, meshtastic_TelemetrySensorType_INA219)
SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::INA3221, meshtastic_TelemetrySensorType_INA3221)
@@ -679,6 +687,11 @@ void setup()
digitalWrite(SX126X_ANT_SW, 1);
#endif
#ifdef PIN_PWR_DELAY_MS
// This may be required to give the peripherals time to power up.
delay(PIN_PWR_DELAY_MS);
#endif
#ifdef ARCH_PORTDUINO
if (settingsMap[use_sx1262]) {
if (!rIf) {
@@ -857,6 +870,11 @@ void setup()
#endif
#ifdef ARCH_PORTDUINO
#if __has_include(<ulfius.h>)
if (settingsMap[webserverport] != -1) {
piwebServerThread = new PiWebServerThread();
}
#endif
initApiServer(TCPPort);
#endif
@@ -947,4 +965,4 @@ void loop()
mainDelay.delay(delayMsec);
}
// if (didWake) LOG_DEBUG("wake!\n");
}
}

View File

@@ -2,10 +2,13 @@
#include "CryptoEngine.h"
#include "DisplayFormatters.h"
#include "NodeDB.h"
#include "RadioInterface.h"
#include "configuration.h"
#include <assert.h>
#include "mqtt/MQTT.h"
/// 16 bytes of random PSK for our _public_ default channel that all devices power up on (AES128)
static const uint8_t defaultpsk[] = {0xd4, 0xf1, 0xbb, 0x3a, 0x20, 0x29, 0x07, 0x59,
0xf0, 0xbc, 0xff, 0xab, 0xcf, 0x4e, 0x69, 0x01};
@@ -192,6 +195,10 @@ void Channels::onConfigChanged()
if (ch.role == meshtastic_Channel_Role_PRIMARY)
primaryIndex = i;
}
if (channels.anyMqttEnabled() && mqtt && !mqtt->isEnabled()) {
LOG_DEBUG("MQTT is enabled on at least one channel, so set MQTT thread to run immediately\n");
mqtt->start();
}
}
meshtastic_Channel &Channels::getByIndex(ChannelIndex chIndex)
@@ -236,6 +243,16 @@ void Channels::setChannel(const meshtastic_Channel &c)
old = c; // slam in the new settings/role
}
bool Channels::anyMqttEnabled()
{
for (int i = 0; i < getNumChannels(); i++)
if (channelFile.channels[i].role != meshtastic_Channel_Role_DISABLED && channelFile.channels[i].has_settings &&
(channelFile.channels[i].settings.downlink_enabled || channelFile.channels[i].settings.uplink_enabled))
return true;
return false;
}
const char *Channels::getName(size_t chIndex)
{
// Convert the short "" representation for Default into a usable string
@@ -254,38 +271,23 @@ const char *Channels::getName(size_t chIndex)
return channelName;
}
/**
* Generate a short suffix used to disambiguate channels that might have the same "name" entered by the human but different PSKs.
* The ideas is that the PSK changing should be visible to the user so that they see they probably messed up and that's why they
their nodes
* aren't talking to each other.
*
* This string is of the form "#name-X".
*
* Where X is either:
* (for custom PSKS) a letter from A to Z (base26), and formed by xoring all the bytes of the PSK together,
*
* This function will also need to be implemented in GUI apps that talk to the radio.
*
* https://github.com/meshtastic/firmware/issues/269
*/
const char *Channels::getPrimaryName()
bool Channels::hasDefaultChannel()
{
static char buf[32];
char suffix;
// auto channelSettings = getPrimary();
// if (channelSettings.psk.size != 1) {
// We have a standard PSK, so generate a letter based hash.
uint8_t code = getHash(primaryIndex);
suffix = 'A' + (code % 26);
/* } else {
suffix = '0' + channelSettings.psk.bytes[0];
} */
snprintf(buf, sizeof(buf), "#%s-%c", getName(primaryIndex), suffix);
return buf;
// If we don't use a preset or the default frequency slot, or we override the frequency, we don't have a default channel
if (!config.lora.use_preset || !RadioInterface::uses_default_frequency_slot || config.lora.override_frequency)
return false;
// Check if any of the channels are using the default name and PSK
for (size_t i = 0; i < getNumChannels(); i++) {
const auto &ch = getByIndex(i);
if (ch.settings.psk.size == 1 && ch.settings.psk.bytes[0] == 1) {
const char *name = getName(i);
const char *presetName = DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false);
// Check if the name is the default derived from the modem preset
if (strcmp(name, presetName) == 0)
return true;
}
}
return false;
}
/** Given a channel hash setup crypto for decoding that channel (or the primary channel if that channel is unsecured)

View File

@@ -61,25 +61,6 @@ class Channels
ChannelIndex getNumChannels() { return channelFile.channels_count; }
/**
* Generate a short suffix used to disambiguate channels that might have the same "name" entered by the human but different
PSKs.
* The ideas is that the PSK changing should be visible to the user so that they see they probably messed up and that's why
they their nodes
* aren't talking to each other.
*
* This string is of the form "#name-X".
*
* Where X is either:
* (for custom PSKS) a letter from A to Z (base26), and formed by xoring all the bytes of the PSK together,
* OR (for the standard minimially secure PSKs) a number from 0 to 9.
*
* This function will also need to be implemented in GUI apps that talk to the radio.
*
* https://github.com/meshtastic/firmware/issues/269
*/
const char *getPrimaryName();
/// Called by NodeDB on initial boot when the radio config settings are unset. Set a default single channel config.
void initDefaults();
@@ -102,6 +83,12 @@ class Channels
*/
int16_t setActiveByIndex(ChannelIndex channelIndex);
// Returns true if we can be reached via a channel with the default settings given a region and modem preset
bool hasDefaultChannel();
// Returns true if any of our channels have enabled MQTT uplink or downlink
bool anyMqttEnabled();
private:
/** Given a channel index, change to use the crypto key specified by that index
*

23
src/mesh/Default.cpp Normal file
View File

@@ -0,0 +1,23 @@
#include "Default.h"
uint32_t Default::getConfiguredOrDefaultMs(uint32_t configuredInterval)
{
if (configuredInterval > 0)
return configuredInterval * 1000;
return default_broadcast_interval_secs * 1000;
}
uint32_t Default::getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t defaultInterval)
{
if (configuredInterval > 0)
return configuredInterval * 1000;
return defaultInterval * 1000;
}
uint32_t Default::getConfiguredOrDefault(uint32_t configured, uint32_t defaultValue)
{
if (configured > 0)
return configured;
return defaultValue;
}

30
src/mesh/Default.h Normal file
View File

@@ -0,0 +1,30 @@
#pragma once
#include <NodeDB.h>
#include <cstdint>
#define ONE_DAY 24 * 60 * 60
#define default_gps_update_interval IF_ROUTER(ONE_DAY, 2 * 60)
#define default_broadcast_interval_secs IF_ROUTER(ONE_DAY / 2, 15 * 60)
#define default_wait_bluetooth_secs IF_ROUTER(1, 60)
#define default_sds_secs IF_ROUTER(ONE_DAY, UINT32_MAX) // Default to forever super deep sleep
#define default_ls_secs IF_ROUTER(ONE_DAY, 5 * 60)
#define default_min_wake_secs 10
#define default_screen_on_secs IF_ROUTER(1, 60 * 10)
#define default_node_info_broadcast_secs 3 * 60 * 60
#define min_node_info_broadcast_secs 60 * 60 // No regular broadcasts of more than once an hour
#define default_mqtt_address "mqtt.meshtastic.org"
#define default_mqtt_username "meshdev"
#define default_mqtt_password "large4cats"
#define default_mqtt_root "msh"
#define IF_ROUTER(routerVal, normalVal) \
((config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER) ? (routerVal) : (normalVal))
class Default
{
public:
static uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval);
static uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t defaultInterval);
static uint32_t getConfiguredOrDefault(uint32_t configured, uint32_t defaultValue);
};

View File

@@ -32,7 +32,8 @@ MeshModule::~MeshModule()
assert(0); // FIXME - remove from list of modules once someone needs this feature
}
meshtastic_MeshPacket *MeshModule::allocAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex)
meshtastic_MeshPacket *MeshModule::allocAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex,
uint8_t hopStart, uint8_t hopLimit)
{
meshtastic_Routing c = meshtastic_Routing_init_default;
@@ -49,7 +50,7 @@ meshtastic_MeshPacket *MeshModule::allocAckNak(meshtastic_Routing_Error err, Nod
p->priority = meshtastic_MeshPacket_Priority_ACK;
p->hop_limit = config.lora.hop_limit; // Flood ACK back to original sender
p->hop_limit = routingModule->getHopLimitForResponse(hopStart, hopLimit); // Flood ACK back to original sender
p->to = to;
p->decoded.request_id = idFrom;
p->channel = chIndex;
@@ -176,7 +177,8 @@ void MeshModule::callPlugins(meshtastic_MeshPacket &mp, RxSource src)
// SECURITY NOTE! I considered sending back a different error code if we didn't find the psk (i.e. !isDecoded)
// but opted NOT TO. Because it is not a good idea to let remote nodes 'probe' to find out which PSKs were "good" vs
// bad.
routingModule->sendAckNak(meshtastic_Routing_Error_NO_RESPONSE, getFrom(&mp), mp.id, mp.channel);
routingModule->sendAckNak(meshtastic_Routing_Error_NO_RESPONSE, getFrom(&mp), mp.id, mp.channel, mp.hop_start,
mp.hop_limit);
}
}
@@ -217,6 +219,7 @@ void setReplyTo(meshtastic_MeshPacket *p, const meshtastic_MeshPacket &to)
assert(p->which_payload_variant == meshtastic_MeshPacket_decoded_tag); // Should already be set by now
p->to = getFrom(&to); // Make sure that if we are sending to the local node, we use our local node addr, not 0
p->channel = to.channel; // Use the same channel that the request came in on
p->hop_limit = routingModule->getHopLimitForResponse(to.hop_start, to.hop_limit);
// No need for an ack if we are just delivering locally (it just generates an ignored ack)
p->want_ack = (to.from != 0) ? to.want_ack : false;

View File

@@ -153,7 +153,8 @@ class MeshModule
virtual bool wantUIFrame() { return false; }
virtual Observable<const UIFrameEvent *> *getUIFrameObservable() { return NULL; }
meshtastic_MeshPacket *allocAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex);
meshtastic_MeshPacket *allocAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex,
uint8_t hopStart = 0, uint8_t hopLimit = 0);
/// Send an error response for the specified packet.
meshtastic_MeshPacket *allocErrorResponse(meshtastic_Routing_Error err, const meshtastic_MeshPacket *p);

View File

@@ -3,6 +3,7 @@
#include "../detect/ScanI2C.h"
#include "Channels.h"
#include "CryptoEngine.h"
#include "Default.h"
#include "FSCommon.h"
#include "GPS.h"
#include "MeshRadio.h"
@@ -97,22 +98,6 @@ bool NodeDB::resetRadioConfig(bool factory_reset)
channels.onConfigChanged();
// temp hack for quicker testing
// devicestate.no_save = true;
if (devicestate.no_save) {
LOG_DEBUG("***** DEVELOPMENT MODE - DO NOT RELEASE *****\n");
// Sleep quite frequently to stress test the BLE comms, broadcast position every 6 mins
config.display.screen_on_secs = 10;
config.power.wait_bluetooth_secs = 10;
config.position.position_broadcast_secs = 6 * 60;
config.power.ls_secs = 60;
config.lora.region = meshtastic_Config_LoRaConfig_RegionCode_TW;
// Enter super deep sleep soon and stay there not very long
// radioConfig.preferences.sds_secs = 60;
}
// Update the global myRegion
initRegion();
@@ -130,6 +115,9 @@ bool NodeDB::factoryReset()
LOG_INFO("Performing factory reset!\n");
// first, remove the "/prefs" (this removes most prefs)
rmDir("/prefs");
if (FSCom.exists("/static/rangetest.csv") && !FSCom.remove("/static/rangetest.csv")) {
LOG_WARN("Could not remove rangetest.csv file\n");
}
// second, install default state (this will deal with the duplicate mac address issue)
installDefaultDeviceState();
installDefaultConfig();
@@ -196,7 +184,7 @@ void NodeDB::installDefaultConfig()
config.position.broadcast_smart_minimum_distance = 100;
config.position.broadcast_smart_minimum_interval_secs = 30;
if (config.device.role != meshtastic_Config_DeviceConfig_Role_ROUTER)
config.device.node_info_broadcast_secs = 3 * 60 * 60;
config.device.node_info_broadcast_secs = default_node_info_broadcast_secs;
config.device.serial_enabled = true;
resetRadioConfig();
strncpy(config.network.ntp_server, "0.pool.ntp.org", 32);
@@ -650,61 +638,53 @@ bool NodeDB::saveProto(const char *filename, size_t protoSize, const pb_msgdesc_
void NodeDB::saveChannelsToDisk()
{
if (!devicestate.no_save) {
#ifdef FSCom
FSCom.mkdir("/prefs");
FSCom.mkdir("/prefs");
#endif
saveProto(channelFileName, meshtastic_ChannelFile_size, &meshtastic_ChannelFile_msg, &channelFile);
}
saveProto(channelFileName, meshtastic_ChannelFile_size, &meshtastic_ChannelFile_msg, &channelFile);
}
void NodeDB::saveDeviceStateToDisk()
{
if (!devicestate.no_save) {
#ifdef FSCom
FSCom.mkdir("/prefs");
FSCom.mkdir("/prefs");
#endif
saveProto(prefFileName, meshtastic_DeviceState_size, &meshtastic_DeviceState_msg, &devicestate);
}
saveProto(prefFileName, meshtastic_DeviceState_size, &meshtastic_DeviceState_msg, &devicestate);
}
void NodeDB::saveToDisk(int saveWhat)
{
if (!devicestate.no_save) {
#ifdef FSCom
FSCom.mkdir("/prefs");
FSCom.mkdir("/prefs");
#endif
if (saveWhat & SEGMENT_DEVICESTATE) {
saveDeviceStateToDisk();
}
if (saveWhat & SEGMENT_DEVICESTATE) {
saveDeviceStateToDisk();
}
if (saveWhat & SEGMENT_CONFIG) {
config.has_device = true;
config.has_display = true;
config.has_lora = true;
config.has_position = true;
config.has_power = true;
config.has_network = true;
config.has_bluetooth = true;
saveProto(configFileName, meshtastic_LocalConfig_size, &meshtastic_LocalConfig_msg, &config);
}
if (saveWhat & SEGMENT_CONFIG) {
config.has_device = true;
config.has_display = true;
config.has_lora = true;
config.has_position = true;
config.has_power = true;
config.has_network = true;
config.has_bluetooth = true;
saveProto(configFileName, meshtastic_LocalConfig_size, &meshtastic_LocalConfig_msg, &config);
}
if (saveWhat & SEGMENT_MODULECONFIG) {
moduleConfig.has_canned_message = true;
moduleConfig.has_external_notification = true;
moduleConfig.has_mqtt = true;
moduleConfig.has_range_test = true;
moduleConfig.has_serial = true;
moduleConfig.has_store_forward = true;
moduleConfig.has_telemetry = true;
saveProto(moduleConfigFileName, meshtastic_LocalModuleConfig_size, &meshtastic_LocalModuleConfig_msg, &moduleConfig);
}
if (saveWhat & SEGMENT_MODULECONFIG) {
moduleConfig.has_canned_message = true;
moduleConfig.has_external_notification = true;
moduleConfig.has_mqtt = true;
moduleConfig.has_range_test = true;
moduleConfig.has_serial = true;
moduleConfig.has_store_forward = true;
moduleConfig.has_telemetry = true;
saveProto(moduleConfigFileName, meshtastic_LocalModuleConfig_size, &meshtastic_LocalModuleConfig_msg, &moduleConfig);
}
if (saveWhat & SEGMENT_CHANNELS) {
saveChannelsToDisk();
}
} else {
LOG_DEBUG("***** DEVELOPMENT MODE - DO NOT RELEASE - not saving to flash *****\n");
if (saveWhat & SEGMENT_CHANNELS) {
saveChannelsToDisk();
}
}
@@ -741,14 +721,17 @@ uint32_t sinceReceived(const meshtastic_MeshPacket *p)
#define NUM_ONLINE_SECS (60 * 60 * 2) // 2 hrs to consider someone offline
size_t NodeDB::getNumOnlineMeshNodes()
size_t NodeDB::getNumOnlineMeshNodes(bool localOnly)
{
size_t numseen = 0;
// FIXME this implementation is kinda expensive
for (int i = 0; i < *numMeshNodes; i++)
for (int i = 0; i < *numMeshNodes; i++) {
if (localOnly && meshNodes[i].via_mqtt)
continue;
if (sinceLastSeen(&meshNodes[i]) < NUM_ONLINE_SECS)
numseen++;
}
return numseen;
}
@@ -872,6 +855,12 @@ void NodeDB::updateFrom(const meshtastic_MeshPacket &mp)
if (mp.rx_snr)
info->snr = mp.rx_snr; // keep the most recent SNR we received for this node.
info->via_mqtt = mp.via_mqtt; // Store if we received this packet via MQTT
// If hopStart was set and there wasn't someone messing with the limit in the middle, add hopsAway
if (mp.hop_start != 0 && mp.hop_limit <= mp.hop_start)
info->hops_away = mp.hop_start - mp.hop_limit;
}
}

View File

@@ -108,8 +108,10 @@ class NodeDB
// get channel channel index we heard a nodeNum on, defaults to 0 if not found
uint8_t getMeshNodeChannel(NodeNum n);
/// Return the number of nodes we've heard from recently (within the last 2 hrs?)
size_t getNumOnlineMeshNodes();
/* Return the number of nodes we've heard from recently (within the last 2 hrs?)
* @param localOnly if true, ignore nodes heard via MQTT
*/
size_t getNumOnlineMeshNodes(bool localOnly = false);
void initConfigIntervals(), initModuleConfigIntervals(), resetNodes(), removeNodeByNum(uint nodeNum);
@@ -131,8 +133,13 @@ class NodeDB
meshtastic_NodeInfoLite *getMeshNode(NodeNum n);
size_t getNumMeshNodes() { return *numMeshNodes; }
void setLocalPosition(meshtastic_Position position)
void setLocalPosition(meshtastic_Position position, bool timeOnly = false)
{
if (timeOnly) {
LOG_DEBUG("Setting local position time only: time=%i\n", position.time);
localPosition.time = position.time;
return;
}
LOG_DEBUG("Setting local position: latitude=%i, longitude=%i, time=%i\n", position.latitude_i, position.longitude_i,
position.time);
localPosition = position;
@@ -184,46 +191,6 @@ extern NodeDB nodeDB;
// Our delay functions check for this for times that should never expire
#define NODE_DELAY_FOREVER 0xffffffff
#define IF_ROUTER(routerVal, normalVal) \
((config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER) ? (routerVal) : (normalVal))
#define ONE_DAY 24 * 60 * 60
#define default_gps_update_interval IF_ROUTER(ONE_DAY, 2 * 60)
#define default_broadcast_interval_secs IF_ROUTER(ONE_DAY / 2, 15 * 60)
#define default_wait_bluetooth_secs IF_ROUTER(1, 60)
#define default_sds_secs IF_ROUTER(ONE_DAY, UINT32_MAX) // Default to forever super deep sleep
#define default_ls_secs IF_ROUTER(ONE_DAY, 5 * 60)
#define default_min_wake_secs 10
#define default_screen_on_secs IF_ROUTER(1, 60 * 10)
#define default_mqtt_address "mqtt.meshtastic.org"
#define default_mqtt_username "meshdev"
#define default_mqtt_password "large4cats"
#define default_mqtt_root "msh"
inline uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval)
{
if (configuredInterval > 0)
return configuredInterval * 1000;
return default_broadcast_interval_secs * 1000;
}
inline uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t defaultInterval)
{
if (configuredInterval > 0)
return configuredInterval * 1000;
return defaultInterval * 1000;
}
inline uint32_t getConfiguredOrDefault(uint32_t configured, uint32_t defaultValue)
{
if (configured > 0)
return configured;
return defaultValue;
}
/// Sometimes we will have Position objects that only have a time, so check for
/// valid lat/lon
static inline bool hasValidPosition(const meshtastic_NodeInfoLite *n)
@@ -247,3 +214,5 @@ extern uint32_t error_address;
(ModuleConfig_CannedMessageConfig_size + ModuleConfig_ExternalNotificationConfig_size + ModuleConfig_MQTTConfig_size + \
ModuleConfig_RangeTestConfig_size + ModuleConfig_SerialConfig_size + ModuleConfig_StoreForwardConfig_size + \
ModuleConfig_TelemetryConfig_size + ModuleConfig_size)
// Please do not remove this comment, it makes trunk and compiler happy at the same time.

View File

@@ -1,5 +1,6 @@
#include "PhoneAPI.h"
#include "Channels.h"
#include "Default.h"
#include "GPS.h"
#include "MeshService.h"
#include "NodeDB.h"
@@ -105,10 +106,17 @@ bool PhoneAPI::handleToRadio(const uint8_t *buf, size_t bufLength)
break;
case meshtastic_ToRadio_mqttClientProxyMessage_tag:
LOG_INFO("Got MqttClientProxy message\n");
if (mqtt && moduleConfig.mqtt.proxy_to_client_enabled) {
if (mqtt && moduleConfig.mqtt.proxy_to_client_enabled && moduleConfig.mqtt.enabled &&
(channels.anyMqttEnabled() || moduleConfig.mqtt.map_reporting_enabled)) {
mqtt->onClientProxyReceive(toRadioScratch.mqttClientProxyMessage);
} else {
LOG_WARN("MqttClientProxy received but proxy is not enabled, no channels have up/downlink, or map reporting "
"not enabled\n");
}
break;
case meshtastic_ToRadio_heartbeat_tag:
LOG_DEBUG("Got client heartbeat\n");
break;
default:
// Ignore nop messages
// LOG_DEBUG("Error: unexpected ToRadio variant\n");

View File

@@ -1,5 +1,6 @@
#include "RadioInterface.h"
#include "Channels.h"
#include "DisplayFormatters.h"
#include "MeshRadio.h"
#include "MeshService.h"
#include "NodeDB.h"
@@ -143,6 +144,7 @@ const RegionInfo regions[] = {
};
const RegionInfo *myRegion;
bool RadioInterface::uses_default_frequency_slot = true;
static uint8_t bytes[MAX_RHPACKETLEN];
@@ -302,6 +304,8 @@ void printPacket(const char *prefix, const meshtastic_MeshPacket *p)
out += DEBUG_PORT.mt_sprintf(" rxRSSI=%i", p->rx_rssi);
if (p->via_mqtt != 0)
out += DEBUG_PORT.mt_sprintf(" via MQTT");
if (p->hop_start != 0)
out += DEBUG_PORT.mt_sprintf(" hopStart=%d", p->hop_start);
if (p->priority != 0)
out += DEBUG_PORT.mt_sprintf(" priority=%d", p->priority);
@@ -484,6 +488,10 @@ void RadioInterface::applyModemConfig()
// channel_num is actually (channel_num - 1), since modulus (%) returns values from 0 to (numChannels - 1)
int channel_num = (loraConfig.channel_num ? loraConfig.channel_num - 1 : hash(channelName)) % numChannels;
// Check if we use the default frequency slot
RadioInterface::uses_default_frequency_slot =
channel_num == hash(DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false)) % numChannels;
// Old frequency selection formula
// float freq = myRegion->freqStart + ((((myRegion->freqEnd - myRegion->freqStart) / numChannels) / 2) * channel_num);
@@ -561,6 +569,7 @@ size_t RadioInterface::beginSending(meshtastic_MeshPacket *p)
p->hop_limit = HOP_RELIABLE;
}
h->flags = p->hop_limit | (p->want_ack ? PACKET_FLAGS_WANT_ACK_MASK : 0) | (p->via_mqtt ? PACKET_FLAGS_VIA_MQTT_MASK : 0);
h->flags |= (p->hop_start << PACKET_FLAGS_HOP_START_SHIFT) & PACKET_FLAGS_HOP_START_MASK;
// if the sender nodenum is zero, that means uninitialized
assert(h->from);
@@ -569,4 +578,4 @@ size_t RadioInterface::beginSending(meshtastic_MeshPacket *p)
sendingPacket = p;
return p->encrypted.size + sizeof(PacketHeader);
}
}

View File

@@ -10,9 +10,11 @@
#define MAX_RHPACKETLEN 256
#define PACKET_FLAGS_HOP_MASK 0x07
#define PACKET_FLAGS_HOP_LIMIT_MASK 0x07
#define PACKET_FLAGS_WANT_ACK_MASK 0x08
#define PACKET_FLAGS_VIA_MQTT_MASK 0x10
#define PACKET_FLAGS_HOP_START_MASK 0xE0
#define PACKET_FLAGS_HOP_START_SHIFT 5
/**
* This structure has to exactly match the wire layout when sent over the radio link. Used to keep compatibility
@@ -173,6 +175,9 @@ class RadioInterface
/// Some boards (1st gen Pinetab Lora module) have broken IRQ wires, so we need to poll via i2c registers
virtual bool isIRQPending() { return false; }
// Whether we use the default frequency slot given our LoRa config (region and modem preset)
static bool uses_default_frequency_slot;
protected:
int8_t power = 17; // Set by applyModemConfig()
@@ -224,4 +229,4 @@ class RadioInterface
};
/// Debug printing for packets
void printPacket(const char *prefix, const meshtastic_MeshPacket *p);
void printPacket(const char *prefix, const meshtastic_MeshPacket *p);

View File

@@ -359,8 +359,9 @@ void RadioLibInterface::handleReceiveInterrupt()
mp->to = h->to;
mp->id = h->id;
mp->channel = h->channel;
assert(HOP_MAX <= PACKET_FLAGS_HOP_MASK); // If hopmax changes, carefully check this code
mp->hop_limit = h->flags & PACKET_FLAGS_HOP_MASK;
assert(HOP_MAX <= PACKET_FLAGS_HOP_LIMIT_MASK); // If hopmax changes, carefully check this code
mp->hop_limit = h->flags & PACKET_FLAGS_HOP_LIMIT_MASK;
mp->hop_start = (h->flags & PACKET_FLAGS_HOP_START_MASK) >> PACKET_FLAGS_HOP_START_SHIFT;
mp->want_ack = !!(h->flags & PACKET_FLAGS_WANT_ACK_MASK);
mp->via_mqtt = !!(h->flags & PACKET_FLAGS_VIA_MQTT_MASK);
@@ -407,4 +408,4 @@ void RadioLibInterface::startSend(meshtastic_MeshPacket *txp)
// bits
enableInterrupt(isrTxLevel0);
}
}
}

View File

@@ -71,12 +71,12 @@ bool ReliableRouter::shouldFilterReceived(const meshtastic_MeshPacket *p)
i->second.nextTxMsec += iface->getPacketTime(p);
}
/* Resend implicit ACKs for repeated packets (assuming the original packet was sent with HOP_RELIABLE)
/* Resend implicit ACKs for repeated packets (hopStart equals hopLimit);
* this way if an implicit ACK is dropped and a packet is resent we'll rebroadcast again.
* Resending real ACKs is omitted, as you might receive a packet multiple times due to flooding and
* flooding this ACK back to the original sender already adds redundancy. */
if (wasSeenRecently(p, false) && p->hop_limit == HOP_RELIABLE && !MeshModule::currentReply && p->to != nodeDB.getNodeNum()) {
// retransmission on broadcast has hop_limit still equal to HOP_RELIABLE
bool isRepeated = p->hop_start == 0 ? (p->hop_limit == HOP_RELIABLE) : (p->hop_start == p->hop_limit);
if (wasSeenRecently(p, false) && isRepeated && !MeshModule::currentReply && p->to != nodeDB.getNodeNum()) {
LOG_DEBUG("Resending implicit ack for a repeated floodmsg\n");
meshtastic_MeshPacket *tosend = packetPool.allocCopy(*p);
tosend->hop_limit--; // bump down the hop count
@@ -107,10 +107,11 @@ void ReliableRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtas
if (MeshModule::currentReply) {
LOG_DEBUG("Some other module has replied to this message, no need for a 2nd ack\n");
} else if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) {
sendAckNak(meshtastic_Routing_Error_NONE, getFrom(p), p->id, p->channel);
sendAckNak(meshtastic_Routing_Error_NONE, getFrom(p), p->id, p->channel, p->hop_start, p->hop_limit);
} else {
// Send a 'NO_CHANNEL' error on the primary channel if want_ack packet destined for us cannot be decoded
sendAckNak(meshtastic_Routing_Error_NO_CHANNEL, getFrom(p), p->id, channels.getPrimaryIndex());
sendAckNak(meshtastic_Routing_Error_NO_CHANNEL, getFrom(p), p->id, channels.getPrimaryIndex(), p->hop_start,
p->hop_limit);
}
}
@@ -166,8 +167,6 @@ bool ReliableRouter::stopRetransmission(GlobalPacketId key)
auto old = findPendingPacket(key);
if (old) {
auto p = old->packet;
auto numErased = pending.erase(key);
assert(numErased == 1);
/* Only when we already transmitted a packet via LoRa, we will cancel the packet in the Tx queue
to avoid canceling a transmission if it was ACKed super fast via MQTT */
if (old->numRetransmissions < NUM_RETRANSMISSIONS - 1) {
@@ -176,6 +175,8 @@ bool ReliableRouter::stopRetransmission(GlobalPacketId key)
// now free the pooled copy for retransmission too
packetPool.release(p);
}
auto numErased = pending.erase(key);
assert(numErased == 1);
return true;
} else
return false;
@@ -255,4 +256,4 @@ void ReliableRouter::setNextTx(PendingPacket *pending)
LOG_DEBUG("Setting next retransmission in %u msecs: ", d);
printPacket("", pending->packet);
setReceivedMessage(); // Run ASAP, so we can figure out our correct sleep time
}
}

View File

@@ -132,9 +132,10 @@ meshtastic_MeshPacket *Router::allocForSending()
/**
* Send an ack or a nak packet back towards whoever sent idFrom
*/
void Router::sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex)
void Router::sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex, uint8_t hopStart,
uint8_t hopLimit)
{
routingModule->sendAckNak(err, to, idFrom, chIndex);
routingModule->sendAckNak(err, to, idFrom, chIndex, hopStart, hopLimit);
}
void Router::abortSendAndNak(meshtastic_Routing_Error err, meshtastic_MeshPacket *p)
@@ -240,6 +241,10 @@ ErrorCode Router::send(meshtastic_MeshPacket *p)
// the lora we need to make sure we have replaced it with our local address
p->from = getFrom(p);
// If we are the original transmitter, set the hop limit with which we start
if (p->from == getNodeNum())
p->hop_start = p->hop_limit;
// If the packet hasn't yet been encrypted, do so now (it might already be encrypted if we are just forwarding it)
assert(p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag ||
@@ -292,7 +297,7 @@ bool perhapsDecode(meshtastic_MeshPacket *p)
return false;
if (config.device.rebroadcast_mode == meshtastic_Config_DeviceConfig_RebroadcastMode_KNOWN_ONLY &&
!nodeDB.getMeshNode(p->from)->has_user) {
(nodeDB.getMeshNode(p->from) == NULL || !nodeDB.getMeshNode(p->from)->has_user)) {
LOG_DEBUG("Node 0x%x not in NodeDB. Rebroadcast mode KNOWN_ONLY will ignore packet\n", p->from);
return false;
}
@@ -435,6 +440,7 @@ NodeNum Router::getNodeNum()
*/
void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src)
{
bool skipHandle = false;
// Also, we should set the time from the ISR and it should have msec level resolution
p->rx_time = getValidTime(RTCQualityFromNet); // store the arrival timestamp for the phone
// Store a copy of encrypted packet for MQTT
@@ -451,8 +457,17 @@ void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src)
else
printPacket("handleReceived(REMOTE)", p);
// Neighbor info module is disabled, ignore expensive neighbor info packets
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag &&
p->decoded.portnum == meshtastic_PortNum_NEIGHBORINFO_APP &&
(!moduleConfig.has_neighbor_info || !moduleConfig.neighbor_info.enabled)) {
LOG_DEBUG("Neighbor info module is disabled, ignoring neighbor packet\n");
cancelSending(p->from, p->id);
skipHandle = true;
}
// Publish received message to MQTT if we're not the original transmitter of the packet
if (moduleConfig.mqtt.enabled && getFrom(p) != nodeDB.getNodeNum() && mqtt)
if (!skipHandle && moduleConfig.mqtt.enabled && getFrom(p) != nodeDB.getNodeNum() && mqtt)
mqtt->onSend(*p_encrypted, *p, p->channel);
} else {
printPacket("packet decoding failed or skipped (no PSK?)", p);
@@ -461,7 +476,8 @@ void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src)
packetPool.release(p_encrypted); // Release the encrypted packet
// call modules here
MeshModule::callPlugins(*p, src);
if (!skipHandle)
MeshModule::callPlugins(*p, src);
}
void Router::perhapsHandleReceived(meshtastic_MeshPacket *p)

View File

@@ -104,7 +104,8 @@ class Router : protected concurrency::OSThread
/**
* Send an ack or a nak packet back towards whoever sent idFrom
*/
void sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex);
void sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex, uint8_t hopStart = 0,
uint8_t hopLimit = 0);
private:
/**

View File

@@ -10,6 +10,8 @@ meshtastic_NodeInfo TypeConversions::ConvertToNodeInfo(const meshtastic_NodeInfo
info.snr = lite->snr;
info.last_heard = lite->last_heard;
info.channel = lite->channel;
info.via_mqtt = lite->via_mqtt;
info.hops_away = lite->hops_away;
if (lite->has_position) {
info.has_position = true;

View File

@@ -65,6 +65,10 @@ typedef struct _meshtastic_NodeInfoLite {
meshtastic_DeviceMetrics device_metrics;
/* local channel index we heard that node on. Only populated if its not the default channel. */
uint8_t channel;
/* True if we witnessed the node over MQTT instead of LoRA transport */
bool via_mqtt;
/* Number of hops away from us this node is (0 if adjacent) */
uint8_t hops_away;
} meshtastic_NodeInfoLite;
/* The on-disk saved channels */
@@ -137,7 +141,8 @@ typedef struct _meshtastic_DeviceState {
NodeDB.cpp in the device code. */
uint32_t version;
/* Used only during development.
Indicates developer is testing and changes should never be saved to flash. */
Indicates developer is testing and changes should never be saved to flash.
Deprecated in 2.3.1 */
bool no_save;
/* Some GPS receivers seem to have bogus settings from the factory, so we always do one factory reset. */
bool did_gps_reset;
@@ -175,13 +180,13 @@ extern "C" {
/* Initializer values for message structs */
#define meshtastic_DeviceState_init_default {false, meshtastic_MyNodeInfo_init_default, false, meshtastic_User_init_default, 0, {meshtastic_MeshPacket_init_default}, false, meshtastic_MeshPacket_init_default, 0, 0, 0, false, meshtastic_MeshPacket_init_default, 0, {meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default}, 0, {meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default, meshtastic_NodeInfoLite_init_default}}
#define meshtastic_NodeInfoLite_init_default {0, false, meshtastic_User_init_default, false, meshtastic_PositionLite_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0}
#define meshtastic_NodeInfoLite_init_default {0, false, meshtastic_User_init_default, false, meshtastic_PositionLite_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0, 0, 0}
#define meshtastic_PositionLite_init_default {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN}
#define meshtastic_ChannelFile_init_default {0, {meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default, meshtastic_Channel_init_default}, 0}
#define meshtastic_OEMStore_init_default {0, 0, {0, {0}}, _meshtastic_ScreenFonts_MIN, "", {0, {0}}, false, meshtastic_LocalConfig_init_default, false, meshtastic_LocalModuleConfig_init_default}
#define meshtastic_NodeRemoteHardwarePin_init_default {0, false, meshtastic_RemoteHardwarePin_init_default}
#define meshtastic_DeviceState_init_zero {false, meshtastic_MyNodeInfo_init_zero, false, meshtastic_User_init_zero, 0, {meshtastic_MeshPacket_init_zero}, false, meshtastic_MeshPacket_init_zero, 0, 0, 0, false, meshtastic_MeshPacket_init_zero, 0, {meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero}, 0, {meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero, meshtastic_NodeInfoLite_init_zero}}
#define meshtastic_NodeInfoLite_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_PositionLite_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0}
#define meshtastic_NodeInfoLite_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_PositionLite_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0, 0, 0}
#define meshtastic_PositionLite_init_zero {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN}
#define meshtastic_ChannelFile_init_zero {0, {meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero, meshtastic_Channel_init_zero}, 0}
#define meshtastic_OEMStore_init_zero {0, 0, {0, {0}}, _meshtastic_ScreenFonts_MIN, "", {0, {0}}, false, meshtastic_LocalConfig_init_zero, false, meshtastic_LocalModuleConfig_init_zero}
@@ -200,6 +205,8 @@ extern "C" {
#define meshtastic_NodeInfoLite_last_heard_tag 5
#define meshtastic_NodeInfoLite_device_metrics_tag 6
#define meshtastic_NodeInfoLite_channel_tag 7
#define meshtastic_NodeInfoLite_via_mqtt_tag 8
#define meshtastic_NodeInfoLite_hops_away_tag 9
#define meshtastic_ChannelFile_channels_tag 1
#define meshtastic_ChannelFile_version_tag 2
#define meshtastic_OEMStore_oem_icon_width_tag 1
@@ -252,7 +259,9 @@ X(a, STATIC, OPTIONAL, MESSAGE, position, 3) \
X(a, STATIC, SINGULAR, FLOAT, snr, 4) \
X(a, STATIC, SINGULAR, FIXED32, last_heard, 5) \
X(a, STATIC, OPTIONAL, MESSAGE, device_metrics, 6) \
X(a, STATIC, SINGULAR, UINT32, channel, 7)
X(a, STATIC, SINGULAR, UINT32, channel, 7) \
X(a, STATIC, SINGULAR, BOOL, via_mqtt, 8) \
X(a, STATIC, SINGULAR, UINT32, hops_away, 9)
#define meshtastic_NodeInfoLite_CALLBACK NULL
#define meshtastic_NodeInfoLite_DEFAULT NULL
#define meshtastic_NodeInfoLite_user_MSGTYPE meshtastic_User
@@ -313,10 +322,10 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg;
/* Maximum encoded size of messages (where known) */
#define meshtastic_ChannelFile_size 702
#define meshtastic_DeviceState_size 17062
#define meshtastic_NodeInfoLite_size 153
#define meshtastic_DeviceState_size 17571
#define meshtastic_NodeInfoLite_size 158
#define meshtastic_NodeRemoteHardwarePin_size 29
#define meshtastic_OEMStore_size 3246
#define meshtastic_OEMStore_size 3278
#define meshtastic_PositionLite_size 28
#ifdef __cplusplus

View File

@@ -181,7 +181,7 @@ extern const pb_msgdesc_t meshtastic_LocalModuleConfig_msg;
/* Maximum encoded size of messages (where known) */
#define meshtastic_LocalConfig_size 469
#define meshtastic_LocalModuleConfig_size 631
#define meshtastic_LocalModuleConfig_size 663
#ifdef __cplusplus
} /* extern "C" */

View File

@@ -60,6 +60,9 @@ PB_BIND(meshtastic_Neighbor, meshtastic_Neighbor, AUTO)
PB_BIND(meshtastic_DeviceMetadata, meshtastic_DeviceMetadata, AUTO)
PB_BIND(meshtastic_Heartbeat, meshtastic_Heartbeat, AUTO)

View File

@@ -534,8 +534,7 @@ typedef struct _meshtastic_MeshPacket {
Note: Our crypto implementation uses this field as well.
See [crypto](/docs/overview/encryption) for details. */
uint32_t from;
/* The (immediatSee Priority description for more details.y should be fixed32 instead, this encoding only
hurts the ble link though. */
/* The (immediate) destination for this packet */
uint32_t to;
/* (Usually) If set, this indicates the index in the secondary_channels table that this packet was sent/received on.
If unset, packet was on the primary channel.
@@ -594,6 +593,9 @@ typedef struct _meshtastic_MeshPacket {
meshtastic_MeshPacket_Delayed delayed;
/* Describes whether this packet passed via MQTT somewhere along the path it currently took. */
bool via_mqtt;
/* Hop limit with which the original packet started. Sent via LoRa using three bits in the unencrypted header.
When receiving a packet, the difference between hop_start and hop_limit gives how many hops it traveled. */
uint8_t hop_start;
} meshtastic_MeshPacket;
/* The bluetooth to device link:
@@ -632,6 +634,10 @@ typedef struct _meshtastic_NodeInfo {
meshtastic_DeviceMetrics device_metrics;
/* local channel index we heard that node on. Only populated if its not the default channel. */
uint8_t channel;
/* True if we witnessed the node over MQTT instead of LoRA transport */
bool via_mqtt;
/* Number of hops away from us this node is (0 if adjacent) */
uint8_t hops_away;
} meshtastic_NodeInfo;
/* Unique local debugging info for this node
@@ -676,32 +682,6 @@ typedef struct _meshtastic_QueueStatus {
uint32_t mesh_packet_id;
} meshtastic_QueueStatus;
/* Packets/commands to the radio will be written (reliably) to the toRadio characteristic.
Once the write completes the phone can assume it is handled. */
typedef struct _meshtastic_ToRadio {
pb_size_t which_payload_variant;
union {
/* Send this packet on the mesh */
meshtastic_MeshPacket packet;
/* Phone wants radio to send full node db to the phone, This is
typically the first packet sent to the radio when the phone gets a
bluetooth connection. The radio will respond by sending back a
MyNodeInfo, a owner, a radio config and a series of
FromRadio.node_infos, and config_complete
the integer you write into this field will be reported back in the
config_complete_id response this allows clients to never be confused by
a stale old partially sent config. */
uint32_t want_config_id;
/* Tell API server we are disconnecting now.
This is useful for serial links where there is no hardware/protocol based notification that the client has dropped the link.
(Sending this message is optional for clients) */
bool disconnect;
meshtastic_XModem xmodemPacket;
/* MQTT Client Proxy Message (for client / phone subscribed to MQTT sending to device) */
meshtastic_MqttClientProxyMessage mqttClientProxyMessage;
};
} meshtastic_ToRadio;
typedef PB_BYTES_ARRAY_T(237) meshtastic_Compressed_data_t;
/* Compressed message payload */
typedef struct _meshtastic_Compressed {
@@ -809,6 +789,40 @@ typedef struct _meshtastic_FromRadio {
};
} meshtastic_FromRadio;
/* A heartbeat message is sent to the node from the client to keep the connection alive.
This is currently only needed to keep serial connections alive, but can be used by any PhoneAPI. */
typedef struct _meshtastic_Heartbeat {
char dummy_field;
} meshtastic_Heartbeat;
/* Packets/commands to the radio will be written (reliably) to the toRadio characteristic.
Once the write completes the phone can assume it is handled. */
typedef struct _meshtastic_ToRadio {
pb_size_t which_payload_variant;
union {
/* Send this packet on the mesh */
meshtastic_MeshPacket packet;
/* Phone wants radio to send full node db to the phone, This is
typically the first packet sent to the radio when the phone gets a
bluetooth connection. The radio will respond by sending back a
MyNodeInfo, a owner, a radio config and a series of
FromRadio.node_infos, and config_complete
the integer you write into this field will be reported back in the
config_complete_id response this allows clients to never be confused by
a stale old partially sent config. */
uint32_t want_config_id;
/* Tell API server we are disconnecting now.
This is useful for serial links where there is no hardware/protocol based notification that the client has dropped the link.
(Sending this message is optional for clients) */
bool disconnect;
meshtastic_XModem xmodemPacket;
/* MQTT Client Proxy Message (for client / phone subscribed to MQTT sending to device) */
meshtastic_MqttClientProxyMessage mqttClientProxyMessage;
/* Heartbeat message (used to keep the device connection awake on serial) */
meshtastic_Heartbeat heartbeat;
};
} meshtastic_ToRadio;
#ifdef __cplusplus
extern "C" {
@@ -882,6 +896,7 @@ extern "C" {
#define meshtastic_DeviceMetadata_hw_model_ENUMTYPE meshtastic_HardwareModel
/* Initializer values for message structs */
#define meshtastic_Position_init_default {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN, _meshtastic_Position_AltSource_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define meshtastic_User_init_default {"", "", "", {0}, _meshtastic_HardwareModel_MIN, 0, _meshtastic_Config_DeviceConfig_Role_MIN}
@@ -890,8 +905,8 @@ extern "C" {
#define meshtastic_Data_init_default {_meshtastic_PortNum_MIN, {0, {0}}, 0, 0, 0, 0, 0, 0}
#define meshtastic_Waypoint_init_default {0, 0, 0, 0, 0, "", "", 0}
#define meshtastic_MqttClientProxyMessage_init_default {"", 0, {{0, {0}}}, 0}
#define meshtastic_MeshPacket_init_default {0, 0, 0, 0, {meshtastic_Data_init_default}, 0, 0, 0, 0, 0, _meshtastic_MeshPacket_Priority_MIN, 0, _meshtastic_MeshPacket_Delayed_MIN, 0}
#define meshtastic_NodeInfo_init_default {0, false, meshtastic_User_init_default, false, meshtastic_Position_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0}
#define meshtastic_MeshPacket_init_default {0, 0, 0, 0, {meshtastic_Data_init_default}, 0, 0, 0, 0, 0, _meshtastic_MeshPacket_Priority_MIN, 0, _meshtastic_MeshPacket_Delayed_MIN, 0, 0}
#define meshtastic_NodeInfo_init_default {0, false, meshtastic_User_init_default, false, meshtastic_Position_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0, 0, 0}
#define meshtastic_MyNodeInfo_init_default {0, 0, 0}
#define meshtastic_LogRecord_init_default {"", 0, "", _meshtastic_LogRecord_Level_MIN}
#define meshtastic_QueueStatus_init_default {0, 0, 0, 0}
@@ -901,6 +916,7 @@ extern "C" {
#define meshtastic_NeighborInfo_init_default {0, 0, 0, 0, {meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default}}
#define meshtastic_Neighbor_init_default {0, 0, 0, 0}
#define meshtastic_DeviceMetadata_init_default {"", 0, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_Role_MIN, 0, _meshtastic_HardwareModel_MIN, 0}
#define meshtastic_Heartbeat_init_default {0}
#define meshtastic_Position_init_zero {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN, _meshtastic_Position_AltSource_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define meshtastic_User_init_zero {"", "", "", {0}, _meshtastic_HardwareModel_MIN, 0, _meshtastic_Config_DeviceConfig_Role_MIN}
#define meshtastic_RouteDiscovery_init_zero {0, {0, 0, 0, 0, 0, 0, 0, 0}}
@@ -908,8 +924,8 @@ extern "C" {
#define meshtastic_Data_init_zero {_meshtastic_PortNum_MIN, {0, {0}}, 0, 0, 0, 0, 0, 0}
#define meshtastic_Waypoint_init_zero {0, 0, 0, 0, 0, "", "", 0}
#define meshtastic_MqttClientProxyMessage_init_zero {"", 0, {{0, {0}}}, 0}
#define meshtastic_MeshPacket_init_zero {0, 0, 0, 0, {meshtastic_Data_init_zero}, 0, 0, 0, 0, 0, _meshtastic_MeshPacket_Priority_MIN, 0, _meshtastic_MeshPacket_Delayed_MIN, 0}
#define meshtastic_NodeInfo_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_Position_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0}
#define meshtastic_MeshPacket_init_zero {0, 0, 0, 0, {meshtastic_Data_init_zero}, 0, 0, 0, 0, 0, _meshtastic_MeshPacket_Priority_MIN, 0, _meshtastic_MeshPacket_Delayed_MIN, 0, 0}
#define meshtastic_NodeInfo_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_Position_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0, 0, 0}
#define meshtastic_MyNodeInfo_init_zero {0, 0, 0}
#define meshtastic_LogRecord_init_zero {"", 0, "", _meshtastic_LogRecord_Level_MIN}
#define meshtastic_QueueStatus_init_zero {0, 0, 0, 0}
@@ -919,6 +935,7 @@ extern "C" {
#define meshtastic_NeighborInfo_init_zero {0, 0, 0, 0, {meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero}}
#define meshtastic_Neighbor_init_zero {0, 0, 0, 0}
#define meshtastic_DeviceMetadata_init_zero {"", 0, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_Role_MIN, 0, _meshtastic_HardwareModel_MIN, 0}
#define meshtastic_Heartbeat_init_zero {0}
/* Field tags (for use in manual encoding/decoding) */
#define meshtastic_Position_latitude_i_tag 1
@@ -989,6 +1006,7 @@ extern "C" {
#define meshtastic_MeshPacket_rx_rssi_tag 12
#define meshtastic_MeshPacket_delayed_tag 13
#define meshtastic_MeshPacket_via_mqtt_tag 14
#define meshtastic_MeshPacket_hop_start_tag 15
#define meshtastic_NodeInfo_num_tag 1
#define meshtastic_NodeInfo_user_tag 2
#define meshtastic_NodeInfo_position_tag 3
@@ -996,6 +1014,8 @@ extern "C" {
#define meshtastic_NodeInfo_last_heard_tag 5
#define meshtastic_NodeInfo_device_metrics_tag 6
#define meshtastic_NodeInfo_channel_tag 7
#define meshtastic_NodeInfo_via_mqtt_tag 8
#define meshtastic_NodeInfo_hops_away_tag 9
#define meshtastic_MyNodeInfo_my_node_num_tag 1
#define meshtastic_MyNodeInfo_reboot_count_tag 8
#define meshtastic_MyNodeInfo_min_app_version_tag 11
@@ -1007,11 +1027,6 @@ extern "C" {
#define meshtastic_QueueStatus_free_tag 2
#define meshtastic_QueueStatus_maxlen_tag 3
#define meshtastic_QueueStatus_mesh_packet_id_tag 4
#define meshtastic_ToRadio_packet_tag 1
#define meshtastic_ToRadio_want_config_id_tag 3
#define meshtastic_ToRadio_disconnect_tag 4
#define meshtastic_ToRadio_xmodemPacket_tag 5
#define meshtastic_ToRadio_mqttClientProxyMessage_tag 6
#define meshtastic_Compressed_portnum_tag 1
#define meshtastic_Compressed_data_tag 2
#define meshtastic_Neighbor_node_id_tag 1
@@ -1046,6 +1061,12 @@ extern "C" {
#define meshtastic_FromRadio_xmodemPacket_tag 12
#define meshtastic_FromRadio_metadata_tag 13
#define meshtastic_FromRadio_mqttClientProxyMessage_tag 14
#define meshtastic_ToRadio_packet_tag 1
#define meshtastic_ToRadio_want_config_id_tag 3
#define meshtastic_ToRadio_disconnect_tag 4
#define meshtastic_ToRadio_xmodemPacket_tag 5
#define meshtastic_ToRadio_mqttClientProxyMessage_tag 6
#define meshtastic_ToRadio_heartbeat_tag 7
/* Struct field encoding specification for nanopb */
#define meshtastic_Position_FIELDLIST(X, a) \
@@ -1146,7 +1167,8 @@ X(a, STATIC, SINGULAR, BOOL, want_ack, 10) \
X(a, STATIC, SINGULAR, UENUM, priority, 11) \
X(a, STATIC, SINGULAR, INT32, rx_rssi, 12) \
X(a, STATIC, SINGULAR, UENUM, delayed, 13) \
X(a, STATIC, SINGULAR, BOOL, via_mqtt, 14)
X(a, STATIC, SINGULAR, BOOL, via_mqtt, 14) \
X(a, STATIC, SINGULAR, UINT32, hop_start, 15)
#define meshtastic_MeshPacket_CALLBACK NULL
#define meshtastic_MeshPacket_DEFAULT NULL
#define meshtastic_MeshPacket_payload_variant_decoded_MSGTYPE meshtastic_Data
@@ -1158,7 +1180,9 @@ X(a, STATIC, OPTIONAL, MESSAGE, position, 3) \
X(a, STATIC, SINGULAR, FLOAT, snr, 4) \
X(a, STATIC, SINGULAR, FIXED32, last_heard, 5) \
X(a, STATIC, OPTIONAL, MESSAGE, device_metrics, 6) \
X(a, STATIC, SINGULAR, UINT32, channel, 7)
X(a, STATIC, SINGULAR, UINT32, channel, 7) \
X(a, STATIC, SINGULAR, BOOL, via_mqtt, 8) \
X(a, STATIC, SINGULAR, UINT32, hops_away, 9)
#define meshtastic_NodeInfo_CALLBACK NULL
#define meshtastic_NodeInfo_DEFAULT NULL
#define meshtastic_NodeInfo_user_MSGTYPE meshtastic_User
@@ -1222,12 +1246,14 @@ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,packet,packet), 1) \
X(a, STATIC, ONEOF, UINT32, (payload_variant,want_config_id,want_config_id), 3) \
X(a, STATIC, ONEOF, BOOL, (payload_variant,disconnect,disconnect), 4) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,xmodemPacket,xmodemPacket), 5) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,mqttClientProxyMessage,mqttClientProxyMessage), 6)
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,mqttClientProxyMessage,mqttClientProxyMessage), 6) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,heartbeat,heartbeat), 7)
#define meshtastic_ToRadio_CALLBACK NULL
#define meshtastic_ToRadio_DEFAULT NULL
#define meshtastic_ToRadio_payload_variant_packet_MSGTYPE meshtastic_MeshPacket
#define meshtastic_ToRadio_payload_variant_xmodemPacket_MSGTYPE meshtastic_XModem
#define meshtastic_ToRadio_payload_variant_mqttClientProxyMessage_MSGTYPE meshtastic_MqttClientProxyMessage
#define meshtastic_ToRadio_payload_variant_heartbeat_MSGTYPE meshtastic_Heartbeat
#define meshtastic_Compressed_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UENUM, portnum, 1) \
@@ -1266,6 +1292,11 @@ X(a, STATIC, SINGULAR, BOOL, hasRemoteHardware, 10)
#define meshtastic_DeviceMetadata_CALLBACK NULL
#define meshtastic_DeviceMetadata_DEFAULT NULL
#define meshtastic_Heartbeat_FIELDLIST(X, a) \
#define meshtastic_Heartbeat_CALLBACK NULL
#define meshtastic_Heartbeat_DEFAULT NULL
extern const pb_msgdesc_t meshtastic_Position_msg;
extern const pb_msgdesc_t meshtastic_User_msg;
extern const pb_msgdesc_t meshtastic_RouteDiscovery_msg;
@@ -1284,6 +1315,7 @@ extern const pb_msgdesc_t meshtastic_Compressed_msg;
extern const pb_msgdesc_t meshtastic_NeighborInfo_msg;
extern const pb_msgdesc_t meshtastic_Neighbor_msg;
extern const pb_msgdesc_t meshtastic_DeviceMetadata_msg;
extern const pb_msgdesc_t meshtastic_Heartbeat_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define meshtastic_Position_fields &meshtastic_Position_msg
@@ -1304,19 +1336,21 @@ extern const pb_msgdesc_t meshtastic_DeviceMetadata_msg;
#define meshtastic_NeighborInfo_fields &meshtastic_NeighborInfo_msg
#define meshtastic_Neighbor_fields &meshtastic_Neighbor_msg
#define meshtastic_DeviceMetadata_fields &meshtastic_DeviceMetadata_msg
#define meshtastic_Heartbeat_fields &meshtastic_Heartbeat_msg
/* Maximum encoded size of messages (where known) */
#define meshtastic_Compressed_size 243
#define meshtastic_Data_size 270
#define meshtastic_DeviceMetadata_size 46
#define meshtastic_FromRadio_size 510
#define meshtastic_Heartbeat_size 0
#define meshtastic_LogRecord_size 81
#define meshtastic_MeshPacket_size 323
#define meshtastic_MeshPacket_size 326
#define meshtastic_MqttClientProxyMessage_size 501
#define meshtastic_MyNodeInfo_size 18
#define meshtastic_NeighborInfo_size 258
#define meshtastic_Neighbor_size 22
#define meshtastic_NodeInfo_size 270
#define meshtastic_NodeInfo_size 275
#define meshtastic_Position_size 144
#define meshtastic_QueueStatus_size 23
#define meshtastic_RouteDiscovery_size 40

View File

@@ -6,10 +6,13 @@
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(meshtastic_ModuleConfig, meshtastic_ModuleConfig, AUTO)
PB_BIND(meshtastic_ModuleConfig, meshtastic_ModuleConfig, 2)
PB_BIND(meshtastic_ModuleConfig_MQTTConfig, meshtastic_ModuleConfig_MQTTConfig, AUTO)
PB_BIND(meshtastic_ModuleConfig_MQTTConfig, meshtastic_ModuleConfig_MQTTConfig, 2)
PB_BIND(meshtastic_ModuleConfig_MapReportSettings, meshtastic_ModuleConfig_MapReportSettings, AUTO)
PB_BIND(meshtastic_ModuleConfig_RemoteHardwareConfig, meshtastic_ModuleConfig_RemoteHardwareConfig, AUTO)

View File

@@ -84,6 +84,14 @@ typedef enum _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar {
} meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar;
/* Struct definitions */
/* Settings for reporting unencrypted information about our node to a map via MQTT */
typedef struct _meshtastic_ModuleConfig_MapReportSettings {
/* How often we should report our info to the map (in seconds) */
uint32_t publish_interval_secs;
/* Bits of precision for the location sent (default of 32 is full precision). */
uint32_t position_precision;
} meshtastic_ModuleConfig_MapReportSettings;
/* MQTT Client Config */
typedef struct _meshtastic_ModuleConfig_MQTTConfig {
/* If a meshtastic node is able to reach the internet it will normally attempt to gateway any channels that are marked as
@@ -111,9 +119,14 @@ typedef struct _meshtastic_ModuleConfig_MQTTConfig {
bool tls_enabled;
/* The root topic to use for MQTT messages. Default is "msh".
This is useful if you want to use a single MQTT server for multiple meshtastic networks and separate them via ACLs */
char root[16];
char root[32];
/* If true, we can use the connected phone / client to proxy messages to MQTT instead of a direct connection */
bool proxy_to_client_enabled;
/* If true, we will periodically report unencrypted information about our node to a map via MQTT */
bool map_reporting_enabled;
/* Settings for reporting information about our node to a map via MQTT */
bool has_map_report_settings;
meshtastic_ModuleConfig_MapReportSettings map_report_settings;
} meshtastic_ModuleConfig_MQTTConfig;
/* NeighborInfoModule Config */
@@ -427,6 +440,7 @@ extern "C" {
#define meshtastic_ModuleConfig_AudioConfig_bitrate_ENUMTYPE meshtastic_ModuleConfig_AudioConfig_Audio_Baud
@@ -447,7 +461,8 @@ extern "C" {
/* Initializer values for message structs */
#define meshtastic_ModuleConfig_init_default {0, {meshtastic_ModuleConfig_MQTTConfig_init_default}}
#define meshtastic_ModuleConfig_MQTTConfig_init_default {0, "", "", "", 0, 0, 0, "", 0}
#define meshtastic_ModuleConfig_MQTTConfig_init_default {0, "", "", "", 0, 0, 0, "", 0, 0, false, meshtastic_ModuleConfig_MapReportSettings_init_default}
#define meshtastic_ModuleConfig_MapReportSettings_init_default {0, 0}
#define meshtastic_ModuleConfig_RemoteHardwareConfig_init_default {0, 0, 0, {meshtastic_RemoteHardwarePin_init_default, meshtastic_RemoteHardwarePin_init_default, meshtastic_RemoteHardwarePin_init_default, meshtastic_RemoteHardwarePin_init_default}}
#define meshtastic_ModuleConfig_NeighborInfoConfig_init_default {0, 0}
#define meshtastic_ModuleConfig_DetectionSensorConfig_init_default {0, 0, 0, 0, "", 0, 0, 0}
@@ -462,7 +477,8 @@ extern "C" {
#define meshtastic_ModuleConfig_AmbientLightingConfig_init_default {0, 0, 0, 0, 0}
#define meshtastic_RemoteHardwarePin_init_default {0, "", _meshtastic_RemoteHardwarePinType_MIN}
#define meshtastic_ModuleConfig_init_zero {0, {meshtastic_ModuleConfig_MQTTConfig_init_zero}}
#define meshtastic_ModuleConfig_MQTTConfig_init_zero {0, "", "", "", 0, 0, 0, "", 0}
#define meshtastic_ModuleConfig_MQTTConfig_init_zero {0, "", "", "", 0, 0, 0, "", 0, 0, false, meshtastic_ModuleConfig_MapReportSettings_init_zero}
#define meshtastic_ModuleConfig_MapReportSettings_init_zero {0, 0}
#define meshtastic_ModuleConfig_RemoteHardwareConfig_init_zero {0, 0, 0, {meshtastic_RemoteHardwarePin_init_zero, meshtastic_RemoteHardwarePin_init_zero, meshtastic_RemoteHardwarePin_init_zero, meshtastic_RemoteHardwarePin_init_zero}}
#define meshtastic_ModuleConfig_NeighborInfoConfig_init_zero {0, 0}
#define meshtastic_ModuleConfig_DetectionSensorConfig_init_zero {0, 0, 0, 0, "", 0, 0, 0}
@@ -478,6 +494,8 @@ extern "C" {
#define meshtastic_RemoteHardwarePin_init_zero {0, "", _meshtastic_RemoteHardwarePinType_MIN}
/* Field tags (for use in manual encoding/decoding) */
#define meshtastic_ModuleConfig_MapReportSettings_publish_interval_secs_tag 1
#define meshtastic_ModuleConfig_MapReportSettings_position_precision_tag 2
#define meshtastic_ModuleConfig_MQTTConfig_enabled_tag 1
#define meshtastic_ModuleConfig_MQTTConfig_address_tag 2
#define meshtastic_ModuleConfig_MQTTConfig_username_tag 3
@@ -487,6 +505,8 @@ extern "C" {
#define meshtastic_ModuleConfig_MQTTConfig_tls_enabled_tag 7
#define meshtastic_ModuleConfig_MQTTConfig_root_tag 8
#define meshtastic_ModuleConfig_MQTTConfig_proxy_to_client_enabled_tag 9
#define meshtastic_ModuleConfig_MQTTConfig_map_reporting_enabled_tag 10
#define meshtastic_ModuleConfig_MQTTConfig_map_report_settings_tag 11
#define meshtastic_ModuleConfig_NeighborInfoConfig_enabled_tag 1
#define meshtastic_ModuleConfig_NeighborInfoConfig_update_interval_tag 2
#define meshtastic_ModuleConfig_DetectionSensorConfig_enabled_tag 1
@@ -623,9 +643,18 @@ X(a, STATIC, SINGULAR, BOOL, encryption_enabled, 5) \
X(a, STATIC, SINGULAR, BOOL, json_enabled, 6) \
X(a, STATIC, SINGULAR, BOOL, tls_enabled, 7) \
X(a, STATIC, SINGULAR, STRING, root, 8) \
X(a, STATIC, SINGULAR, BOOL, proxy_to_client_enabled, 9)
X(a, STATIC, SINGULAR, BOOL, proxy_to_client_enabled, 9) \
X(a, STATIC, SINGULAR, BOOL, map_reporting_enabled, 10) \
X(a, STATIC, OPTIONAL, MESSAGE, map_report_settings, 11)
#define meshtastic_ModuleConfig_MQTTConfig_CALLBACK NULL
#define meshtastic_ModuleConfig_MQTTConfig_DEFAULT NULL
#define meshtastic_ModuleConfig_MQTTConfig_map_report_settings_MSGTYPE meshtastic_ModuleConfig_MapReportSettings
#define meshtastic_ModuleConfig_MapReportSettings_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UINT32, publish_interval_secs, 1) \
X(a, STATIC, SINGULAR, UINT32, position_precision, 2)
#define meshtastic_ModuleConfig_MapReportSettings_CALLBACK NULL
#define meshtastic_ModuleConfig_MapReportSettings_DEFAULT NULL
#define meshtastic_ModuleConfig_RemoteHardwareConfig_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, BOOL, enabled, 1) \
@@ -764,6 +793,7 @@ X(a, STATIC, SINGULAR, UENUM, type, 3)
extern const pb_msgdesc_t meshtastic_ModuleConfig_msg;
extern const pb_msgdesc_t meshtastic_ModuleConfig_MQTTConfig_msg;
extern const pb_msgdesc_t meshtastic_ModuleConfig_MapReportSettings_msg;
extern const pb_msgdesc_t meshtastic_ModuleConfig_RemoteHardwareConfig_msg;
extern const pb_msgdesc_t meshtastic_ModuleConfig_NeighborInfoConfig_msg;
extern const pb_msgdesc_t meshtastic_ModuleConfig_DetectionSensorConfig_msg;
@@ -781,6 +811,7 @@ extern const pb_msgdesc_t meshtastic_RemoteHardwarePin_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define meshtastic_ModuleConfig_fields &meshtastic_ModuleConfig_msg
#define meshtastic_ModuleConfig_MQTTConfig_fields &meshtastic_ModuleConfig_MQTTConfig_msg
#define meshtastic_ModuleConfig_MapReportSettings_fields &meshtastic_ModuleConfig_MapReportSettings_msg
#define meshtastic_ModuleConfig_RemoteHardwareConfig_fields &meshtastic_ModuleConfig_RemoteHardwareConfig_msg
#define meshtastic_ModuleConfig_NeighborInfoConfig_fields &meshtastic_ModuleConfig_NeighborInfoConfig_msg
#define meshtastic_ModuleConfig_DetectionSensorConfig_fields &meshtastic_ModuleConfig_DetectionSensorConfig_msg
@@ -801,7 +832,8 @@ extern const pb_msgdesc_t meshtastic_RemoteHardwarePin_msg;
#define meshtastic_ModuleConfig_CannedMessageConfig_size 49
#define meshtastic_ModuleConfig_DetectionSensorConfig_size 44
#define meshtastic_ModuleConfig_ExternalNotificationConfig_size 42
#define meshtastic_ModuleConfig_MQTTConfig_size 222
#define meshtastic_ModuleConfig_MQTTConfig_size 254
#define meshtastic_ModuleConfig_MapReportSettings_size 12
#define meshtastic_ModuleConfig_NeighborInfoConfig_size 8
#define meshtastic_ModuleConfig_PaxcounterConfig_size 8
#define meshtastic_ModuleConfig_RangeTestConfig_size 10
@@ -809,7 +841,7 @@ extern const pb_msgdesc_t meshtastic_RemoteHardwarePin_msg;
#define meshtastic_ModuleConfig_SerialConfig_size 28
#define meshtastic_ModuleConfig_StoreForwardConfig_size 22
#define meshtastic_ModuleConfig_TelemetryConfig_size 36
#define meshtastic_ModuleConfig_size 225
#define meshtastic_ModuleConfig_size 257
#define meshtastic_RemoteHardwarePin_size 21
#ifdef __cplusplus

View File

@@ -9,4 +9,7 @@
PB_BIND(meshtastic_ServiceEnvelope, meshtastic_ServiceEnvelope, AUTO)
PB_BIND(meshtastic_MapReport, meshtastic_MapReport, AUTO)

View File

@@ -5,6 +5,7 @@
#define PB_MESHTASTIC_MESHTASTIC_MQTT_PB_H_INCLUDED
#include <pb.h>
#include "meshtastic/mesh.pb.h"
#include "meshtastic/config.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
@@ -23,6 +24,38 @@ typedef struct _meshtastic_ServiceEnvelope {
char *gateway_id;
} meshtastic_ServiceEnvelope;
/* Information about a node intended to be reported unencrypted to a map using MQTT. */
typedef struct _meshtastic_MapReport {
/* A full name for this user, i.e. "Kevin Hester" */
char long_name[40];
/* A VERY short name, ideally two characters.
Suitable for a tiny OLED screen */
char short_name[5];
/* Role of the node that applies specific settings for a particular use-case */
meshtastic_Config_DeviceConfig_Role role;
/* Hardware model of the node, i.e. T-Beam, Heltec V3, etc... */
meshtastic_HardwareModel hw_model;
/* Device firmware version string */
char firmware_version[18];
/* The region code for the radio (US, CN, EU433, etc...) */
meshtastic_Config_LoRaConfig_RegionCode region;
/* Modem preset used by the radio (LongFast, MediumSlow, etc...) */
meshtastic_Config_LoRaConfig_ModemPreset modem_preset;
/* Whether the node has a channel with default PSK and name (LongFast, MediumSlow, etc...)
and it uses the default frequency slot given the region and modem preset. */
bool has_default_channel;
/* Latitude: multiply by 1e-7 to get degrees in floating point */
int32_t latitude_i;
/* Longitude: multiply by 1e-7 to get degrees in floating point */
int32_t longitude_i;
/* Altitude in meters above MSL */
int32_t altitude;
/* Indicates the bits of precision for latitude and longitude set by the sending node */
uint32_t position_precision;
/* Number of online nodes (heard in the last 2 hours) this node has in its list that were received locally (not via MQTT) */
uint16_t num_online_local_nodes;
} meshtastic_MapReport;
#ifdef __cplusplus
extern "C" {
@@ -30,12 +63,27 @@ extern "C" {
/* Initializer values for message structs */
#define meshtastic_ServiceEnvelope_init_default {NULL, NULL, NULL}
#define meshtastic_MapReport_init_default {"", "", _meshtastic_Config_DeviceConfig_Role_MIN, _meshtastic_HardwareModel_MIN, "", _meshtastic_Config_LoRaConfig_RegionCode_MIN, _meshtastic_Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, 0, 0}
#define meshtastic_ServiceEnvelope_init_zero {NULL, NULL, NULL}
#define meshtastic_MapReport_init_zero {"", "", _meshtastic_Config_DeviceConfig_Role_MIN, _meshtastic_HardwareModel_MIN, "", _meshtastic_Config_LoRaConfig_RegionCode_MIN, _meshtastic_Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, 0, 0}
/* Field tags (for use in manual encoding/decoding) */
#define meshtastic_ServiceEnvelope_packet_tag 1
#define meshtastic_ServiceEnvelope_channel_id_tag 2
#define meshtastic_ServiceEnvelope_gateway_id_tag 3
#define meshtastic_MapReport_long_name_tag 1
#define meshtastic_MapReport_short_name_tag 2
#define meshtastic_MapReport_role_tag 3
#define meshtastic_MapReport_hw_model_tag 4
#define meshtastic_MapReport_firmware_version_tag 5
#define meshtastic_MapReport_region_tag 6
#define meshtastic_MapReport_modem_preset_tag 7
#define meshtastic_MapReport_has_default_channel_tag 8
#define meshtastic_MapReport_latitude_i_tag 9
#define meshtastic_MapReport_longitude_i_tag 10
#define meshtastic_MapReport_altitude_tag 11
#define meshtastic_MapReport_position_precision_tag 12
#define meshtastic_MapReport_num_online_local_nodes_tag 13
/* Struct field encoding specification for nanopb */
#define meshtastic_ServiceEnvelope_FIELDLIST(X, a) \
@@ -46,13 +94,33 @@ X(a, POINTER, SINGULAR, STRING, gateway_id, 3)
#define meshtastic_ServiceEnvelope_DEFAULT NULL
#define meshtastic_ServiceEnvelope_packet_MSGTYPE meshtastic_MeshPacket
#define meshtastic_MapReport_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, STRING, long_name, 1) \
X(a, STATIC, SINGULAR, STRING, short_name, 2) \
X(a, STATIC, SINGULAR, UENUM, role, 3) \
X(a, STATIC, SINGULAR, UENUM, hw_model, 4) \
X(a, STATIC, SINGULAR, STRING, firmware_version, 5) \
X(a, STATIC, SINGULAR, UENUM, region, 6) \
X(a, STATIC, SINGULAR, UENUM, modem_preset, 7) \
X(a, STATIC, SINGULAR, BOOL, has_default_channel, 8) \
X(a, STATIC, SINGULAR, SFIXED32, latitude_i, 9) \
X(a, STATIC, SINGULAR, SFIXED32, longitude_i, 10) \
X(a, STATIC, SINGULAR, INT32, altitude, 11) \
X(a, STATIC, SINGULAR, UINT32, position_precision, 12) \
X(a, STATIC, SINGULAR, UINT32, num_online_local_nodes, 13)
#define meshtastic_MapReport_CALLBACK NULL
#define meshtastic_MapReport_DEFAULT NULL
extern const pb_msgdesc_t meshtastic_ServiceEnvelope_msg;
extern const pb_msgdesc_t meshtastic_MapReport_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define meshtastic_ServiceEnvelope_fields &meshtastic_ServiceEnvelope_msg
#define meshtastic_MapReport_fields &meshtastic_MapReport_msg
/* Maximum encoded size of messages (where known) */
/* meshtastic_ServiceEnvelope_size depends on runtime parameters */
#define meshtastic_MapReport_size 108
#ifdef __cplusplus
} /* extern "C" */

View File

@@ -38,19 +38,19 @@ typedef enum _meshtastic_PortNum {
ENCODING: Protobuf */
meshtastic_PortNum_REMOTE_HARDWARE_APP = 2,
/* The built-in position messaging app.
Payload is a [Position](/docs/developers/protobufs/api#position) message
Payload is a Position message.
ENCODING: Protobuf */
meshtastic_PortNum_POSITION_APP = 3,
/* The built-in user info app.
Payload is a [User](/docs/developers/protobufs/api#user) message
Payload is a User message.
ENCODING: Protobuf */
meshtastic_PortNum_NODEINFO_APP = 4,
/* Protocol control packets for mesh protocol use.
Payload is a [Routing](/docs/developers/protobufs/api#routing) message
Payload is a Routing message.
ENCODING: Protobuf */
meshtastic_PortNum_ROUTING_APP = 5,
/* Admin control packets.
Payload is a [AdminMessage](/docs/developers/protobufs/api#adminmessage) message
Payload is a AdminMessage message.
ENCODING: Protobuf */
meshtastic_PortNum_ADMIN_APP = 6,
/* Compressed TEXT_MESSAGE payloads.
@@ -60,7 +60,7 @@ typedef enum _meshtastic_PortNum {
any incoming TEXT_MESSAGE_COMPRESSED_APP payload and convert to TEXT_MESSAGE_APP. */
meshtastic_PortNum_TEXT_MESSAGE_COMPRESSED_APP = 7,
/* Waypoint payloads.
Payload is a [Waypoint](/docs/developers/protobufs/api#waypoint) message
Payload is a Waypoint message.
ENCODING: Protobuf */
meshtastic_PortNum_WAYPOINT_APP = 8,
/* Audio Payloads.
@@ -122,6 +122,8 @@ typedef enum _meshtastic_PortNum {
/* ATAK Plugin
Portnum for payloads from the official Meshtastic ATAK plugin */
meshtastic_PortNum_ATAK_PLUGIN = 72,
/* Provides unencrypted information about a node for consumption by a map via MQTT */
meshtastic_PortNum_MAP_REPORT_APP = 73,
/* Private applications should use portnums >= 256.
To simplify initial development and testing you can use "PRIVATE_APP"
in your code without needing to rebuild protobuf files (via [regen-protos.sh](https://github.com/meshtastic/firmware/blob/master/bin/regen-protos.sh)) */

View File

@@ -41,7 +41,9 @@ typedef enum _meshtastic_TelemetrySensorType {
/* PM2.5 air quality sensor */
meshtastic_TelemetrySensorType_PMSA003I = 13,
/* INA3221 3 Channel Voltage / Current Sensor */
meshtastic_TelemetrySensorType_INA3221 = 14
meshtastic_TelemetrySensorType_INA3221 = 14,
/* BMP085/BMP180 High accuracy temperature and pressure (older Version of BMP280) */
meshtastic_TelemetrySensorType_BMP085 = 15
} meshtastic_TelemetrySensorType;
/* Struct definitions */
@@ -141,8 +143,8 @@ extern "C" {
/* Helper constants for enums */
#define _meshtastic_TelemetrySensorType_MIN meshtastic_TelemetrySensorType_SENSOR_UNSET
#define _meshtastic_TelemetrySensorType_MAX meshtastic_TelemetrySensorType_INA3221
#define _meshtastic_TelemetrySensorType_ARRAYSIZE ((meshtastic_TelemetrySensorType)(meshtastic_TelemetrySensorType_INA3221+1))
#define _meshtastic_TelemetrySensorType_MAX meshtastic_TelemetrySensorType_BMP085
#define _meshtastic_TelemetrySensorType_ARRAYSIZE ((meshtastic_TelemetrySensorType)(meshtastic_TelemetrySensorType_BMP085+1))

View File

@@ -0,0 +1,530 @@
/*
Adds a WebServer and WebService callbacks to meshtastic as Linux Version. The WebServer & Webservices
runs in a real linux thread beside the portdunio threading emulation. It replaces the complete ESP32
Webserver libs including generation of SSL certifcicates, because the use ESP specific details in
the lib that can't be emulated.
The WebServices adapt to the two major phoneapi functions "handleAPIv1FromRadio,handleAPIv1ToRadio"
The WebServer just adds basaic support to deliver WebContent, so it can be used to
deliver the WebGui definded by the WebClient Project.
Steps to get it running:
1.) Add these Linux Libs to the compile and target machine:
sudo apt update && \
apt -y install openssl libssl-dev libopenssl libsdl2-dev \
libulfius-dev liborcania-dev
2.) Configure the root directory of the web Content in the config.yaml file.
The followinng tags should be included and set at your needs
Example entry in the config.yaml
Webserver:
Port: 9001 # Port for Webserver & Webservices
RootPath: /home/marc/web # Root Dir of WebServer
3.) Checkout the web project
https://github.com/meshtastic/web.git
Build it and copy the content of the folder web/dist/* to the folder you did set as "RootPath"
!!!The WebServer should not be used as production system or exposed to the Internet. Its a raw basic version!!!
Author: Marc Philipp Hammermann
mail: marchammermann@googlemail.com
*/
#ifdef PORTDUINO_LINUX_HARDWARE
#if __has_include(<ulfius.h>)
#include "PiWebServer.h"
#include "NodeDB.h"
#include "PhoneAPI.h"
#include "PowerFSM.h"
#include "RadioLibInterface.h"
#include "airtime.h"
#include "graphics/Screen.h"
#include "main.h"
#include "mesh/wifi/WiFiAPClient.h"
#include "sleep.h"
#include <openssl/bn.h>
#include <openssl/evp.h>
#include <openssl/pem.h>
#include <openssl/rsa.h>
#include <openssl/x509.h>
#include <orcania.h>
#include <string.h>
#include <ulfius.h>
#include <yder.h>
#include <cstring>
#include <string>
#include "PortduinoFS.h"
#include "platform/portduino/PortduinoGlue.h"
#define DEFAULT_REALM "default_realm"
#define PREFIX ""
struct _file_config configWeb;
// We need to specify some content-type mapping, so the resources get delivered with the
// right content type and are displayed correctly in the browser
char contentTypes[][2][32] = {{".txt", "text/plain"}, {".html", "text/html"},
{".js", "text/javascript"}, {".png", "image/png"},
{".jpg", "image/jpg"}, {".gz", "application/gzip"},
{".gif", "image/gif"}, {".json", "application/json"},
{".css", "text/css"}, {".ico", "image/vnd.microsoft.icon"},
{".svg", "image/svg+xml"}, {".ts", "text/javascript"},
{".tsx", "text/javascript"}, {"", ""}};
#undef str
volatile bool isWebServerReady;
volatile bool isCertReady;
HttpAPI webAPI;
PiWebServerThread *piwebServerThread;
/**
* Return the filename extension
*/
const char *get_filename_ext(const char *path)
{
const char *dot = strrchr(path, '.');
if (!dot || dot == path)
return "*";
if (strchr(dot, '?') != NULL) {
//*strchr(dot, '?') = '\0';
const char *empty = "\0";
return empty;
}
return dot;
}
/**
* Streaming callback function to ease sending large files
*/
static ssize_t callback_static_file_stream(void *cls, uint64_t pos, char *buf, size_t max)
{
(void)(pos);
if (cls != NULL) {
return fread(buf, 1, max, (FILE *)cls);
} else {
return U_STREAM_END;
}
}
/**
* Cleanup FILE* structure when streaming is complete
*/
static void callback_static_file_stream_free(void *cls)
{
if (cls != NULL) {
fclose((FILE *)cls);
}
}
/**
* static file callback endpoint that delivers the content for WebServer calls
*/
int callback_static_file(const struct _u_request *request, struct _u_response *response, void *user_data)
{
size_t length;
FILE *f;
char *file_requested, *file_path, *url_dup_save, *real_path = NULL;
const char *content_type;
/*
* Comment this if statement if you don't access static files url from root dir, like /app
*/
if (request->callback_position > 0) {
return U_CALLBACK_CONTINUE;
} else if (user_data != NULL && (configWeb.files_path != NULL)) {
file_requested = o_strdup(request->http_url);
url_dup_save = file_requested;
while (file_requested[0] == '/') {
file_requested++;
}
file_requested += o_strlen(configWeb.url_prefix);
while (file_requested[0] == '/') {
file_requested++;
}
if (strchr(file_requested, '#') != NULL) {
*strchr(file_requested, '#') = '\0';
}
if (strchr(file_requested, '?') != NULL) {
*strchr(file_requested, '?') = '\0';
}
if (file_requested == NULL || o_strlen(file_requested) == 0 || 0 == o_strcmp("/", file_requested)) {
o_free(url_dup_save);
url_dup_save = file_requested = o_strdup("index.html");
}
file_path = msprintf("%s/%s", configWeb.files_path, file_requested);
real_path = realpath(file_path, NULL);
if (0 == o_strncmp(configWeb.files_path, real_path, o_strlen(configWeb.files_path))) {
if (access(file_path, F_OK) != -1) {
f = fopen(file_path, "rb");
if (f) {
fseek(f, 0, SEEK_END);
length = ftell(f);
fseek(f, 0, SEEK_SET);
content_type = u_map_get_case(&configWeb.mime_types, get_filename_ext(file_requested));
if (content_type == NULL) {
content_type = u_map_get(&configWeb.mime_types, "*");
LOG_DEBUG("Static File Server - Unknown mime type for extension %s \n", get_filename_ext(file_requested));
}
u_map_put(response->map_header, "Content-Type", content_type);
u_map_copy_into(response->map_header, &configWeb.map_header);
if (ulfius_set_stream_response(response, 200, callback_static_file_stream, callback_static_file_stream_free,
length, STATIC_FILE_CHUNK, f) != U_OK) {
LOG_DEBUG("callback_static_file - Error ulfius_set_stream_response\n ");
}
}
} else {
if (configWeb.redirect_on_404 == NULL) {
ulfius_set_string_body_response(response, 404, "File not found");
} else {
ulfius_add_header_to_response(response, "Location", configWeb.redirect_on_404);
response->status = 302;
}
}
} else {
if (configWeb.redirect_on_404 == NULL) {
ulfius_set_string_body_response(response, 404, "File not found");
} else {
ulfius_add_header_to_response(response, "Location", configWeb.redirect_on_404);
response->status = 302;
}
}
o_free(file_path);
o_free(url_dup_save);
free(real_path); // realpath uses malloc
return U_CALLBACK_CONTINUE;
} else {
LOG_DEBUG("Static File Server - Error, user_data is NULL or inconsistent\n");
return U_CALLBACK_ERROR;
}
}
static void handleWebResponse() {}
/*
* Adapt the radioapi to the Webservice handleAPIv1ToRadio
* Trigger : WebGui(SAVE)->WebServcice->phoneApi
*/
int handleAPIv1ToRadio(const struct _u_request *req, struct _u_response *res, void *user_data)
{
LOG_DEBUG("handleAPIv1ToRadio web -> radio \n");
ulfius_add_header_to_response(res, "Content-Type", "application/x-protobuf");
ulfius_add_header_to_response(res, "Access-Control-Allow-Headers", "Content-Type");
ulfius_add_header_to_response(res, "Access-Control-Allow-Origin", "*");
ulfius_add_header_to_response(res, "Access-Control-Allow-Methods", "PUT, OPTIONS");
ulfius_add_header_to_response(res, "X-Protobuf-Schema",
"https://raw.githubusercontent.com/meshtastic/protobufs/master/mesh.proto");
if (req->http_verb == "OPTIONS") {
ulfius_set_response_properties(res, U_OPT_STATUS, 204);
return U_CALLBACK_CONTINUE;
}
byte buffer[MAX_TO_FROM_RADIO_SIZE];
size_t s = req->binary_body_length;
memcpy(buffer, req->binary_body, MAX_TO_FROM_RADIO_SIZE);
// FIXME* Problem with portdunio loosing mountpoint maybe because of running in a real sep. thread
portduinoVFS->mountpoint("/home/marc/.portduino/default");
LOG_DEBUG("Received %d bytes from PUT request\n", s);
webAPI.handleToRadio(buffer, s);
LOG_DEBUG("end web->radio \n");
return U_CALLBACK_COMPLETE;
}
/*
* Adapt the radioapi to the Webservice handleAPIv1FromRadio
* Trigger : WebGui(POLL)->handleAPIv1FromRadio->phoneapi->Meshtastic(Radio) events
*/
int handleAPIv1FromRadio(const struct _u_request *req, struct _u_response *res, void *user_data)
{
// LOG_DEBUG("handleAPIv1FromRadio radio -> web\n");
std::string valueAll;
// Status code is 200 OK by default.
ulfius_add_header_to_response(res, "Content-Type", "application/x-protobuf");
ulfius_add_header_to_response(res, "Access-Control-Allow-Origin", "*");
ulfius_add_header_to_response(res, "Access-Control-Allow-Methods", "GET");
ulfius_add_header_to_response(res, "X-Protobuf-Schema",
"https://raw.githubusercontent.com/meshtastic/protobufs/master/mesh.proto");
uint8_t txBuf[MAX_STREAM_BUF_SIZE];
uint32_t len = 1;
if (valueAll == "true") {
while (len) {
len = webAPI.getFromRadio(txBuf);
ulfius_set_response_properties(res, U_OPT_STATUS, 200, U_OPT_BINARY_BODY, txBuf, len);
const char *tmpa = (const char *)txBuf;
ulfius_set_string_body_response(res, 200, tmpa);
// LOG_DEBUG("\n----webAPI response all:----\n");
LOG_DEBUG(tmpa);
LOG_DEBUG("\n");
}
// Otherwise, just return one protobuf
} else {
len = webAPI.getFromRadio(txBuf);
const char *tmpa = (const char *)txBuf;
ulfius_set_binary_body_response(res, 200, tmpa, len);
// LOG_DEBUG("\n----webAPI response:\n");
LOG_DEBUG(tmpa);
LOG_DEBUG("\n");
}
// LOG_DEBUG("end radio->web\n", len);
return U_CALLBACK_COMPLETE;
}
/*
OpenSSL RSA Key Gen
*/
int generate_rsa_key(EVP_PKEY **pkey)
{
EVP_PKEY_CTX *pkey_ctx = EVP_PKEY_CTX_new_id(EVP_PKEY_RSA, NULL);
if (!pkey_ctx)
return -1;
if (EVP_PKEY_keygen_init(pkey_ctx) <= 0)
return -1;
if (EVP_PKEY_CTX_set_rsa_keygen_bits(pkey_ctx, 2048) <= 0)
return -1;
if (EVP_PKEY_keygen(pkey_ctx, pkey) <= 0)
return -1;
EVP_PKEY_CTX_free(pkey_ctx);
return 0; // SUCCESS
}
int generate_self_signed_x509(EVP_PKEY *pkey, X509 **x509)
{
*x509 = X509_new();
if (!*x509)
return -1;
if (X509_set_version(*x509, 2) != 1)
return -1;
ASN1_INTEGER_set(X509_get_serialNumber(*x509), 1);
X509_gmtime_adj(X509_get_notBefore(*x509), 0);
X509_gmtime_adj(X509_get_notAfter(*x509), 31536000L); // 1 YEAR ACCESS
X509_set_pubkey(*x509, pkey);
// SET Subject Name
X509_NAME *name = X509_get_subject_name(*x509);
X509_NAME_add_entry_by_txt(name, "C", MBSTRING_ASC, (unsigned char *)"DE", -1, -1, 0);
X509_NAME_add_entry_by_txt(name, "O", MBSTRING_ASC, (unsigned char *)"Meshtastic", -1, -1, 0);
X509_NAME_add_entry_by_txt(name, "CN", MBSTRING_ASC, (unsigned char *)"meshtastic.local", -1, -1, 0);
// Selfsigned, Issuer = Subject
X509_set_issuer_name(*x509, name);
// Certificate signed with our privte key
if (X509_sign(*x509, pkey, EVP_sha256()) <= 0)
return -1;
return 0;
}
char *read_file_into_string(const char *filename)
{
FILE *file = fopen(filename, "rb");
if (file == NULL) {
LOG_ERROR("Error reading File : %s \n", filename);
return NULL;
}
// Size of file
fseek(file, 0, SEEK_END);
long filesize = ftell(file);
rewind(file);
// reserve mem for file + 1 byte
char *buffer = (char *)malloc(filesize + 1);
if (buffer == NULL) {
LOG_ERROR("Malloc of mem failed for file : %s \n", filename);
fclose(file);
return NULL;
}
// read content
size_t readSize = fread(buffer, 1, filesize, file);
if (readSize != filesize) {
LOG_ERROR("Error reading file into buffer\n");
free(buffer);
fclose(file);
return NULL;
}
// add terminator sign at the end
buffer[filesize] = '\0';
fclose(file);
return buffer; // return pointer
}
int PiWebServerThread::CheckSSLandLoad()
{
// read certificate
cert_pem = read_file_into_string("certificate.pem");
if (cert_pem == NULL) {
LOG_ERROR("ERROR SSL Certificate File can't be loaded or is missing\n");
return 1;
}
// read private key
key_pem = read_file_into_string("private_key.pem");
if (key_pem == NULL) {
LOG_ERROR("ERROR file private_key can't be loaded or is missing\n");
return 2;
}
return 0;
}
int PiWebServerThread::CreateSSLCertificate()
{
EVP_PKEY *pkey = NULL;
X509 *x509 = NULL;
if (generate_rsa_key(&pkey) != 0) {
LOG_ERROR("Error generating RSA-Key.\n");
return 1;
}
if (generate_self_signed_x509(pkey, &x509) != 0) {
LOG_ERROR("Error generating of X509-Certificat.\n");
return 2;
}
// Ope file to write private key file
FILE *pkey_file = fopen("private_key.pem", "wb");
if (!pkey_file) {
LOG_ERROR("Error opening private key file.\n");
return 3;
}
// write private key file
PEM_write_PrivateKey(pkey_file, pkey, NULL, NULL, 0, NULL, NULL);
fclose(pkey_file);
// open Certificate file
FILE *x509_file = fopen("certificate.pem", "wb");
if (!x509_file) {
LOG_ERROR("Error opening certificate.\n");
return 4;
}
// write cirtificate
PEM_write_X509(x509_file, x509);
fclose(x509_file);
EVP_PKEY_free(pkey);
X509_free(x509);
LOG_INFO("Create SSL Certifictate -certificate.pem- succesfull \n");
return 0;
}
void initWebServer() {}
PiWebServerThread::PiWebServerThread()
{
int ret, retssl, webservport;
if (CheckSSLandLoad() != 0) {
CreateSSLCertificate();
if (CheckSSLandLoad() != 0) {
LOG_ERROR("Major Error Gen & Read SSL Certificate\n");
}
}
if (settingsMap[webserverport] != 0) {
webservport = settingsMap[webserverport];
LOG_INFO("Using webserver port from yaml config. %i \n", webservport);
} else {
LOG_INFO("Webserver port in yaml config set to 0, so defaulting to port 443.\n");
webservport = 443;
}
// Web Content Service Instance
if (ulfius_init_instance(&instanceWeb, webservport, NULL, DEFAULT_REALM) != U_OK) {
LOG_ERROR("Webserver couldn't be started, abort execution\n");
} else {
LOG_INFO("Webserver started ....\n");
u_map_init(&configWeb.mime_types);
u_map_put(&configWeb.mime_types, "*", "application/octet-stream");
u_map_put(&configWeb.mime_types, ".html", "text/html");
u_map_put(&configWeb.mime_types, ".htm", "text/html");
u_map_put(&configWeb.mime_types, ".tsx", "application/javascript");
u_map_put(&configWeb.mime_types, ".ts", "application/javascript");
u_map_put(&configWeb.mime_types, ".css", "text/css");
u_map_put(&configWeb.mime_types, ".js", "application/javascript");
u_map_put(&configWeb.mime_types, ".json", "application/json");
u_map_put(&configWeb.mime_types, ".png", "image/png");
u_map_put(&configWeb.mime_types, ".gif", "image/gif");
u_map_put(&configWeb.mime_types, ".jpeg", "image/jpeg");
u_map_put(&configWeb.mime_types, ".jpg", "image/jpeg");
u_map_put(&configWeb.mime_types, ".ttf", "font/ttf");
u_map_put(&configWeb.mime_types, ".woff", "font/woff");
u_map_put(&configWeb.mime_types, ".ico", "image/x-icon");
u_map_put(&configWeb.mime_types, ".svg", "image/svg+xml");
webrootpath = settingsStrings[webserverrootpath];
configWeb.files_path = (char *)webrootpath.c_str();
configWeb.url_prefix = "";
configWeb.rootPath = strdup(portduinoVFS->mountpoint());
u_map_put(instanceWeb.default_headers, "Access-Control-Allow-Origin", "*");
// Maximum body size sent by the client is 1 Kb
instanceWeb.max_post_body_size = 1024;
ulfius_add_endpoint_by_val(&instanceWeb, "GET", PREFIX, "/api/v1/fromradio/*", 1, &handleAPIv1FromRadio, NULL);
ulfius_add_endpoint_by_val(&instanceWeb, "PUT", PREFIX, "/api/v1/toradio/*", 1, &handleAPIv1ToRadio, configWeb.rootPath);
// Add callback function to all endpoints for the Web Server
ulfius_add_endpoint_by_val(&instanceWeb, "GET", NULL, "/*", 2, &callback_static_file, &configWeb);
// thats for serving without SSL
// retssl = ulfius_start_framework(&instanceWeb);
// thats for serving with SSL
retssl = ulfius_start_secure_framework(&instanceWeb, key_pem, cert_pem);
if (retssl == U_OK) {
LOG_INFO("Web Server framework started on port: %i \n", webservport);
LOG_INFO("Web Server root %s\n", (char *)webrootpath.c_str());
} else {
LOG_ERROR("Error starting Web Server framework\n");
}
}
}
PiWebServerThread::~PiWebServerThread()
{
u_map_clean(&configWeb.mime_types);
ulfius_stop_framework(&instanceWeb);
ulfius_stop_framework(&instanceWeb);
free(configWeb.rootPath);
ulfius_clean_instance(&instanceService);
ulfius_clean_instance(&instanceService);
free(cert_pem);
LOG_INFO("End framework");
}
#endif
#endif

View File

@@ -0,0 +1,61 @@
#pragma once
#ifdef PORTDUINO_LINUX_HARDWARE
#if __has_include(<ulfius.h>)
#include "PhoneAPI.h"
#include "ulfius-cfg.h"
#include "ulfius.h"
#include <Arduino.h>
#include <functional>
#define STATIC_FILE_CHUNK 256
void initWebServer();
void createSSLCert();
int callback_static_file(const struct _u_request *request, struct _u_response *response, void *user_data);
const char *get_filename_ext(const char *path);
struct _file_config {
char *files_path;
char *url_prefix;
struct _u_map mime_types;
struct _u_map map_header;
char *redirect_on_404;
char *rootPath;
};
class PiWebServerThread
{
private:
char *key_pem = NULL;
char *cert_pem = NULL;
// struct _u_map mime_types;
std::string webrootpath;
public:
PiWebServerThread();
~PiWebServerThread();
int CreateSSLCertificate();
int CheckSSLandLoad();
uint32_t requestRestart = 0;
struct _u_instance instanceWeb;
struct _u_instance instanceService;
};
class HttpAPI : public PhoneAPI
{
public:
// Nothing here yet
private:
// Nothing here yet
protected:
/// Check the current underlying physical link to see if the client is currently connected
virtual bool checkIsConnected() override { return true; } // FIXME, be smarter about this
};
extern PiWebServerThread *piwebServerThread;
#endif
#endif

View File

@@ -16,6 +16,7 @@
#ifdef ARCH_PORTDUINO
#include "unistd.h"
#endif
#include "Default.h"
#include "mqtt/MQTT.h"
@@ -302,6 +303,10 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c)
// If we're setting router role for the first time, install its intervals
if (existingRole != c.payload_variant.device.role)
nodeDB.installRoleDefaults(c.payload_variant.device.role);
if (config.device.node_info_broadcast_secs < min_node_info_broadcast_secs) {
LOG_DEBUG("Tried to set node_info_broadcast_secs too low, setting to %d\n", min_node_info_broadcast_secs);
config.device.node_info_broadcast_secs = min_node_info_broadcast_secs;
}
break;
case meshtastic_Config_position_tag:
LOG_INFO("Setting config: Position\n");

View File

@@ -1,4 +1,5 @@
#include "AtakPluginModule.h"
#include "Default.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"

View File

@@ -18,40 +18,7 @@
#define INPUTBROKER_MATRIX_TYPE 0
#endif
#ifdef OLED_RU
#include "graphics/fonts/OLEDDisplayFontsRU.h"
#endif
#ifdef OLED_UA
#include "graphics/fonts/OLEDDisplayFontsUA.h"
#endif
#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \
!defined(DISPLAY_FORCE_SMALL_FONTS)
// The screen is bigger so use bigger fonts
#define FONT_SMALL ArialMT_Plain_16
#define FONT_MEDIUM ArialMT_Plain_24
#define FONT_LARGE ArialMT_Plain_24
#else
#ifdef OLED_RU
#define FONT_SMALL ArialMT_Plain_10_RU
#else
#ifdef OLED_UA
#define FONT_SMALL ArialMT_Plain_10_UA
#else
#define FONT_SMALL ArialMT_Plain_10
#endif
#endif
#define FONT_MEDIUM ArialMT_Plain_16
#define FONT_LARGE ArialMT_Plain_24
#endif
#define fontHeight(font) ((font)[1] + 1) // height is position 1
#define FONT_HEIGHT_SMALL fontHeight(FONT_SMALL)
#define FONT_HEIGHT_MEDIUM fontHeight(FONT_MEDIUM)
#define FONT_HEIGHT_LARGE fontHeight(FONT_LARGE)
#include "graphics/ScreenFonts.h"
// Remove Canned message screen if no action is taken for some milliseconds
#define INACTIVATE_AFTER_MS 20000

View File

@@ -1,10 +1,10 @@
#include "DetectionSensorModule.h"
#include "Default.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "configuration.h"
#include "main.h"
DetectionSensorModule *detectionSensorModule;
#define GPIO_POLLING_INTERVAL 100
@@ -49,7 +49,7 @@ int32_t DetectionSensorModule::runOnce()
// LOG_DEBUG("Detection Sensor Module: Current pin state: %i\n", digitalRead(moduleConfig.detection_sensor.monitor_pin));
if ((millis() - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.detection_sensor.minimum_broadcast_secs) &&
if ((millis() - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.detection_sensor.minimum_broadcast_secs) &&
hasDetectionEvent()) {
sendDetectionMessage();
return DELAYED_INTERVAL;
@@ -58,7 +58,8 @@ int32_t DetectionSensorModule::runOnce()
// of heartbeat. We only do this if the minimum broadcast interval is greater than zero, otherwise we'll only broadcast state
// change detections.
else if (moduleConfig.detection_sensor.state_broadcast_secs > 0 &&
(millis() - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.detection_sensor.state_broadcast_secs)) {
(millis() - lastSentToMesh) >=
Default::getConfiguredOrDefaultMs(moduleConfig.detection_sensor.state_broadcast_secs)) {
sendCurrentStateMessage();
return DELAYED_INTERVAL;
}

View File

@@ -81,7 +81,7 @@ int32_t ExternalNotificationModule::runOnce()
// let the song finish if we reach timeout
nagCycleCutoff = UINT32_MAX;
LOG_INFO("Turning off external notification: ");
for (int i = 0; i < 2; i++) {
for (int i = 0; i < 3; i++) {
setExternalOff(i);
externalTurnedOn[i] = 0;
LOG_INFO("%d ", i);

View File

@@ -1,74 +1,112 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_INPUTBROKER
#include "input/InputBroker.h"
#include "input/RotaryEncoderInterruptImpl1.h"
#include "input/TrackballInterruptImpl1.h"
#include "input/UpDownInterruptImpl1.h"
#include "input/cardKbI2cImpl.h"
#include "input/kbMatrixImpl.h"
#endif
#include "modules/AdminModule.h"
#if !MESHTASTIC_EXCLUDE_ATAK
#include "modules/AtakPluginModule.h"
#endif
#if !MESHTASTIC_EXCLUDE_CANNEDMESSAGES
#include "modules/CannedMessageModule.h"
#endif
#if !MESHTASTIC_EXCLUDE_DETECTIONSENSOR
#include "modules/DetectionSensorModule.h"
#endif
#if !MESHTASTIC_EXCLUDE_NEIGHBORINFO
#include "modules/NeighborInfoModule.h"
#endif
#include "modules/NodeInfoModule.h"
#include "modules/PositionModule.h"
#if !MESHTASTIC_EXCLUDE_REMOTEHARDWARE
#include "modules/RemoteHardwareModule.h"
#include "modules/ReplyModule.h"
#endif
#include "modules/RoutingModule.h"
#include "modules/TextMessageModule.h"
#if !MESHTASTIC_EXCLUDE_TRACEROUTE
#include "modules/TraceRouteModule.h"
#endif
#if !MESHTASTIC_EXCLUDE_WAYPOINT
#include "modules/WaypointModule.h"
#endif
#if ARCH_PORTDUINO
#include "input/LinuxInputImpl.h"
#endif
#if HAS_TELEMETRY
#include "modules/Telemetry/DeviceTelemetry.h"
#endif
#if HAS_SENSOR
#if HAS_SENSOR && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "modules/Telemetry/AirQualityTelemetry.h"
#include "modules/Telemetry/EnvironmentTelemetry.h"
#endif
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO)
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) && !MESHTASTIC_EXCLUDE_POWER_TELEMETRY
#include "modules/Telemetry/PowerTelemetry.h"
#endif
#ifdef ARCH_ESP32
#ifdef USE_SX1280
#if defined(USE_SX1280) && !MESHTASTIC_EXCLUDE_AUDIO
#include "modules/esp32/AudioModule.h"
#endif
#if !MESHTASTIC_EXCLUDE_PAXCOUNTER
#include "modules/esp32/PaxcounterModule.h"
#endif
#if !MESHTASTIC_EXCLUDE_STOREFORWARD
#include "modules/esp32/StoreForwardModule.h"
#endif
#endif
#if defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)
#if !MESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION
#include "modules/ExternalNotificationModule.h"
#endif
#if !MESHTASTIC_EXCLUDE_RANGETEST
#include "modules/RangeTestModule.h"
#endif
#if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)) && !defined(CONFIG_IDF_TARGET_ESP32S2)
#if !MESHTASTIC_EXCLUDE_SERIAL
#include "modules/SerialModule.h"
#endif
#endif
#endif
/**
* Create module instances here. If you are adding a new module, you must 'new' it here (or somewhere else)
*/
void setupModules()
{
if (config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER) {
#if HAS_BUTTON || ARCH_PORTDUINO
#if (HAS_BUTTON || ARCH_PORTDUINO) && !MESHTASTIC_EXCLUDE_INPUTBROKER
inputBroker = new InputBroker();
#endif
adminModule = new AdminModule();
nodeInfoModule = new NodeInfoModule();
positionModule = new PositionModule();
#if !MESHTASTIC_EXCLUDE_WAYPOINT
waypointModule = new WaypointModule();
#endif
textMessageModule = new TextMessageModule();
#if !MESHTASTIC_EXCLUDE_TRACEROUTE
traceRouteModule = new TraceRouteModule();
#endif
#if !MESHTASTIC_EXCLUDE_NEIGHBORINFO
neighborInfoModule = new NeighborInfoModule();
#endif
#if !MESHTASTIC_EXCLUDE_DETECTIONSENSOR
detectionSensorModule = new DetectionSensorModule();
#endif
#if !MESHTASTIC_EXCLUDE_ATAK
atakPluginModule = new AtakPluginModule();
#endif
// Note: if the rest of meshtastic doesn't need to explicitly use your module, you do not need to assign the instance
// to a global variable.
#if !MESHTASTIC_EXCLUDE_REMOTEHARDWARE
new RemoteHardwareModule();
new ReplyModule();
#if HAS_BUTTON || ARCH_PORTDUINO
#endif
// Example: Put your module here
// new ReplyModule();
#if (HAS_BUTTON || ARCH_PORTDUINO) && !MESHTASTIC_EXCLUDE_INPUTBROKER
rotaryEncoderInterruptImpl1 = new RotaryEncoderInterruptImpl1();
if (!rotaryEncoderInterruptImpl1->init()) {
delete rotaryEncoderInterruptImpl1;
@@ -90,47 +128,59 @@ void setupModules()
aLinuxInputImpl = new LinuxInputImpl();
aLinuxInputImpl->init();
#endif
#if HAS_TRACKBALL
#if HAS_TRACKBALL && !MESHTASTIC_EXCLUDE_INPUTBROKER
trackballInterruptImpl1 = new TrackballInterruptImpl1();
trackballInterruptImpl1->init();
#endif
#if HAS_SCREEN
#if HAS_SCREEN && !MESHTASTIC_EXCLUDE_CANNEDMESSAGES
cannedMessageModule = new CannedMessageModule();
#endif
#if HAS_TELEMETRY
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO)
new DeviceTelemetryModule();
#endif
#if HAS_SENSOR
#if HAS_SENSOR && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
new EnvironmentTelemetryModule();
if (nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_PMSA003I].first > 0) {
new AirQualityTelemetryModule();
}
#endif
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO)
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) && !MESHTASTIC_EXCLUDE_POWER_TELEMETRY
new PowerTelemetryModule();
#endif
#if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)) && !defined(CONFIG_IDF_TARGET_ESP32S2) && \
!defined(CONFIG_IDF_TARGET_ESP32C3)
#if !MESHTASTIC_EXCLUDE_SERIAL
new SerialModule();
#endif
#endif
#ifdef ARCH_ESP32
// Only run on an esp32 based device.
#ifdef USE_SX1280
#if defined(USE_SX1280) && !MESHTASTIC_EXCLUDE_AUDIO
audioModule = new AudioModule();
#endif
#if !MESHTASTIC_EXCLUDE_STOREFORWARD
storeForwardModule = new StoreForwardModule();
#endif
#if !MESHTASTIC_EXCLUDE_PAXCOUNTER
paxcounterModule = new PaxcounterModule();
#endif
#endif
#if defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)
#if !MESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION
externalNotificationModule = new ExternalNotificationModule();
#endif
#if !MESHTASTIC_EXCLUDE_RANGETEST
new RangeTestModule();
#endif
#endif
} else {
adminModule = new AdminModule();
#if HAS_TELEMETRY
new DeviceTelemetryModule();
#endif
#if !MESHTASTIC_EXCLUDE_TRACEROUTE
traceRouteModule = new TraceRouteModule();
#endif
}
// NOTE! This module must be added LAST because it likes to check for replies from other modules and avoid sending extra
// acks

View File

@@ -1,4 +1,5 @@
#include "NeighborInfoModule.h"
#include "Default.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "RTC.h"
@@ -95,6 +96,7 @@ NeighborInfoModule::NeighborInfoModule()
ourPortNum = meshtastic_PortNum_NEIGHBORINFO_APP;
if (moduleConfig.neighbor_info.enabled) {
isPromiscuous = true; // Update neighbors from all packets
this->loadProtoForModule();
setIntervalFromNow(35 * 1000);
} else {
@@ -193,7 +195,7 @@ int32_t NeighborInfoModule::runOnce()
{
bool requestReplies = false;
sendNeighborInfo(NODENUM_BROADCAST, requestReplies);
return getConfiguredOrDefaultMs(moduleConfig.neighbor_info.update_interval, default_broadcast_interval_secs);
return Default::getConfiguredOrDefaultMs(moduleConfig.neighbor_info.update_interval, default_broadcast_interval_secs);
}
/*
@@ -202,9 +204,12 @@ Pass it to an upper client; do not persist this data on the mesh
*/
bool NeighborInfoModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_NeighborInfo *np)
{
if (enabled) {
if (np) {
printNeighborInfo("RECEIVED", np);
updateNeighbors(mp, np);
} else if (mp.hop_start != 0 && mp.hop_start == mp.hop_limit) {
// If the hopLimit is the same as hopStart, then it is a neighbor
getOrCreateNeighbor(mp.from, mp.from, 0, mp.rx_snr); // Set the broadcast interval to 0, as we don't know it
}
// Allow others to handle this packet
return false;
@@ -261,7 +266,7 @@ meshtastic_Neighbor *NeighborInfoModule::getOrCreateNeighbor(NodeNum originalSen
nbr->snr = snr;
nbr->last_rx_time = getTime();
// Only if this is the original sender, the broadcast interval corresponds to it
if (originalSender == n)
if (originalSender == n && node_broadcast_interval_secs != 0)
nbr->node_broadcast_interval_secs = node_broadcast_interval_secs;
saveProtoForModule(); // Save the updated neighbor
return nbr;
@@ -277,8 +282,10 @@ meshtastic_Neighbor *NeighborInfoModule::getOrCreateNeighbor(NodeNum originalSen
new_nbr->snr = snr;
new_nbr->last_rx_time = getTime();
// Only if this is the original sender, the broadcast interval corresponds to it
if (originalSender == n)
if (originalSender == n && node_broadcast_interval_secs != 0)
new_nbr->node_broadcast_interval_secs = node_broadcast_interval_secs;
else // Assume the same broadcast interval as us for the neighbor if we don't know it
new_nbr->node_broadcast_interval_secs = moduleConfig.neighbor_info.update_interval;
saveProtoForModule(); // Save the new neighbor
return new_nbr;
}

View File

@@ -75,6 +75,9 @@ class NeighborInfoModule : public ProtobufModule<meshtastic_NeighborInfo>, priva
/* Does our periodic broadcast */
int32_t runOnce() override;
// Override wantPacket to say we want to see all packets when enabled, not just those for our port number
virtual bool wantPacket(const meshtastic_MeshPacket *p) override { return enabled; }
/* These are for debugging only */
void printNeighborInfo(const char *header, const meshtastic_NeighborInfo *np);
void printNodeDBNodes(const char *header);

View File

@@ -1,4 +1,5 @@
#include "NodeInfoModule.h"
#include "Default.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "RTC.h"
@@ -58,8 +59,8 @@ void NodeInfoModule::sendOurNodeInfo(NodeNum dest, bool wantReplies, uint8_t cha
meshtastic_MeshPacket *NodeInfoModule::allocReply()
{
uint32_t now = millis();
// If we sent our NodeInfo less than 1 min. ago, don't send it again as it may be still underway.
if (lastSentToMesh && (now - lastSentToMesh) < 60 * 1000) {
// If we sent our NodeInfo less than 5 min. ago, don't send it again as it may be still underway.
if (lastSentToMesh && (now - lastSentToMesh) < (5 * 60 * 1000)) {
LOG_DEBUG("Sending NodeInfo will be ignored since we just sent it.\n");
ignoreRequest = true; // Mark it as ignored for MeshModule
return NULL;
@@ -91,6 +92,5 @@ int32_t NodeInfoModule::runOnce()
LOG_INFO("Sending our nodeinfo to mesh (wantReplies=%d)\n", requestReplies);
sendOurNodeInfo(NODENUM_BROADCAST, requestReplies); // Send our info (don't request replies)
}
return getConfiguredOrDefaultMs(config.device.node_info_broadcast_secs, default_broadcast_interval_secs);
return Default::getConfiguredOrDefaultMs(config.device.node_info_broadcast_secs, default_node_info_broadcast_secs);
}

View File

@@ -1,4 +1,5 @@
#include "PositionModule.h"
#include "Default.h"
#include "GPS.h"
#include "MeshService.h"
#include "NodeDB.h"
@@ -59,9 +60,15 @@ bool PositionModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes
// to set fixed location, EUD-GPS location or just the time (see also issue #900)
bool isLocal = false;
if (nodeDB.getNodeNum() == getFrom(&mp)) {
LOG_DEBUG("Incoming update from MYSELF\n");
isLocal = true;
nodeDB.setLocalPosition(p);
if (config.position.fixed_position) {
LOG_DEBUG("Ignore incoming position update from myself except for time, because position.fixed_position is true\n");
nodeDB.setLocalPosition(p, true);
return false;
} else {
LOG_DEBUG("Incoming update from MYSELF\n");
nodeDB.setLocalPosition(p);
}
}
// Log packet size and data fields
@@ -116,6 +123,11 @@ meshtastic_MeshPacket *PositionModule::allocReply()
}
localPosition.seq_number++;
if (localPosition.latitude_i == 0 && localPosition.longitude_i == 0) {
LOG_WARN("Skipping position send because lat/lon are zero!\n");
return nullptr;
}
// lat/lon are unconditionally included - IF AVAILABLE!
LOG_DEBUG("Sending location with precision %i\n", precision);
if (precision < 32 && precision > 0) {
@@ -269,7 +281,7 @@ int32_t PositionModule::runOnce()
{
if (sleepOnNextExecution == true) {
sleepOnNextExecution = false;
uint32_t nightyNightMs = getConfiguredOrDefaultMs(config.position.position_broadcast_secs);
uint32_t nightyNightMs = Default::getConfiguredOrDefaultMs(config.position.position_broadcast_secs);
LOG_DEBUG("Sleeping for %ims, then awaking to send position again.\n", nightyNightMs);
doDeepSleep(nightyNightMs, false);
}
@@ -280,7 +292,8 @@ int32_t PositionModule::runOnce()
// We limit our GPS broadcasts to a max rate
uint32_t now = millis();
uint32_t intervalMs = getConfiguredOrDefaultMs(config.position.position_broadcast_secs, default_broadcast_interval_secs);
uint32_t intervalMs =
Default::getConfiguredOrDefaultMs(config.position.position_broadcast_secs, default_broadcast_interval_secs);
uint32_t msSinceLastSend = now - lastGpsSend;
// Only send packets if the channel util. is less than 25% utilized or we're a tracker with less than 40% utilized.
if (!airTime->isTxAllowedChannelUtil(config.device.role != meshtastic_Config_DeviceConfig_Role_TRACKER &&
@@ -311,7 +324,7 @@ int32_t PositionModule::runOnce()
if (hasValidPosition(node2)) {
// The minimum time (in seconds) that would pass before we are able to send a new position packet.
const uint32_t minimumTimeThreshold =
getConfiguredOrDefaultMs(config.position.broadcast_smart_minimum_interval_secs, 30);
Default::getConfiguredOrDefaultMs(config.position.broadcast_smart_minimum_interval_secs, 30);
auto smartPosition = getDistanceTraveledSinceLastSend(node->position);
@@ -358,7 +371,8 @@ void PositionModule::sendLostAndFoundText()
struct SmartPosition PositionModule::getDistanceTraveledSinceLastSend(meshtastic_PositionLite currentPosition)
{
// The minimum distance to travel before we are able to send a new position packet.
const uint32_t distanceTravelThreshold = getConfiguredOrDefault(config.position.broadcast_smart_minimum_distance, 100);
const uint32_t distanceTravelThreshold =
Default::getConfiguredOrDefault(config.position.broadcast_smart_minimum_distance, 100);
// Determine the distance in meters between two points on the globe
float distanceTraveledSinceLastSend = GeoCoord::latLongToMeter(

View File

@@ -113,8 +113,8 @@ void RangeTestModuleRadio::sendPayload(NodeNum dest, bool wantReplies)
meshtastic_MeshPacket *p = allocDataPacket();
p->to = dest;
p->decoded.want_response = wantReplies;
p->want_ack = true;
p->hop_limit = 0;
p->want_ack = false;
packetSequence++;
@@ -295,4 +295,4 @@ bool RangeTestModuleRadio::appendFile(const meshtastic_MeshPacket &mp)
#endif
return 1;
}
}

View File

@@ -36,13 +36,28 @@ meshtastic_MeshPacket *RoutingModule::allocReply()
return NULL;
}
void RoutingModule::sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex)
void RoutingModule::sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex, uint8_t hopStart,
uint8_t hopLimit)
{
auto p = allocAckNak(err, to, idFrom, chIndex);
auto p = allocAckNak(err, to, idFrom, chIndex, hopStart, hopLimit);
router->sendLocal(p); // we sometimes send directly to the local node
}
uint8_t RoutingModule::getHopLimitForResponse(uint8_t hopStart, uint8_t hopLimit)
{
if (hopStart != 0) {
// Hops used by the request. If somebody in between running modified firmware modified it, ignore it
uint8_t hopsUsed = hopStart < hopLimit ? config.lora.hop_limit : hopStart - hopLimit;
if (hopsUsed > config.lora.hop_limit) {
return hopsUsed; // If the request used more hops than the limit, use the same amount of hops
} else if (hopsUsed + 2 < config.lora.hop_limit) {
return hopsUsed + 2; // Use only the amount of hops needed with some margin as the way back may be different
}
}
return config.lora.hop_limit; // Use the default hop limit
}
RoutingModule::RoutingModule() : ProtobufModule("routing", meshtastic_PortNum_ROUTING_APP, &meshtastic_Routing_msg)
{
isPromiscuous = true;

View File

@@ -13,7 +13,11 @@ class RoutingModule : public ProtobufModule<meshtastic_Routing>
*/
RoutingModule();
void sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex);
void sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex, uint8_t hopStart = 0,
uint8_t hopLimit = 0);
// Given the hopStart and hopLimit upon reception of a request, return the hop limit to use for the response
uint8_t getHopLimitForResponse(uint8_t hopStart, uint8_t hopLimit);
protected:
friend class Router;

View File

@@ -126,8 +126,13 @@ int32_t SerialModule::runOnce()
uint32_t baud = getBaudRate();
if (moduleConfig.serial.override_console_serial_port) {
#ifdef RP2040_SLOW_CLOCK
Serial2.flush();
serialPrint = &Serial2;
#else
Serial.flush();
serialPrint = &Serial;
#endif
// Give it a chance to flush out 💩
delay(10);
}
@@ -151,8 +156,13 @@ int32_t SerialModule::runOnce()
Serial2.begin(baud, SERIAL_8N1);
Serial2.setTimeout(moduleConfig.serial.timeout > 0 ? moduleConfig.serial.timeout : TIMEOUT);
} else {
#ifdef RP2040_SLOW_CLOCK
Serial2.begin(baud, SERIAL_8N1);
Serial2.setTimeout(moduleConfig.serial.timeout > 0 ? moduleConfig.serial.timeout : TIMEOUT);
#else
Serial.begin(baud, SERIAL_8N1);
Serial.setTimeout(moduleConfig.serial.timeout > 0 ? moduleConfig.serial.timeout : TIMEOUT);
#endif
}
#else
Serial.begin(baud, SERIAL_8N1);

View File

@@ -1,5 +1,6 @@
#include "AirQualityTelemetry.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "Default.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
@@ -43,7 +44,7 @@ int32_t AirQualityTelemetryModule::runOnce()
uint32_t now = millis();
if (((lastSentToMesh == 0) ||
((now - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.telemetry.air_quality_interval))) &&
((now - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.air_quality_interval))) &&
airTime->isTxAllowedAirUtil()) {
sendTelemetry();
lastSentToMesh = now;
@@ -112,7 +113,7 @@ bool AirQualityTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
if (config.device.role == meshtastic_Config_DeviceConfig_Role_SENSOR)
p->priority = meshtastic_MeshPacket_Priority_RELIABLE;
else
p->priority = meshtastic_MeshPacket_Priority_MIN;
p->priority = meshtastic_MeshPacket_Priority_BACKGROUND;
// release previous packet before occupying a new spot
if (lastMeasurementPacket != nullptr)

View File

@@ -1,5 +1,6 @@
#include "DeviceTelemetry.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "Default.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
@@ -16,7 +17,7 @@ int32_t DeviceTelemetryModule::runOnce()
{
uint32_t now = millis();
if (((lastSentToMesh == 0) ||
((now - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.telemetry.device_update_interval))) &&
((now - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.device_update_interval))) &&
airTime->isTxAllowedChannelUtil() && airTime->isTxAllowedAirUtil() &&
config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER &&
config.device.role != meshtastic_Config_DeviceConfig_Role_CLIENT_HIDDEN) {
@@ -91,7 +92,7 @@ bool DeviceTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
meshtastic_MeshPacket *p = allocDataProtobuf(telemetry);
p->to = dest;
p->decoded.want_response = false;
p->priority = meshtastic_MeshPacket_Priority_MIN;
p->priority = meshtastic_MeshPacket_Priority_BACKGROUND;
nodeDB.updateTelemetry(nodeDB.getNodeNum(), telemetry, RX_SRC_LOCAL);
if (phoneOnly) {

View File

@@ -1,5 +1,6 @@
#include "EnvironmentTelemetry.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "Default.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
@@ -16,12 +17,14 @@
// Sensors
#include "Sensor/BME280Sensor.h"
#include "Sensor/BME680Sensor.h"
#include "Sensor/BMP085Sensor.h"
#include "Sensor/BMP280Sensor.h"
#include "Sensor/LPS22HBSensor.h"
#include "Sensor/MCP9808Sensor.h"
#include "Sensor/SHT31Sensor.h"
#include "Sensor/SHTC3Sensor.h"
BMP085Sensor bmp085Sensor;
BMP280Sensor bmp280Sensor;
BME280Sensor bme280Sensor;
BME680Sensor bme680Sensor;
@@ -33,29 +36,13 @@ SHT31Sensor sht31Sensor;
#define FAILED_STATE_SENSOR_READ_MULTIPLIER 10
#define DISPLAY_RECEIVEID_MEASUREMENTS_ON_SCREEN true
#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \
!defined(DISPLAY_FORCE_SMALL_FONTS)
// The screen is bigger so use bigger fonts
#define FONT_SMALL ArialMT_Plain_16
#define FONT_MEDIUM ArialMT_Plain_24
#define FONT_LARGE ArialMT_Plain_24
#else
#define FONT_SMALL ArialMT_Plain_10
#define FONT_MEDIUM ArialMT_Plain_16
#define FONT_LARGE ArialMT_Plain_24
#endif
#define fontHeight(font) ((font)[1] + 1) // height is position 1
#define FONT_HEIGHT_SMALL fontHeight(FONT_SMALL)
#define FONT_HEIGHT_MEDIUM fontHeight(FONT_MEDIUM)
#include "graphics/ScreenFonts.h"
int32_t EnvironmentTelemetryModule::runOnce()
{
if (sleepOnNextExecution == true) {
sleepOnNextExecution = false;
uint32_t nightyNightMs = getConfiguredOrDefaultMs(moduleConfig.telemetry.environment_update_interval);
uint32_t nightyNightMs = Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.environment_update_interval);
LOG_DEBUG("Sleeping for %ims, then awaking to send metrics again.\n", nightyNightMs);
doDeepSleep(nightyNightMs, true);
}
@@ -83,6 +70,8 @@ int32_t EnvironmentTelemetryModule::runOnce()
LOG_INFO("Environment Telemetry: Initializing\n");
// it's possible to have this module enabled, only for displaying values on the screen.
// therefore, we should only enable the sensor loop if measurement is also enabled
if (bmp085Sensor.hasSensor())
result = bmp085Sensor.runOnce();
if (bmp280Sensor.hasSensor())
result = bmp280Sensor.runOnce();
if (bme280Sensor.hasSensor())
@@ -114,7 +103,7 @@ int32_t EnvironmentTelemetryModule::runOnce()
uint32_t now = millis();
if (((lastSentToMesh == 0) ||
((now - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.telemetry.environment_update_interval))) &&
((now - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.environment_update_interval))) &&
airTime->isTxAllowedAirUtil()) {
sendTelemetry();
lastSentToMesh = now;
@@ -235,6 +224,8 @@ bool EnvironmentTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
valid = lps22hbSensor.getMetrics(&m);
if (shtc3Sensor.hasSensor())
valid = shtc3Sensor.getMetrics(&m);
if (bmp085Sensor.hasSensor())
valid = bmp085Sensor.getMetrics(&m);
if (bmp280Sensor.hasSensor())
valid = bmp280Sensor.getMetrics(&m);
if (bme280Sensor.hasSensor())
@@ -263,7 +254,7 @@ bool EnvironmentTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
if (config.device.role == meshtastic_Config_DeviceConfig_Role_SENSOR)
p->priority = meshtastic_MeshPacket_Priority_RELIABLE;
else
p->priority = meshtastic_MeshPacket_Priority_MIN;
p->priority = meshtastic_MeshPacket_Priority_BACKGROUND;
// release previous packet before occupying a new spot
if (lastMeasurementPacket != nullptr)
packetPool.release(lastMeasurementPacket);

View File

@@ -1,5 +1,6 @@
#include "PowerTelemetry.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "Default.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
@@ -14,29 +15,13 @@
#define FAILED_STATE_SENSOR_READ_MULTIPLIER 10
#define DISPLAY_RECEIVEID_MEASUREMENTS_ON_SCREEN true
#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \
!defined(DISPLAY_FORCE_SMALL_FONTS)
// The screen is bigger so use bigger fonts
#define FONT_SMALL ArialMT_Plain_16
#define FONT_MEDIUM ArialMT_Plain_24
#define FONT_LARGE ArialMT_Plain_24
#else
#define FONT_SMALL ArialMT_Plain_10
#define FONT_MEDIUM ArialMT_Plain_16
#define FONT_LARGE ArialMT_Plain_24
#endif
#define fontHeight(font) ((font)[1] + 1) // height is position 1
#define FONT_HEIGHT_SMALL fontHeight(FONT_SMALL)
#define FONT_HEIGHT_MEDIUM fontHeight(FONT_MEDIUM)
#include "graphics/ScreenFonts.h"
int32_t PowerTelemetryModule::runOnce()
{
if (sleepOnNextExecution == true) {
sleepOnNextExecution = false;
uint32_t nightyNightMs = getConfiguredOrDefaultMs(moduleConfig.telemetry.power_update_interval);
uint32_t nightyNightMs = Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.power_update_interval);
LOG_DEBUG("Sleeping for %ims, then awaking to send metrics again.\n", nightyNightMs);
doDeepSleep(nightyNightMs, true);
}
@@ -82,7 +67,7 @@ int32_t PowerTelemetryModule::runOnce()
uint32_t now = millis();
if (((lastSentToMesh == 0) ||
((now - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.telemetry.power_update_interval))) &&
((now - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.power_update_interval))) &&
airTime->isTxAllowedAirUtil()) {
sendTelemetry();
lastSentToMesh = now;
@@ -211,7 +196,7 @@ bool PowerTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
if (config.device.role == meshtastic_Config_DeviceConfig_Role_SENSOR)
p->priority = meshtastic_MeshPacket_Priority_RELIABLE;
else
p->priority = meshtastic_MeshPacket_Priority_MIN;
p->priority = meshtastic_MeshPacket_Priority_BACKGROUND;
// release previous packet before occupying a new spot
if (lastMeasurementPacket != nullptr)
packetPool.release(lastMeasurementPacket);

View File

@@ -0,0 +1,31 @@
#include "BMP085Sensor.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include "configuration.h"
#include <Adafruit_BMP085.h>
#include <typeinfo>
BMP085Sensor::BMP085Sensor() : TelemetrySensor(meshtastic_TelemetrySensorType_BMP085, "BMP085") {}
int32_t BMP085Sensor::runOnce()
{
LOG_INFO("Init sensor: %s\n", sensorName);
if (!hasSensor()) {
return DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS;
}
bmp085 = Adafruit_BMP085();
status = bmp085.begin(nodeTelemetrySensorsMap[sensorType].first, nodeTelemetrySensorsMap[sensorType].second);
return initI2CSensor();
}
void BMP085Sensor::setup() {}
bool BMP085Sensor::getMetrics(meshtastic_Telemetry *measurement)
{
LOG_DEBUG("BMP085Sensor::getMetrics\n");
measurement->variant.environment_metrics.temperature = bmp085.readTemperature();
measurement->variant.environment_metrics.barometric_pressure = bmp085.readPressure() / 100.0F;
return true;
}

View File

@@ -0,0 +1,17 @@
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include <Adafruit_BMP085.h>
class BMP085Sensor : public TelemetrySensor
{
private:
Adafruit_BMP085 bmp085;
protected:
virtual void setup() override;
public:
BMP085Sensor();
virtual int32_t runOnce() override;
virtual bool getMetrics(meshtastic_Telemetry *measurement) override;
};

View File

@@ -4,6 +4,10 @@
#include "configuration.h"
#include <Adafruit_INA219.h>
#ifndef INA219_MULTIPLIER
#define INA219_MULTIPLIER 1.0f
#endif
INA219Sensor::INA219Sensor() : TelemetrySensor(meshtastic_TelemetrySensorType_INA219, "INA219") {}
int32_t INA219Sensor::runOnce()
@@ -26,7 +30,7 @@ void INA219Sensor::setup() {}
bool INA219Sensor::getMetrics(meshtastic_Telemetry *measurement)
{
measurement->variant.environment_metrics.voltage = ina219.getBusVoltage_V();
measurement->variant.environment_metrics.current = ina219.getCurrent_mA();
measurement->variant.environment_metrics.current = ina219.getCurrent_mA() * INA219_MULTIPLIER;
return true;
}

View File

@@ -12,7 +12,8 @@ int32_t SHT31Sensor::runOnce()
if (!hasSensor()) {
return DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS;
}
status = sht31.begin();
sht31 = Adafruit_SHT31(nodeTelemetrySensorsMap[sensorType].second);
status = sht31.begin(nodeTelemetrySensorsMap[sensorType].first);
return initI2CSensor();
}

View File

@@ -5,7 +5,7 @@
class SHT31Sensor : public TelemetrySensor
{
private:
Adafruit_SHT31 sht31 = Adafruit_SHT31();
Adafruit_SHT31 sht31;
protected:
virtual void setup() override;

View File

@@ -8,14 +8,6 @@
#include "RTC.h"
#include "Router.h"
#ifdef OLED_RU
#include "graphics/fonts/OLEDDisplayFontsRU.h"
#endif
#ifdef OLED_UA
#include "graphics/fonts/OLEDDisplayFontsUA.h"
#endif
/*
AudioModule
A interface to send raw codec2 audio data over the mesh network. Based on the example code from the ESP32_codec2 project.
@@ -48,32 +40,7 @@ AudioModule *audioModule;
#define YIELD_FROM_ISR(x) portYIELD_FROM_ISR(x)
#endif
#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \
!defined(DISPLAY_FORCE_SMALL_FONTS)
// The screen is bigger so use bigger fonts
#define FONT_SMALL ArialMT_Plain_16
#define FONT_MEDIUM ArialMT_Plain_24
#define FONT_LARGE ArialMT_Plain_24
#else
#ifdef OLED_RU
#define FONT_SMALL ArialMT_Plain_10_RU
#else
#ifdef OLED_UA
#define FONT_SMALL ArialMT_Plain_10_UA
#else
#define FONT_SMALL ArialMT_Plain_10
#endif
#endif
#define FONT_MEDIUM ArialMT_Plain_16
#define FONT_LARGE ArialMT_Plain_24
#endif
#define fontHeight(font) ((font)[1] + 1) // height is position 1
#define FONT_HEIGHT_SMALL fontHeight(FONT_SMALL)
#define FONT_HEIGHT_MEDIUM fontHeight(FONT_MEDIUM)
#define FONT_HEIGHT_LARGE fontHeight(FONT_LARGE)
#include "graphics/ScreenFonts.h"
void run_codec2(void *parameter)
{

View File

@@ -1,15 +1,25 @@
#include "configuration.h"
#if defined(ARCH_ESP32)
#include "Default.h"
#include "MeshService.h"
#include "PaxcounterModule.h"
#include <assert.h>
PaxcounterModule *paxcounterModule;
void NullFunc(){};
// paxcounterModule->sendInfo(NODENUM_BROADCAST);
/**
* Callback function for libpax.
* We only clear our sent flag here, since this function is called from another thread, so we
* cannot send to the mesh directly.
*/
void PaxcounterModule::handlePaxCounterReportRequest()
{
// The libpax library already updated our data structure, just before invoking this callback.
LOG_INFO("PaxcounterModule: libpax reported new data: wifi=%d; ble=%d; uptime=%lu\n",
paxcounterModule->count_from_libpax.wifi_count, paxcounterModule->count_from_libpax.ble_count, millis() / 1000);
paxcounterModule->reportedDataSent = false;
paxcounterModule->setIntervalFromNow(0);
}
PaxcounterModule::PaxcounterModule()
: concurrency::OSThread("PaxcounterModule"),
@@ -17,11 +27,20 @@ PaxcounterModule::PaxcounterModule()
{
}
/**
* Send the Pax information to the mesh if we got new data from libpax.
* This is called periodically from our runOnce() method and will actually send the data to the mesh
* if libpax updated it since the last transmission through the callback.
* @param dest - destination node (usually NODENUM_BROADCAST)
* @return false if sending is unnecessary, true if information was sent
*/
bool PaxcounterModule::sendInfo(NodeNum dest)
{
libpax_counter_count(&count_from_libpax);
LOG_INFO("(Sending): pax: wifi=%d; ble=%d; uptime=%d\n", count_from_libpax.wifi_count, count_from_libpax.ble_count,
millis() / 1000);
if (paxcounterModule->reportedDataSent)
return false;
LOG_INFO("PaxcounterModule: sending pax info wifi=%d; ble=%d; uptime=%lu\n", count_from_libpax.wifi_count,
count_from_libpax.ble_count, millis() / 1000);
meshtastic_Paxcount pl = meshtastic_Paxcount_init_default;
pl.wifi = count_from_libpax.wifi_count;
@@ -31,9 +50,12 @@ bool PaxcounterModule::sendInfo(NodeNum dest)
meshtastic_MeshPacket *p = allocDataProtobuf(pl);
p->to = dest;
p->decoded.want_response = false;
p->priority = meshtastic_MeshPacket_Priority_MIN;
p->priority = meshtastic_MeshPacket_Priority_BACKGROUND;
service.sendToMesh(p, RX_SRC_LOCAL, true);
paxcounterModule->reportedDataSent = true;
return true;
}
@@ -60,14 +82,14 @@ int32_t PaxcounterModule::runOnce()
if (isActive()) {
if (firstTime) {
firstTime = false;
LOG_DEBUG(
"Paxcounter starting up with interval of %d seconds\n",
getConfiguredOrDefault(moduleConfig.paxcounter.paxcounter_update_interval, default_broadcast_interval_secs));
LOG_DEBUG("Paxcounter starting up with interval of %d seconds\n",
Default::getConfiguredOrDefault(moduleConfig.paxcounter.paxcounter_update_interval,
default_broadcast_interval_secs));
struct libpax_config_t configuration;
libpax_default_config(&configuration);
configuration.blecounter = 1;
configuration.blescantime = 0; // infinit
configuration.blescantime = 0; // infinite
configuration.wificounter = 1;
configuration.wifi_channel_map = WIFI_CHANNEL_ALL;
configuration.wifi_channel_switch_interval = 50;
@@ -76,12 +98,14 @@ int32_t PaxcounterModule::runOnce()
libpax_update_config(&configuration);
// internal processing initialization
libpax_counter_init(NullFunc, &count_from_libpax, UINT16_MAX, 1);
libpax_counter_init(handlePaxCounterReportRequest, &count_from_libpax,
moduleConfig.paxcounter.paxcounter_update_interval, 0);
libpax_counter_start();
} else {
sendInfo(NODENUM_BROADCAST);
}
return getConfiguredOrDefaultMs(moduleConfig.paxcounter.paxcounter_update_interval, default_broadcast_interval_secs);
return Default::getConfiguredOrDefaultMs(moduleConfig.paxcounter.paxcounter_update_interval,
default_broadcast_interval_secs);
} else {
return disable();
}
@@ -89,38 +113,7 @@ int32_t PaxcounterModule::runOnce()
#if HAS_SCREEN
#ifdef OLED_RU
#include "graphics/fonts/OLEDDisplayFontsRU.h"
#endif
#ifdef OLED_UA
#include "graphics/fonts/OLEDDisplayFontsUA.h"
#endif
// TODO / FIXME: This code is copied from src/graphics/Screen.cpp
// It appears (in slightly variants) also in other modules like
// src/modules/Telemetry/PowerTelemetry.cpp, src/modules/Telemetry/EnvironmentTelemetry.cpp
// and src/modules/CannedMessageModule.cpp
// It probably should go to a common header file for consistency
#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS) || defined(ST7789_CS)) && \
!defined(DISPLAY_FORCE_SMALL_FONTS)
// The screen is bigger so use bigger fonts
#define FONT_SMALL ArialMT_Plain_16 // Height: 19
#define FONT_MEDIUM ArialMT_Plain_24 // Height: 28
#define FONT_LARGE ArialMT_Plain_24 // Height: 28
#else
#ifdef OLED_RU
#define FONT_SMALL ArialMT_Plain_10_RU
#else
#ifdef OLED_UA
#define FONT_SMALL ArialMT_Plain_10_UA
#else
#define FONT_SMALL ArialMT_Plain_10 // Height: 13
#endif
#endif
#define FONT_MEDIUM ArialMT_Plain_16 // Height: 19
#define FONT_LARGE ArialMT_Plain_24 // Height: 28
#endif
#include "graphics/ScreenFonts.h"
void PaxcounterModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
@@ -138,4 +131,4 @@ void PaxcounterModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state
}
#endif // HAS_SCREEN
#endif
#endif

View File

@@ -8,11 +8,15 @@
#include <libpax_api.h>
/**
* A simple example module that just replies with "Message received" to any message it receives.
* Wrapper module for the estimate passenger (PAX) count library (https://github.com/dbinfrago/libpax) which
* implements the core functionality of the ESP32 Paxcounter project (https://github.com/cyberman54/ESP32-Paxcounter)
*/
class PaxcounterModule : private concurrency::OSThread, public ProtobufModule<meshtastic_Paxcount>
{
bool firstTime = true;
bool reportedDataSent = true;
static void handlePaxCounterReportRequest();
public:
PaxcounterModule();

View File

@@ -255,7 +255,7 @@ void StoreForwardModule::sendMessage(NodeNum dest, const meshtastic_StoreAndForw
p->to = dest;
p->priority = meshtastic_MeshPacket_Priority_MIN;
p->priority = meshtastic_MeshPacket_Priority_BACKGROUND;
// FIXME - Determine if the delayed packet is broadcast or delayed. For now, assume
// everything is broadcast.
@@ -334,7 +334,7 @@ ProcessMessage StoreForwardModule::handleReceived(const meshtastic_MeshPacket &m
LOG_INFO("*** S&F - Busy. Try again shortly.\n");
meshtastic_MeshPacket *pr = allocReply();
pr->to = getFrom(&mp);
pr->priority = meshtastic_MeshPacket_Priority_MIN;
pr->priority = meshtastic_MeshPacket_Priority_BACKGROUND;
pr->want_ack = false;
pr->decoded.want_response = false;
pr->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_APP;

View File

@@ -17,6 +17,7 @@
#include "mesh/wifi/WiFiAPClient.h"
#include <WiFi.h>
#endif
#include "Default.h"
#include <assert.h>
const int reconnectMax = 5;
@@ -77,8 +78,7 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length)
if (jsonPayloadStr.length() <= sizeof(p->decoded.payload.bytes)) {
memcpy(p->decoded.payload.bytes, jsonPayloadStr.c_str(), jsonPayloadStr.length());
p->decoded.payload.size = jsonPayloadStr.length();
meshtastic_MeshPacket *packet = packetPool.allocCopy(*p);
service.sendToMesh(packet, RX_SRC_LOCAL);
service.sendToMesh(p, RX_SRC_LOCAL);
} else {
LOG_WARN("Received MQTT json payload too long, dropping\n");
}
@@ -186,10 +186,17 @@ MQTT::MQTT() : concurrency::OSThread("mqtt"), mqttQueue(MAX_MQTT_QUEUE)
statusTopic = moduleConfig.mqtt.root + statusTopic;
cryptTopic = moduleConfig.mqtt.root + cryptTopic;
jsonTopic = moduleConfig.mqtt.root + jsonTopic;
mapTopic = moduleConfig.mqtt.root + mapTopic;
} else {
statusTopic = "msh" + statusTopic;
cryptTopic = "msh" + cryptTopic;
jsonTopic = "msh" + jsonTopic;
mapTopic = "msh" + mapTopic;
}
if (moduleConfig.mqtt.map_reporting_enabled && moduleConfig.mqtt.has_map_report_settings) {
map_position_precision = moduleConfig.mqtt.map_report_settings.position_precision;
map_publish_interval_secs = moduleConfig.mqtt.map_report_settings.publish_interval_secs;
}
#ifdef HAS_NETWORKING
@@ -365,38 +372,30 @@ void MQTT::sendSubscriptions()
bool MQTT::wantsLink() const
{
bool hasChannel = false;
bool hasChannelorMapReport =
moduleConfig.mqtt.enabled && (moduleConfig.mqtt.map_reporting_enabled || channels.anyMqttEnabled());
if (moduleConfig.mqtt.enabled) {
// No need for link if no channel needed it
size_t numChan = channels.getNumChannels();
for (size_t i = 0; i < numChan; i++) {
const auto &ch = channels.getByIndex(i);
if (ch.settings.uplink_enabled || ch.settings.downlink_enabled) {
hasChannel = true;
break;
}
}
}
if (hasChannel && moduleConfig.mqtt.proxy_to_client_enabled)
if (hasChannelorMapReport && moduleConfig.mqtt.proxy_to_client_enabled)
return true;
#if HAS_WIFI
return hasChannel && WiFi.isConnected();
return hasChannelorMapReport && WiFi.isConnected();
#endif
#if HAS_ETHERNET
return hasChannel && Ethernet.linkStatus() == LinkON;
return hasChannelorMapReport && Ethernet.linkStatus() == LinkON;
#endif
return false;
}
int32_t MQTT::runOnce()
{
if (!moduleConfig.mqtt.enabled)
if (!moduleConfig.mqtt.enabled || !(moduleConfig.mqtt.map_reporting_enabled || channels.anyMqttEnabled()))
return disable();
bool wantConnection = wantsLink();
perhapsReportToMap();
// If connected poll rapidly, otherwise only occasionally check for a wifi connection change and ability to contact server
if (moduleConfig.mqtt.proxy_to_client_enabled) {
publishQueuedMessages();
@@ -475,9 +474,9 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket &
auto &ch = channels.getByIndex(chIndex);
if (&mp.decoded && strcmp(moduleConfig.mqtt.address, default_mqtt_address) == 0 &&
(mp.decoded.portnum == meshtastic_PortNum_RANGE_TEST_APP ||
mp.decoded.portnum == meshtastic_PortNum_DETECTION_SENSOR_APP)) {
if (&mp_decoded.decoded && strcmp(moduleConfig.mqtt.address, default_mqtt_address) == 0 &&
(mp_decoded.decoded.portnum == meshtastic_PortNum_RANGE_TEST_APP ||
mp_decoded.decoded.portnum == meshtastic_PortNum_DETECTION_SENSOR_APP)) {
LOG_DEBUG("MQTT onSend - Ignoring range test or detection sensor message on public mqtt\n");
return;
}
@@ -536,6 +535,78 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket &
}
}
void MQTT::perhapsReportToMap()
{
if (!moduleConfig.mqtt.map_reporting_enabled || !(moduleConfig.mqtt.proxy_to_client_enabled || isConnectedDirectly()))
return;
if (millis() - last_report_to_map < map_publish_interval_secs * 1000) {
return;
} else {
if (map_position_precision == 0 || (localPosition.latitude_i == 0 && localPosition.longitude_i == 0)) {
LOG_WARN("MQTT Map reporting is enabled, but precision is 0 or no position available.\n");
return;
}
// Allocate ServiceEnvelope and fill it
meshtastic_ServiceEnvelope *se = mqttPool.allocZeroed();
se->channel_id = (char *)channels.getGlobalId(channels.getPrimaryIndex()); // Use primary channel as the channel_id
se->gateway_id = owner.id;
// Allocate MeshPacket and fill it
meshtastic_MeshPacket *mp = packetPool.allocZeroed();
mp->which_payload_variant = meshtastic_MeshPacket_decoded_tag;
mp->from = nodeDB.getNodeNum();
mp->to = NODENUM_BROADCAST;
mp->decoded.portnum = meshtastic_PortNum_MAP_REPORT_APP;
// Fill MapReport message
meshtastic_MapReport mapReport = meshtastic_MapReport_init_default;
memcpy(mapReport.long_name, owner.long_name, sizeof(owner.long_name));
memcpy(mapReport.short_name, owner.short_name, sizeof(owner.short_name));
mapReport.role = config.device.role;
mapReport.hw_model = owner.hw_model;
strncpy(mapReport.firmware_version, optstr(APP_VERSION), sizeof(mapReport.firmware_version));
mapReport.region = config.lora.region;
mapReport.modem_preset = config.lora.modem_preset;
mapReport.has_default_channel = channels.hasDefaultChannel();
// Set position with precision (same as in PositionModule)
if (map_position_precision < 32 && map_position_precision > 0) {
mapReport.latitude_i = localPosition.latitude_i & (UINT32_MAX << (32 - map_position_precision));
mapReport.longitude_i = localPosition.longitude_i & (UINT32_MAX << (32 - map_position_precision));
mapReport.latitude_i += (1 << (31 - map_position_precision));
mapReport.longitude_i += (1 << (31 - map_position_precision));
} else {
mapReport.latitude_i = localPosition.latitude_i;
mapReport.longitude_i = localPosition.longitude_i;
}
mapReport.altitude = localPosition.altitude;
mapReport.position_precision = map_position_precision;
mapReport.num_online_local_nodes = nodeDB.getNumOnlineMeshNodes(true);
// Encode MapReport message and set it to MeshPacket in ServiceEnvelope
mp->decoded.payload.size = pb_encode_to_bytes(mp->decoded.payload.bytes, sizeof(mp->decoded.payload.bytes),
&meshtastic_MapReport_msg, &mapReport);
se->packet = mp;
// FIXME - this size calculation is super sloppy, but it will go away once we dynamically alloc meshpackets
static uint8_t bytes[meshtastic_MeshPacket_size + 64];
size_t numBytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_ServiceEnvelope_msg, se);
LOG_INFO("MQTT Publish map report to %s\n", mapTopic.c_str());
publish(mapTopic.c_str(), bytes, numBytes, false);
// Release the allocated memory for ServiceEnvelope and MeshPacket
mqttPool.release(se);
packetPool.release(mp);
// Update the last report time
last_report_to_map = millis();
}
}
// converts a downstream packet into a json message
std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp)
{
@@ -655,6 +726,9 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp)
if ((int)decoded->VDOP) {
msgPayload["VDOP"] = new JSONValue((int)decoded->VDOP);
}
if ((int)decoded->precision_bits) {
msgPayload["precision_bits"] = new JSONValue((int)decoded->precision_bits);
}
jsonObj["payload"] = new JSONValue(msgPayload);
} else {
LOG_ERROR("Error decoding protobuf for position message!\n");
@@ -808,6 +882,8 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp)
jsonObj["rssi"] = new JSONValue((int)mp->rx_rssi);
if (mp->rx_snr != 0)
jsonObj["snr"] = new JSONValue((float)mp->rx_snr);
if (mp->hop_start != 0 && mp->hop_limit <= mp->hop_start)
jsonObj["hops_away"] = new JSONValue((uint)(mp->hop_start - mp->hop_limit));
// serialize and write it to the stream
JSONValue *value = new JSONValue(jsonObj);

View File

@@ -71,6 +71,10 @@ class MQTT : private concurrency::OSThread
void onClientProxyReceive(meshtastic_MqttClientProxyMessage msg);
bool isEnabled() { return this->enabled; };
void start() { setIntervalFromNow(0); };
protected:
PointerQueue<meshtastic_ServiceEnvelope> mqttQueue;
@@ -79,10 +83,17 @@ class MQTT : private concurrency::OSThread
virtual int32_t runOnce() override;
private:
std::string statusTopic = "/2/stat/";
std::string cryptTopic = "/2/c/"; // msh/2/c/CHANNELID/NODEID
std::string jsonTopic = "/2/json/"; // msh/2/json/CHANNELID/NODEID
/** return true if we have a channel that wants uplink/downlink
std::string statusTopic = "/2/stat/"; // For "online"/"offline" message
std::string cryptTopic = "/2/e/"; // msh/2/e/CHANNELID/NODEID
std::string jsonTopic = "/2/json/"; // msh/2/json/CHANNELID/NODEID
std::string mapTopic = "/2/map/"; // For protobuf-encoded MapReport messages
// For map reporting (only applies when enabled)
uint32_t last_report_to_map = 0;
uint32_t map_position_precision = 32; // default to full precision
uint32_t map_publish_interval_secs = 60 * 15; // default to 15 minutes
/** return true if we have a channel that wants uplink/downlink or map reporting is enabled
*/
bool wantsLink() const;
@@ -102,6 +113,9 @@ class MQTT : private concurrency::OSThread
void publishStatus();
void publishQueuedMessages();
// Check if we should report unencrypted information about our node for consumption by a map
void perhapsReportToMap();
// returns true if this is a valid JSON envelope which we accept on downlink
bool isValidJsonEnvelope(JSONObject &json);

View File

@@ -16,5 +16,5 @@ class NimbleBluetooth : BluetoothApi
void startAdvertising();
};
void setBluetoothEnable(bool on);
void clearNVS();
void setBluetoothEnable(bool enable);
void clearNVS();

View File

@@ -20,21 +20,21 @@
#if !defined(CONFIG_IDF_TARGET_ESP32S2)
void setBluetoothEnable(bool on)
void setBluetoothEnable(bool enable)
{
if (!isWifiAvailable() && config.bluetooth.enabled == true) {
if (!nimbleBluetooth) {
nimbleBluetooth = new NimbleBluetooth();
}
if (on && !nimbleBluetooth->isActive()) {
if (enable && !nimbleBluetooth->isActive()) {
nimbleBluetooth->setup();
} else if (!on) {
} else if (!enable) {
nimbleBluetooth->shutdown();
}
}
}
#else
void setBluetoothEnable(bool on) {}
void setBluetoothEnable(bool enable) {}
void updateBatteryLevel(uint8_t level) {}
#endif

View File

@@ -202,16 +202,16 @@ void setupMeshService(void)
toRadio.begin();
}
// FIXME, turn off soft device access for debugging
static bool isSoftDeviceAllowed = true;
static uint32_t configuredPasskey;
void NRF52Bluetooth::shutdown()
{
// Shutdown bluetooth for minimum power draw
LOG_INFO("Disable NRF52 bluetooth\n");
if (connectionHandle != 0) {
Bluefruit.disconnect(connectionHandle);
}
Bluefruit.Advertising.stop();
Bluefruit.setTxPower(0); // Minimum power
}
bool NRF52Bluetooth::isConnected()
@@ -279,14 +279,19 @@ void NRF52Bluetooth::setup()
LOG_INFO("Configuring the Mesh bluetooth service\n");
setupMeshService();
// Supposedly debugging works with soft device if you disable advertising
if (isSoftDeviceAllowed) {
// Setup the advertising packet(s)
LOG_INFO("Setting up the advertising payload(s)\n");
startAdv();
// Setup the advertising packet(s)
LOG_INFO("Setting up the advertising payload(s)\n");
startAdv();
LOG_INFO("Advertising\n");
}
LOG_INFO("Advertising\n");
}
void NRF52Bluetooth::resumeAdverising()
{
Bluefruit.Advertising.restartOnDisconnect(true);
Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms
Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode
Bluefruit.Advertising.start(0);
}
/// Given a level between 0-100, update the BLE attribute

View File

@@ -8,6 +8,7 @@ class NRF52Bluetooth : BluetoothApi
public:
void setup();
void shutdown();
void resumeAdverising();
void clearBonds();
bool isConnected();
int getRssi();
@@ -17,4 +18,4 @@ class NRF52Bluetooth : BluetoothApi
void convertToUint8(uint8_t target[4], uint32_t source);
static bool onPairingPasskey(uint16_t conn_handle, uint8_t const passkey[6], bool match_request);
static void onPairingCompleted(uint16_t conn_handle, uint8_t auth_status);
};
};

Some files were not shown because too many files have changed in this diff Show More