Compare commits

...

226 Commits

Author SHA1 Message Date
Ben Meadors
a6b115b2dc Merge branch 'master' into no-arduino-strings 2025-06-01 15:56:37 -05:00
Ben Meadors
6749d9ffc5 Get rid of Arduino Strings 2025-06-01 15:54:54 -05:00
Ben Meadors
21404de7fc Name cleanup 2025-05-31 19:30:53 -05:00
Ben Meadors
0f69f6ca71 Draw columns 2025-05-31 17:32:08 -05:00
Ben Meadors
633924ced8 Fixed compassarrow renderer 2025-05-31 15:41:54 -05:00
Ben Meadors
298e5d36c9 Another 2025-05-31 13:51:30 -05:00
Ben Meadors
3770e43d86 Moar 2025-05-31 13:45:02 -05:00
Ben Meadors
6e376aeea6 CompassRenderer methods 2025-05-31 13:22:14 -05:00
Ben Meadors
6f922641b2 Put the imperial back 2025-05-31 11:13:16 -05:00
Ben Meadors
0ced4188b6 Move drawfunctionoverlay 2025-05-31 10:52:17 -05:00
Ben Meadors
f34b9859c6 Fully qualify 2025-05-31 09:38:56 -05:00
Ben Meadors
e7e15af282 Update src/graphics/draw/NotificationRenderer.cpp
Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com>
2025-05-31 09:32:26 -05:00
Ben Meadors
d1c86a088a Update alignments and spacing 2025-05-31 09:13:14 -05:00
Ben Meadors
0a5e703a94 Remove useless wrapper functions 2025-05-31 09:09:43 -05:00
Ben Meadors
22be1f031d Eink fixes 2025-05-31 08:50:42 -05:00
Ben Meadors
b1e7a26dfc Move EInk ones 2025-05-31 08:45:02 -05:00
Ben Meadors
134e01aa70 Merge remote-tracking branch 'origin/unify-tft' into screen-refactor 2025-05-31 07:38:29 -05:00
Ben Meadors
a30f5c8d93 Namespacing and more moved methods 2025-05-31 07:35:38 -05:00
Ben Meadors
1df2f32ae0 Draw nodes and device focused 2025-05-31 06:39:14 -05:00
Jonathan Bennett
0edccf5b86 Do position broadcast on secondary channel if disabled on primary (#6920)
* Do default position broadcast on secondary channel if disabled on primary

* Consolidate the ifs

* For Loops, how do they work?
2025-05-31 06:21:55 -05:00
Ben Meadors
29402a5e7a Notification and time 2025-05-30 20:50:24 -05:00
Ben Meadors
6627f2e873 WIP 2025-05-30 19:11:13 -05:00
Ben Meadors
5bdae47379 WIP Screen.cpp refactoring 2025-05-30 14:20:31 -05:00
Jason P
3df894106b Update alignments and spacing (#6924)
-Update alignment on node list
-Adjust signal bar baseline
2025-05-30 11:34:45 -05:00
Jonathan Bennett
218f5bdbf3 Move keyVerification messages to showOverlayBanner 2025-05-30 11:14:14 -05:00
Jonathan Bennett
749c3ca53c Add missed merge line 2025-05-30 09:51:29 -05:00
Jonathan Bennett
43aa906017 trunk 2025-05-30 09:31:13 -05:00
Jonathan Bennett
763c80e571 Merge remote-tracking branch 'baseui/StandaloneAddons' into unify-tft 2025-05-30 09:29:45 -05:00
Jonathan Bennett
8cbc5fbeae Merge branch 'master' into unify-tft 2025-05-30 09:01:03 -05:00
HarukiToreda
ea9c71ecd9 Unified header for sending. 2025-05-30 02:11:04 -04:00
HarukiToreda
53f2f615b2 Tdeck fixes and cursor support added 2025-05-30 00:56:19 -04:00
HarukiToreda
fe3ad06d21 Merge branch 'meshtastic:master' into StandaloneAddons 2025-05-29 15:16:48 -04:00
Jonathan Bennett
5f36da4374 Merge branch 'master' into unify-tft 2025-05-29 14:14:21 -05:00
HarukiToreda
699e1a15b3 Fix horizontal battery for EInk and adjust favorite node notation on node lists 2025-05-29 13:48:30 -04:00
HarukiToreda
69058002d7 Eink Cycling code moving frames 2025-05-29 11:34:22 -04:00
Manuel
9fc98b1154 Merge branch 'master' into unify-tft 2025-05-29 14:33:02 +02:00
HarukiToreda
303006e1df Indents indents indents 2025-05-29 02:31:09 -04:00
HarukiToreda
69a08cb69d GPS compass now supports portrait and square displays 2025-05-29 01:57:59 -04:00
HarukiToreda
ac0547ca3e Support for Comapass on square and portrait screens 2025-05-29 01:44:06 -04:00
HarukiToreda
a66f381a5d Compact lines for Device focus screen 2025-05-28 23:22:11 -04:00
HarukiToreda
fda6de2f51 Favorite Node Info screens 2025-05-28 21:41:44 -04:00
Jonathan Bennett
8a997eb529 Merge branch 'master' into unify-tft 2025-05-28 13:49:43 -05:00
HarukiToreda
051e7331f2 Fix for shutdown banner 2025-05-28 03:04:19 -04:00
Jonathan Bennett
ec2efa55fc Merge branch 'master' into unify-tft 2025-05-27 21:08:54 -05:00
Jonathan Bennett
03b59ae39a Key verification implementation (#6892)
* Very rough start on key verification routine

* KeyVerification mostly working

* Actually working

* Properly hide KeyVerification behind PKI enabled defines

* Change to avoid admin.admin

* Update src/modules/KeyVerificationModule.cpp

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

---------

Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com>
2025-05-27 17:18:18 -05:00
Jonathan Bennett
cc2dd66ce2 Merge branch 'master' into unify-tft 2025-05-27 15:53:19 -05:00
HarukiToreda
bdd03bc853 Fix to but that takes you to message selection screen 2025-05-26 23:45:53 -04:00
HarukiToreda
aaf9f4011f Bluetooth dissable icon 2025-05-26 23:45:28 -04:00
HarukiToreda
7c9ec46d8f move destination option to top of canned message screen 2025-05-26 18:53:14 -04:00
HarukiToreda
4fdc5f094a More cleanup 2025-05-26 18:46:15 -04:00
HarukiToreda
4935e91454 More cannedmessage cleanup 2025-05-26 18:01:16 -04:00
HarukiToreda
6aff2179d1 Revert "Virtual keyboard fix"
This reverts commit dbfa703cfa.
2025-05-26 04:37:58 -04:00
HarukiToreda
3741b78a32 Revert "bug fix"
This reverts commit 3108de207e.
2025-05-26 04:37:41 -04:00
HarukiToreda
3108de207e bug fix 2025-05-26 03:23:08 -04:00
HarukiToreda
dbfa703cfa Virtual keyboard fix 2025-05-26 03:00:38 -04:00
HarukiToreda
7c4714afbb Unified navigation inputs for cannedmessages 2025-05-26 01:35:34 -04:00
Jonathan Bennett
0d37804db5 Trigger a reboot when moving between Display Types 2025-05-25 17:11:12 -05:00
Manuel
8179af3968 Merge branch 'master' into unify-tft 2025-05-25 14:13:22 +02:00
HarukiToreda
e974a58d18 Cannedmessagemodule.h cleanup 2025-05-24 20:46:33 -04:00
HarukiToreda
b2663d4b19 Fixed Ack and Nack messages 2025-05-24 20:38:47 -04:00
HarukiToreda
bed25406c1 Facelist to cannedmessage screen 2025-05-24 14:16:28 -04:00
mverch67
6a22bb5187 PICOmputer 2025-05-24 18:02:28 +02:00
mverch67
61de338aa2 unphone 2025-05-24 18:02:13 +02:00
mverch67
bf21481bef fix compilation errors (for targets which have no telemetry) 2025-05-24 18:01:47 +02:00
HarukiToreda
b5f74cead1 Fixed invertion to tittles 2025-05-24 04:37:10 -04:00
HarukiToreda
13421b32b5 Inverted on default header 2025-05-24 04:12:15 -04:00
HarukiToreda
295ed2a8cf Increased cycling time for NodeInfo screens to 3 secs 2025-05-24 04:09:35 -04:00
HarukiToreda
8f717d58e7 Scroll navigation bar to next page when too long 2025-05-24 03:52:49 -04:00
HarukiToreda
06a65bd80e Nodeinfo screens for favorites feature 2025-05-24 03:45:00 -04:00
HarukiToreda
10f1567b96 Bluetooth dissabled indicator 2025-05-23 21:08:25 -04:00
HarukiToreda
4a55f6468a Emote code cleanup 2025-05-23 02:57:20 -04:00
HarukiToreda
9e3cf441a1 Encoder fix 2025-05-22 23:50:41 -04:00
HarukiToreda
c59f16db42 Eink adjustment 2025-05-22 13:33:24 -04:00
HarukiToreda
d98612a2ca Added select as the rotary encoder button press 2025-05-22 01:42:08 -04:00
HarukiToreda
9d9fb2d74c Navigation bar should no longer hide on Eink displays 2025-05-22 01:09:11 -04:00
HarukiToreda
351dff14e8 No more blinking icons for Eink 2025-05-22 00:25:54 -04:00
HarukiToreda
2432d0616b Added destination change on Cannedmessage screen and dismiss text message frame on reply. 2025-05-22 00:14:28 -04:00
HarukiToreda
b35fb886e4 Node selection optimization for encoder and fix for ACK messages. 2025-05-21 21:13:46 -04:00
HarukiToreda
53d5801790 Compiling error fixes 2025-05-21 14:33:39 -04:00
HarukiToreda
93aa88129c Re-arranged Lora Screen 2025-05-20 23:08:32 -04:00
HarukiToreda
f1d4e5fa48 Save on shutdown added to buttonthead 2025-05-20 22:40:53 -04:00
HarukiToreda
25b2a75dfe Lora Screen Refactored 2025-05-20 22:11:43 -04:00
Jonathan Bennett
3e3a55a971 Merge branch 'master' into unify-tft 2025-05-20 13:36:20 -05:00
Jonathan Bennett
4226d4c4f8 Merge branch 'master' into unify-tft 2025-05-19 22:01:56 -05:00
Jonathan Bennett
a4ef8bf5f0 Unify tft for unphone 2025-05-19 22:01:17 -05:00
Jonathan Bennett
021f872507 Gate more modules behind config.display.displaymode 2025-05-19 21:53:58 -05:00
HarukiToreda
ec50801726 Merge remote-tracking branch 'upstream/master' into StandaloneAddons 2025-05-19 20:00:03 -04:00
HarukiToreda
6db585051e Save on reboot and shutdown 2025-05-19 19:56:32 -04:00
HarukiToreda
aca5159170 Adding date to GPS screen 2025-05-19 19:43:28 -04:00
Jonathan Bennett
3fe44755d0 Merge branch 'master' into unify-tft 2025-05-19 09:40:41 -05:00
Jonathan Bennett
7f0afcdae2 Enable cannedMessages for t-deck 2025-05-18 23:18:08 -05:00
Jonathan Bennett
9aff65e313 One of the classic blunders 2025-05-18 23:01:46 -05:00
Jonathan Bennett
286376e46a Seeed indicator working with unified tft 2025-05-18 22:58:25 -05:00
mverch67
660a7058c8 fix rotation 2025-05-18 22:08:44 -05:00
Jonathan Bennett
584ac8bdc9 Default to MUI display for devices that support it 2025-05-18 20:03:42 -05:00
Jonathan Bennett
d7697e6dec Trunk 2025-05-18 19:58:37 -05:00
Jonathan Bennett
7411dd4f0c guard against a few more null screen pointers 2025-05-18 19:57:49 -05:00
Jonathan Bennett
4d1d89644b Merge branch 'master' into unify-tft-scratch 2025-05-18 19:48:52 -05:00
Jonathan Bennett
61ebce5241 Get t-deck working with both UIs for tft build 2025-05-18 19:46:48 -05:00
Jonathan Bennett
f1440a27d7 Check for null screen 2025-05-17 22:03:23 -05:00
Jonathan Bennett
212005bfe9 More checking for null screen 2025-05-17 20:07:33 -05:00
Jonathan Bennett
afc5d1fdeb Get MUI and legacy screen co-existing on Portduino 2025-05-17 18:43:07 -05:00
Jonathan Bennett
e7352cada4 First attempt at honoring config.display.displaymode 2025-05-17 16:24:53 -05:00
Jonathan Bennett
61d918751e Unify the native display config between legacy display and MUI 2025-05-17 15:07:46 -05:00
HarukiToreda
a8294b983a Fix for Magnetic compass. 2025-05-16 02:14:50 -04:00
HarukiToreda
2a6944fe12 Merge remote-tracking branch 'upstream/master' into StandaloneAddons 2025-05-15 21:18:01 -04:00
HarukiToreda
512183c39f Line added to text message screen 2025-05-15 12:15:03 -04:00
HarukiToreda
18d11d28d4 Line added to non-inverted header 2025-05-15 12:14:24 -04:00
HarukiToreda
ace63eee8d Fix for dismissing channel frame when replied. 2025-05-13 14:15:56 -04:00
HarukiToreda
9cba2e7b7f Screen logo, mute icon, and screen wake on new node 2025-05-13 10:00:34 -04:00
HarukiToreda
efb3f85cd0 Fix for emote and mute icon 2025-05-13 00:49:59 -04:00
HarukiToreda
fe25e5efd5 Mute icon and bell emote added 2025-05-13 00:25:55 -04:00
HarukiToreda
c40fdc9a43 Adjustments to GPS screen 2025-05-12 13:58:13 -04:00
HarukiToreda
7293e542ec GPS toggle now tells if it's on or off 2025-05-11 23:24:05 -04:00
HarukiToreda
2f4f2b1202 Bug fix where freetext screen activates when alert banner shows 2025-05-11 12:15:44 -04:00
HarukiToreda
d9bfed242c Fixed bug making time dissapear when mute icon shows 2025-05-11 02:07:40 -04:00
HarukiToreda
4b770ceade Mute symbol on Header 2025-05-11 01:43:56 -04:00
HarukiToreda
9fc208df5f Bold effect on text in ** Like this ** 2025-05-11 00:02:40 -04:00
HarukiToreda
6542c7bb47 Degree sign fix 2025-05-10 23:05:08 -04:00
HarukiToreda
48dc44ea8f Fix for degree sign type characters on text message screen 2025-05-10 17:29:18 -04:00
HarukiToreda
6bc9986f22 Spacing added in text to allow bigger emotes. 2025-05-10 01:10:20 -04:00
HarukiToreda
9c4dae3bf6 Inline Emote and text feature 2025-05-10 00:23:13 -04:00
HarukiToreda
dbc0122bbd Adjustments and alignments to IconScreen 2025-05-09 23:31:56 -04:00
HarukiToreda
a1d859bf4c Base UI Logo change 2025-05-09 21:19:50 -04:00
HarukiToreda
71ba6fa9ce Update Screen.cpp 2025-05-09 14:49:19 -04:00
HarukiToreda
212963156b Fixed logic check for minimum pop-up size 2025-05-09 12:36:21 -04:00
HarukiToreda
ae88ec96f7 Extra padding for tft alert banner and BaseUI on welcome screen 2025-05-09 12:06:21 -04:00
HarukiToreda
b66d3d7157 Bell Icon added 2025-05-09 11:02:31 -04:00
HarukiToreda
2a7059c86e Alert Message banner 2025-05-08 23:12:05 -04:00
HarukiToreda
14752caee5 Notification banners implemented 2025-05-08 22:00:57 -04:00
HarukiToreda
581021031c Update SharedUIDisplay.cpp 2025-05-07 18:44:18 -04:00
HarukiToreda
4e8ae7b108 Removed Jitter 2025-05-07 02:49:11 -04:00
HarukiToreda
0a61ea4137 Ad-hoc Position banner added 2025-05-07 01:05:14 -04:00
HarukiToreda
bc1cc0081f Added IAQ alert and new Overlay Alert Banner function 2025-05-07 00:54:11 -04:00
HarukiToreda
9a57a774f6 More detailed IAQ Levels for hazardous environments 2025-05-06 01:54:09 -04:00
HarukiToreda
7bc473ed99 Dismiss Memory and wifi screen 2025-05-06 01:07:29 -04:00
HarukiToreda
3596ea20bc Navigation bar peek on bottom 2025-05-06 00:04:47 -04:00
HarukiToreda
eebf174735 Update Screen.cpp 2025-05-05 21:27:49 -04:00
HarukiToreda
849e06497a Telemetry Screen Module 2025-05-05 21:27:20 -04:00
HarukiToreda
66a06230c4 New Icons for navigation bar - Submitted by JasonP 2025-05-05 20:10:00 -04:00
HarukiToreda
75c5080fd9 New Feature
Iconed Screen navigation bar.
2025-05-04 20:21:02 -04:00
HarukiToreda
33093e28fa Memory bar fix 2025-05-04 15:08:39 -04:00
HarukiToreda
df631d480b Fix to battery logo on Eink 2025-05-04 15:07:44 -04:00
HarukiToreda
0e1a1c99f0 Merge remote-tracking branch 'upstream/master' into StandaloneAddons 2025-04-30 17:46:40 -04:00
HarukiToreda
5f245177bc Added tick marks for Channel Util bar 2025-04-21 19:51:40 -04:00
HarukiToreda
257165431f Update Screen.cpp 2025-04-14 02:19:04 -04:00
HarukiToreda
f1fda7bdeb Lots fixes 2025-04-13 23:34:10 -04:00
HarukiToreda
900a7c4c5e Update Screen.cpp 2025-04-11 20:45:45 -04:00
HarukiToreda
d90b721f7b Values on node list aligned 2025-04-11 01:30:46 -04:00
HarukiToreda
9e4847840a GPS tittle offset
-GPS Enabled
-GPS Disabled
-GPS Not Present
-GPS Disabled with Fixed Position
-GPS Not Present with Fixed Position
-GPS Enabled - Toggle off and on
-GPS Disabled - Toggle on and off
2025-04-11 00:51:06 -04:00
HarukiToreda
f1f6b63380 Pull back on scrolling change 2025-04-10 04:29:42 -04:00
HarukiToreda
56fbfe13ae Fix the tittle name 2025-04-10 03:45:59 -04:00
HarukiToreda
6b2e03e9d2 Last heard fix 2025-04-10 03:30:52 -04:00
HarukiToreda
bf9a7d3a7f Scroll on message screen restarts on visit 2025-04-10 02:22:53 -04:00
HarukiToreda
35d4784c5c Node list cleanup and optimization 2025-04-10 02:10:42 -04:00
HarukiToreda
5fa236c77d Conbined distance screen into cycling screen 2025-04-10 00:37:39 -04:00
HarukiToreda
f7849f2bd4 Adjustments to Lora Focus screen 2025-04-09 23:59:26 -04:00
HarukiToreda
6d53ce7956 Merge remote-tracking branch 'upstream/master' into StandaloneAddons 2025-04-09 18:14:20 -04:00
HarukiToreda
9f56e613f2 Refactored Lora Screen 2025-04-09 17:54:47 -04:00
HarukiToreda
f03f547e9e Terrible clock format change 2025-04-09 01:10:15 -04:00
HarukiToreda
09fd3c0782 Prototype Cycling screens 2025-04-08 15:07:00 -04:00
HarukiToreda
ebea34520d Cleanup 2025-04-08 11:19:13 -04:00
HarukiToreda
383ae7a82f New lightning bolts for battery 2025-04-08 01:41:37 -04:00
HarukiToreda
38b118fb8b Update Screen.cpp 2025-04-08 01:15:08 -04:00
HarukiToreda
2a4582da20 Fix for Mail notification not drawing screen. 2025-04-08 01:05:52 -04:00
HarukiToreda
7c4ac89059 Text message notification 2025-04-07 22:33:16 -04:00
HarukiToreda
cdbf0bec2d Cleanup 2025-04-06 16:41:06 -04:00
HarukiToreda
d5d20fe33f Smart portrait logic for battery 2025-04-06 15:57:19 -04:00
HarukiToreda
99f6b398b3 Cleanup 2025-04-06 15:14:51 -04:00
HarukiToreda
396fc1824e removed tft tag 2025-04-06 14:55:00 -04:00
HarukiToreda
74325ba439 Cleanup and labeling borth variants to tft 2025-04-06 14:28:45 -04:00
HarukiToreda
33cfe14d4a Cleanup for nodeinfo 2025-04-06 04:31:40 -04:00
HarukiToreda
01f7cd998a re-circumcised 2025-04-05 23:41:35 -04:00
HarukiToreda
c49f20f96c Battery Circumcision 2025-04-05 23:29:47 -04:00
HarukiToreda
afc710a868 Mini compass screen shape change 2025-04-05 22:37:05 -04:00
HarukiToreda
9cdeedfcbd Update Screen.cpp 2025-04-05 21:40:40 -04:00
HarukiToreda
b7218f4a53 Update Screen.cpp 2025-04-05 21:23:27 -04:00
HarukiToreda
08bbff260c Adjustments 2025-04-05 21:23:16 -04:00
HarukiToreda
225e2726f3 Fixed mini compass and rearranged screen order 2025-04-05 19:47:44 -04:00
HarukiToreda
ae47de152c Node list cleanup and unification 2025-04-05 19:07:33 -04:00
HarukiToreda
2b7bc6696f Fixed Node list screens 2025-04-05 15:28:39 -04:00
HarukiToreda
52d1d8d7c8 Minor alignment adjustments in common header, changed time to be a/p versus AM/PM 2025-04-05 00:10:06 -04:00
HarukiToreda
75490f410b Scrolling issues fixed 2025-04-04 23:04:59 -04:00
HarukiToreda
67ae1c553c Merge remote-tracking branch 'upstream/master' into StandaloneAddons 2025-04-04 11:12:06 -04:00
HarukiToreda
a1df41a9e0 offset by 2 and removed Activity Screen
-General cleanup of unused screens
-Temporarily commented out SD card code on Memory screen
-Removed Activity Screen
-Slight adjustment to content layout
2025-04-04 10:53:26 -04:00
HarukiToreda
65f00e9474 Animated emotes 2025-04-04 01:36:51 -04:00
HarukiToreda
6e0cca16d1 center Emotes 2025-04-04 01:21:53 -04:00
HarukiToreda
2711c53b5f Improved message screen with scrolling 2025-04-04 01:13:15 -04:00
HarukiToreda
7856e069a5 Update Screen.cpp 2025-04-04 00:15:04 -04:00
HarukiToreda
6270c5663c Update Screen.cpp 2025-04-03 10:47:25 -04:00
HarukiToreda
13b4093d84 GPS compass sizing fix 2025-04-03 01:03:57 -04:00
HarukiToreda
b7aaf3ae47 Column separator and scrillbar alignment 2025-04-02 21:30:30 -04:00
HarukiToreda
047ccbcb55 Update Screen.cpp 2025-04-02 20:55:42 -04:00
HarukiToreda
e4e8d28831 Refactored Device Focus screen and messages 2025-04-02 20:37:14 -04:00
HarukiToreda
52eb4eca03 Delta chainge indicator commented out 2025-04-02 19:51:45 -04:00
HarukiToreda
6f47035420 Memory screen fix 2025-04-02 04:45:25 -04:00
HarukiToreda
af7a70ce08 Compas offset 2025-04-02 04:23:45 -04:00
HarukiToreda
22b44ce7e6 Offset Header for Node list screens 2025-04-02 03:32:13 -04:00
HarukiToreda
2f8a1dba8f Rows adjustment 2025-04-02 02:40:34 -04:00
HarukiToreda
c693cd59a9 Update Screen.cpp 2025-04-01 13:51:21 -04:00
HarukiToreda
c271515fb0 Centered battery 2025-04-01 11:39:55 -04:00
HarukiToreda
efc69550ef Corrected rounding 2025-04-01 10:12:02 -04:00
HarukiToreda
6ee7644070 Offset everything by 1 down 2025-04-01 03:55:43 -04:00
HarukiToreda
bb961e855e Update Screen.cpp 2025-04-01 01:49:06 -04:00
HarukiToreda
7554ff6c57 Update Screen.cpp 2025-04-01 01:43:01 -04:00
HarukiToreda
9993306751 Add heap leak counter will be removed to be toggled in the future. 2025-03-31 14:34:01 -04:00
HarukiToreda
2acb2fee79 Merge branch 'meshtastic:master' into StandaloneAddons 2025-03-31 01:54:40 -04:00
HarukiToreda
ca1e09d780 Added GPS tittle 2025-03-31 00:33:01 -04:00
HarukiToreda
71f774aa37 Adde Lora screen tittle and removed old code 2025-03-30 23:47:56 -04:00
HarukiToreda
99ca59b8a1 Jason's cleanup 2025-03-30 23:26:33 -04:00
HarukiToreda
f60c4ec5bc Conditional tittle and data based on screen size 2025-03-30 17:42:52 -04:00
HarukiToreda
7181e1a296 changed order 2025-03-30 16:54:57 -04:00
HarukiToreda
aff0834f8e New Memory screen 2025-03-30 16:53:44 -04:00
HarukiToreda
1fd95d85b8 Bug was making bold get undone 2025-03-30 01:42:34 -04:00
HarukiToreda
50db11fff6 Compass north fix 2025-03-30 01:25:22 -04:00
HarukiToreda
2fc6781322 Added xaositek screens 2025-03-29 23:46:54 -04:00
HarukiToreda
0480ddd266 Compass and Location Screen 2025-03-29 23:22:54 -04:00
HarukiToreda
a3a0c14923 Made the header it's own code to be easier to create future screens 2025-03-29 20:27:59 -04:00
HarukiToreda
213a178d71 Added local Time to banner screen 2025-03-29 20:10:05 -04:00
HarukiToreda
72f6fde772 Added "Uptime:" to the uptime value 2025-03-29 19:22:09 -04:00
HarukiToreda
62a6c91c70 color change for the screen on the T114 2025-03-29 17:47:51 -04:00
HarukiToreda
bd20c74287 Added scrollbar code for node list screens 2025-03-29 04:21:43 -04:00
HarukiToreda
c9e71173de centered header contents while highlighted
Instead of manually centeing the contents of the headers, it now calculates the center on its own, better for other screen resolutions
2025-03-29 02:47:08 -04:00
HarukiToreda
41c44353f7 removed the 3x scale 2025-03-28 21:23:41 -04:00
HarukiToreda
7fce089540 Support to enlarge battery image depending on screen size
I adjusted the battery code to recognize the screen size and scale the battery based on that to fit on the top header.
2025-03-28 21:03:37 -04:00
HarukiToreda
1dedd291fb New Screens
Introducing
Default screen
Nodelist (Last head nodes)
Distance Screen
Compass screen
Hops and Signal Screen

Improved node receipient list using navigation bar and search bar for canned messages
2025-03-28 14:39:15 -04:00
71 changed files with 7229 additions and 2436 deletions

54
.vscode/settings.json vendored
View File

@@ -10,5 +10,59 @@
},
"[powershell]": {
"editor.defaultFormatter": "ms-vscode.powershell"
},
"files.associations": {
"array": "cpp",
"atomic": "cpp",
"*.tcc": "cpp",
"cctype": "cpp",
"clocale": "cpp",
"cmath": "cpp",
"csignal": "cpp",
"cstdarg": "cpp",
"cstddef": "cpp",
"cstdint": "cpp",
"cstdio": "cpp",
"cstdlib": "cpp",
"cstring": "cpp",
"ctime": "cpp",
"cwchar": "cpp",
"cwctype": "cpp",
"deque": "cpp",
"list": "cpp",
"unordered_map": "cpp",
"unordered_set": "cpp",
"vector": "cpp",
"exception": "cpp",
"algorithm": "cpp",
"functional": "cpp",
"iterator": "cpp",
"map": "cpp",
"memory": "cpp",
"memory_resource": "cpp",
"numeric": "cpp",
"optional": "cpp",
"random": "cpp",
"string": "cpp",
"string_view": "cpp",
"system_error": "cpp",
"tuple": "cpp",
"type_traits": "cpp",
"utility": "cpp",
"fstream": "cpp",
"initializer_list": "cpp",
"iomanip": "cpp",
"iosfwd": "cpp",
"iostream": "cpp",
"istream": "cpp",
"limits": "cpp",
"new": "cpp",
"ostream": "cpp",
"sstream": "cpp",
"stdexcept": "cpp",
"streambuf": "cpp",
"cinttypes": "cpp",
"typeinfo": "cpp",
"*.xbm": "cpp"
}
}

View File

@@ -9,6 +9,7 @@
#include "RadioLibInterface.h"
#include "buzz.h"
#include "main.h"
#include "modules/CannedMessageModule.h"
#include "modules/ExternalNotificationModule.h"
#include "power.h"
#include "sleep.h"
@@ -26,6 +27,7 @@
using namespace concurrency;
ButtonThread *buttonThread; // Declared extern in header
extern CannedMessageModule *cannedMessageModule;
volatile ButtonThread::ButtonEventType ButtonThread::btnEvent = ButtonThread::BUTTON_EVENT_NONE;
#if defined(BUTTON_PIN) || defined(ARCH_PORTDUINO) || defined(USERPREFS_BUTTON_PIN)
@@ -118,6 +120,17 @@ ButtonThread::ButtonThread() : OSThread("Button")
void ButtonThread::switchPage()
{
// Prevent screen switch if CannedMessageModule is focused and intercepting input
#if HAS_SCREEN
extern CannedMessageModule *cannedMessageModule;
if (cannedMessageModule && cannedMessageModule->isInterceptingAndFocused()) {
LOG_DEBUG("User button ignored during canned message input");
return; // Skip screen change
}
#endif
// Default behavior if not blocked
#ifdef BUTTON_PIN
#if !defined(USERPREFS_BUTTON_PIN)
if (((config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN) !=
@@ -135,8 +148,8 @@ void ButtonThread::switchPage()
powerFSM.trigger(EVENT_PRESS);
}
#endif
#endif
#if defined(ARCH_PORTDUINO)
if ((settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) &&
(settingsMap[user] != moduleConfig.canned_message.inputbroker_pin_press) ||
@@ -219,11 +232,17 @@ int32_t ButtonThread::runOnce()
case BUTTON_EVENT_DOUBLE_PRESSED: {
LOG_BUTTON("Double press!");
#ifdef ELECROW_ThinkNode_M1
digitalWrite(PIN_EINK_EN, digitalRead(PIN_EINK_EN) == LOW);
break;
#endif
// Send GPS position immediately
sendAdHocPosition();
// Show temporary on-screen confirmation banner for 3 seconds
screen->showOverlayBanner("Ad-hoc Ping Sent", 3000);
break;
}
@@ -235,8 +254,15 @@ int32_t ButtonThread::runOnce()
case 3:
if (!config.device.disable_triple_click && (gps != nullptr)) {
gps->toggleGpsMode();
if (screen)
const char *statusMsg = (config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_ENABLED)
? "GPS Enabled"
: "GPS Disabled";
if (screen) {
screen->forceDisplay(true); // Force a new UI frame, then force an EInk update
screen->showOverlayBanner(statusMsg, 3000);
}
}
break;
#elif defined(ELECROW_ThinkNode_M1) || defined(ELECROW_ThinkNode_M2)
@@ -280,9 +306,12 @@ int32_t ButtonThread::runOnce()
case BUTTON_EVENT_LONG_PRESSED: {
LOG_BUTTON("Long press!");
powerFSM.trigger(EVENT_PRESS);
if (screen) {
screen->startAlert("Shutting down...");
// Show shutdown message as a temporary overlay banner
screen->showOverlayBanner("Shutting Down..."); // Display for 3 seconds
}
playBeep();
break;
}
@@ -294,6 +323,7 @@ int32_t ButtonThread::runOnce()
playShutdownMelody();
delay(3000);
power->shutdown();
nodeDB->saveToDisk();
break;
}

View File

@@ -40,6 +40,7 @@ class ButtonThread : public concurrency::OSThread
bool isBuzzing() { return buzzer_flag; }
void setScreenFlag(bool flag) { screen_flag = flag; }
bool getScreenFlag() { return screen_flag; }
bool isInterceptingAndFocused();
// Disconnect and reconnect interrupts for light sleep
#ifdef ARCH_ESP32

View File

@@ -853,6 +853,7 @@ int32_t Power::runOnce()
#ifndef T_WATCH_S3 // FIXME - why is this triggering on the T-Watch S3?
if (PMU->isPekeyLongPressIrq()) {
LOG_DEBUG("PEK long button press");
if (screen)
screen->setOn(false);
}
#endif

View File

@@ -82,6 +82,7 @@ static uint32_t secsSlept;
static void lsEnter()
{
LOG_INFO("lsEnter begin, ls_secs=%u", config.power.ls_secs);
if (screen)
screen->setOn(false);
secsSlept = 0; // How long have we been sleeping this time
@@ -160,6 +161,7 @@ static void lsExit()
static void nbEnter()
{
LOG_DEBUG("State: NB");
if (screen)
screen->setOn(false);
#ifdef ARCH_ESP32
// Only ESP32 should turn off bluetooth
@@ -172,6 +174,7 @@ static void nbEnter()
static void darkEnter()
{
setBluetoothEnable(true);
if (screen)
screen->setOn(false);
}
@@ -179,14 +182,17 @@ static void serialEnter()
{
LOG_DEBUG("State: SERIAL");
setBluetoothEnable(false);
if (screen) {
screen->setOn(true);
screen->print("Serial connected\n");
}
}
static void serialExit()
{
// Turn bluetooth back on when we leave serial stream API
setBluetoothEnable(true);
if (screen)
screen->print("Serial disconnected\n");
}
@@ -198,6 +204,7 @@ static void powerEnter()
LOG_INFO("Loss of power in Powered");
powerFSM.trigger(EVENT_POWER_DISCONNECTED);
} else {
if (screen)
screen->setOn(true);
setBluetoothEnable(true);
// within enter() the function getState() returns the state we came from
@@ -221,6 +228,7 @@ static void powerIdle()
static void powerExit()
{
if (screen)
screen->setOn(true);
setBluetoothEnable(true);
@@ -232,6 +240,7 @@ static void powerExit()
static void onEnter()
{
LOG_DEBUG("State: ON");
if (screen)
screen->setOn(true);
setBluetoothEnable(true);
}
@@ -246,6 +255,7 @@ static void onIdle()
static void screenPress()
{
if (screen)
screen->onPress();
}

File diff suppressed because it is too large Load Diff

View File

@@ -5,6 +5,10 @@
#include "detect/ScanI2C.h"
#include "mesh/generated/meshtastic/config.pb.h"
#include <OLEDDisplay.h>
#include <string>
#include <vector>
#define getStringCenteredX(s) ((SCREEN_WIDTH - display->getStringWidth(s)) / 2)
#if !HAS_SCREEN
#include "power.h"
@@ -64,6 +68,7 @@ class Screen
#include "mesh/MeshModule.h"
#include "power.h"
#include <string>
#include <vector>
// 0 to 255, though particular variants might define different defaults
#ifndef BRIGHTNESS_DEFAULT
@@ -90,7 +95,7 @@ class Screen
/// Convert an integer GPS coords to a floating point
#define DegD(i) (i * 1e-7)
extern bool hasUnreadMessage;
namespace
{
/// A basic 2D point class for drawing
@@ -181,9 +186,23 @@ class Screen : public concurrency::OSThread
public:
explicit Screen(ScanI2C::DeviceAddress, meshtastic_Config_DisplayConfig_OledType, OLEDDISPLAY_GEOMETRY);
size_t frameCount = 0; // Total number of active frames
~Screen();
// Which frame we want to be displayed, after we regen the frameset by calling setFrames
enum FrameFocus : uint8_t {
FOCUS_DEFAULT, // No specific frame
FOCUS_PRESERVE, // Return to the previous frame
FOCUS_FAULT,
FOCUS_TEXTMESSAGE,
FOCUS_MODULE, // Note: target module should call requestFocus(), otherwise no info about which module to focus
};
// Regenerate the normal set of frames, focusing a specific frame if requested
// Call when a frame should be added / removed, or custom frames should be cleared
void setFrames(FrameFocus focus = FOCUS_DEFAULT);
std::vector<const uint8_t *> indicatorIcons; // Per-frame custom icon pointers
Screen(const Screen &) = delete;
Screen &operator=(const Screen &) = delete;
@@ -214,21 +233,11 @@ class Screen : public concurrency::OSThread
void blink();
void drawFrameText(OLEDDisplay *, OLEDDisplayUiState *, int16_t, int16_t, const char *);
void getTimeAgoStr(uint32_t agoSecs, char *timeStr, uint8_t maxLength);
// Draw north
void drawCompassNorth(OLEDDisplay *display, int16_t compassX, int16_t compassY, float myHeading);
static uint16_t getCompassDiam(uint32_t displayWidth, uint32_t displayHeight);
float estimatedHeading(double lat, double lon);
void drawNodeHeading(OLEDDisplay *display, int16_t compassX, int16_t compassY, uint16_t compassDiam, float headingRadian);
void drawColumns(OLEDDisplay *display, int16_t x, int16_t y, const char **fields);
/// Handle button press, trackball or swipe action)
void onPress() { enqueueCmd(ScreenCmd{.cmd = Cmd::ON_PRESS}); }
void showPrevFrame() { enqueueCmd(ScreenCmd{.cmd = Cmd::SHOW_PREV_FRAME}); }
@@ -260,6 +269,8 @@ class Screen : public concurrency::OSThread
enqueueCmd(cmd);
}
void showOverlayBanner(const char *message, uint32_t durationMs = 3000);
void startFirmwareUpdateScreen()
{
ScreenCmd cmd;
@@ -306,9 +317,6 @@ class Screen : public concurrency::OSThread
}
}
/// generates a very brief time delta display
std::string drawTimeDelta(uint32_t days, uint32_t hours, uint32_t minutes, uint32_t seconds);
/// Overrides the default utf8 character conversion, to replace empty space with question marks
static char customFontTableLookup(const uint8_t ch)
{
@@ -600,30 +608,26 @@ class Screen : public concurrency::OSThread
// - Used to dismiss the currently shown frame (txt; waypoint) by CardKB combo
struct FramesetInfo {
struct FramePositions {
uint8_t fault = 0;
uint8_t textMessage = 0;
uint8_t waypoint = 0;
uint8_t focusedModule = 0;
uint8_t log = 0;
uint8_t settings = 0;
uint8_t wifi = 0;
uint8_t fault = 255;
uint8_t textMessage = 255;
uint8_t waypoint = 255;
uint8_t focusedModule = 255;
uint8_t log = 255;
uint8_t settings = 255;
uint8_t wifi = 255;
uint8_t deviceFocused = 255;
uint8_t memory = 255;
} positions;
uint8_t frameCount = 0;
} framesetInfo;
// Which frame we want to be displayed, after we regen the frameset by calling setFrames
enum FrameFocus : uint8_t {
FOCUS_DEFAULT, // No specific frame
FOCUS_PRESERVE, // Return to the previous frame
FOCUS_FAULT,
FOCUS_TEXTMESSAGE,
FOCUS_MODULE, // Note: target module should call requestFocus(), otherwise no info about which module to focus
};
// Regenerate the normal set of frames, focusing a specific frame if requested
// Call when a frame should be added / removed, or custom frames should be cleared
void setFrames(FrameFocus focus = FOCUS_DEFAULT);
struct DismissedFrames {
bool textMessage = false;
bool waypoint = false;
bool wifi = false;
bool memory = false;
} dismissedFrames;
/// Try to start drawing ASAP
void setFastFramerate();
@@ -631,13 +635,6 @@ class Screen : public concurrency::OSThread
// Sets frame up for immediate drawing
void setFrameImmediateDraw(FrameCallback *drawFrames);
/// Called when debug screen is to be drawn, calls through to debugInfo.drawFrame.
static void drawDebugInfoTrampoline(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
static void drawDebugInfoSettingsTrampoline(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
static void drawDebugInfoWiFiTrampoline(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
#if defined(DISPLAY_CLOCK_FRAME)
static void drawAnalogClockFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
@@ -691,4 +688,13 @@ class Screen : public concurrency::OSThread
} // namespace graphics
extern "C" {
extern char *alertBannerMessage;
extern uint32_t alertBannerUntil;
}
// Extern declarations for function symbols used in UIRenderer
extern std::vector<std::string> functionSymbol;
extern std::string functionSymbolString;
#endif

View File

@@ -0,0 +1,6 @@
#include <string>
#include <vector>
// Global variables for screen function overlay
std::vector<std::string> functionSymbol;
std::string functionSymbolString;

View File

@@ -0,0 +1,256 @@
#include "graphics/SharedUIDisplay.h"
#include "RTC.h"
#include "graphics/ScreenFonts.h"
#include "main.h"
#include "meshtastic/config.pb.h"
#include "power.h"
#include <OLEDDisplay.h>
#include <graphics/images.h>
namespace graphics
{
// === Shared External State ===
bool hasUnreadMessage = false;
bool isMuted = false;
// === Internal State ===
bool isBoltVisibleShared = true;
uint32_t lastBlinkShared = 0;
bool isMailIconVisible = true;
uint32_t lastMailBlink = 0;
// *********************************
// * Rounded Header when inverted *
// *********************************
void drawRoundedHighlight(OLEDDisplay *display, int16_t x, int16_t y, int16_t w, int16_t h, int16_t r)
{
// Draw the center and side rectangles
display->fillRect(x + r, y, w - 2 * r, h); // center bar
display->fillRect(x, y + r, r, h - 2 * r); // left edge
display->fillRect(x + w - r, y + r, r, h - 2 * r); // right edge
// Draw the rounded corners using filled circles
display->fillCircle(x + r + 1, y + r, r); // top-left
display->fillCircle(x + w - r - 1, y + r, r); // top-right
display->fillCircle(x + r + 1, y + h - r - 1, r); // bottom-left
display->fillCircle(x + w - r - 1, y + h - r - 1, r); // bottom-right
}
// *************************
// * Common Header Drawing *
// *************************
void drawCommonHeader(OLEDDisplay *display, int16_t x, int16_t y)
{
constexpr int HEADER_OFFSET_Y = 1;
y += HEADER_OFFSET_Y;
display->setFont(FONT_SMALL);
display->setTextAlignment(TEXT_ALIGN_LEFT);
const int xOffset = 4;
const int highlightHeight = FONT_HEIGHT_SMALL - 1;
const bool isInverted = (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_INVERTED);
const bool isBold = config.display.heading_bold;
const int screenW = display->getWidth();
const int screenH = display->getHeight();
const bool useBigIcons = (screenW > 128);
// === Inverted Header Background ===
if (isInverted) {
drawRoundedHighlight(display, x, y, screenW, highlightHeight, 2);
display->setColor(BLACK);
} else {
if (screenW > 128) {
display->drawLine(0, 20, screenW, 20);
} else {
display->drawLine(0, 14, screenW, 14);
}
}
// === Battery State ===
int chargePercent = powerStatus->getBatteryChargePercent();
bool isCharging = powerStatus->getIsCharging() == meshtastic::OptionalBool::OptTrue;
static uint32_t lastBlinkShared = 0;
static bool isBoltVisibleShared = true;
uint32_t now = millis();
#ifndef USE_EINK
if (isCharging && now - lastBlinkShared > 500) {
isBoltVisibleShared = !isBoltVisibleShared;
lastBlinkShared = now;
}
#endif
bool useHorizontalBattery = (screenW > 128 && screenW >= screenH);
const int textY = y + (highlightHeight - FONT_HEIGHT_SMALL) / 2;
// === Battery Icons ===
if (useHorizontalBattery) {
int batteryX = 2;
int batteryY = HEADER_OFFSET_Y + 2;
display->drawXbm(batteryX, batteryY, 29, 15, batteryBitmap_h);
if (isCharging && isBoltVisibleShared)
display->drawXbm(batteryX + 9, batteryY + 1, 9, 13, lightning_bolt_h);
else {
display->drawXbm(batteryX + 8, batteryY, 12, 15, batteryBitmap_sidegaps_h);
int fillWidth = 24 * chargePercent / 100;
display->fillRect(batteryX + 1, batteryY + 1, fillWidth, 13);
}
} else {
int batteryX = 1;
int batteryY = HEADER_OFFSET_Y + 1;
#ifdef USE_EINK
batteryY += 2;
#endif
display->drawXbm(batteryX, batteryY, 7, 11, batteryBitmap_v);
if (isCharging && isBoltVisibleShared)
display->drawXbm(batteryX + 1, batteryY + 3, 5, 5, lightning_bolt_v);
else {
display->drawXbm(batteryX - 1, batteryY + 4, 8, 3, batteryBitmap_sidegaps_v);
int fillHeight = 8 * chargePercent / 100;
int fillY = batteryY - fillHeight;
display->fillRect(batteryX + 1, fillY + 10, 5, fillHeight);
}
}
// === Battery % Display ===
char chargeStr[4];
snprintf(chargeStr, sizeof(chargeStr), "%d", chargePercent);
int chargeNumWidth = display->getStringWidth(chargeStr);
const int batteryOffset = useHorizontalBattery ? 28 : 6;
#ifdef USE_EINK
const int percentX = x + xOffset + batteryOffset - 2;
#else
const int percentX = x + xOffset + batteryOffset;
#endif
display->drawString(percentX, textY, chargeStr);
display->drawString(percentX + chargeNumWidth - 1, textY, "%");
if (isBold) {
display->drawString(percentX + 1, textY, chargeStr);
display->drawString(percentX + chargeNumWidth, textY, "%");
}
// === Time and Right-aligned Icons ===
uint32_t rtc_sec = getValidTime(RTCQuality::RTCQualityDevice, true);
char timeStr[10] = "--:--"; // Fallback display
int timeStrWidth = display->getStringWidth("12:34"); // Default alignment
int timeX = screenW - xOffset - timeStrWidth + 4;
if (rtc_sec > 0) {
// === Build Time String ===
long hms = (rtc_sec % SEC_PER_DAY + SEC_PER_DAY) % SEC_PER_DAY;
int hour = hms / SEC_PER_HOUR;
int minute = (hms % SEC_PER_HOUR) / SEC_PER_MIN;
snprintf(timeStr, sizeof(timeStr), "%d:%02d", hour, minute);
if (config.display.use_12h_clock) {
bool isPM = hour >= 12;
hour %= 12;
if (hour == 0)
hour = 12;
snprintf(timeStr, sizeof(timeStr), "%d:%02d%s", hour, minute, isPM ? "p" : "a");
}
timeStrWidth = display->getStringWidth(timeStr);
timeX = screenW - xOffset - timeStrWidth + 4;
// === Show Mail or Mute Icon to the Left of Time ===
int iconRightEdge = timeX - 2;
static bool isMailIconVisible = true;
static uint32_t lastMailBlink = 0;
bool showMail = false;
#ifndef USE_EINK
if (hasUnreadMessage) {
if (now - lastMailBlink > 500) {
isMailIconVisible = !isMailIconVisible;
lastMailBlink = now;
}
showMail = isMailIconVisible;
}
#else
if (hasUnreadMessage) {
showMail = true;
}
#endif
if (showMail) {
if (useHorizontalBattery) {
int iconW = 16, iconH = 12;
int iconX = iconRightEdge - iconW;
int iconY = textY + (FONT_HEIGHT_SMALL - iconH) / 2 - 1;
display->drawRect(iconX, iconY, iconW + 1, iconH);
display->drawLine(iconX, iconY, iconX + iconW / 2, iconY + iconH - 4);
display->drawLine(iconX + iconW, iconY, iconX + iconW / 2, iconY + iconH - 4);
} else {
int iconX = iconRightEdge - mail_width;
int iconY = textY + (FONT_HEIGHT_SMALL - mail_height) / 2;
display->drawXbm(iconX, iconY, mail_width, mail_height, mail);
}
} else if (isMuted) {
if (useBigIcons) {
int iconX = iconRightEdge - mute_symbol_big_width;
int iconY = textY + (FONT_HEIGHT_SMALL - mute_symbol_big_height) / 2;
display->drawXbm(iconX, iconY, mute_symbol_big_width, mute_symbol_big_height, mute_symbol_big);
} else {
int iconX = iconRightEdge - mute_symbol_width;
int iconY = textY + (FONT_HEIGHT_SMALL - mail_height) / 2;
display->drawXbm(iconX, iconY, mute_symbol_width, mute_symbol_height, mute_symbol);
}
}
// === Draw Time ===
display->drawString(timeX, textY, timeStr);
if (isBold)
display->drawString(timeX - 1, textY, timeStr);
} else {
// === No Time Available: Mail/Mute Icon Moves to Far Right ===
int iconRightEdge = screenW - xOffset;
static bool isMailIconVisible = true;
static uint32_t lastMailBlink = 0;
bool showMail = false;
if (hasUnreadMessage) {
if (now - lastMailBlink > 500) {
isMailIconVisible = !isMailIconVisible;
lastMailBlink = now;
}
showMail = isMailIconVisible;
}
if (showMail) {
if (useHorizontalBattery) {
int iconW = 16, iconH = 12;
int iconX = iconRightEdge - iconW;
int iconY = textY + (FONT_HEIGHT_SMALL - iconH) / 2 - 1;
display->drawRect(iconX, iconY, iconW + 1, iconH);
display->drawLine(iconX, iconY, iconX + iconW / 2, iconY + iconH - 4);
display->drawLine(iconX + iconW, iconY, iconX + iconW / 2, iconY + iconH - 4);
} else {
int iconX = iconRightEdge - mail_width;
int iconY = textY + (FONT_HEIGHT_SMALL - mail_height) / 2;
display->drawXbm(iconX, iconY, mail_width, mail_height, mail);
}
} else if (isMuted) {
if (useBigIcons) {
int iconX = iconRightEdge - mute_symbol_big_width;
int iconY = textY + (FONT_HEIGHT_SMALL - mute_symbol_big_height) / 2;
display->drawXbm(iconX, iconY, mute_symbol_big_width, mute_symbol_big_height, mute_symbol_big);
} else {
int iconX = iconRightEdge - mute_symbol_width;
int iconY = textY + (FONT_HEIGHT_SMALL - mail_height) / 2;
display->drawXbm(iconX, iconY, mute_symbol_width, mute_symbol_height, mute_symbol);
}
}
}
display->setColor(WHITE); // Reset for other UI
}
} // namespace graphics

View File

@@ -0,0 +1,46 @@
#pragma once
#include <OLEDDisplay.h>
namespace graphics
{
// =======================
// Shared UI Helpers
// =======================
// Compact line layout
#define compactFirstLine ((FONT_HEIGHT_SMALL - 1) * 1)
#define compactSecondLine ((FONT_HEIGHT_SMALL - 1) * 2) - 2
#define compactThirdLine ((FONT_HEIGHT_SMALL - 1) * 3) - 4
#define compactFourthLine ((FONT_HEIGHT_SMALL - 1) * 4) - 6
#define compactFifthLine ((FONT_HEIGHT_SMALL - 1) * 5) - 8
// Standard line layout
#define standardFirstLine (FONT_HEIGHT_SMALL + 1) * 1
#define standardSecondLine (FONT_HEIGHT_SMALL + 1) * 2
#define standardThirdLine (FONT_HEIGHT_SMALL + 1) * 3
#define standardFourthLine (FONT_HEIGHT_SMALL + 1) * 4
// More Compact line layout
#define moreCompactFirstLine compactFirstLine
#define moreCompactSecondLine (moreCompactFirstLine + (FONT_HEIGHT_SMALL - 5))
#define moreCompactThirdLine (moreCompactSecondLine + (FONT_HEIGHT_SMALL - 5))
#define moreCompactFourthLine (moreCompactThirdLine + (FONT_HEIGHT_SMALL - 5))
#define moreCompactFifthLine (moreCompactFourthLine + (FONT_HEIGHT_SMALL - 5))
// Quick screen access
#define SCREEN_WIDTH display->getWidth()
#define SCREEN_HEIGHT display->getHeight()
// Shared state (declare inside namespace)
extern bool hasUnreadMessage;
extern bool isMuted;
// Rounded highlight (used for inverted headers)
void drawRoundedHighlight(OLEDDisplay *display, int16_t x, int16_t y, int16_t w, int16_t h, int16_t r);
// Shared battery/time/mail header
void drawCommonHeader(OLEDDisplay *display, int16_t x, int16_t y);
} // namespace graphics

View File

@@ -653,7 +653,7 @@ static LGFX *tft = nullptr;
#include <TFT_eSPI.h> // Graphics and font library for ILI9342 driver chip
static TFT_eSPI *tft = nullptr; // Invoke library, pins defined in User_Setup.h
#elif ARCH_PORTDUINO && HAS_SCREEN != 0 && !HAS_TFT
#elif ARCH_PORTDUINO
#include <LovyanGFX.hpp> // Graphics and font library for ST7735 driver chip
class LGFX : public lgfx::LGFX_Device
@@ -697,11 +697,16 @@ class LGFX : public lgfx::LGFX_Device
_panel_instance->setBus(&_bus_instance); // set the bus on the panel.
auto cfg = _panel_instance->config(); // Gets a structure for display panel settings.
LOG_DEBUG("Height: %d, Width: %d ", settingsMap[displayHeight], settingsMap[displayWidth]);
LOG_DEBUG("Width: %d, Height: %d", settingsMap[displayWidth], settingsMap[displayHeight]);
cfg.pin_cs = settingsMap[displayCS]; // Pin number where CS is connected (-1 = disable)
cfg.pin_rst = settingsMap[displayReset];
if (settingsMap[displayRotate]) {
cfg.panel_width = settingsMap[displayHeight]; // actual displayable width
cfg.panel_height = settingsMap[displayWidth]; // actual displayable height
} else {
cfg.panel_width = settingsMap[displayWidth]; // actual displayable width
cfg.panel_height = settingsMap[displayHeight]; // actual displayable height
}
cfg.offset_x = settingsMap[displayOffsetX]; // Panel offset amount in X direction
cfg.offset_y = settingsMap[displayOffsetY]; // Panel offset amount in Y direction
cfg.offset_rotation = settingsMap[displayOffsetRotate]; // Rotation direction value offset 0~7 (4~7 is mirrored)
@@ -978,9 +983,9 @@ TFTDisplay::TFTDisplay(uint8_t address, int sda, int scl, OLEDDISPLAY_GEOMETRY g
#if ARCH_PORTDUINO
if (settingsMap[displayRotate]) {
setGeometry(GEOMETRY_RAWMODE, settingsMap[configNames::displayHeight], settingsMap[configNames::displayWidth]);
} else {
setGeometry(GEOMETRY_RAWMODE, settingsMap[configNames::displayWidth], settingsMap[configNames::displayHeight]);
} else {
setGeometry(GEOMETRY_RAWMODE, settingsMap[configNames::displayHeight], settingsMap[configNames::displayWidth]);
}
#elif defined(SCREEN_ROTATE)
@@ -1169,6 +1174,8 @@ bool TFTDisplay::connect()
tft->setRotation(1); // T-Deck has the TFT in landscape
#elif defined(T_WATCH_S3) || defined(SENSECAP_INDICATOR)
tft->setRotation(2); // T-Watch S3 left-handed orientation
#elif ARCH_PORTDUINO
tft->setRotation(0);
#else
tft->setRotation(3); // Orient horizontal and wide underneath the silkscreen name label
#endif

View File

@@ -0,0 +1,40 @@
#pragma once
#include "graphics/Screen.h"
#include <OLEDDisplay.h>
#include <OLEDDisplayUi.h>
namespace graphics
{
/// Forward declarations
class Screen;
/**
* @brief Clock drawing functions
*
* Contains all functions related to drawing analog and digital clocks,
* segmented displays, and time-related UI elements.
*/
namespace ClockRenderer
{
// Clock frame functions
void drawAnalogClockFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
void drawDigitalClockFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
// Segmented display functions
void drawSegmentedDisplayCharacter(OLEDDisplay *display, int x, int y, uint8_t number, float scale = 1);
void drawSegmentedDisplayColon(OLEDDisplay *display, int x, int y, float scale = 1);
void drawHorizontalSegment(OLEDDisplay *display, int x, int y, int width, int height);
void drawVerticalSegment(OLEDDisplay *display, int x, int y, int width, int height);
// UI elements for clock displays
void drawWatchFaceToggleButton(OLEDDisplay *display, int16_t x, int16_t y, bool digitalMode = true, float scale = 1);
void drawBluetoothConnectedIcon(OLEDDisplay *display, int16_t x, int16_t y);
// Utility functions
bool deltaToTimestamp(uint32_t secondsAgo, uint8_t *hours, uint8_t *minutes, int32_t *daysAgo);
} // namespace ClockRenderer
} // namespace graphics

View File

@@ -0,0 +1,132 @@
#include "CompassRenderer.h"
#include "NodeDB.h"
#include "UIRenderer.h"
#include "configuration.h"
#include "gps/GeoCoord.h"
#include "graphics/ScreenFonts.h"
#include <cmath>
namespace graphics
{
namespace CompassRenderer
{
// Point helper class for compass calculations
struct Point {
float x, y;
Point(float x, float y) : x(x), y(y) {}
void rotate(float angle)
{
float cos_a = cos(angle);
float sin_a = sin(angle);
float new_x = x * cos_a - y * sin_a;
float new_y = x * sin_a + y * cos_a;
x = new_x;
y = new_y;
}
void scale(float factor)
{
x *= factor;
y *= factor;
}
void translate(float dx, float dy)
{
x += dx;
y += dy;
}
};
void drawCompassNorth(OLEDDisplay *display, int16_t compassX, int16_t compassY, float myHeading)
{
// Show the compass heading (not implemented in original)
// This could draw a "N" indicator or north arrow
// For now, we'll draw a simple north indicator
const float radius = 8.0f;
Point north(0, -radius);
north.rotate(-myHeading);
north.translate(compassX, compassY);
// Draw a small "N" or north indicator
display->drawCircle(north.x, north.y, 2);
display->setFont(FONT_SMALL);
display->setTextAlignment(TEXT_ALIGN_CENTER);
display->drawString(north.x, north.y - 3, "N");
}
void drawNodeHeading(OLEDDisplay *display, int16_t compassX, int16_t compassY, uint16_t compassDiam, float headingRadian)
{
Point tip(0.0f, 0.5f), tail(0.0f, -0.35f); // pointing up initially
float arrowOffsetX = 0.14f, arrowOffsetY = 1.0f;
Point leftArrow(tip.x - arrowOffsetX, tip.y - arrowOffsetY), rightArrow(tip.x + arrowOffsetX, tip.y - arrowOffsetY);
Point *arrowPoints[] = {&tip, &tail, &leftArrow, &rightArrow};
for (int i = 0; i < 4; i++) {
arrowPoints[i]->rotate(headingRadian);
arrowPoints[i]->scale(compassDiam * 0.6);
arrowPoints[i]->translate(compassX, compassY);
}
#ifdef USE_EINK
display->drawTriangle(tip.x, tip.y, rightArrow.x, rightArrow.y, tail.x, tail.y);
#else
display->fillTriangle(tip.x, tip.y, rightArrow.x, rightArrow.y, tail.x, tail.y);
#endif
display->drawTriangle(tip.x, tip.y, leftArrow.x, leftArrow.y, tail.x, tail.y);
}
void drawArrowToNode(OLEDDisplay *display, int16_t x, int16_t y, int16_t size, float bearing)
{
float radians = bearing * DEG_TO_RAD;
Point tip(0, -size / 2);
Point left(-size / 4, size / 4);
Point right(size / 4, size / 4);
tip.rotate(radians);
left.rotate(radians);
right.rotate(radians);
tip.translate(x, y);
left.translate(x, y);
right.translate(x, y);
display->drawTriangle(tip.x, tip.y, left.x, left.y, right.x, right.y);
}
float estimatedHeading(double lat, double lon)
{
// Simple magnetic declination estimation
// This is a very basic implementation - the original might be more sophisticated
return 0.0f; // Return 0 for now, indicating no heading available
}
uint16_t getCompassDiam(uint32_t displayWidth, uint32_t displayHeight)
{
// Calculate appropriate compass diameter based on display size
uint16_t minDimension = (displayWidth < displayHeight) ? displayWidth : displayHeight;
uint16_t maxDiam = minDimension / 3; // Use 1/3 of the smaller dimension
// Ensure minimum and maximum bounds
if (maxDiam < 16)
maxDiam = 16;
if (maxDiam > 64)
maxDiam = 64;
return maxDiam;
}
float calculateBearing(double lat1, double lon1, double lat2, double lon2)
{
double dLon = (lon2 - lon1) * DEG_TO_RAD;
double y = sin(dLon) * cos(lat2 * DEG_TO_RAD);
double x = cos(lat1 * DEG_TO_RAD) * sin(lat2 * DEG_TO_RAD) - sin(lat1 * DEG_TO_RAD) * cos(lat2 * DEG_TO_RAD) * cos(dLon);
double bearing = atan2(y, x) * RAD_TO_DEG;
return fmod(bearing + 360.0, 360.0);
}
} // namespace CompassRenderer
} // namespace graphics

View File

@@ -0,0 +1,36 @@
#pragma once
#include "graphics/Screen.h"
#include "mesh/generated/meshtastic/mesh.pb.h"
#include <OLEDDisplay.h>
#include <OLEDDisplayUi.h>
namespace graphics
{
/// Forward declarations
class Screen;
/**
* @brief Compass and navigation drawing functions
*
* Contains all functions related to drawing compass elements, headings,
* navigation arrows, and location-based UI components.
*/
namespace CompassRenderer
{
// Compass drawing functions
void drawCompassNorth(OLEDDisplay *display, int16_t compassX, int16_t compassY, float myHeading);
void drawNodeHeading(OLEDDisplay *display, int16_t compassX, int16_t compassY, uint16_t compassDiam, float headingRadian);
void drawArrowToNode(OLEDDisplay *display, int16_t x, int16_t y, int16_t size, float bearing);
// Navigation and location functions
float estimatedHeading(double lat, double lon);
uint16_t getCompassDiam(uint32_t displayWidth, uint32_t displayHeight);
// Utility functions for bearing calculations
float calculateBearing(double lat1, double lon1, double lat2, double lon2);
} // namespace CompassRenderer
} // namespace graphics

View File

@@ -0,0 +1,677 @@
#include "DebugRenderer.h"
#include "../Screen.h"
#include "FSCommon.h"
#include "NodeDB.h"
#include "Throttle.h"
#include "UIRenderer.h"
#include "airtime.h"
#include "configuration.h"
#include "gps/RTC.h"
#include "graphics/ScreenFonts.h"
#include "graphics/SharedUIDisplay.h"
#include "graphics/images.h"
#include "main.h"
#include "mesh/Channels.h"
#include "mesh/generated/meshtastic/deviceonly.pb.h"
#include "sleep.h"
#if HAS_WIFI && !defined(ARCH_PORTDUINO)
#include "mesh/wifi/WiFiAPClient.h"
#include <WiFi.h>
#ifdef ARCH_ESP32
#include "mesh/wifi/WiFiAPClient.h"
#endif
#endif
#ifdef ARCH_ESP32
#include "modules/StoreForwardModule.h"
#endif
#include <DisplayFormatters.h>
#include <RadioLibInterface.h>
#include <target_specific.h>
using namespace meshtastic;
// Battery icon array
static uint8_t imgBattery[16] = {0xFF, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0xE7, 0x3C};
// External variables
extern graphics::Screen *screen;
extern PowerStatus *powerStatus;
extern NodeStatus *nodeStatus;
extern GPSStatus *gpsStatus;
extern Channels channels;
extern "C" {
extern char ourId[5];
}
extern AirTime *airTime;
// External functions from Screen.cpp
extern bool heartbeat;
#ifdef ARCH_ESP32
extern StoreForwardModule *storeForwardModule;
#endif
namespace graphics
{
namespace DebugRenderer
{
void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
display->setFont(FONT_SMALL);
// The coordinates define the left starting point of the text
display->setTextAlignment(TEXT_ALIGN_LEFT);
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_INVERTED) {
display->fillRect(0 + x, 0 + y, x + display->getWidth(), y + FONT_HEIGHT_SMALL);
display->setColor(BLACK);
}
char channelStr[20];
snprintf(channelStr, sizeof(channelStr), "#%s", channels.getName(channels.getPrimaryIndex()));
// Display power status
if (powerStatus->getHasBattery()) {
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_DEFAULT) {
UIRenderer::drawBattery(display, x, y + 2, imgBattery, powerStatus);
} else {
UIRenderer::drawBattery(display, x + 1, y + 3, imgBattery, powerStatus);
}
} else if (powerStatus->knowsUSB()) {
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_DEFAULT) {
display->drawFastImage(x, y + 2, 16, 8, powerStatus->getHasUSB() ? imgUSB : imgPower);
} else {
display->drawFastImage(x + 1, y + 3, 16, 8, powerStatus->getHasUSB() ? imgUSB : imgPower);
}
}
// Display nodes status
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_DEFAULT) {
UIRenderer::drawNodes(display, x + (SCREEN_WIDTH * 0.25), y + 2, nodeStatus);
} else {
UIRenderer::drawNodes(display, x + (SCREEN_WIDTH * 0.25), y + 3, nodeStatus);
}
#if HAS_GPS
// Display GPS status
if (config.position.gps_mode != meshtastic_Config_PositionConfig_GpsMode_ENABLED) {
UIRenderer::drawGpsPowerStatus(display, x, y + 2, gpsStatus);
} else {
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_DEFAULT) {
UIRenderer::drawGps(display, x + (SCREEN_WIDTH * 0.63), y + 2, gpsStatus);
} else {
UIRenderer::drawGps(display, x + (SCREEN_WIDTH * 0.63), y + 3, gpsStatus);
}
}
#endif
display->setColor(WHITE);
// Draw the channel name
display->drawString(x, y + FONT_HEIGHT_SMALL, channelStr);
// Draw our hardware ID to assist with bluetooth pairing. Either prefix with Info or S&F Logo
if (moduleConfig.store_forward.enabled) {
#ifdef ARCH_ESP32
if (!Throttle::isWithinTimespanMs(storeForwardModule->lastHeartbeat,
(storeForwardModule->heartbeatInterval * 1200))) { // no heartbeat, overlap a bit
#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) || defined(ST7701_CS) || defined(ST7735_CS) || \
defined(ST7789_CS) || defined(USE_ST7789) || defined(ILI9488_CS) || defined(HX8357_CS) || ARCH_PORTDUINO) && \
!defined(DISPLAY_FORCE_SMALL_FONTS)
display->drawFastImage(x + SCREEN_WIDTH - 14 - display->getStringWidth(ourId), y + 3 + FONT_HEIGHT_SMALL, 12, 8,
imgQuestionL1);
display->drawFastImage(x + SCREEN_WIDTH - 14 - display->getStringWidth(ourId), y + 11 + FONT_HEIGHT_SMALL, 12, 8,
imgQuestionL2);
#else
display->drawFastImage(x + SCREEN_WIDTH - 10 - display->getStringWidth(ourId), y + 2 + FONT_HEIGHT_SMALL, 8, 8,
imgQuestion);
#endif
} else {
#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) || defined(ST7701_CS) || defined(ST7735_CS) || \
defined(ST7789_CS) || defined(USE_ST7789) || defined(ILI9488_CS) || defined(HX8357_CS)) && \
!defined(DISPLAY_FORCE_SMALL_FONTS)
display->drawFastImage(x + SCREEN_WIDTH - 18 - display->getStringWidth(ourId), y + 3 + FONT_HEIGHT_SMALL, 16, 8,
imgSFL1);
display->drawFastImage(x + SCREEN_WIDTH - 18 - display->getStringWidth(ourId), y + 11 + FONT_HEIGHT_SMALL, 16, 8,
imgSFL2);
#else
display->drawFastImage(x + SCREEN_WIDTH - 13 - display->getStringWidth(ourId), y + 2 + FONT_HEIGHT_SMALL, 11, 8,
imgSF);
#endif
}
#endif
} else {
// TODO: Raspberry Pi supports more than just the one screen size
#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) || defined(ST7701_CS) || defined(ST7735_CS) || \
defined(ST7789_CS) || defined(USE_ST7789) || defined(ILI9488_CS) || defined(HX8357_CS) || ARCH_PORTDUINO) && \
!defined(DISPLAY_FORCE_SMALL_FONTS)
display->drawFastImage(x + SCREEN_WIDTH - 14 - display->getStringWidth(ourId), y + 3 + FONT_HEIGHT_SMALL, 12, 8,
imgInfoL1);
display->drawFastImage(x + SCREEN_WIDTH - 14 - display->getStringWidth(ourId), y + 11 + FONT_HEIGHT_SMALL, 12, 8,
imgInfoL2);
#else
display->drawFastImage(x + SCREEN_WIDTH - 10 - display->getStringWidth(ourId), y + 2 + FONT_HEIGHT_SMALL, 8, 8, imgInfo);
#endif
}
display->drawString(x + SCREEN_WIDTH - display->getStringWidth(ourId), y + FONT_HEIGHT_SMALL, ourId);
// Draw any log messages
display->drawLogBuffer(x, y + (FONT_HEIGHT_SMALL * 2));
/* Display a heartbeat pixel that blinks every time the frame is redrawn */
#ifdef SHOW_REDRAWS
if (heartbeat)
display->setPixel(0, 0);
heartbeat = !heartbeat;
#endif
}
void drawFrameWiFi(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
#if HAS_WIFI && !defined(ARCH_PORTDUINO)
const char *wifiName = config.network.wifi_ssid;
display->setFont(FONT_SMALL);
// The coordinates define the left starting point of the text
display->setTextAlignment(TEXT_ALIGN_LEFT);
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_INVERTED) {
display->fillRect(0 + x, 0 + y, x + display->getWidth(), y + FONT_HEIGHT_SMALL);
display->setColor(BLACK);
}
if (WiFi.status() != WL_CONNECTED) {
display->drawString(x, y, "WiFi: Not Connected");
if (config.display.heading_bold)
display->drawString(x + 1, y, "WiFi: Not Connected");
} else {
display->drawString(x, y, "WiFi: Connected");
if (config.display.heading_bold)
display->drawString(x + 1, y, "WiFi: Connected");
char rssiStr[32];
snprintf(rssiStr, sizeof(rssiStr), "RSSI %d", WiFi.RSSI());
display->drawString(x + SCREEN_WIDTH - display->getStringWidth(rssiStr), y, rssiStr);
if (config.display.heading_bold) {
display->drawString(x + SCREEN_WIDTH - display->getStringWidth(rssiStr) - 1, y, rssiStr);
}
}
display->setColor(WHITE);
/*
- WL_CONNECTED: assigned when connected to a WiFi network;
- WL_NO_SSID_AVAIL: assigned when no SSID are available;
- WL_CONNECT_FAILED: assigned when the connection fails for all the attempts;
- WL_CONNECTION_LOST: assigned when the connection is lost;
- WL_DISCONNECTED: assigned when disconnected from a network;
- WL_IDLE_STATUS: it is a temporary status assigned when WiFi.begin() is called and remains active until the number of
attempts expires (resulting in WL_CONNECT_FAILED) or a connection is established (resulting in WL_CONNECTED);
- WL_SCAN_COMPLETED: assigned when the scan networks is completed;
- WL_NO_SHIELD: assigned when no WiFi shield is present;
*/
if (WiFi.status() == WL_CONNECTED) {
char ipStr[64];
snprintf(ipStr, sizeof(ipStr), "IP: %s", WiFi.localIP().toString().c_str());
display->drawString(x, y + FONT_HEIGHT_SMALL * 1, ipStr);
} else if (WiFi.status() == WL_NO_SSID_AVAIL) {
display->drawString(x, y + FONT_HEIGHT_SMALL * 1, "SSID Not Found");
} else if (WiFi.status() == WL_CONNECTION_LOST) {
display->drawString(x, y + FONT_HEIGHT_SMALL * 1, "Connection Lost");
} else if (WiFi.status() == WL_IDLE_STATUS) {
display->drawString(x, y + FONT_HEIGHT_SMALL * 1, "Idle ... Reconnecting");
} else if (WiFi.status() == WL_CONNECT_FAILED) {
display->drawString(x, y + FONT_HEIGHT_SMALL * 1, "Connection Failed");
}
#ifdef ARCH_ESP32
else {
// Codes:
// https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-guides/wifi.html#wi-fi-reason-code
display->drawString(x, y + FONT_HEIGHT_SMALL * 1,
WiFi.disconnectReasonName(static_cast<wifi_err_reason_t>(getWifiDisconnectReason())));
}
#else
else {
char statusStr[32];
snprintf(statusStr, sizeof(statusStr), "Unknown status: %d", WiFi.status());
display->drawString(x, y + FONT_HEIGHT_SMALL * 1, statusStr);
}
#endif
char ssidStr[64];
snprintf(ssidStr, sizeof(ssidStr), "SSID: %s", wifiName);
display->drawString(x, y + FONT_HEIGHT_SMALL * 2, ssidStr);
display->drawString(x, y + FONT_HEIGHT_SMALL * 3, "http://meshtastic.local");
/* Display a heartbeat pixel that blinks every time the frame is redrawn */
#ifdef SHOW_REDRAWS
if (heartbeat)
display->setPixel(0, 0);
heartbeat = !heartbeat;
#endif
#endif
}
void drawFrameSettings(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
display->setFont(FONT_SMALL);
// The coordinates define the left starting point of the text
display->setTextAlignment(TEXT_ALIGN_LEFT);
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_INVERTED) {
display->fillRect(0 + x, 0 + y, x + display->getWidth(), y + FONT_HEIGHT_SMALL);
display->setColor(BLACK);
}
char batStr[20];
if (powerStatus->getHasBattery()) {
int batV = powerStatus->getBatteryVoltageMv() / 1000;
int batCv = (powerStatus->getBatteryVoltageMv() % 1000) / 10;
snprintf(batStr, sizeof(batStr), "B %01d.%02dV %3d%% %c%c", batV, batCv, powerStatus->getBatteryChargePercent(),
powerStatus->getIsCharging() ? '+' : ' ', powerStatus->getHasUSB() ? 'U' : ' ');
// Line 1
display->drawString(x, y, batStr);
if (config.display.heading_bold)
display->drawString(x + 1, y, batStr);
} else {
// Line 1
display->drawString(x, y, "USB");
if (config.display.heading_bold)
display->drawString(x + 1, y, "USB");
}
// auto mode = DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, true);
// display->drawString(x + SCREEN_WIDTH - display->getStringWidth(mode), y, mode);
// if (config.display.heading_bold)
// display->drawString(x + SCREEN_WIDTH - display->getStringWidth(mode) - 1, y, mode);
uint32_t currentMillis = millis();
uint32_t seconds = currentMillis / 1000;
uint32_t minutes = seconds / 60;
uint32_t hours = minutes / 60;
uint32_t days = hours / 24;
// currentMillis %= 1000;
// seconds %= 60;
// minutes %= 60;
// hours %= 24;
// Show uptime as days, hours, minutes OR seconds
std::string uptime = UIRenderer::drawTimeDelta(days, hours, minutes, seconds);
// Line 1 (Still)
display->drawString(x + SCREEN_WIDTH - display->getStringWidth(uptime.c_str()), y, uptime.c_str());
if (config.display.heading_bold)
display->drawString(x - 1 + SCREEN_WIDTH - display->getStringWidth(uptime.c_str()), y, uptime.c_str());
display->setColor(WHITE);
// Setup string to assemble analogClock string
std::string analogClock = "";
uint32_t rtc_sec = getValidTime(RTCQuality::RTCQualityDevice, true); // Display local timezone
if (rtc_sec > 0) {
long hms = rtc_sec % SEC_PER_DAY;
// hms += tz.tz_dsttime * SEC_PER_HOUR;
// hms -= tz.tz_minuteswest * SEC_PER_MIN;
// mod `hms` to ensure in positive range of [0...SEC_PER_DAY)
hms = (hms + SEC_PER_DAY) % SEC_PER_DAY;
// Tear apart hms into h:m:s
int hour = hms / SEC_PER_HOUR;
int min = (hms % SEC_PER_HOUR) / SEC_PER_MIN;
int sec = (hms % SEC_PER_HOUR) % SEC_PER_MIN; // or hms % SEC_PER_MIN
char timebuf[12];
if (config.display.use_12h_clock) {
std::string meridiem = "am";
if (hour >= 12) {
if (hour > 12)
hour -= 12;
meridiem = "pm";
}
if (hour == 00) {
hour = 12;
}
snprintf(timebuf, sizeof(timebuf), "%d:%02d:%02d%s", hour, min, sec, meridiem.c_str());
} else {
snprintf(timebuf, sizeof(timebuf), "%02d:%02d:%02d", hour, min, sec);
}
analogClock += timebuf;
}
// Line 2
display->drawString(x, y + FONT_HEIGHT_SMALL * 1, analogClock.c_str());
// Display Channel Utilization
char chUtil[13];
snprintf(chUtil, sizeof(chUtil), "ChUtil %2.0f%%", airTime->channelUtilizationPercent());
display->drawString(x + SCREEN_WIDTH - display->getStringWidth(chUtil), y + FONT_HEIGHT_SMALL * 1, chUtil);
#if HAS_GPS
if (config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_ENABLED) {
// Line 3
if (config.display.gps_format !=
meshtastic_Config_DisplayConfig_GpsCoordinateFormat_DMS) // if DMS then don't draw altitude
UIRenderer::drawGpsAltitude(display, x, y + FONT_HEIGHT_SMALL * 2, gpsStatus);
// Line 4
UIRenderer::drawGpsCoordinates(display, x, y + FONT_HEIGHT_SMALL * 3, gpsStatus);
} else {
UIRenderer::drawGpsPowerStatus(display, x, y + FONT_HEIGHT_SMALL * 2, gpsStatus);
}
#endif
/* Display a heartbeat pixel that blinks every time the frame is redrawn */
#ifdef SHOW_REDRAWS
if (heartbeat)
display->setPixel(0, 0);
heartbeat = !heartbeat;
#endif
}
// Trampoline functions for DebugInfo class access
void drawDebugInfoTrampoline(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
drawFrame(display, state, x, y);
}
void drawDebugInfoSettingsTrampoline(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
drawFrameSettings(display, state, x, y);
}
void drawDebugInfoWiFiTrampoline(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
drawFrameWiFi(display, state, x, y);
}
// ****************************
// * LoRa Focused Screen *
// ****************************
void drawLoRaFocused(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
display->clear();
display->setTextAlignment(TEXT_ALIGN_LEFT);
display->setFont(FONT_SMALL);
// === Header ===
graphics::drawCommonHeader(display, x, y);
// === Draw title (aligned with header baseline) ===
const int highlightHeight = FONT_HEIGHT_SMALL - 1;
const int textY = y + 1 + (highlightHeight - FONT_HEIGHT_SMALL) / 2;
const char *titleStr = (SCREEN_WIDTH > 128) ? "LoRa Info" : "LoRa";
const int centerX = x + SCREEN_WIDTH / 2;
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_INVERTED) {
display->setColor(BLACK);
}
display->setTextAlignment(TEXT_ALIGN_CENTER);
display->drawString(centerX, textY, titleStr);
if (config.display.heading_bold) {
display->drawString(centerX + 1, textY, titleStr);
}
display->setColor(WHITE);
display->setTextAlignment(TEXT_ALIGN_LEFT);
// === First Row: Region / BLE Name ===
graphics::UIRenderer::drawNodes(display, x, compactFirstLine + 3, nodeStatus, 0, true, "");
uint8_t dmac[6];
char shortnameble[35];
getMacAddr(dmac);
snprintf(ourId, sizeof(ourId), "%02x%02x", dmac[4], dmac[5]);
snprintf(shortnameble, sizeof(shortnameble), "BLE: %s", ourId);
int textWidth = display->getStringWidth(shortnameble);
int nameX = (SCREEN_WIDTH - textWidth);
display->drawString(nameX, compactFirstLine, shortnameble);
// === Second Row: Radio Preset ===
auto mode = DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false);
char regionradiopreset[25];
const char *region = myRegion ? myRegion->name : NULL;
snprintf(regionradiopreset, sizeof(regionradiopreset), "%s/%s", region, mode);
textWidth = display->getStringWidth(regionradiopreset);
nameX = (SCREEN_WIDTH - textWidth) / 2;
display->drawString(nameX, compactSecondLine, regionradiopreset);
// === Third Row: Frequency / ChanNum ===
char frequencyslot[35];
char freqStr[16];
float freq = RadioLibInterface::instance->getFreq();
snprintf(freqStr, sizeof(freqStr), "%.3f", freq);
if (config.lora.channel_num == 0) {
snprintf(frequencyslot, sizeof(frequencyslot), "Freq: %s", freqStr);
} else {
snprintf(frequencyslot, sizeof(frequencyslot), "Freq/Chan: %s (%d)", freqStr, config.lora.channel_num);
}
size_t len = strlen(frequencyslot);
if (len >= 4 && strcmp(frequencyslot + len - 4, " (0)") == 0) {
frequencyslot[len - 4] = '\0'; // Remove the last three characters
}
textWidth = display->getStringWidth(frequencyslot);
nameX = (SCREEN_WIDTH - textWidth) / 2;
display->drawString(nameX, compactThirdLine, frequencyslot);
// === Fourth Row: Channel Utilization ===
const char *chUtil = "ChUtil:";
char chUtilPercentage[10];
snprintf(chUtilPercentage, sizeof(chUtilPercentage), "%2.0f%%", airTime->channelUtilizationPercent());
int chUtil_x = (SCREEN_WIDTH > 128) ? display->getStringWidth(chUtil) + 10 : display->getStringWidth(chUtil) + 5;
int chUtil_y = compactFourthLine + 3;
int chutil_bar_width = (SCREEN_WIDTH > 128) ? 100 : 50;
int chutil_bar_height = (SCREEN_WIDTH > 128) ? 12 : 7;
int extraoffset = (SCREEN_WIDTH > 128) ? 6 : 3;
int chutil_percent = airTime->channelUtilizationPercent();
int centerofscreen = SCREEN_WIDTH / 2;
int total_line_content_width = (chUtil_x + chutil_bar_width + display->getStringWidth(chUtilPercentage) + extraoffset) / 2;
int starting_position = centerofscreen - total_line_content_width;
display->drawString(starting_position, compactFourthLine, chUtil);
// Force 56% or higher to show a full 100% bar, text would still show related percent.
if (chutil_percent >= 61) {
chutil_percent = 100;
}
// Weighting for nonlinear segments
float milestone1 = 25;
float milestone2 = 40;
float weight1 = 0.45; // Weight for 025%
float weight2 = 0.35; // Weight for 2540%
float weight3 = 0.20; // Weight for 40100%
float totalWeight = weight1 + weight2 + weight3;
int seg1 = chutil_bar_width * (weight1 / totalWeight);
int seg2 = chutil_bar_width * (weight2 / totalWeight);
int seg3 = chutil_bar_width * (weight3 / totalWeight);
int fillRight = 0;
if (chutil_percent <= milestone1) {
fillRight = (seg1 * (chutil_percent / milestone1));
} else if (chutil_percent <= milestone2) {
fillRight = seg1 + (seg2 * ((chutil_percent - milestone1) / (milestone2 - milestone1)));
} else {
fillRight = seg1 + seg2 + (seg3 * ((chutil_percent - milestone2) / (100 - milestone2)));
}
// Draw outline
display->drawRect(starting_position + chUtil_x, chUtil_y, chutil_bar_width, chutil_bar_height);
// Fill progress
if (fillRight > 0) {
display->fillRect(starting_position + chUtil_x, chUtil_y, fillRight, chutil_bar_height);
}
display->drawString(starting_position + chUtil_x + chutil_bar_width + extraoffset, compactFourthLine, chUtilPercentage);
}
// ****************************
// * Memory Screen *
// ****************************
void drawMemoryUsage(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
display->clear();
display->setFont(FONT_SMALL);
display->setTextAlignment(TEXT_ALIGN_LEFT);
// === Header ===
graphics::drawCommonHeader(display, x, y);
// === Draw title ===
const int highlightHeight = FONT_HEIGHT_SMALL - 1;
const int textY = y + 1 + (highlightHeight - FONT_HEIGHT_SMALL) / 2;
const char *titleStr = (SCREEN_WIDTH > 128) ? "Memory" : "Mem";
const int centerX = x + SCREEN_WIDTH / 2;
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_INVERTED) {
display->setColor(BLACK);
}
display->setTextAlignment(TEXT_ALIGN_CENTER);
display->drawString(centerX, textY, titleStr);
if (config.display.heading_bold) {
display->drawString(centerX + 1, textY, titleStr);
}
display->setColor(WHITE);
// === Layout ===
int contentY = y + FONT_HEIGHT_SMALL;
const int rowYOffset = FONT_HEIGHT_SMALL - 3;
const int barHeight = 6;
const int labelX = x;
const int barsOffset = (SCREEN_WIDTH > 128) ? 24 : 0;
const int barX = x + 40 + barsOffset;
int rowY = contentY;
// === Heap delta tracking (disabled) ===
/*
static uint32_t previousHeapFree = 0;
static int32_t totalHeapDelta = 0;
static int deltaChangeCount = 0;
*/
auto drawUsageRow = [&](const char *label, uint32_t used, uint32_t total, bool isHeap = false) {
if (total == 0)
return;
int percent = (used * 100) / total;
char combinedStr[24];
if (SCREEN_WIDTH > 128) {
snprintf(combinedStr, sizeof(combinedStr), "%s%3d%% %lu/%luKB", (percent > 80) ? "! " : "", percent, used / 1024,
total / 1024);
} else {
snprintf(combinedStr, sizeof(combinedStr), "%s%3d%%", (percent > 80) ? "! " : "", percent);
}
int textWidth = display->getStringWidth(combinedStr);
int adjustedBarWidth = SCREEN_WIDTH - barX - textWidth - 6;
if (adjustedBarWidth < 10)
adjustedBarWidth = 10;
int fillWidth = (used * adjustedBarWidth) / total;
// Label
display->setTextAlignment(TEXT_ALIGN_LEFT);
display->drawString(labelX, rowY, label);
// Bar
int barY = rowY + (FONT_HEIGHT_SMALL - barHeight) / 2;
display->setColor(WHITE);
display->drawRect(barX, barY, adjustedBarWidth, barHeight);
display->fillRect(barX, barY, fillWidth, barHeight);
display->setColor(WHITE);
// Value string
display->setTextAlignment(TEXT_ALIGN_RIGHT);
display->drawString(SCREEN_WIDTH - 2, rowY, combinedStr);
rowY += rowYOffset;
// === Heap delta display (disabled) ===
/*
if (isHeap && previousHeapFree > 0) {
int32_t delta = (int32_t)(memGet.getFreeHeap() - previousHeapFree);
if (delta != 0) {
totalHeapDelta += delta;
deltaChangeCount++;
char deltaStr[16];
snprintf(deltaStr, sizeof(deltaStr), "%ld", delta);
int deltaX = centerX - display->getStringWidth(deltaStr) / 2 - 8;
int deltaY = rowY + 1;
// Triangle
if (delta > 0) {
display->drawLine(deltaX, deltaY + 6, deltaX + 3, deltaY);
display->drawLine(deltaX + 3, deltaY, deltaX + 6, deltaY + 6);
display->drawLine(deltaX, deltaY + 6, deltaX + 6, deltaY + 6);
} else {
display->drawLine(deltaX, deltaY, deltaX + 3, deltaY + 6);
display->drawLine(deltaX + 3, deltaY + 6, deltaX + 6, deltaY);
display->drawLine(deltaX, deltaY, deltaX + 6, deltaY);
}
display->setTextAlignment(TEXT_ALIGN_CENTER);
display->drawString(centerX + 6, deltaY, deltaStr);
rowY += rowYOffset;
}
}
if (isHeap) {
previousHeapFree = memGet.getFreeHeap();
}
*/
};
// === Memory values ===
uint32_t heapUsed = memGet.getHeapSize() - memGet.getFreeHeap();
uint32_t heapTotal = memGet.getHeapSize();
uint32_t psramUsed = memGet.getPsramSize() - memGet.getFreePsram();
uint32_t psramTotal = memGet.getPsramSize();
uint32_t flashUsed = 0, flashTotal = 0;
#ifdef ESP32
flashUsed = FSCom.usedBytes();
flashTotal = FSCom.totalBytes();
#endif
uint32_t sdUsed = 0, sdTotal = 0;
bool hasSD = false;
/*
#ifdef HAS_SDCARD
hasSD = SD.cardType() != CARD_NONE;
if (hasSD) {
sdUsed = SD.usedBytes();
sdTotal = SD.totalBytes();
}
#endif
*/
// === Draw memory rows
drawUsageRow("Heap:", heapUsed, heapTotal, true);
drawUsageRow("PSRAM:", psramUsed, psramTotal);
#ifdef ESP32
if (flashTotal > 0)
drawUsageRow("Flash:", flashUsed, flashTotal);
#endif
if (hasSD && sdTotal > 0)
drawUsageRow("SD:", sdUsed, sdTotal);
}
} // namespace DebugRenderer
} // namespace graphics

View File

@@ -0,0 +1,38 @@
#pragma once
#include <OLEDDisplay.h>
#include <OLEDDisplayUi.h>
namespace graphics
{
/// Forward declarations
class Screen;
class DebugInfo;
/**
* @brief Debug and diagnostic drawing functions
*
* Contains all functions related to drawing debug information,
* WiFi status, settings screens, and diagnostic data.
*/
namespace DebugRenderer
{
// Debug frame functions
void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
void drawFrameSettings(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
void drawFrameWiFi(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
// Trampoline functions for framework callback compatibility
void drawDebugInfoTrampoline(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
void drawDebugInfoSettingsTrampoline(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
void drawDebugInfoWiFiTrampoline(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
// LoRa information display
void drawLoRaFocused(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
// Memory screen display
void drawMemoryUsage(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
} // namespace DebugRenderer
} // namespace graphics

View File

@@ -0,0 +1,38 @@
#pragma once
/**
* @brief Master include file for all Screen draw renderers
*
* This file includes all the individual renderer headers to provide
* a convenient single include for accessing all draw functions.
*/
#include "graphics/draw/ClockRenderer.h"
#include "graphics/draw/CompassRenderer.h"
#include "graphics/draw/DebugRenderer.h"
#include "graphics/draw/NodeListRenderer.h"
#include "graphics/draw/ScreenRenderer.h"
#include "graphics/draw/UIRenderer.h"
namespace graphics
{
/**
* @brief Collection of all draw renderers
*
* This namespace provides access to all the specialized rendering
* functions organized by category.
*/
namespace DrawRenderers
{
// Re-export all renderer namespaces for convenience
using namespace ClockRenderer;
using namespace CompassRenderer;
using namespace DebugRenderer;
using namespace NodeListRenderer;
using namespace ScreenRenderer;
using namespace UIRenderer;
} // namespace DrawRenderers
} // namespace graphics

View File

@@ -0,0 +1,448 @@
/*
BaseUI
Developed and Maintained By:
- Ronald Garcia (HarukiToreda) Lead development and implementation.
- JasonP (Xaositek) Screen layout and icon design, UI improvements and testing.
- TonyG (Tropho) Project management, structural planning, and testing
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "MessageRenderer.h"
// Core includes
#include "NodeDB.h"
#include "configuration.h"
#include "gps/RTC.h"
#include "graphics/ScreenFonts.h"
#include "graphics/SharedUIDisplay.h"
#include "graphics/emotes.h"
#include "main.h"
#include "meshUtils.h"
// Additional includes for UI rendering
#include "UIRenderer.h"
// Additional includes for dependencies
#include <string>
#include <vector>
// External declarations
extern bool hasUnreadMessage;
extern meshtastic_DeviceState devicestate;
using graphics::Emote;
using graphics::emotes;
using graphics::numEmotes;
namespace graphics
{
namespace MessageRenderer
{
// Forward declaration from Screen.cpp - this function needs to be accessible
// For now, we'll implement a local version that matches the Screen.cpp functionality
bool deltaToTimestamp(uint32_t secondsAgo, uint8_t *hours, uint8_t *minutes, int32_t *daysAgo)
{
// Cache the result - avoid frequent recalculation
static uint8_t hoursCached = 0, minutesCached = 0;
static uint32_t daysAgoCached = 0;
static uint32_t secondsAgoCached = 0;
static bool validCached = false;
// Abort: if timezone not set
if (strlen(config.device.tzdef) == 0) {
validCached = false;
return validCached;
}
// Abort: if invalid pointers passed
if (hours == nullptr || minutes == nullptr || daysAgo == nullptr) {
validCached = false;
return validCached;
}
// Abort: if time seems invalid.. (> 6 months ago, probably seen before RTC set)
if (secondsAgo > SEC_PER_DAY * 30UL * 6) {
validCached = false;
return validCached;
}
// If repeated request, don't bother recalculating
if (secondsAgo - secondsAgoCached < 60 && secondsAgoCached != 0) {
if (validCached) {
*hours = hoursCached;
*minutes = minutesCached;
*daysAgo = daysAgoCached;
}
return validCached;
}
// Get local time
uint32_t secondsRTC = getValidTime(RTCQuality::RTCQualityDevice, true); // Get local time
// Abort: if RTC not set
if (!secondsRTC) {
validCached = false;
return validCached;
}
// Get absolute time when last seen
uint32_t secondsSeenAt = secondsRTC - secondsAgo;
// Calculate daysAgo
*daysAgo = (secondsRTC / SEC_PER_DAY) - (secondsSeenAt / SEC_PER_DAY); // How many "midnights" have passed
// Get seconds since midnight
uint32_t hms = (secondsRTC - secondsAgo) % SEC_PER_DAY;
hms = (hms + SEC_PER_DAY) % SEC_PER_DAY;
// Tear apart hms into hours and minutes
*hours = hms / SEC_PER_HOUR;
*minutes = (hms % SEC_PER_HOUR) / SEC_PER_MIN;
// Cache the result
daysAgoCached = *daysAgo;
hoursCached = *hours;
minutesCached = *minutes;
secondsAgoCached = secondsAgo;
validCached = true;
return validCached;
}
void drawStringWithEmotes(OLEDDisplay *display, int x, int y, const std::string &line, const Emote *emotes, int emoteCount)
{
int cursorX = x;
const int fontHeight = FONT_HEIGHT_SMALL;
// === Step 1: Find tallest emote in the line ===
int maxIconHeight = fontHeight;
for (size_t i = 0; i < line.length();) {
bool matched = false;
for (int e = 0; e < emoteCount; ++e) {
size_t emojiLen = strlen(emotes[e].label);
if (line.compare(i, emojiLen, emotes[e].label) == 0) {
if (emotes[e].height > maxIconHeight)
maxIconHeight = emotes[e].height;
i += emojiLen;
matched = true;
break;
}
}
if (!matched) {
uint8_t c = static_cast<uint8_t>(line[i]);
if ((c & 0xE0) == 0xC0)
i += 2;
else if ((c & 0xF0) == 0xE0)
i += 3;
else if ((c & 0xF8) == 0xF0)
i += 4;
else
i += 1;
}
}
// === Step 2: Baseline alignment ===
int lineHeight = std::max(fontHeight, maxIconHeight);
int baselineOffset = (lineHeight - fontHeight) / 2;
int fontY = y + baselineOffset;
int fontMidline = fontY + fontHeight / 2;
// === Step 3: Render line in segments ===
size_t i = 0;
bool inBold = false;
while (i < line.length()) {
// Check for ** start/end for faux bold
if (line.compare(i, 2, "**") == 0) {
inBold = !inBold;
i += 2;
continue;
}
// Look ahead for the next emote match
size_t nextEmotePos = std::string::npos;
const Emote *matchedEmote = nullptr;
size_t emojiLen = 0;
for (int e = 0; e < emoteCount; ++e) {
size_t pos = line.find(emotes[e].label, i);
if (pos != std::string::npos && (nextEmotePos == std::string::npos || pos < nextEmotePos)) {
nextEmotePos = pos;
matchedEmote = &emotes[e];
emojiLen = strlen(emotes[e].label);
}
}
// Render normal text segment up to the emote or bold toggle
size_t nextControl = std::min(nextEmotePos, line.find("**", i));
if (nextControl == std::string::npos)
nextControl = line.length();
if (nextControl > i) {
std::string textChunk = line.substr(i, nextControl - i);
if (inBold) {
// Faux bold: draw twice, offset by 1px
display->drawString(cursorX + 1, fontY, textChunk.c_str());
}
display->drawString(cursorX, fontY, textChunk.c_str());
cursorX += display->getStringWidth(textChunk.c_str());
i = nextControl;
continue;
}
// Render the emote (if found)
if (matchedEmote && i == nextEmotePos) {
int iconY = fontMidline - matchedEmote->height / 2 - 1;
display->drawXbm(cursorX, iconY, matchedEmote->width, matchedEmote->height, matchedEmote->bitmap);
cursorX += matchedEmote->width + 1;
i += emojiLen;
} else {
// No more emotes — render the rest of the line
std::string remaining = line.substr(i);
if (inBold) {
display->drawString(cursorX + 1, fontY, remaining.c_str());
}
display->drawString(cursorX, fontY, remaining.c_str());
cursorX += display->getStringWidth(remaining.c_str());
break;
}
}
}
void drawTextMessageFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
// Clear the unread message indicator when viewing the message
hasUnreadMessage = false;
const meshtastic_MeshPacket &mp = devicestate.rx_text_message;
const char *msg = reinterpret_cast<const char *>(mp.decoded.payload.bytes);
display->setTextAlignment(TEXT_ALIGN_LEFT);
display->setFont(FONT_SMALL);
const int navHeight = FONT_HEIGHT_SMALL;
const int scrollBottom = SCREEN_HEIGHT - navHeight;
const int usableHeight = scrollBottom;
const int textWidth = SCREEN_WIDTH;
const int cornerRadius = 2;
bool isInverted = (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_INVERTED);
bool isBold = config.display.heading_bold;
// === Header Construction ===
meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(getFrom(&mp));
char headerStr[80];
const char *sender = "???";
if (node && node->has_user) {
if (SCREEN_WIDTH >= 200 && strlen(node->user.long_name) > 0) {
sender = node->user.long_name;
} else {
sender = node->user.short_name;
}
}
uint32_t seconds = sinceReceived(&mp), minutes = seconds / 60, hours = minutes / 60, days = hours / 24;
uint8_t timestampHours, timestampMinutes;
int32_t daysAgo;
bool useTimestamp = deltaToTimestamp(seconds, &timestampHours, &timestampMinutes, &daysAgo);
if (useTimestamp && minutes >= 15 && daysAgo == 0) {
std::string prefix = (daysAgo == 1 && SCREEN_WIDTH >= 200) ? "Yesterday" : "At";
if (config.display.use_12h_clock) {
bool isPM = timestampHours >= 12;
timestampHours = timestampHours % 12;
if (timestampHours == 0)
timestampHours = 12;
snprintf(headerStr, sizeof(headerStr), "%s %d:%02d%s from %s", prefix.c_str(), timestampHours, timestampMinutes,
isPM ? "p" : "a", sender);
} else {
snprintf(headerStr, sizeof(headerStr), "%s %d:%02d from %s", prefix.c_str(), timestampHours, timestampMinutes,
sender);
}
} else {
snprintf(headerStr, sizeof(headerStr), "%s ago from %s", UIRenderer::drawTimeDelta(days, hours, minutes, seconds).c_str(),
sender);
}
#ifndef EXCLUDE_EMOJI
// === Bounce animation setup ===
static uint32_t lastBounceTime = 0;
static int bounceY = 0;
const int bounceRange = 2; // Max pixels to bounce up/down
const int bounceInterval = 60; // How quickly to change bounce direction (ms)
uint32_t now = millis();
if (now - lastBounceTime >= bounceInterval) {
lastBounceTime = now;
bounceY = (bounceY + 1) % (bounceRange * 2);
}
for (int i = 0; i < numEmotes; ++i) {
const Emote &e = emotes[i];
if (strcmp(msg, e.label) == 0) {
// Draw the header
if (isInverted) {
drawRoundedHighlight(display, x, 0, SCREEN_WIDTH, FONT_HEIGHT_SMALL - 1, cornerRadius);
display->setColor(BLACK);
display->drawString(x + 3, 0, headerStr);
if (isBold)
display->drawString(x + 4, 0, headerStr);
display->setColor(WHITE);
} else {
display->drawString(x, 0, headerStr);
if (SCREEN_WIDTH > 128) {
display->drawLine(0, 20, SCREEN_WIDTH, 20);
} else {
display->drawLine(0, 14, SCREEN_WIDTH, 14);
}
}
// Center the emote below header + apply bounce
int remainingHeight = SCREEN_HEIGHT - FONT_HEIGHT_SMALL - navHeight;
int emoteY = FONT_HEIGHT_SMALL + (remainingHeight - e.height) / 2 + bounceY - bounceRange;
display->drawXbm((SCREEN_WIDTH - e.width) / 2, emoteY, e.width, e.height, e.bitmap);
return;
}
}
#endif
// === Word-wrap and build line list ===
char messageBuf[237];
snprintf(messageBuf, sizeof(messageBuf), "%s", msg);
std::vector<std::string> lines;
lines.push_back(std::string(headerStr)); // Header line is always first
std::string line, word;
for (int i = 0; messageBuf[i]; ++i) {
char ch = messageBuf[i];
if (ch == '\n') {
if (!word.empty())
line += word;
if (!line.empty())
lines.push_back(line);
line.clear();
word.clear();
} else if (ch == ' ') {
line += word + ' ';
word.clear();
} else {
word += ch;
std::string test = line + word;
if (display->getStringWidth(test.c_str()) > textWidth + 4) {
if (!line.empty())
lines.push_back(line);
line = word;
word.clear();
}
}
}
if (!word.empty())
line += word;
if (!line.empty())
lines.push_back(line);
// === Scrolling logic ===
std::vector<int> rowHeights;
for (const auto &line : lines) {
int maxHeight = FONT_HEIGHT_SMALL;
for (int i = 0; i < numEmotes; ++i) {
const Emote &e = emotes[i];
if (line.find(e.label) != std::string::npos) {
if (e.height > maxHeight)
maxHeight = e.height;
}
}
rowHeights.push_back(maxHeight);
}
int totalHeight = 0;
for (size_t i = 1; i < rowHeights.size(); ++i) {
totalHeight += rowHeights[i];
}
int usableScrollHeight = usableHeight - rowHeights[0]; // remove header height
int scrollStop = std::max(0, totalHeight - usableScrollHeight);
static float scrollY = 0.0f;
static uint32_t lastTime = 0, scrollStartDelay = 0, pauseStart = 0;
static bool waitingToReset = false, scrollStarted = false;
// === Smooth scrolling adjustment ===
// You can tweak this divisor to change how smooth it scrolls.
// Lower = smoother, but can feel slow.
float delta = (now - lastTime) / 400.0f;
lastTime = now;
const float scrollSpeed = 2.0f; // pixels per second
// Delay scrolling start by 2 seconds
if (scrollStartDelay == 0)
scrollStartDelay = now;
if (!scrollStarted && now - scrollStartDelay > 2000)
scrollStarted = true;
if (totalHeight > usableHeight) {
if (scrollStarted) {
if (!waitingToReset) {
scrollY += delta * scrollSpeed;
if (scrollY >= scrollStop) {
scrollY = scrollStop;
waitingToReset = true;
pauseStart = lastTime;
}
} else if (lastTime - pauseStart > 3000) {
scrollY = 0;
waitingToReset = false;
scrollStarted = false;
scrollStartDelay = lastTime;
}
}
} else {
scrollY = 0;
}
int scrollOffset = static_cast<int>(scrollY);
int yOffset = -scrollOffset;
if (!isInverted) {
if (SCREEN_WIDTH > 128) {
display->drawLine(0, yOffset + 20, SCREEN_WIDTH, yOffset + 20);
} else {
display->drawLine(0, yOffset + 14, SCREEN_WIDTH, yOffset + 14);
}
}
// === Render visible lines ===
for (size_t i = 0; i < lines.size(); ++i) {
int lineY = yOffset;
for (size_t j = 0; j < i; ++j)
lineY += rowHeights[j];
if (lineY > -rowHeights[i] && lineY < scrollBottom) {
if (i == 0 && isInverted) {
drawRoundedHighlight(display, x, lineY, SCREEN_WIDTH, FONT_HEIGHT_SMALL - 1, cornerRadius);
display->setColor(BLACK);
display->drawString(x + 3, lineY, lines[i].c_str());
if (isBold)
display->drawString(x + 4, lineY, lines[i].c_str());
display->setColor(WHITE);
} else {
drawStringWithEmotes(display, x, lineY, lines[i], emotes, numEmotes);
}
}
}
}
} // namespace MessageRenderer
} // namespace graphics

View File

@@ -0,0 +1,18 @@
#pragma once
#include "OLEDDisplay.h"
#include "OLEDDisplayUi.h"
#include "graphics/emotes.h"
namespace graphics
{
namespace MessageRenderer
{
// Text and emote rendering
void drawStringWithEmotes(OLEDDisplay *display, int x, int y, const std::string &line, const Emote *emotes, int emoteCount);
/// Draws the text message frame for displaying received messages
void drawTextMessageFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
} // namespace MessageRenderer
} // namespace graphics

View File

@@ -0,0 +1,878 @@
#include "NodeListRenderer.h"
#include "CompassRenderer.h"
#include "NodeDB.h"
#include "UIRenderer.h"
#include "configuration.h"
#include "gps/GeoCoord.h"
#include "gps/RTC.h" // for getTime() function
#include "graphics/ScreenFonts.h"
#include "graphics/SharedUIDisplay.h"
#include "graphics/images.h"
#include <algorithm>
// Forward declarations for functions defined in Screen.cpp
namespace graphics
{
extern bool haveGlyphs(const char *str);
} // namespace graphics
// Global screen instance
extern graphics::Screen *screen;
namespace graphics
{
namespace NodeListRenderer
{
// Function moved from Screen.cpp to NodeListRenderer.cpp since it's primarily used here
void drawScaledXBitmap16x16(int x, int y, int width, int height, const uint8_t *bitmapXBM, OLEDDisplay *display)
{
for (int row = 0; row < height; row++) {
uint8_t rowMask = (1 << row);
for (int col = 0; col < width; col++) {
uint8_t colData = pgm_read_byte(&bitmapXBM[col]);
if (colData & rowMask) {
// Note: rows become X, columns become Y after transpose
display->fillRect(x + row * 2, y + col * 2, 2, 2);
}
}
}
}
// Static variables for dynamic cycling
static NodeListMode currentMode = MODE_LAST_HEARD;
static int scrollIndex = 0;
// =============================
// Utility Functions
// =============================
const char *getSafeNodeName(meshtastic_NodeInfoLite *node)
{
static char nodeName[16] = "?";
if (node->has_user && strlen(node->user.short_name) > 0) {
bool valid = true;
const char *name = node->user.short_name;
for (size_t i = 0; i < strlen(name); i++) {
uint8_t c = (uint8_t)name[i];
if (c < 32 || c > 126) {
valid = false;
break;
}
}
if (valid) {
strncpy(nodeName, name, sizeof(nodeName) - 1);
nodeName[sizeof(nodeName) - 1] = '\0';
} else {
snprintf(nodeName, sizeof(nodeName), "%04X", (uint16_t)(node->num & 0xFFFF));
}
} else {
strcpy(nodeName, "?");
}
return nodeName;
}
uint32_t sinceLastSeen(meshtastic_NodeInfoLite *node)
{
uint32_t now = getTime();
uint32_t last_seen = node->last_heard;
if (last_seen == 0 || now < last_seen) {
return UINT32_MAX;
}
return now - last_seen;
}
const char *getCurrentModeTitle(int screenWidth)
{
switch (currentMode) {
case MODE_LAST_HEARD:
return "Node List";
case MODE_HOP_SIGNAL:
return (screenWidth > 128) ? "Hops/Signal" : "Hops/Sig";
case MODE_DISTANCE:
return "Distance";
default:
return "Nodes";
}
}
// Use dynamic timing based on mode
unsigned long getModeCycleIntervalMs()
{
return 3000;
}
// Calculate bearing between two lat/lon points
float calculateBearing(double lat1, double lon1, double lat2, double lon2)
{
double dLon = (lon2 - lon1) * DEG_TO_RAD;
double y = sin(dLon) * cos(lat2 * DEG_TO_RAD);
double x = cos(lat1 * DEG_TO_RAD) * sin(lat2 * DEG_TO_RAD) - sin(lat1 * DEG_TO_RAD) * cos(lat2 * DEG_TO_RAD) * cos(dLon);
double bearing = atan2(y, x) * RAD_TO_DEG;
return fmod(bearing + 360.0, 360.0);
}
int calculateMaxScroll(int totalEntries, int visibleRows)
{
return std::max(0, (totalEntries - 1) / (visibleRows * 2));
}
void retrieveAndSortNodes(std::vector<NodeEntry> &nodeList)
{
size_t numNodes = nodeDB->getNumMeshNodes();
for (size_t i = 0; i < numNodes; i++) {
meshtastic_NodeInfoLite *node = nodeDB->getMeshNodeByIndex(i);
if (!node || node->num == nodeDB->getNodeNum())
continue;
NodeEntry entry;
entry.node = node;
entry.sortValue = sinceLastSeen(node);
nodeList.push_back(entry);
}
// Sort nodes: favorites first, then by last heard (most recent first)
std::sort(nodeList.begin(), nodeList.end(), [](const NodeEntry &a, const NodeEntry &b) {
bool aFav = a.node->is_favorite;
bool bFav = b.node->is_favorite;
if (aFav != bFav)
return aFav > bFav;
if (a.sortValue == 0 || a.sortValue == UINT32_MAX)
return false;
if (b.sortValue == 0 || b.sortValue == UINT32_MAX)
return true;
return a.sortValue < b.sortValue;
});
}
void drawColumnSeparator(OLEDDisplay *display, int16_t x, int16_t yStart, int16_t yEnd)
{
int columnWidth = display->getWidth() / 2;
int separatorX = x + columnWidth - 1;
for (int y = yStart; y <= yEnd; y += 2) {
display->setPixel(separatorX, y);
}
}
void drawScrollbar(OLEDDisplay *display, int visibleNodeRows, int totalEntries, int scrollIndex, int columns, int scrollStartY)
{
if (totalEntries <= visibleNodeRows * columns)
return;
int scrollbarX = display->getWidth() - 2;
int scrollbarHeight = display->getHeight() - scrollStartY - 10;
int thumbHeight = std::max(4, (scrollbarHeight * visibleNodeRows * columns) / totalEntries);
int maxScroll = calculateMaxScroll(totalEntries, visibleNodeRows);
int thumbY = scrollStartY + (scrollIndex * (scrollbarHeight - thumbHeight)) / std::max(1, maxScroll);
for (int i = 0; i < thumbHeight; i++) {
display->setPixel(scrollbarX, thumbY + i);
}
}
// =============================
// Entry Renderers
// =============================
void drawEntryLastHeard(OLEDDisplay *display, meshtastic_NodeInfoLite *node, int16_t x, int16_t y, int columnWidth)
{
bool isLeftCol = (x < SCREEN_WIDTH / 2);
int timeOffset = (SCREEN_WIDTH > 128) ? (isLeftCol ? 7 : 10) : (isLeftCol ? 3 : 7);
const char *nodeName = getSafeNodeName(node);
char timeStr[10];
uint32_t seconds = sinceLastSeen(node);
if (seconds == 0 || seconds == UINT32_MAX) {
snprintf(timeStr, sizeof(timeStr), "?");
} else {
uint32_t minutes = seconds / 60, hours = minutes / 60, days = hours / 24;
snprintf(timeStr, sizeof(timeStr), (days > 365 ? "?" : "%d%c"),
(days ? days
: hours ? hours
: minutes),
(days ? 'd'
: hours ? 'h'
: 'm'));
}
display->setTextAlignment(TEXT_ALIGN_LEFT);
display->setFont(FONT_SMALL);
display->drawString(x + ((SCREEN_WIDTH > 128) ? 6 : 3), y, nodeName);
if (node->is_favorite) {
if (SCREEN_WIDTH > 128) {
drawScaledXBitmap16x16(x, y + 6, smallbulletpoint_width, smallbulletpoint_height, smallbulletpoint, display);
} else {
display->drawXbm(x, y + 5, smallbulletpoint_width, smallbulletpoint_height, smallbulletpoint);
}
}
int rightEdge = x + columnWidth - timeOffset;
int textWidth = display->getStringWidth(timeStr);
display->drawString(rightEdge - textWidth, y, timeStr);
}
void drawEntryHopSignal(OLEDDisplay *display, meshtastic_NodeInfoLite *node, int16_t x, int16_t y, int columnWidth)
{
bool isLeftCol = (x < SCREEN_WIDTH / 2);
int nameMaxWidth = columnWidth - 25;
int barsOffset = (SCREEN_WIDTH > 128) ? (isLeftCol ? 16 : 20) : (isLeftCol ? 15 : 19);
int hopOffset = (SCREEN_WIDTH > 128) ? (isLeftCol ? 17 : 25) : (isLeftCol ? 13 : 17);
int barsXOffset = columnWidth - barsOffset;
const char *nodeName = getSafeNodeName(node);
display->setTextAlignment(TEXT_ALIGN_LEFT);
display->setFont(FONT_SMALL);
display->drawStringMaxWidth(x + ((SCREEN_WIDTH > 128) ? 6 : 3), y, nameMaxWidth, nodeName);
if (node->is_favorite) {
if (SCREEN_WIDTH > 128) {
drawScaledXBitmap16x16(x, y + 6, smallbulletpoint_width, smallbulletpoint_height, smallbulletpoint, display);
} else {
display->drawXbm(x, y + 5, smallbulletpoint_width, smallbulletpoint_height, smallbulletpoint);
}
}
// Draw signal strength bars
int bars = (node->snr > 5) ? 4 : (node->snr > 0) ? 3 : (node->snr > -5) ? 2 : (node->snr > -10) ? 1 : 0;
int barWidth = 2;
int barStartX = x + barsXOffset;
int barStartY = y + 1 + (FONT_HEIGHT_SMALL / 2) + 2;
for (int b = 0; b < 4; b++) {
if (b < bars) {
int height = (b * 2);
display->fillRect(barStartX + (b * (barWidth + 1)), barStartY - height, barWidth, height);
}
}
// Draw hop count
char hopStr[6] = "";
if (node->has_hops_away && node->hops_away > 0)
snprintf(hopStr, sizeof(hopStr), "[%d]", node->hops_away);
if (hopStr[0] != '\0') {
int rightEdge = x + columnWidth - hopOffset;
int textWidth = display->getStringWidth(hopStr);
display->drawString(rightEdge - textWidth, y, hopStr);
}
}
void drawNodeDistance(OLEDDisplay *display, meshtastic_NodeInfoLite *node, int16_t x, int16_t y, int columnWidth)
{
bool isLeftCol = (x < SCREEN_WIDTH / 2);
int nameMaxWidth = columnWidth - (SCREEN_WIDTH > 128 ? (isLeftCol ? 25 : 28) : (isLeftCol ? 20 : 22));
const char *nodeName = getSafeNodeName(node);
char distStr[10] = "";
meshtastic_NodeInfoLite *ourNode = nodeDB->getMeshNode(nodeDB->getNodeNum());
if (nodeDB->hasValidPosition(ourNode) && nodeDB->hasValidPosition(node)) {
double lat1 = ourNode->position.latitude_i * 1e-7;
double lon1 = ourNode->position.longitude_i * 1e-7;
double lat2 = node->position.latitude_i * 1e-7;
double lon2 = node->position.longitude_i * 1e-7;
double earthRadiusKm = 6371.0;
double dLat = (lat2 - lat1) * DEG_TO_RAD;
double dLon = (lon2 - lon1) * DEG_TO_RAD;
double a =
sin(dLat / 2) * sin(dLat / 2) + cos(lat1 * DEG_TO_RAD) * cos(lat2 * DEG_TO_RAD) * sin(dLon / 2) * sin(dLon / 2);
double c = 2 * atan2(sqrt(a), sqrt(1 - a));
double distanceKm = earthRadiusKm * c;
if (config.display.units == meshtastic_Config_DisplayConfig_DisplayUnits_IMPERIAL) {
double miles = distanceKm * 0.621371;
if (miles < 0.1) {
int feet = (int)(miles * 5280);
if (feet < 1000)
snprintf(distStr, sizeof(distStr), "%dft", feet);
else
snprintf(distStr, sizeof(distStr), "¼mi"); // 4-char max
} else {
int roundedMiles = (int)(miles + 0.5);
if (roundedMiles < 1000)
snprintf(distStr, sizeof(distStr), "%dmi", roundedMiles);
else
snprintf(distStr, sizeof(distStr), "999"); // Max display cap
}
} else {
if (distanceKm < 1.0) {
int meters = (int)(distanceKm * 1000);
if (meters < 1000)
snprintf(distStr, sizeof(distStr), "%dm", meters);
else
snprintf(distStr, sizeof(distStr), "1k");
} else {
int km = (int)(distanceKm + 0.5);
if (km < 1000)
snprintf(distStr, sizeof(distStr), "%dk", km);
else
snprintf(distStr, sizeof(distStr), "999");
}
}
}
display->setTextAlignment(TEXT_ALIGN_LEFT);
display->setFont(FONT_SMALL);
display->drawStringMaxWidth(x + ((SCREEN_WIDTH > 128) ? 6 : 3), y, nameMaxWidth, nodeName);
if (node->is_favorite) {
if (SCREEN_WIDTH > 128) {
drawScaledXBitmap16x16(x, y + 6, smallbulletpoint_width, smallbulletpoint_height, smallbulletpoint, display);
} else {
display->drawXbm(x, y + 5, smallbulletpoint_width, smallbulletpoint_height, smallbulletpoint);
}
}
if (strlen(distStr) > 0) {
int offset = (SCREEN_WIDTH > 128) ? (isLeftCol ? 7 : 10) // Offset for Wide Screens (Left Column:Right Column)
: (isLeftCol ? 5 : 8); // Offset for Narrow Screens (Left Column:Right Column)
int rightEdge = x + columnWidth - offset;
int textWidth = display->getStringWidth(distStr);
display->drawString(rightEdge - textWidth, y, distStr);
}
}
void drawEntryDynamic(OLEDDisplay *display, meshtastic_NodeInfoLite *node, int16_t x, int16_t y, int columnWidth)
{
switch (currentMode) {
case MODE_LAST_HEARD:
drawEntryLastHeard(display, node, x, y, columnWidth);
break;
case MODE_HOP_SIGNAL:
drawEntryHopSignal(display, node, x, y, columnWidth);
break;
case MODE_DISTANCE:
drawNodeDistance(display, node, x, y, columnWidth);
break;
default:
break;
}
}
void drawEntryCompass(OLEDDisplay *display, meshtastic_NodeInfoLite *node, int16_t x, int16_t y, int columnWidth)
{
bool isLeftCol = (x < SCREEN_WIDTH / 2);
// Adjust max text width depending on column and screen width
int nameMaxWidth = columnWidth - (SCREEN_WIDTH > 128 ? (isLeftCol ? 25 : 28) : (isLeftCol ? 20 : 22));
const char *nodeName = getSafeNodeName(node);
display->setTextAlignment(TEXT_ALIGN_LEFT);
display->setFont(FONT_SMALL);
display->drawStringMaxWidth(x + ((SCREEN_WIDTH > 128) ? 6 : 3), y, nameMaxWidth, nodeName);
if (node->is_favorite) {
if (SCREEN_WIDTH > 128) {
drawScaledXBitmap16x16(x, y + 6, smallbulletpoint_width, smallbulletpoint_height, smallbulletpoint, display);
} else {
display->drawXbm(x, y + 5, smallbulletpoint_width, smallbulletpoint_height, smallbulletpoint);
}
}
}
void drawCompassArrow(OLEDDisplay *display, meshtastic_NodeInfoLite *node, int16_t x, int16_t y, int columnWidth, float myHeading,
double userLat, double userLon)
{
if (!nodeDB->hasValidPosition(node))
return;
bool isLeftCol = (x < SCREEN_WIDTH / 2);
int arrowXOffset = (SCREEN_WIDTH > 128) ? (isLeftCol ? 22 : 24) : (isLeftCol ? 12 : 18);
int centerX = x + columnWidth - arrowXOffset;
int centerY = y + FONT_HEIGHT_SMALL / 2;
double nodeLat = node->position.latitude_i * 1e-7;
double nodeLon = node->position.longitude_i * 1e-7;
float bearingToNode = calculateBearing(userLat, userLon, nodeLat, nodeLon);
float relativeBearing = fmod((bearingToNode - myHeading + 360), 360);
float angle = relativeBearing * DEG_TO_RAD;
// Shrink size by 2px
int size = FONT_HEIGHT_SMALL - 5;
float halfSize = size / 2.0;
// Point of the arrow
int tipX = centerX + halfSize * cos(angle);
int tipY = centerY - halfSize * sin(angle);
float baseAngle = radians(35);
float sideLen = halfSize * 0.95;
float notchInset = halfSize * 0.35;
// Left and right corners
int leftX = centerX + sideLen * cos(angle + PI - baseAngle);
int leftY = centerY - sideLen * sin(angle + PI - baseAngle);
int rightX = centerX + sideLen * cos(angle + PI + baseAngle);
int rightY = centerY - sideLen * sin(angle + PI + baseAngle);
// Center notch (cut-in)
int notchX = centerX - notchInset * cos(angle);
int notchY = centerY + notchInset * sin(angle);
// Draw the chevron-style arrowhead
display->fillTriangle(tipX, tipY, leftX, leftY, notchX, notchY);
display->fillTriangle(tipX, tipY, notchX, notchY, rightX, rightY);
}
// =============================
// Main Screen Functions
// =============================
void drawNodeListScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y, const char *title,
EntryRenderer renderer, NodeExtrasRenderer extras, float heading, double lat, double lon)
{
const int COMMON_HEADER_HEIGHT = FONT_HEIGHT_SMALL - 1;
const int rowYOffset = FONT_HEIGHT_SMALL - 3;
int columnWidth = display->getWidth() / 2;
display->clear();
// Draw the battery/time header
graphics::drawCommonHeader(display, x, y);
// Draw the centered title within the header
const int highlightHeight = COMMON_HEADER_HEIGHT;
const int textY = y + 1 + (highlightHeight - FONT_HEIGHT_SMALL) / 2;
const int centerX = x + SCREEN_WIDTH / 2;
display->setFont(FONT_SMALL);
display->setTextAlignment(TEXT_ALIGN_CENTER);
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_INVERTED)
display->setColor(BLACK);
display->drawString(centerX, textY, title);
if (config.display.heading_bold)
display->drawString(centerX + 1, textY, title);
display->setColor(WHITE);
display->setTextAlignment(TEXT_ALIGN_LEFT);
// Space below header
y += COMMON_HEADER_HEIGHT;
// Fetch and display sorted node list
std::vector<NodeEntry> nodeList;
retrieveAndSortNodes(nodeList);
int totalEntries = nodeList.size();
int totalRowsAvailable = (display->getHeight() - y) / rowYOffset;
#ifdef USE_EINK
totalRowsAvailable -= 1;
#endif
int visibleNodeRows = totalRowsAvailable;
int totalColumns = 2;
int startIndex = scrollIndex * visibleNodeRows * totalColumns;
int endIndex = std::min(startIndex + visibleNodeRows * totalColumns, totalEntries);
int yOffset = 0;
int col = 0;
int lastNodeY = y;
int shownCount = 0;
int rowCount = 0;
for (int i = startIndex; i < endIndex; ++i) {
int xPos = x + (col * columnWidth);
int yPos = y + yOffset;
renderer(display, nodeList[i].node, xPos, yPos, columnWidth);
if (extras) {
extras(display, nodeList[i].node, xPos, yPos, columnWidth, heading, lat, lon);
}
lastNodeY = std::max(lastNodeY, yPos + FONT_HEIGHT_SMALL);
yOffset += rowYOffset;
shownCount++;
rowCount++;
if (rowCount >= totalRowsAvailable) {
yOffset = 0;
rowCount = 0;
col++;
if (col > (totalColumns - 1))
break;
}
}
// Draw column separator
if (shownCount > 0) {
const int firstNodeY = y + 3;
drawColumnSeparator(display, x, firstNodeY, lastNodeY);
}
const int scrollStartY = y + 3;
drawScrollbar(display, visibleNodeRows, totalEntries, scrollIndex, 2, scrollStartY);
}
// =============================
// Screen Frame Functions
// =============================
#ifndef USE_EINK
void drawDynamicNodeListScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
// Static variables to track mode and duration
static NodeListMode lastRenderedMode = MODE_COUNT;
static unsigned long modeStartTime = 0;
unsigned long now = millis();
// On very first call (on boot or state enter)
if (lastRenderedMode == MODE_COUNT) {
currentMode = MODE_LAST_HEARD;
modeStartTime = now;
}
// Time to switch to next mode?
if (now - modeStartTime >= getModeCycleIntervalMs()) {
currentMode = static_cast<NodeListMode>((currentMode + 1) % MODE_COUNT);
modeStartTime = now;
}
// Render screen based on currentMode
const char *title = getCurrentModeTitle(display->getWidth());
drawNodeListScreen(display, state, x, y, title, drawEntryDynamic);
// Track the last mode to avoid reinitializing modeStartTime
lastRenderedMode = currentMode;
}
#endif
#ifdef USE_EINK
void drawLastHeardScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
const char *title = "Node List";
drawNodeListScreen(display, state, x, y, title, drawEntryLastHeard);
}
void drawHopSignalScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
const char *title = "Hops/Signal";
drawNodeListScreen(display, state, x, y, title, drawEntryHopSignal);
}
void drawDistanceScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
const char *title = "Distance";
drawNodeListScreen(display, state, x, y, title, drawNodeDistance);
}
#endif
void drawNodeListWithCompasses(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
float heading = 0;
bool validHeading = false;
double lat = 0;
double lon = 0;
#if HAS_GPS
if (screen->hasHeading()) {
heading = screen->getHeading(); // degrees
validHeading = true;
} else {
heading = screen->estimatedHeading(lat, lon);
validHeading = !isnan(heading);
}
#endif
if (!validHeading)
return;
drawNodeListScreen(display, state, x, y, "Bearings", drawEntryCompass, drawCompassArrow, heading, lat, lon);
}
void drawNodeInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
// Cache favorite nodes for the current frame only, to save computation
static std::vector<meshtastic_NodeInfoLite *> favoritedNodes;
static int prevFrame = -1;
// Only rebuild favorites list if we're on a new frame
if (state->currentFrame != prevFrame) {
prevFrame = state->currentFrame;
favoritedNodes.clear();
size_t total = nodeDB->getNumMeshNodes();
for (size_t i = 0; i < total; i++) {
meshtastic_NodeInfoLite *n = nodeDB->getMeshNodeByIndex(i);
// Skip nulls and ourself
if (!n || n->num == nodeDB->getNodeNum())
continue;
if (n->is_favorite)
favoritedNodes.push_back(n);
}
// Keep a stable, consistent display order
std::sort(favoritedNodes.begin(), favoritedNodes.end(),
[](meshtastic_NodeInfoLite *a, meshtastic_NodeInfoLite *b) { return a->num < b->num; });
}
if (favoritedNodes.empty())
return;
// Only display if index is valid
int nodeIndex = state->currentFrame - (screen->frameCount - favoritedNodes.size());
if (nodeIndex < 0 || nodeIndex >= (int)favoritedNodes.size())
return;
meshtastic_NodeInfoLite *node = favoritedNodes[nodeIndex];
if (!node || node->num == nodeDB->getNodeNum() || !node->is_favorite)
return;
display->clear();
// Draw battery/time/mail header (common across screens)
graphics::drawCommonHeader(display, x, y);
// Draw the short node name centered at the top, with bold shadow if set
const int highlightHeight = FONT_HEIGHT_SMALL - 1;
const int textY = y + 1 + (highlightHeight - FONT_HEIGHT_SMALL) / 2;
const int centerX = x + SCREEN_WIDTH / 2;
const char *shortName = (node->has_user && haveGlyphs(node->user.short_name)) ? node->user.short_name : "Node";
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_INVERTED)
display->setColor(BLACK);
display->setTextAlignment(TEXT_ALIGN_CENTER);
display->setFont(FONT_SMALL);
display->drawString(centerX, textY, shortName);
if (config.display.heading_bold)
display->drawString(centerX + 1, textY, shortName);
display->setColor(WHITE);
display->setTextAlignment(TEXT_ALIGN_LEFT);
display->setFont(FONT_SMALL);
// Dynamic row stacking with predefined Y positions
const int yPositions[5] = {moreCompactFirstLine, moreCompactSecondLine, moreCompactThirdLine, moreCompactFourthLine,
moreCompactFifthLine};
int line = 0;
// 1. Long Name (always try to show first)
const char *username = (node->has_user && node->user.long_name[0]) ? node->user.long_name : nullptr;
if (username && line < 5) {
display->drawString(x, yPositions[line++], username);
}
// 2. Signal and Hops (combined on one line, if available)
char signalHopsStr[32] = "";
bool haveSignal = false;
int percentSignal = clamp((int)((node->snr + 10) * 5), 0, 100);
const char *signalLabel = " Sig";
// If SNR looks reasonable, show signal
if ((int)((node->snr + 10) * 5) >= 0 && node->snr > -100) {
snprintf(signalHopsStr, sizeof(signalHopsStr), "%s: %d%%", signalLabel, percentSignal);
haveSignal = true;
}
// If hops is valid (>0), show right after signal
if (node->hops_away > 0) {
size_t len = strlen(signalHopsStr);
if (haveSignal) {
snprintf(signalHopsStr + len, sizeof(signalHopsStr) - len, " [%d %s]", node->hops_away,
(node->hops_away == 1 ? "Hop" : "Hops"));
} else {
snprintf(signalHopsStr, sizeof(signalHopsStr), "[%d %s]", node->hops_away, (node->hops_away == 1 ? "Hop" : "Hops"));
}
}
if (signalHopsStr[0] && line < 5) {
display->drawString(x, yPositions[line++], signalHopsStr);
}
// 3. Heard (last seen, skip if node never seen)
char seenStr[20] = "";
uint32_t seconds = sinceLastSeen(node);
if (seconds != 0 && seconds != UINT32_MAX) {
uint32_t minutes = seconds / 60, hours = minutes / 60, days = hours / 24;
snprintf(seenStr, sizeof(seenStr), (days > 365 ? " Heard: ?" : " Heard: %d%c ago"),
(days ? days
: hours ? hours
: minutes),
(days ? 'd'
: hours ? 'h'
: 'm'));
}
if (seenStr[0] && line < 5) {
display->drawString(x, yPositions[line++], seenStr);
}
// 4. Uptime (only show if metric is present)
char uptimeStr[32] = "";
if (node->has_device_metrics && node->device_metrics.has_uptime_seconds) {
uint32_t uptime = node->device_metrics.uptime_seconds;
uint32_t days = uptime / 86400;
uint32_t hours = (uptime % 86400) / 3600;
uint32_t mins = (uptime % 3600) / 60;
if (days > 0) {
snprintf(uptimeStr, sizeof(uptimeStr), " Uptime: %dd %dh", days, hours);
} else if (hours > 0) {
snprintf(uptimeStr, sizeof(uptimeStr), " Uptime: %dh %dm", hours, mins);
} else {
snprintf(uptimeStr, sizeof(uptimeStr), " Uptime: %dm", mins);
}
}
if (uptimeStr[0] && line < 5) {
display->drawString(x, yPositions[line++], uptimeStr);
}
// 5. Distance (only if both nodes have GPS position)
meshtastic_NodeInfoLite *ourNode = nodeDB->getMeshNode(nodeDB->getNodeNum());
char distStr[24] = "";
bool haveDistance = false;
if (nodeDB->hasValidPosition(ourNode) && nodeDB->hasValidPosition(node)) {
double lat1 = ourNode->position.latitude_i * 1e-7;
double lon1 = ourNode->position.longitude_i * 1e-7;
double lat2 = node->position.latitude_i * 1e-7;
double lon2 = node->position.longitude_i * 1e-7;
double earthRadiusKm = 6371.0;
double dLat = (lat2 - lat1) * DEG_TO_RAD;
double dLon = (lon2 - lon1) * DEG_TO_RAD;
double a =
sin(dLat / 2) * sin(dLat / 2) + cos(lat1 * DEG_TO_RAD) * cos(lat2 * DEG_TO_RAD) * sin(dLon / 2) * sin(dLon / 2);
double c = 2 * atan2(sqrt(a), sqrt(1 - a));
double distanceKm = earthRadiusKm * c;
// Format distance appropriately
if (distanceKm < 1.0) {
double miles = distanceKm * 0.621371;
if (miles < 0.1) {
int feet = (int)(miles * 5280);
if (feet > 0 && feet < 1000) {
snprintf(distStr, sizeof(distStr), " Distance: %dft", feet);
haveDistance = true;
} else if (feet >= 1000) {
snprintf(distStr, sizeof(distStr), " Distance: ¼mi");
haveDistance = true;
}
} else {
int roundedMiles = (int)(miles + 0.5);
if (roundedMiles > 0 && roundedMiles < 1000) {
snprintf(distStr, sizeof(distStr), " Distance: %dmi", roundedMiles);
haveDistance = true;
}
}
} else {
int km = (int)(distanceKm + 0.5);
if (km > 0 && km < 1000) {
snprintf(distStr, sizeof(distStr), " Distance: %dkm", km);
haveDistance = true;
}
}
}
// Only display if we actually have a value!
if (haveDistance && distStr[0] && line < 5) {
display->drawString(x, yPositions[line++], distStr);
}
// Compass rendering for different screen orientations
if (SCREEN_WIDTH > SCREEN_HEIGHT) {
// Landscape: side-aligned compass
bool showCompass = false;
if (ourNode && (nodeDB->hasValidPosition(ourNode) || screen->hasHeading()) && nodeDB->hasValidPosition(node)) {
showCompass = true;
}
if (showCompass) {
const int16_t topY = compactFirstLine;
const int16_t bottomY = SCREEN_HEIGHT - (FONT_HEIGHT_SMALL - 1);
const int16_t usableHeight = bottomY - topY - 5;
int16_t compassRadius = usableHeight / 2;
if (compassRadius < 8)
compassRadius = 8;
const int16_t compassDiam = compassRadius * 2;
const int16_t compassX = x + SCREEN_WIDTH - compassRadius - 8;
const int16_t compassY = topY + (usableHeight / 2) + ((FONT_HEIGHT_SMALL - 1) / 2) + 2;
const auto &op = ourNode->position;
float myHeading = screen->hasHeading() ? screen->getHeading() * PI / 180
: screen->estimatedHeading(DegD(op.latitude_i), DegD(op.longitude_i));
CompassRenderer::drawCompassNorth(display, compassX, compassY, myHeading);
const auto &p = node->position;
float bearing = GeoCoord::bearing(DegD(op.latitude_i), DegD(op.longitude_i), DegD(p.latitude_i), DegD(p.longitude_i));
if (!config.display.compass_north_top)
bearing -= myHeading;
CompassRenderer::drawNodeHeading(display, compassX, compassY, compassDiam, bearing);
display->drawCircle(compassX, compassY, compassRadius);
}
} else {
// Portrait: bottom-centered compass
bool showCompass = false;
if (ourNode && (nodeDB->hasValidPosition(ourNode) || screen->hasHeading()) && nodeDB->hasValidPosition(node)) {
showCompass = true;
}
if (showCompass) {
int yBelowContent = (line > 0 && line <= 5) ? (yPositions[line - 1] + FONT_HEIGHT_SMALL + 2) : moreCompactFirstLine;
const int margin = 4;
#if defined(USE_EINK)
const int iconSize = (SCREEN_WIDTH > 128) ? 16 : 8;
const int navBarHeight = iconSize + 6;
#else
const int navBarHeight = 0;
#endif
int availableHeight = SCREEN_HEIGHT - yBelowContent - navBarHeight - margin;
if (availableHeight < FONT_HEIGHT_SMALL * 2)
return;
int compassRadius = availableHeight / 2;
if (compassRadius < 8)
compassRadius = 8;
if (compassRadius * 2 > SCREEN_WIDTH - 16)
compassRadius = (SCREEN_WIDTH - 16) / 2;
int compassX = x + SCREEN_WIDTH / 2;
int compassY = yBelowContent + availableHeight / 2;
const auto &op = ourNode->position;
float myHeading = screen->hasHeading() ? screen->getHeading() * PI / 180
: screen->estimatedHeading(DegD(op.latitude_i), DegD(op.longitude_i));
CompassRenderer::drawCompassNorth(display, compassX, compassY, myHeading);
const auto &p = node->position;
float bearing = GeoCoord::bearing(DegD(op.latitude_i), DegD(op.longitude_i), DegD(p.latitude_i), DegD(p.longitude_i));
if (!config.display.compass_north_top)
bearing -= myHeading;
CompassRenderer::drawNodeHeading(display, compassX, compassY, compassRadius * 2, bearing);
display->drawCircle(compassX, compassY, compassRadius);
}
}
}
/// Draw a series of fields in a column, wrapping to multiple columns if needed
void drawColumns(OLEDDisplay *display, int16_t x, int16_t y, const char **fields)
{
// The coordinates define the left starting point of the text
display->setTextAlignment(TEXT_ALIGN_LEFT);
const char **f = fields;
int xo = x, yo = y;
while (*f) {
display->drawString(xo, yo, *f);
if ((display->getColor() == BLACK) && config.display.heading_bold)
display->drawString(xo + 1, yo, *f);
display->setColor(WHITE);
yo += FONT_HEIGHT_SMALL;
if (yo > SCREEN_HEIGHT - FONT_HEIGHT_SMALL) {
xo += SCREEN_WIDTH / 2;
yo = 0;
}
f++;
}
}
} // namespace NodeListRenderer
} // namespace graphics

View File

@@ -0,0 +1,71 @@
#pragma once
#include "graphics/Screen.h"
#include "mesh/generated/meshtastic/mesh.pb.h"
#include <OLEDDisplay.h>
#include <OLEDDisplayUi.h>
namespace graphics
{
/// Forward declarations
class Screen;
/**
* @brief Node list and entry rendering functions
*
* Contains all functions related to drawing node lists and individual node entries
* including last heard, hop signal, distance, and compass views.
*/
namespace NodeListRenderer
{
// Entry renderer function types
typedef void (*EntryRenderer)(OLEDDisplay *, meshtastic_NodeInfoLite *, int16_t, int16_t, int);
typedef void (*NodeExtrasRenderer)(OLEDDisplay *, meshtastic_NodeInfoLite *, int16_t, int16_t, int, float, double, double);
// Node entry structure
struct NodeEntry {
meshtastic_NodeInfoLite *node;
uint32_t sortValue;
};
// Node list mode enumeration
enum NodeListMode { MODE_LAST_HEARD = 0, MODE_HOP_SIGNAL = 1, MODE_DISTANCE = 2, MODE_COUNT = 3 };
// Main node list screen function
void drawNodeListScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y, const char *title,
EntryRenderer renderer, NodeExtrasRenderer extras = nullptr, float heading = 0, double lat = 0,
double lon = 0);
// Entry renderers
void drawEntryLastHeard(OLEDDisplay *display, meshtastic_NodeInfoLite *node, int16_t x, int16_t y, int columnWidth);
void drawEntryHopSignal(OLEDDisplay *display, meshtastic_NodeInfoLite *node, int16_t x, int16_t y, int columnWidth);
void drawNodeDistance(OLEDDisplay *display, meshtastic_NodeInfoLite *node, int16_t x, int16_t y, int columnWidth);
void drawEntryDynamic(OLEDDisplay *display, meshtastic_NodeInfoLite *node, int16_t x, int16_t y, int columnWidth);
void drawEntryCompass(OLEDDisplay *display, meshtastic_NodeInfoLite *node, int16_t x, int16_t y, int columnWidth);
// Extras renderers
void drawCompassArrow(OLEDDisplay *display, meshtastic_NodeInfoLite *node, int16_t x, int16_t y, int columnWidth, float myHeading,
double userLat, double userLon);
// Screen frame functions
void drawLastHeardScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
void drawHopSignalScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
void drawDistanceScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
void drawDynamicNodeListScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
void drawNodeListWithCompasses(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
void drawNodeInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
// Utility functions
const char *getCurrentModeTitle(int screenWidth);
void retrieveAndSortNodes(std::vector<NodeEntry> &nodeList);
const char *getSafeNodeName(meshtastic_NodeInfoLite *node);
uint32_t sinceLastSeen(meshtastic_NodeInfoLite *node);
void drawColumns(OLEDDisplay *display, int16_t x, int16_t y, const char **fields);
// Bitmap drawing function
void drawScaledXBitmap16x16(int x, int y, int width, int height, const uint8_t *bitmapXBM, OLEDDisplay *display);
} // namespace NodeListRenderer
} // namespace graphics

View File

@@ -0,0 +1,185 @@
#include "NotificationRenderer.h"
#include "DisplayFormatters.h"
#include "NodeDB.h"
#include "configuration.h"
#include "graphics/Screen.h"
#include "graphics/ScreenFonts.h"
#include "graphics/SharedUIDisplay.h"
#include "graphics/images.h"
#include "main.h"
#include <algorithm>
#include <string>
#include <vector>
#ifdef ARCH_ESP32
#include "esp_task_wdt.h"
#endif
using namespace meshtastic;
// External references to global variables from Screen.cpp
extern std::vector<std::string> functionSymbol;
extern std::string functionSymbolString;
extern bool hasUnreadMessage;
namespace graphics
{
namespace NotificationRenderer
{
// Used on boot when a certificate is being created
void NotificationRenderer::drawSSLScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
display->setTextAlignment(TEXT_ALIGN_CENTER);
display->setFont(FONT_SMALL);
display->drawString(64 + x, y, "Creating SSL certificate");
#ifdef ARCH_ESP32
yield();
esp_task_wdt_reset();
#endif
display->setFont(FONT_SMALL);
if ((millis() / 1000) % 2) {
display->drawString(64 + x, FONT_HEIGHT_SMALL + y + 2, "Please wait . . .");
} else {
display->drawString(64 + x, FONT_HEIGHT_SMALL + y + 2, "Please wait . . ");
}
}
// Used when booting without a region set
void NotificationRenderer::drawWelcomeScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
display->setFont(FONT_SMALL);
display->setTextAlignment(TEXT_ALIGN_CENTER);
display->drawString(64 + x, y, "//\\ E S H T /\\ S T / C");
display->drawString(64 + x, y + FONT_HEIGHT_SMALL, getDeviceName());
display->setTextAlignment(TEXT_ALIGN_LEFT);
if ((millis() / 10000) % 2) {
display->drawString(x, y + FONT_HEIGHT_SMALL * 2 - 3, "Set the region using the");
display->drawString(x, y + FONT_HEIGHT_SMALL * 3 - 3, "Meshtastic Android, iOS,");
display->drawString(x, y + FONT_HEIGHT_SMALL * 4 - 3, "Web or CLI clients.");
} else {
display->drawString(x, y + FONT_HEIGHT_SMALL * 2 - 3, "Visit meshtastic.org");
display->drawString(x, y + FONT_HEIGHT_SMALL * 3 - 3, "for more information.");
display->drawString(x, y + FONT_HEIGHT_SMALL * 4 - 3, "");
}
#ifdef ARCH_ESP32
yield();
esp_task_wdt_reset();
#endif
}
void NotificationRenderer::drawAlertBannerOverlay(OLEDDisplay *display, OLEDDisplayUiState *state)
{
// Exit if no message is active or duration has passed
if (strlen(alertBannerMessage) == 0 || (alertBannerUntil != 0 && millis() > alertBannerUntil))
return;
// === Layout Configuration ===
constexpr uint16_t padding = 5; // Padding around text inside the box
constexpr uint8_t lineSpacing = 1; // Extra space between lines
// Search the message to determine if we need the bell added
bool needs_bell = (strstr(alertBannerMessage, "Alert Received") != nullptr);
// Setup font and alignment
display->setFont(FONT_SMALL);
display->setTextAlignment(TEXT_ALIGN_LEFT); // We will manually center per line
// === Split the message into lines (supports multi-line banners) ===
const int MAX_LINES = 10;
char lines[MAX_LINES][256];
int lineCount = 0;
// Create a working copy of the message to tokenize
char messageCopy[256];
strncpy(messageCopy, alertBannerMessage, sizeof(messageCopy) - 1);
messageCopy[sizeof(messageCopy) - 1] = '\0';
char *line = strtok(messageCopy, "\n");
while (line != nullptr && lineCount < MAX_LINES) {
strncpy(lines[lineCount], line, sizeof(lines[lineCount]) - 1);
lines[lineCount][sizeof(lines[lineCount]) - 1] = '\0';
lineCount++;
line = strtok(nullptr, "\n");
}
// === Measure text dimensions ===
uint16_t minWidth = (SCREEN_WIDTH > 128) ? 106 : 78;
uint16_t maxWidth = 0;
uint16_t lineWidths[MAX_LINES];
for (int i = 0; i < lineCount; i++) {
uint16_t w = display->getStringWidth(lines[i], strlen(lines[i]), true);
lineWidths[i] = w;
if (w > maxWidth)
maxWidth = w;
}
uint16_t boxWidth = padding * 2 + maxWidth;
if (needs_bell && boxWidth < minWidth)
boxWidth += (SCREEN_WIDTH > 128) ? 26 : 20;
uint16_t boxHeight = padding * 2 + lineCount * FONT_HEIGHT_SMALL + (lineCount - 1) * lineSpacing;
int16_t boxLeft = (display->width() / 2) - (boxWidth / 2);
int16_t boxTop = (display->height() / 2) - (boxHeight / 2);
// === Draw background box ===
display->setColor(BLACK);
display->fillRect(boxLeft - 1, boxTop - 1, boxWidth + 2, boxHeight + 2); // Slightly oversized box
display->setColor(WHITE);
display->drawRect(boxLeft, boxTop, boxWidth, boxHeight); // Border
// === Draw each line centered in the box ===
int16_t lineY = boxTop + padding;
for (int i = 0; i < lineCount; i++) {
int16_t textX = boxLeft + (boxWidth - lineWidths[i]) / 2;
uint16_t line_width = display->getStringWidth(lines[i], strlen(lines[i]), true);
if (needs_bell && i == 0) {
int bellY = lineY + (FONT_HEIGHT_SMALL - 8) / 2;
display->drawXbm(textX - 10, bellY, 8, 8, bell_alert);
display->drawXbm(textX + line_width + 2, bellY, 8, 8, bell_alert);
}
display->drawString(textX, lineY, lines[i]);
if (SCREEN_WIDTH > 128)
display->drawString(textX + 1, lineY, lines[i]); // Faux bold
lineY += FONT_HEIGHT_SMALL + lineSpacing;
}
}
/// Draw the last text message we received
void NotificationRenderer::drawCriticalFaultFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
display->setTextAlignment(TEXT_ALIGN_LEFT);
display->setFont(FONT_MEDIUM);
char tempBuf[24];
snprintf(tempBuf, sizeof(tempBuf), "Critical fault #%d", error_code);
display->drawString(0 + x, 0 + y, tempBuf);
display->setTextAlignment(TEXT_ALIGN_LEFT);
display->setFont(FONT_SMALL);
display->drawString(0 + x, FONT_HEIGHT_MEDIUM + y, "For help, please visit \nmeshtastic.org");
}
void NotificationRenderer::drawFrameFirmware(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
display->setTextAlignment(TEXT_ALIGN_CENTER);
display->setFont(FONT_MEDIUM);
display->drawString(64 + x, y, "Updating");
display->setFont(FONT_SMALL);
display->setTextAlignment(TEXT_ALIGN_LEFT);
display->drawStringMaxWidth(0 + x, 2 + y + FONT_HEIGHT_SMALL * 2, x + display->getWidth(),
"Please be patient and do not power off.");
}
} // namespace NotificationRenderer
} // namespace graphics

View File

@@ -0,0 +1,24 @@
#pragma once
#include "OLEDDisplay.h"
#include "OLEDDisplayUi.h"
namespace graphics
{
namespace NotificationRenderer
{
class NotificationRenderer
{
public:
static void drawAlertBannerOverlay(OLEDDisplay *display, OLEDDisplayUiState *state);
static void drawCriticalFaultFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
static void drawSSLScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
static void drawWelcomeScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
static void drawFrameFirmware(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
};
} // namespace NotificationRenderer
} // namespace graphics

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,92 @@
#pragma once
#include "graphics/Screen.h"
#include "graphics/emotes.h"
#include <OLEDDisplay.h>
#include <OLEDDisplayUi.h>
#include <string>
#define HOURS_IN_MONTH 730
// Forward declarations for status types
namespace meshtastic
{
class PowerStatus;
class NodeStatus;
class GPSStatus;
} // namespace meshtastic
namespace graphics
{
/// Forward declarations
class Screen;
/**
* @brief UI utility drawing functions
*
* Contains utility functions for drawing common UI elements, overlays,
* battery indicators, and other shared graphical components.
*/
namespace UIRenderer
{
// Common UI elements
void drawCommonHeader(OLEDDisplay *display, int16_t x, int16_t y);
void drawBattery(OLEDDisplay *display, int16_t x, int16_t y, uint8_t *imgBuffer, const meshtastic::PowerStatus *powerStatus);
void drawNodes(OLEDDisplay *display, int16_t x, int16_t y, const meshtastic::NodeStatus *nodeStatus, int node_offset = 0,
bool show_total = true, String additional_words = "");
// GPS status functions
void drawGps(OLEDDisplay *display, int16_t x, int16_t y, const meshtastic::GPSStatus *gpsStatus);
void drawGpsCoordinates(OLEDDisplay *display, int16_t x, int16_t y, const meshtastic::GPSStatus *gpsStatus);
void drawGpsAltitude(OLEDDisplay *display, int16_t x, int16_t y, const meshtastic::GPSStatus *gpsStatus);
void drawGpsPowerStatus(OLEDDisplay *display, int16_t x, int16_t y, const meshtastic::GPSStatus *gpsStatus);
// Layout and utility functions
void drawScrollbar(OLEDDisplay *display, int visibleItems, int totalItems, int scrollIndex, int x, int startY);
// Overlay and special screens
void drawFrameText(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y, const char *text);
// Function overlay for showing mute/buzzer modifiers etc.
void drawFunctionOverlay(OLEDDisplay *display, OLEDDisplayUiState *state);
// Navigation bar overlay
void drawNavigationBar(OLEDDisplay *display, OLEDDisplayUiState *state);
void drawNodeInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
void drawDeviceFocused(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
// Icon and screen drawing functions
void drawIconScreen(const char *upperMsg, OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
// Compass and location screen
void drawCompassAndLocationScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
// OEM screens
#ifdef USERPREFS_OEM_TEXT
void drawOEMIconScreen(const char *upperMsg, OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
void drawOEMBootScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
#endif
#ifdef USE_EINK
/// Used on eink displays while in deep sleep
void drawDeepSleepFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
/// Used on eink displays when screen updates are paused
void drawScreensaverOverlay(OLEDDisplay *display, OLEDDisplayUiState *state);
#endif
// Time and date utilities
void getTimeAgoStr(uint32_t agoSecs, char *timeStr, uint8_t maxLength);
std::string drawTimeDelta(uint32_t days, uint32_t hours, uint32_t minutes, uint32_t seconds);
int formatDateTime(char *buffer, size_t bufferSize, uint32_t rtc_sec, OLEDDisplay *display, bool showTime);
// Message filtering
bool shouldDrawMessage(const meshtastic_MeshPacket *packet);
// Check if the display can render a string (detect special chars; emoji)
bool haveGlyphs(const char *str);
} // namespace UIRenderer
} // namespace graphics

225
src/graphics/emotes.cpp Normal file
View File

@@ -0,0 +1,225 @@
#include "emotes.h"
namespace graphics
{
// Always define Emote list and count
const Emote emotes[] = {
#ifndef EXCLUDE_EMOJI
// --- Thumbs ---
{"\U0001F44D", thumbup, thumbs_width, thumbs_height}, // 👍 Thumbs Up
{"\U0001F44E", thumbdown, thumbs_width, thumbs_height}, // 👎 Thumbs Down
// --- Smileys (Multiple Unicode Aliases) ---
{"\U0001F60A", smiley, smiley_width, smiley_height}, // 😊 Smiling Face with Smiling Eyes
{"\U0001F600", smiley, smiley_width, smiley_height}, // 😀 Grinning Face
{"\U0001F642", smiley, smiley_width, smiley_height}, // 🙂 Slightly Smiling Face
{"\U0001F609", smiley, smiley_width, smiley_height}, // 😉 Winking Face
{"\U0001F601", smiley, smiley_width, smiley_height}, // 😁 Grinning Face with Smiling Eyes
// --- Question/Alert ---
{"\u2753", question, question_width, question_height}, // ❓ Question Mark
{"\u203C\uFE0F", bang, bang_width, bang_height}, // ‼️ Double Exclamation Mark
// --- Laughing Faces ---
{"\U0001F602", haha, haha_width, haha_height}, // 😂 Face with Tears of Joy
{"\U0001F923", haha, haha_width, haha_height}, // 🤣 Rolling on the Floor Laughing
{"\U0001F606", haha, haha_width, haha_height}, // 😆 Smiling with Open Mouth and Closed Eyes
{"\U0001F605", haha, haha_width, haha_height}, // 😅 Smiling with Sweat
{"\U0001F604", haha, haha_width, haha_height}, // 😄 Grinning Face with Smiling Eyes
// --- Gestures and People ---
{"\U0001F44B", wave_icon, wave_icon_width, wave_icon_height}, // 👋 Waving Hand
{"\U0001F920", cowboy, cowboy_width, cowboy_height}, // 🤠 Cowboy Hat Face
{"\U0001F3A7", deadmau5, deadmau5_width, deadmau5_height}, // 🎧 Headphones
// --- Weather ---
{"\u2600", sun, sun_width, sun_height}, // ☀ Sun (without variation selector)
{"\u2600\uFE0F", sun, sun_width, sun_height}, // ☀️ Sun (with variation selector)
{"\U0001F327\uFE0F", rain, rain_width, rain_height}, // 🌧️ Cloud with Rain
{"\u2601\uFE0F", cloud, cloud_width, cloud_height}, // ☁️ Cloud
{"\U0001F32B\uFE0F", fog, fog_width, fog_height}, // 🌫️ Fog
// --- Misc Faces ---
{"\U0001F608", devil, devil_width, devil_height}, // 😈 Smiling Face with Horns
// --- Hearts (Multiple Unicode Aliases) ---
{"\u2764\uFE0F", heart, heart_width, heart_height}, // ❤️ Red Heart
{"\U0001F9E1", heart, heart_width, heart_height}, // 🧡 Orange Heart
{"\U00002763", heart, heart_width, heart_height}, // ❣ Heart Exclamation
{"\U00002764", heart, heart_width, heart_height}, // ❤ Red Heart (legacy)
{"\U0001F495", heart, heart_width, heart_height}, // 💕 Two Hearts
{"\U0001F496", heart, heart_width, heart_height}, // 💖 Sparkling Heart
{"\U0001F497", heart, heart_width, heart_height}, // 💗 Growing Heart
{"\U0001F498", heart, heart_width, heart_height}, // 💘 Heart with Arrow
// --- Objects ---
{"\U0001F4A9", poo, poo_width, poo_height}, // 💩 Pile of Poo
{"\U0001F514", bell_icon, bell_icon_width, bell_icon_height} // 🔔 Bell
#endif
};
const int numEmotes = sizeof(emotes) / sizeof(emotes[0]);
#ifndef EXCLUDE_EMOJI
const unsigned char thumbup[] PROGMEM = {
0x00, 0x1C, 0x00, 0x00, 0x00, 0x24, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x00, 0x11, 0x00, 0x00, 0x80, 0x09, 0x00, 0x00,
0xC0, 0x08, 0x00, 0x00, 0x40, 0x08, 0x00, 0x00, 0x20, 0x04, 0x00, 0x00, 0x10, 0x04, 0x00, 0x00, 0x18, 0x02, 0x00, 0x00,
0x0C, 0xCE, 0x7F, 0x00, 0x04, 0x20, 0x80, 0x00, 0x02, 0x20, 0x80, 0x00, 0x02, 0x60, 0xC0, 0x00, 0x01, 0xF8, 0xFF, 0x01,
0x01, 0x08, 0x00, 0x01, 0x01, 0x08, 0x00, 0x01, 0x01, 0xF8, 0xFF, 0x00, 0x01, 0x10, 0x80, 0x00, 0x01, 0x18, 0x80, 0x00,
0x02, 0x30, 0xC0, 0x00, 0x06, 0xE0, 0x3F, 0x00, 0x0C, 0x20, 0x30, 0x00, 0x38, 0x20, 0x10, 0x00, 0xE0, 0xCF, 0x1F, 0x00,
};
const unsigned char thumbdown[] PROGMEM = {
0xE0, 0xCF, 0x1F, 0x00, 0x38, 0x20, 0x10, 0x00, 0x0C, 0x20, 0x30, 0x00, 0x06, 0xE0, 0x3F, 0x00, 0x02, 0x30, 0xC0, 0x00,
0x01, 0x18, 0x80, 0x00, 0x01, 0x10, 0x80, 0x00, 0x01, 0xF8, 0xFF, 0x00, 0x01, 0x08, 0x00, 0x01, 0x01, 0x08, 0x00, 0x01,
0x01, 0xF8, 0xFF, 0x01, 0x02, 0x60, 0xC0, 0x00, 0x02, 0x20, 0x80, 0x00, 0x04, 0x20, 0x80, 0x00, 0x0C, 0xCE, 0x7F, 0x00,
0x18, 0x02, 0x00, 0x00, 0x10, 0x04, 0x00, 0x00, 0x20, 0x04, 0x00, 0x00, 0x40, 0x08, 0x00, 0x00, 0xC0, 0x08, 0x00, 0x00,
0x80, 0x09, 0x00, 0x00, 0x00, 0x11, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x00, 0x24, 0x00, 0x00, 0x00, 0x1C, 0x00, 0x00,
};
const unsigned char smiley[] PROGMEM = {
0x00, 0xfe, 0x0f, 0x00, 0x80, 0x01, 0x30, 0x00, 0x40, 0x00, 0xc0, 0x00, 0x20, 0x00, 0x00, 0x01, 0x10, 0x00, 0x00, 0x02,
0x08, 0x00, 0x00, 0x04, 0x04, 0x00, 0x00, 0x08, 0x04, 0x00, 0x00, 0x10, 0x02, 0x0e, 0x0e, 0x10, 0x02, 0x09, 0x12, 0x10,
0x01, 0x09, 0x12, 0x20, 0x01, 0x0f, 0x1e, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20,
0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x81, 0x00, 0x20, 0x20,
0x82, 0x00, 0x20, 0x10, 0x02, 0x01, 0x10, 0x10, 0x04, 0x02, 0x08, 0x08, 0x04, 0xfc, 0x07, 0x08, 0x08, 0x00, 0x00, 0x04,
0x10, 0x00, 0x00, 0x02, 0x20, 0x00, 0x00, 0x01, 0x40, 0x00, 0xc0, 0x00, 0x80, 0x01, 0x30, 0x00, 0x00, 0xfe, 0x0f, 0x00};
const unsigned char question[] PROGMEM = {
0x00, 0x00, 0x00, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x80, 0xFF, 0x01, 0x00, 0xC0, 0xFF, 0x07, 0x00, 0xE0, 0xFF, 0x07, 0x00,
0xE0, 0xC3, 0x0F, 0x00, 0xF0, 0x81, 0x0F, 0x00, 0xF0, 0x01, 0x0F, 0x00, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x80, 0x0F, 0x00,
0x00, 0xC0, 0x0F, 0x00, 0x00, 0xE0, 0x07, 0x00, 0x00, 0xF0, 0x03, 0x00, 0x00, 0xF8, 0x01, 0x00, 0x00, 0x7C, 0x00, 0x00,
0x00, 0x3C, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x3E, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
};
const unsigned char bang[] PROGMEM = {
0xFF, 0x0F, 0xFC, 0x3F, 0xFF, 0x0F, 0xFC, 0x3F, 0xFF, 0x0F, 0xFC, 0x3F, 0xFF, 0x07, 0xF8, 0x3F, 0xFF, 0x07, 0xF8, 0x3F,
0xFE, 0x07, 0xF8, 0x1F, 0xFE, 0x07, 0xF8, 0x1F, 0xFE, 0x07, 0xF8, 0x1F, 0xFE, 0x07, 0xF8, 0x1F, 0xFE, 0x07, 0xF8, 0x1F,
0xFE, 0x03, 0xF0, 0x1F, 0xFE, 0x03, 0xF0, 0x1F, 0xFC, 0x03, 0xF0, 0x0F, 0xFC, 0x03, 0xF0, 0x0F, 0xFC, 0x03, 0xF0, 0x0F,
0xFC, 0x03, 0xF0, 0x0F, 0xFC, 0x03, 0xF0, 0x0F, 0xFC, 0x03, 0xF0, 0x0F, 0xFC, 0x01, 0xE0, 0x0F, 0xFC, 0x01, 0xE0, 0x0F,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xF0, 0x00, 0xC0, 0x03, 0xFC, 0x03, 0xF0, 0x0F, 0xFE, 0x03, 0xF0, 0x1F,
0xFE, 0x07, 0xF8, 0x1F, 0xFE, 0x07, 0xF8, 0x1F, 0xFE, 0x07, 0xF8, 0x1F, 0xFC, 0x03, 0xF0, 0x0F, 0xF8, 0x01, 0xE0, 0x07,
};
const unsigned char haha[] PROGMEM = {
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xE0, 0x01, 0x00,
0x00, 0xFC, 0x0F, 0x00, 0x00, 0x1F, 0x3E, 0x00, 0x80, 0x03, 0x70, 0x00, 0xC0, 0x01, 0xE0, 0x00, 0xC0, 0x00, 0xC2, 0x00,
0x60, 0x00, 0x03, 0x00, 0x60, 0x00, 0xC1, 0x1F, 0x60, 0x80, 0x8F, 0x31, 0x30, 0x0E, 0x80, 0x31, 0x30, 0x10, 0x30, 0x1F,
0x30, 0x08, 0x58, 0x00, 0x30, 0x04, 0x6C, 0x03, 0x60, 0x00, 0xF3, 0x01, 0x60, 0xC0, 0xFC, 0x01, 0x80, 0x38, 0xBF, 0x01,
0xE0, 0xC5, 0xDF, 0x00, 0xB0, 0xF9, 0xEF, 0x00, 0x30, 0xF1, 0x73, 0x00, 0xB0, 0x1D, 0x3E, 0x00, 0xF0, 0xFD, 0x0F, 0x00,
0xE0, 0xE0, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
};
const unsigned char wave_icon[] PROGMEM = {
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x70, 0x00, 0x00, 0x00, 0xC0, 0x00,
0x00, 0x0C, 0x9C, 0x01, 0x80, 0x17, 0x20, 0x01, 0x80, 0x26, 0x46, 0x02, 0x80, 0x44, 0x88, 0x02, 0xC0, 0x89, 0x8A, 0x02,
0x40, 0x93, 0x8B, 0x02, 0x40, 0x26, 0x13, 0x00, 0x80, 0x44, 0x16, 0x00, 0xC0, 0x89, 0x24, 0x00, 0x40, 0x93, 0x60, 0x00,
0x40, 0x26, 0x40, 0x00, 0x80, 0x0C, 0x80, 0x00, 0x00, 0x09, 0x80, 0x00, 0x00, 0x02, 0x80, 0x00, 0x40, 0x06, 0x80, 0x00,
0x50, 0x0C, 0x80, 0x00, 0x50, 0x08, 0x40, 0x00, 0x90, 0x10, 0x20, 0x00, 0xB0, 0x21, 0x10, 0x00, 0x20, 0x47, 0x18, 0x00,
0x40, 0x80, 0x0F, 0x00, 0x80, 0x01, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
};
const unsigned char cowboy[] PROGMEM = {
0x00, 0xF0, 0x03, 0x00, 0x00, 0xFC, 0x0F, 0x00, 0x00, 0xFE, 0x1F, 0x00, 0x00, 0xFF, 0x3F, 0x00, 0x3C, 0xFE, 0x1F, 0x0F,
0xFE, 0xFE, 0xDF, 0x1F, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xFF, 0x3F,
0x3E, 0xC0, 0x00, 0x1F, 0x1E, 0x00, 0x00, 0x1E, 0x0C, 0x0C, 0x0C, 0x0C, 0x08, 0x0E, 0x1C, 0x04, 0x00, 0x0E, 0x1C, 0x00,
0x04, 0x0E, 0x1C, 0x08, 0x04, 0x0E, 0x1C, 0x08, 0x04, 0x04, 0x08, 0x08, 0x04, 0x00, 0x00, 0x08, 0x04, 0x00, 0x00, 0x08,
0x8C, 0x07, 0x70, 0x0C, 0x88, 0xFC, 0x4F, 0x04, 0x88, 0x01, 0x40, 0x04, 0x90, 0xFF, 0x7F, 0x02, 0x30, 0x03, 0x30, 0x03,
0x60, 0x0E, 0x9C, 0x01, 0xC0, 0xF8, 0xC7, 0x00, 0x80, 0x01, 0x60, 0x00, 0x00, 0x0E, 0x1C, 0x00, 0x00, 0xF8, 0x07, 0x00,
};
const unsigned char deadmau5[] PROGMEM = {
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xF8, 0x07, 0x00,
0x00, 0xFC, 0x03, 0x00, 0x00, 0xFF, 0x3F, 0x00, 0x80, 0xFF, 0x0F, 0x00, 0xC0, 0xFF, 0xFF, 0x00, 0xE0, 0xFF, 0x3F, 0x00,
0xE0, 0xFF, 0xFF, 0x01, 0xF0, 0xFF, 0x7F, 0x00, 0xF0, 0xFF, 0xFF, 0x03, 0xF8, 0xFF, 0xFF, 0x00, 0xF0, 0xFF, 0xFF, 0x07,
0xFC, 0xFF, 0xFF, 0x00, 0xF0, 0xFF, 0xFF, 0x0F, 0xFC, 0xFF, 0xFF, 0x00, 0xF0, 0xFF, 0xFF, 0x0F, 0xFE, 0xFF, 0xFF, 0x00,
0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0xE0, 0xFF, 0x3F, 0xFC,
0x0F, 0xFF, 0x7F, 0x00, 0xC0, 0xFF, 0x1F, 0xF8, 0x0F, 0xFC, 0x3F, 0x00, 0x80, 0xFF, 0x0F, 0xF8, 0x1F, 0xFC, 0x1F, 0x00,
0x00, 0xFF, 0x0F, 0xFC, 0x3F, 0xFC, 0x0F, 0x00, 0x00, 0xF8, 0x1F, 0xFF, 0xFF, 0xFE, 0x01, 0x00, 0x00, 0x00, 0xFC, 0xFF,
0xFF, 0x07, 0x00, 0x00, 0x00, 0x00, 0xFC, 0xFF, 0xFF, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x04, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x18, 0x00,
0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x30, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0xE0, 0x00, 0xC0, 0x00, 0x00, 0x00,
0x00, 0x00, 0x80, 0x07, 0x38, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFC, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
};
const unsigned char sun[] PROGMEM = {
0x00, 0xC0, 0x00, 0x00, 0x00, 0xE0, 0x01, 0x00, 0x00, 0xE0, 0x01, 0x00, 0x00, 0xE0, 0x01, 0x00, 0x30, 0xC0, 0x00, 0x03,
0x70, 0x00, 0x80, 0x03, 0xF0, 0x00, 0xC0, 0x03, 0xF0, 0xF8, 0xC7, 0x03, 0xE0, 0xFC, 0xCF, 0x01, 0x00, 0xFE, 0x1F, 0x00,
0x00, 0xFF, 0x3F, 0x00, 0x80, 0xFF, 0x7F, 0x00, 0x80, 0xFF, 0x7F, 0x00, 0x8E, 0xFF, 0x7F, 0x1C, 0x9F, 0xFF, 0x7F, 0x3E,
0x9F, 0xFF, 0x7F, 0x3E, 0x8E, 0xFF, 0x7F, 0x1C, 0x80, 0xFF, 0x7F, 0x00, 0x80, 0xFF, 0x7F, 0x00, 0x00, 0xFF, 0x3F, 0x00,
0x00, 0xFE, 0x1F, 0x00, 0x00, 0xFC, 0x0F, 0x00, 0xC0, 0xF9, 0xE7, 0x00, 0xE0, 0x01, 0xE0, 0x01, 0xF0, 0x01, 0xE0, 0x03,
0xF0, 0xC0, 0xC0, 0x03, 0x00, 0xE0, 0x01, 0x00, 0x00, 0xE0, 0x01, 0x00, 0x00, 0xE0, 0x01, 0x00, 0x00, 0xC0, 0x00, 0x00,
};
const unsigned char rain[] PROGMEM = {
0xC0, 0x0F, 0xC0, 0x00, 0x40, 0x00, 0x80, 0x00, 0x20, 0x00, 0x80, 0x00, 0x20, 0x00, 0x80, 0x03, 0x38, 0x00,
0x00, 0x0E, 0x0C, 0x00, 0x00, 0x18, 0x02, 0x00, 0x00, 0x10, 0x03, 0x00, 0x00, 0x30, 0x01, 0x00, 0x00, 0x20,
0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x03, 0x00, 0x00, 0x30, 0x02, 0x00,
0x00, 0x10, 0x06, 0x00, 0x00, 0x08, 0xFC, 0xFF, 0xFF, 0x07, 0xF0, 0xFF, 0xFF, 0x01, 0x80, 0x00, 0x01, 0x00,
0xC0, 0xC0, 0x81, 0x03, 0xA0, 0x60, 0xC1, 0x03, 0x90, 0x20, 0x41, 0x01, 0xF0, 0xE0, 0xC0, 0x01, 0x60, 0x4C,
0x98, 0x00, 0x00, 0x0E, 0x1C, 0x00, 0x00, 0x0B, 0x12, 0x00, 0x00, 0x09, 0x1A, 0x00, 0x00, 0x06, 0x0E, 0x00,
};
const unsigned char cloud[] PROGMEM = {
0x00, 0x80, 0x07, 0x00, 0x00, 0xE0, 0x1F, 0x00, 0x00, 0x70, 0x30, 0x00, 0x00, 0x10, 0x60, 0x00, 0x80, 0x1F, 0x40, 0x00,
0xC0, 0x0F, 0xC0, 0x00, 0xC0, 0x00, 0x80, 0x00, 0x60, 0x00, 0x80, 0x00, 0x20, 0x00, 0x80, 0x00, 0x20, 0x00, 0x80, 0x01,
0x20, 0x00, 0x00, 0x07, 0x38, 0x00, 0x00, 0x0C, 0x0C, 0x00, 0x00, 0x08, 0x06, 0x00, 0x00, 0x18, 0x02, 0x00, 0x00, 0x10,
0x02, 0x00, 0x00, 0x30, 0x03, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20,
0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x30, 0x03, 0x00, 0x00, 0x10,
0x02, 0x00, 0x00, 0x10, 0x06, 0x00, 0x00, 0x18, 0x0C, 0x00, 0x00, 0x0C, 0xFC, 0xFF, 0xFF, 0x07, 0xF0, 0xFF, 0xFF, 0x03,
};
const unsigned char fog[] PROGMEM = {
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x78, 0x00, 0x3C, 0x00, 0xFE, 0x01, 0xFF, 0x00, 0x87, 0xC7, 0xC3, 0x01, 0x03, 0xFE, 0x80, 0x01,
0x00, 0x38, 0x00, 0x00, 0xFC, 0x00, 0x7E, 0x00, 0xFF, 0x83, 0xFF, 0x01, 0x03, 0xFF, 0x81, 0x01, 0x00, 0x7C, 0x00, 0x00,
0xF8, 0x00, 0x3E, 0x00, 0xFE, 0x01, 0xFF, 0x00, 0x87, 0xC7, 0xC3, 0x01, 0x03, 0xFE, 0x80, 0x01, 0x00, 0x38, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
};
const unsigned char devil[] PROGMEM = {
0x00, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x10, 0x03, 0xC0, 0x01, 0x38, 0x07, 0x7C, 0x0F, 0x38, 0x1F, 0x03, 0x30, 0x1E,
0xFE, 0x01, 0xE0, 0x1F, 0x7E, 0x00, 0x80, 0x1F, 0x3C, 0x00, 0x00, 0x0F, 0x1C, 0x00, 0x00, 0x0E, 0x18, 0x00, 0x00, 0x06,
0x08, 0x00, 0x00, 0x04, 0x0C, 0x00, 0x00, 0x0C, 0x0C, 0x00, 0x00, 0x0C, 0x0C, 0x00, 0x00, 0x0C, 0x0C, 0x0E, 0x1C, 0x0C,
0x0C, 0x18, 0x06, 0x0C, 0x0C, 0x1C, 0x06, 0x0C, 0x0C, 0x1C, 0x0E, 0x0C, 0x0C, 0x1C, 0x0E, 0x0C, 0x0C, 0x0C, 0x06, 0x0C,
0x08, 0x00, 0x00, 0x06, 0x18, 0x02, 0x10, 0x06, 0x10, 0x0C, 0x0C, 0x03, 0x30, 0xF8, 0x07, 0x03, 0x60, 0xE0, 0x80, 0x01,
0xC0, 0x00, 0xC0, 0x00, 0x80, 0x01, 0x70, 0x00, 0x00, 0x06, 0x1C, 0x00, 0x00, 0xF0, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00,
};
const unsigned char heart[] PROGMEM = {
0x00, 0x00, 0x00, 0x00, 0xC0, 0x03, 0xF0, 0x00, 0xF8, 0x0F, 0xFC, 0x07, 0xFC, 0x1F, 0x06, 0x0E, 0xFE, 0x3F, 0x03, 0x18,
0xFE, 0xFF, 0x7F, 0x10, 0xFF, 0xFF, 0xFF, 0x31, 0xFF, 0xFF, 0xFF, 0x33, 0xFF, 0xFF, 0xFF, 0x37, 0xFF, 0xFF, 0xFF, 0x37,
0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xFF, 0x3F, 0xFE, 0xFF, 0xFF, 0x1F, 0xFE, 0xFF, 0xFF, 0x1F,
0xFC, 0xFF, 0xFF, 0x0F, 0xFC, 0xFF, 0xFF, 0x0F, 0xF8, 0xFF, 0xFF, 0x07, 0xF0, 0xFF, 0xFF, 0x03, 0xF0, 0xFF, 0xFF, 0x03,
0xE0, 0xFF, 0xFF, 0x01, 0xC0, 0xFF, 0xFF, 0x00, 0x80, 0xFF, 0x7F, 0x00, 0x00, 0xFF, 0x3F, 0x00, 0x00, 0xFE, 0x1F, 0x00,
0x00, 0xFC, 0x0F, 0x00, 0x00, 0xF8, 0x07, 0x00, 0x00, 0xF0, 0x03, 0x00, 0x00, 0xE0, 0x01, 0x00, 0x00, 0x80, 0x00, 0x00,
};
const unsigned char poo[] PROGMEM = {
0x00, 0x1C, 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x00, 0xEC, 0x01, 0x00, 0x00, 0x8C, 0x07, 0x00, 0x00, 0x0C, 0x06, 0x00,
0x00, 0x24, 0x0C, 0x00, 0x00, 0x34, 0x08, 0x00, 0x00, 0x1F, 0x08, 0x00, 0xC0, 0x0F, 0x08, 0x00, 0xC0, 0x00, 0x3C, 0x00,
0x60, 0x00, 0x7C, 0x00, 0x60, 0x00, 0xC6, 0x00, 0x20, 0x00, 0xCB, 0x00, 0xA0, 0xC7, 0xFF, 0x00, 0xE0, 0x7F, 0xF7, 0x00,
0xF0, 0x18, 0xE3, 0x03, 0x78, 0x18, 0x41, 0x03, 0x6C, 0x9B, 0x5D, 0x06, 0x64, 0x9B, 0x5D, 0x04, 0x44, 0x1A, 0x41, 0x04,
0x4C, 0xD8, 0x63, 0x06, 0xF8, 0xFC, 0x36, 0x06, 0xFE, 0x0F, 0x9C, 0x1F, 0x07, 0x03, 0xC0, 0x30, 0x03, 0x00, 0x78, 0x20,
0x01, 0x00, 0x1F, 0x20, 0x03, 0xE0, 0x03, 0x20, 0x07, 0x7E, 0x04, 0x30, 0xFE, 0x0F, 0xFC, 0x1F, 0xF0, 0x00, 0xF0, 0x0F,
};
const unsigned char bell_icon[] PROGMEM = {
0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b11110000,
0b00000011, 0b00000000, 0b00000000, 0b11111100, 0b00001111, 0b00000000, 0b00000000, 0b00001111, 0b00111100, 0b00000000,
0b00000000, 0b00000011, 0b00110000, 0b00000000, 0b10000000, 0b00000001, 0b01100000, 0b00000000, 0b11000000, 0b00000000,
0b11000000, 0b00000000, 0b11000000, 0b00000000, 0b11000000, 0b00000000, 0b11000000, 0b00000000, 0b11000000, 0b00000000,
0b11000000, 0b00000000, 0b11000000, 0b00000000, 0b11000000, 0b00000000, 0b11000000, 0b00000000, 0b11000000, 0b00000000,
0b11000000, 0b00000000, 0b11000000, 0b00000000, 0b11000000, 0b00000000, 0b11000000, 0b00000000, 0b11000000, 0b00000000,
0b11000000, 0b00000000, 0b11000000, 0b00000000, 0b01000000, 0b00000000, 0b10000000, 0b00000000, 0b01100000, 0b00000000,
0b10000000, 0b00000001, 0b01110000, 0b00000000, 0b10000000, 0b00000011, 0b00110000, 0b00000000, 0b00000000, 0b00000011,
0b00011000, 0b00000000, 0b00000000, 0b00000110, 0b11110000, 0b11111111, 0b11111111, 0b00000011, 0b00000000, 0b00001100,
0b00001100, 0b00000000, 0b00000000, 0b00011000, 0b00000110, 0b00000000, 0b00000000, 0b11111000, 0b00000111, 0b00000000,
0b00000000, 0b11100000, 0b00000001, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000,
0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000};
#endif
} // namespace graphics

86
src/graphics/emotes.h Normal file
View File

@@ -0,0 +1,86 @@
#pragma once
#include <Arduino.h>
namespace graphics
{
// === Emote List ===
struct Emote {
const char *label;
const unsigned char *bitmap;
int width;
int height;
};
extern const Emote emotes[/* numEmotes */];
extern const int numEmotes;
#ifndef EXCLUDE_EMOJI
// === Emote Bitmaps ===
#define thumbs_height 25
#define thumbs_width 25
extern const unsigned char thumbup[] PROGMEM;
extern const unsigned char thumbdown[] PROGMEM;
#define smiley_height 30
#define smiley_width 30
extern const unsigned char smiley[] PROGMEM;
#define question_height 25
#define question_width 25
extern const unsigned char question[] PROGMEM;
#define bang_height 30
#define bang_width 30
extern const unsigned char bang[] PROGMEM;
#define haha_height 30
#define haha_width 30
extern const unsigned char haha[] PROGMEM;
#define wave_icon_height 30
#define wave_icon_width 30
extern const unsigned char wave_icon[] PROGMEM;
#define cowboy_height 30
#define cowboy_width 30
extern const unsigned char cowboy[] PROGMEM;
#define deadmau5_height 30
#define deadmau5_width 60
extern const unsigned char deadmau5[] PROGMEM;
#define sun_height 30
#define sun_width 30
extern const unsigned char sun[] PROGMEM;
#define rain_height 30
#define rain_width 30
extern const unsigned char rain[] PROGMEM;
#define cloud_height 30
#define cloud_width 30
extern const unsigned char cloud[] PROGMEM;
#define fog_height 25
#define fog_width 25
extern const unsigned char fog[] PROGMEM;
#define devil_height 30
#define devil_width 30
extern const unsigned char devil[] PROGMEM;
#define heart_height 30
#define heart_width 30
extern const unsigned char heart[] PROGMEM;
#define poo_height 30
#define poo_width 30
extern const unsigned char poo[] PROGMEM;
#define bell_icon_width 30
#define bell_icon_height 30
extern const unsigned char bell_icon[] PROGMEM;
#endif // EXCLUDE_EMOJI
} // namespace graphics

View File

@@ -37,181 +37,242 @@ const uint8_t imgQuestion[] PROGMEM = {0xbf, 0x41, 0xc0, 0x8b, 0xdb, 0x70, 0xa1,
const uint8_t imgSF[] PROGMEM = {0xd2, 0xb7, 0xad, 0xbb, 0x92, 0x01, 0xfd, 0xfd, 0x15, 0x85, 0xf5};
#endif
#ifndef EXCLUDE_EMOJI
#define thumbs_height 25
#define thumbs_width 25
static unsigned char thumbup[] PROGMEM = {
0x00, 0x1C, 0x00, 0x00, 0x00, 0x24, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x00, 0x11, 0x00, 0x00, 0x80, 0x09, 0x00, 0x00,
0xC0, 0x08, 0x00, 0x00, 0x40, 0x08, 0x00, 0x00, 0x20, 0x04, 0x00, 0x00, 0x10, 0x04, 0x00, 0x00, 0x18, 0x02, 0x00, 0x00,
0x0C, 0xCE, 0x7F, 0x00, 0x04, 0x20, 0x80, 0x00, 0x02, 0x20, 0x80, 0x00, 0x02, 0x60, 0xC0, 0x00, 0x01, 0xF8, 0xFF, 0x01,
0x01, 0x08, 0x00, 0x01, 0x01, 0x08, 0x00, 0x01, 0x01, 0xF8, 0xFF, 0x00, 0x01, 0x10, 0x80, 0x00, 0x01, 0x18, 0x80, 0x00,
0x02, 0x30, 0xC0, 0x00, 0x06, 0xE0, 0x3F, 0x00, 0x0C, 0x20, 0x30, 0x00, 0x38, 0x20, 0x10, 0x00, 0xE0, 0xCF, 0x1F, 0x00,
// === Horizontal battery ===
// Basic battery design and all related pieces
const unsigned char batteryBitmap_h[] PROGMEM = {
0b11111110, 0b00000000, 0b11110000, 0b00000111, 0b00000001, 0b00000000, 0b00000000, 0b00001000, 0b00000001, 0b00000000,
0b00000000, 0b00001000, 0b00000001, 0b00000000, 0b00000000, 0b00001000, 0b00000001, 0b00000000, 0b00000000, 0b00001000,
0b00000001, 0b00000000, 0b00000000, 0b00011000, 0b00000001, 0b00000000, 0b00000000, 0b00011000, 0b00000001, 0b00000000,
0b00000000, 0b00011000, 0b00000001, 0b00000000, 0b00000000, 0b00011000, 0b00000001, 0b00000000, 0b00000000, 0b00011000,
0b00000001, 0b00000000, 0b00000000, 0b00001000, 0b00000001, 0b00000000, 0b00000000, 0b00001000, 0b00000001, 0b00000000,
0b00000000, 0b00001000, 0b00000001, 0b00000000, 0b00000000, 0b00001000, 0b11111110, 0b00000000, 0b11110000, 0b00000111};
// This is the left and right bars for the fill in
const unsigned char batteryBitmap_sidegaps_h[] PROGMEM = {
0b11111111, 0b00001111, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000,
0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000,
0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b00000000, 0b11111111, 0b00001111};
// Lightning Bolt
const unsigned char lightning_bolt_h[] PROGMEM = {
0b11110000, 0b00000000, 0b11110000, 0b00000000, 0b01110000, 0b00000000, 0b00111000, 0b00000000, 0b00111100,
0b00000000, 0b11111100, 0b00000000, 0b01111110, 0b00000000, 0b00111000, 0b00000000, 0b00110000, 0b00000000,
0b00010000, 0b00000000, 0b00010000, 0b00000000, 0b00001000, 0b00000000, 0b00001000, 0b00000000};
// === Vertical battery ===
// Basic battery design and all related pieces
const unsigned char batteryBitmap_v[] PROGMEM = {0b00011100, 0b00111110, 0b01000001, 0b01000001, 0b00000000, 0b00000000,
0b00000000, 0b01000001, 0b01000001, 0b01000001, 0b00111110};
// This is the left and right bars for the fill in
const unsigned char batteryBitmap_sidegaps_v[] PROGMEM = {0b10000010, 0b10000010, 0b10000010};
// Lightning Bolt
const unsigned char lightning_bolt_v[] PROGMEM = {0b00000100, 0b00000110, 0b00011111, 0b00001100, 0b00000100};
#define mail_width 10
#define mail_height 7
static const unsigned char mail[] PROGMEM = {
0b11111111, 0b00, // Top line
0b10000001, 0b00, // Edges
0b11000011, 0b00, // Diagonals start
0b10100101, 0b00, // Inner M part
0b10011001, 0b00, // Inner M part
0b10000001, 0b00, // Edges
0b11111111, 0b00 // Bottom line
};
static unsigned char thumbdown[] PROGMEM = {
0xE0, 0xCF, 0x1F, 0x00, 0x38, 0x20, 0x10, 0x00, 0x0C, 0x20, 0x30, 0x00, 0x06, 0xE0, 0x3F, 0x00, 0x02, 0x30, 0xC0, 0x00,
0x01, 0x18, 0x80, 0x00, 0x01, 0x10, 0x80, 0x00, 0x01, 0xF8, 0xFF, 0x00, 0x01, 0x08, 0x00, 0x01, 0x01, 0x08, 0x00, 0x01,
0x01, 0xF8, 0xFF, 0x01, 0x02, 0x60, 0xC0, 0x00, 0x02, 0x20, 0x80, 0x00, 0x04, 0x20, 0x80, 0x00, 0x0C, 0xCE, 0x7F, 0x00,
0x18, 0x02, 0x00, 0x00, 0x10, 0x04, 0x00, 0x00, 0x20, 0x04, 0x00, 0x00, 0x40, 0x08, 0x00, 0x00, 0xC0, 0x08, 0x00, 0x00,
0x80, 0x09, 0x00, 0x00, 0x00, 0x11, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x00, 0x24, 0x00, 0x00, 0x00, 0x1C, 0x00, 0x00,
// 📬 Mail / Message
const uint8_t icon_mail[] PROGMEM = {
0b00000000, // (padding)
0b11111111, // ████████ top border
0b10000001, // █ █ sides
0b11000011, // ██ ██ diagonal
0b10100101, // █ █ █ █ inner M
0b10011001, // █ ██ █ inner M
0b10000001, // █ █ sides
0b11111111 // ████████ bottom
};
#define smiley_height 30
#define smiley_width 30
static unsigned char smiley[] PROGMEM = {
0x00, 0xfe, 0x0f, 0x00, 0x80, 0x01, 0x30, 0x00, 0x40, 0x00, 0xc0, 0x00, 0x20, 0x00, 0x00, 0x01, 0x10, 0x00, 0x00, 0x02,
0x08, 0x00, 0x00, 0x04, 0x04, 0x00, 0x00, 0x08, 0x04, 0x00, 0x00, 0x10, 0x02, 0x0e, 0x0e, 0x10, 0x02, 0x09, 0x12, 0x10,
0x01, 0x09, 0x12, 0x20, 0x01, 0x0f, 0x1e, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20,
0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x81, 0x00, 0x20, 0x20,
0x82, 0x00, 0x20, 0x10, 0x02, 0x01, 0x10, 0x10, 0x04, 0x02, 0x08, 0x08, 0x04, 0xfc, 0x07, 0x08, 0x08, 0x00, 0x00, 0x04,
0x10, 0x00, 0x00, 0x02, 0x20, 0x00, 0x00, 0x01, 0x40, 0x00, 0xc0, 0x00, 0x80, 0x01, 0x30, 0x00, 0x00, 0xfe, 0x0f, 0x00};
#define question_height 25
#define question_width 25
static unsigned char question[] PROGMEM = {
0x00, 0x00, 0x00, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x80, 0xFF, 0x01, 0x00, 0xC0, 0xFF, 0x07, 0x00, 0xE0, 0xFF, 0x07, 0x00,
0xE0, 0xC3, 0x0F, 0x00, 0xF0, 0x81, 0x0F, 0x00, 0xF0, 0x01, 0x0F, 0x00, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x80, 0x0F, 0x00,
0x00, 0xC0, 0x0F, 0x00, 0x00, 0xE0, 0x07, 0x00, 0x00, 0xF0, 0x03, 0x00, 0x00, 0xF8, 0x01, 0x00, 0x00, 0x7C, 0x00, 0x00,
0x00, 0x3C, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x3E, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
// 📍 GPS Screen / Location Pin
const unsigned char icon_compass[] PROGMEM = {
0x3C, // Row 0: ..####..
0x52, // Row 1: .#..#.#.
0x91, // Row 2: #...#..#
0x91, // Row 3: #...#..#
0x91, // Row 4: #...#..#
0x81, // Row 5: #......#
0x42, // Row 6: .#....#.
0x3C // Row 7: ..####..
};
#define bang_height 30
#define bang_width 30
static unsigned char bang[] PROGMEM = {
0xFF, 0x0F, 0xFC, 0x3F, 0xFF, 0x0F, 0xFC, 0x3F, 0xFF, 0x0F, 0xFC, 0x3F, 0xFF, 0x07, 0xF8, 0x3F, 0xFF, 0x07, 0xF8, 0x3F,
0xFE, 0x07, 0xF8, 0x1F, 0xFE, 0x07, 0xF8, 0x1F, 0xFE, 0x07, 0xF8, 0x1F, 0xFE, 0x07, 0xF8, 0x1F, 0xFE, 0x07, 0xF8, 0x1F,
0xFE, 0x03, 0xF0, 0x1F, 0xFE, 0x03, 0xF0, 0x1F, 0xFC, 0x03, 0xF0, 0x0F, 0xFC, 0x03, 0xF0, 0x0F, 0xFC, 0x03, 0xF0, 0x0F,
0xFC, 0x03, 0xF0, 0x0F, 0xFC, 0x03, 0xF0, 0x0F, 0xFC, 0x03, 0xF0, 0x0F, 0xFC, 0x01, 0xE0, 0x0F, 0xFC, 0x01, 0xE0, 0x0F,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xF0, 0x00, 0xC0, 0x03, 0xFC, 0x03, 0xF0, 0x0F, 0xFE, 0x03, 0xF0, 0x1F,
0xFE, 0x07, 0xF8, 0x1F, 0xFE, 0x07, 0xF8, 0x1F, 0xFE, 0x07, 0xF8, 0x1F, 0xFC, 0x03, 0xF0, 0x0F, 0xF8, 0x01, 0xE0, 0x07,
const uint8_t icon_radio[] PROGMEM = {
0x0F, // Row 0: ####....
0x10, // Row 1: ....#...
0x27, // Row 2: ###..#..
0x48, // Row 3: ...#..#.
0x93, // Row 4: ##..#..#
0xA4, // Row 5: ..#..#.#
0xA8, // Row 6: ...#.#.#
0xA9 // Row 7: #..#.#.#
};
#define haha_height 30
#define haha_width 30
static unsigned char haha[] PROGMEM = {
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xE0, 0x01, 0x00,
0x00, 0xFC, 0x0F, 0x00, 0x00, 0x1F, 0x3E, 0x00, 0x80, 0x03, 0x70, 0x00, 0xC0, 0x01, 0xE0, 0x00, 0xC0, 0x00, 0xC2, 0x00,
0x60, 0x00, 0x03, 0x00, 0x60, 0x00, 0xC1, 0x1F, 0x60, 0x80, 0x8F, 0x31, 0x30, 0x0E, 0x80, 0x31, 0x30, 0x10, 0x30, 0x1F,
0x30, 0x08, 0x58, 0x00, 0x30, 0x04, 0x6C, 0x03, 0x60, 0x00, 0xF3, 0x01, 0x60, 0xC0, 0xFC, 0x01, 0x80, 0x38, 0xBF, 0x01,
0xE0, 0xC5, 0xDF, 0x00, 0xB0, 0xF9, 0xEF, 0x00, 0x30, 0xF1, 0x73, 0x00, 0xB0, 0x1D, 0x3E, 0x00, 0xF0, 0xFD, 0x0F, 0x00,
0xE0, 0xE0, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
// 🪙 Memory Icon
const uint8_t icon_memory[] PROGMEM = {
0x24, // Row 0: ..#..#..
0x3C, // Row 1: ..####..
0xC3, // Row 2: ##....##
0x5A, // Row 3: .#.##.#.
0x5A, // Row 4: .#.##.#.
0xC3, // Row 5: ##....##
0x3C, // Row 6: ..####..
0x24 // Row 7: ..#..#..
};
#define wave_icon_height 30
#define wave_icon_width 30
static unsigned char wave_icon[] PROGMEM = {
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x70, 0x00, 0x00, 0x00, 0xC0, 0x00,
0x00, 0x0C, 0x9C, 0x01, 0x80, 0x17, 0x20, 0x01, 0x80, 0x26, 0x46, 0x02, 0x80, 0x44, 0x88, 0x02, 0xC0, 0x89, 0x8A, 0x02,
0x40, 0x93, 0x8B, 0x02, 0x40, 0x26, 0x13, 0x00, 0x80, 0x44, 0x16, 0x00, 0xC0, 0x89, 0x24, 0x00, 0x40, 0x93, 0x60, 0x00,
0x40, 0x26, 0x40, 0x00, 0x80, 0x0C, 0x80, 0x00, 0x00, 0x09, 0x80, 0x00, 0x00, 0x02, 0x80, 0x00, 0x40, 0x06, 0x80, 0x00,
0x50, 0x0C, 0x80, 0x00, 0x50, 0x08, 0x40, 0x00, 0x90, 0x10, 0x20, 0x00, 0xB0, 0x21, 0x10, 0x00, 0x20, 0x47, 0x18, 0x00,
0x40, 0x80, 0x0F, 0x00, 0x80, 0x01, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
// 🌐 Wi-Fi
const uint8_t icon_wifi[] PROGMEM = {0b00000000, 0b00011000, 0b00111100, 0b01111110,
0b11011011, 0b00011000, 0b00011000, 0b00000000};
const uint8_t icon_nodes[] PROGMEM = {
0xF9, // Row 0 #..#######
0x00, // Row 1
0xF9, // Row 2 #..#######
0x00, // Row 3
0xF9, // Row 4 #..#######
0x00, // Row 5
0xF9, // Row 6 #..#######
0x00 // Row 7
};
#define cowboy_height 30
#define cowboy_width 30
static unsigned char cowboy[] PROGMEM = {
0x00, 0xF0, 0x03, 0x00, 0x00, 0xFC, 0x0F, 0x00, 0x00, 0xFE, 0x1F, 0x00, 0x00, 0xFF, 0x3F, 0x00, 0x3C, 0xFE, 0x1F, 0x0F,
0xFE, 0xFE, 0xDF, 0x1F, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xFF, 0x3F,
0x3E, 0xC0, 0x00, 0x1F, 0x1E, 0x00, 0x00, 0x1E, 0x0C, 0x0C, 0x0C, 0x0C, 0x08, 0x0E, 0x1C, 0x04, 0x00, 0x0E, 0x1C, 0x00,
0x04, 0x0E, 0x1C, 0x08, 0x04, 0x0E, 0x1C, 0x08, 0x04, 0x04, 0x08, 0x08, 0x04, 0x00, 0x00, 0x08, 0x04, 0x00, 0x00, 0x08,
0x8C, 0x07, 0x70, 0x0C, 0x88, 0xFC, 0x4F, 0x04, 0x88, 0x01, 0x40, 0x04, 0x90, 0xFF, 0x7F, 0x02, 0x30, 0x03, 0x30, 0x03,
0x60, 0x0E, 0x9C, 0x01, 0xC0, 0xF8, 0xC7, 0x00, 0x80, 0x01, 0x60, 0x00, 0x00, 0x0E, 0x1C, 0x00, 0x00, 0xF8, 0x07, 0x00,
// ➤ Chevron Triangle Arrow Icon (8x8)
const uint8_t icon_list[] PROGMEM = {
0x10, // Row 0: ...#....
0x10, // Row 1: ...#....
0x38, // Row 2: ..###...
0x38, // Row 3: ..###...
0x7C, // Row 4: .#####..
0x6C, // Row 5: .##.##..
0xC6, // Row 6: ##...##.
0x82 // Row 7: #.....#.
};
#define deadmau5_height 30
#define deadmau5_width 60
static unsigned char deadmau5[] PROGMEM = {
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xF8, 0x07, 0x00,
0x00, 0xFC, 0x03, 0x00, 0x00, 0xFF, 0x3F, 0x00, 0x80, 0xFF, 0x0F, 0x00, 0xC0, 0xFF, 0xFF, 0x00, 0xE0, 0xFF, 0x3F, 0x00,
0xE0, 0xFF, 0xFF, 0x01, 0xF0, 0xFF, 0x7F, 0x00, 0xF0, 0xFF, 0xFF, 0x03, 0xF8, 0xFF, 0xFF, 0x00, 0xF0, 0xFF, 0xFF, 0x07,
0xFC, 0xFF, 0xFF, 0x00, 0xF0, 0xFF, 0xFF, 0x0F, 0xFC, 0xFF, 0xFF, 0x00, 0xF0, 0xFF, 0xFF, 0x0F, 0xFE, 0xFF, 0xFF, 0x00,
0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0xE0, 0xFF, 0x3F, 0xFC,
0x0F, 0xFF, 0x7F, 0x00, 0xC0, 0xFF, 0x1F, 0xF8, 0x0F, 0xFC, 0x3F, 0x00, 0x80, 0xFF, 0x0F, 0xF8, 0x1F, 0xFC, 0x1F, 0x00,
0x00, 0xFF, 0x0F, 0xFC, 0x3F, 0xFC, 0x0F, 0x00, 0x00, 0xF8, 0x1F, 0xFF, 0xFF, 0xFE, 0x01, 0x00, 0x00, 0x00, 0xFC, 0xFF,
0xFF, 0x07, 0x00, 0x00, 0x00, 0x00, 0xFC, 0xFF, 0xFF, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x04, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x18, 0x00,
0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x30, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0xE0, 0x00, 0xC0, 0x00, 0x00, 0x00,
0x00, 0x00, 0x80, 0x07, 0x38, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFC, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
// 📶 Signal Bars Icon (left to right, small to large with spacing)
const uint8_t icon_signal[] PROGMEM = {
0b00000000, // ░░░░░░░
0b10000000, // ░░░░░░░
0b10100000, // ░░░░█░█
0b10100000, // ░░░░█░█
0b10101000, // ░░█░█░█
0b10101000, // ░░█░█░█
0b10101010, // █░█░█░█
0b11111111 // ███████
};
#define sun_width 30
#define sun_height 30
static unsigned char sun[] PROGMEM = {
0x00, 0xC0, 0x00, 0x00, 0x00, 0xE0, 0x01, 0x00, 0x00, 0xE0, 0x01, 0x00, 0x00, 0xE0, 0x01, 0x00, 0x30, 0xC0, 0x00, 0x03,
0x70, 0x00, 0x80, 0x03, 0xF0, 0x00, 0xC0, 0x03, 0xF0, 0xF8, 0xC7, 0x03, 0xE0, 0xFC, 0xCF, 0x01, 0x00, 0xFE, 0x1F, 0x00,
0x00, 0xFF, 0x3F, 0x00, 0x80, 0xFF, 0x7F, 0x00, 0x80, 0xFF, 0x7F, 0x00, 0x8E, 0xFF, 0x7F, 0x1C, 0x9F, 0xFF, 0x7F, 0x3E,
0x9F, 0xFF, 0x7F, 0x3E, 0x8E, 0xFF, 0x7F, 0x1C, 0x80, 0xFF, 0x7F, 0x00, 0x80, 0xFF, 0x7F, 0x00, 0x00, 0xFF, 0x3F, 0x00,
0x00, 0xFE, 0x1F, 0x00, 0x00, 0xFC, 0x0F, 0x00, 0xC0, 0xF9, 0xE7, 0x00, 0xE0, 0x01, 0xE0, 0x01, 0xF0, 0x01, 0xE0, 0x03,
0xF0, 0xC0, 0xC0, 0x03, 0x00, 0xE0, 0x01, 0x00, 0x00, 0xE0, 0x01, 0x00, 0x00, 0xE0, 0x01, 0x00, 0x00, 0xC0, 0x00, 0x00,
// ↔️ Distance / Measurement Icon (double-ended arrow)
const uint8_t icon_distance[] PROGMEM = {
0b00000000, // ░░░░░░░░
0b10000001, // █░░░░░█ arrowheads
0b01000010, // ░█░░░█░
0b00100100, // ░░█░█░░
0b00011000, // ░░░██░░ center
0b00100100, // ░░█░█░░
0b01000010, // ░█░░░█░
0b10000001 // █░░░░░█
};
#define rain_width 30
#define rain_height 30
static unsigned char rain[] PROGMEM = {
0xC0, 0x0F, 0xC0, 0x00, 0x40, 0x00, 0x80, 0x00, 0x20, 0x00, 0x80, 0x00, 0x20, 0x00, 0x80, 0x03, 0x38, 0x00,
0x00, 0x0E, 0x0C, 0x00, 0x00, 0x18, 0x02, 0x00, 0x00, 0x10, 0x03, 0x00, 0x00, 0x30, 0x01, 0x00, 0x00, 0x20,
0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x03, 0x00, 0x00, 0x30, 0x02, 0x00,
0x00, 0x10, 0x06, 0x00, 0x00, 0x08, 0xFC, 0xFF, 0xFF, 0x07, 0xF0, 0xFF, 0xFF, 0x01, 0x80, 0x00, 0x01, 0x00,
0xC0, 0xC0, 0x81, 0x03, 0xA0, 0x60, 0xC1, 0x03, 0x90, 0x20, 0x41, 0x01, 0xF0, 0xE0, 0xC0, 0x01, 0x60, 0x4C,
0x98, 0x00, 0x00, 0x0E, 0x1C, 0x00, 0x00, 0x0B, 0x12, 0x00, 0x00, 0x09, 0x1A, 0x00, 0x00, 0x06, 0x0E, 0x00,
// ⚠️ Error / Fault
const uint8_t icon_error[] PROGMEM = {
0b00011000, // ░░░██░░░
0b00011000, // ░░░██░░░
0b00011000, // ░░░██░░░
0b00011000, // ░░░██░░░
0b00000000, // ░░░░░░░░
0b00011000, // ░░░██░░░
0b00000000, // ░░░░░░░░
0b00000000 // ░░░░░░░░
};
#define cloud_height 30
#define cloud_width 30
static unsigned char cloud[] PROGMEM = {
0x00, 0x80, 0x07, 0x00, 0x00, 0xE0, 0x1F, 0x00, 0x00, 0x70, 0x30, 0x00, 0x00, 0x10, 0x60, 0x00, 0x80, 0x1F, 0x40, 0x00,
0xC0, 0x0F, 0xC0, 0x00, 0xC0, 0x00, 0x80, 0x00, 0x60, 0x00, 0x80, 0x00, 0x20, 0x00, 0x80, 0x00, 0x20, 0x00, 0x80, 0x01,
0x20, 0x00, 0x00, 0x07, 0x38, 0x00, 0x00, 0x0C, 0x0C, 0x00, 0x00, 0x08, 0x06, 0x00, 0x00, 0x18, 0x02, 0x00, 0x00, 0x10,
0x02, 0x00, 0x00, 0x30, 0x03, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20,
0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x30, 0x03, 0x00, 0x00, 0x10,
0x02, 0x00, 0x00, 0x10, 0x06, 0x00, 0x00, 0x18, 0x0C, 0x00, 0x00, 0x0C, 0xFC, 0xFF, 0xFF, 0x07, 0xF0, 0xFF, 0xFF, 0x03,
// 🏠 Optimized Home Icon (8x8)
const uint8_t icon_home[] PROGMEM = {
0b00011000, // ██
0b00111100, // ████
0b01111110, // ██████
0b11111111, // ███████
0b11000011, // ██ ██
0b11011011, // ██ ██ ██
0b11011011, // ██ ██ ██
0b11111111 // ███████
};
#define fog_height 25
#define fog_width 25
static unsigned char fog[] PROGMEM = {
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x78, 0x00, 0x3C, 0x00, 0xFE, 0x01, 0xFF, 0x00, 0x87, 0xC7, 0xC3, 0x01, 0x03, 0xFE, 0x80, 0x01,
0x00, 0x38, 0x00, 0x00, 0xFC, 0x00, 0x7E, 0x00, 0xFF, 0x83, 0xFF, 0x01, 0x03, 0xFF, 0x81, 0x01, 0x00, 0x7C, 0x00, 0x00,
0xF8, 0x00, 0x3E, 0x00, 0xFE, 0x01, 0xFF, 0x00, 0x87, 0xC7, 0xC3, 0x01, 0x03, 0xFE, 0x80, 0x01, 0x00, 0x38, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
// 🔧 Generic module (gear-like shape)
const uint8_t icon_module[] PROGMEM = {
0b00011000, // ░░░██░░░
0b00111100, // ░░████░░
0b01111110, // ░██████░
0b11011011, // ██░██░██
0b11011011, // ██░██░██
0b01111110, // ░██████░
0b00111100, // ░░████░░
0b00011000 // ░░░██░░░
};
#define devil_height 30
#define devil_width 30
static unsigned char devil[] PROGMEM = {
0x00, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x10, 0x03, 0xC0, 0x01, 0x38, 0x07, 0x7C, 0x0F, 0x38, 0x1F, 0x03, 0x30, 0x1E,
0xFE, 0x01, 0xE0, 0x1F, 0x7E, 0x00, 0x80, 0x1F, 0x3C, 0x00, 0x00, 0x0F, 0x1C, 0x00, 0x00, 0x0E, 0x18, 0x00, 0x00, 0x06,
0x08, 0x00, 0x00, 0x04, 0x0C, 0x00, 0x00, 0x0C, 0x0C, 0x00, 0x00, 0x0C, 0x0C, 0x00, 0x00, 0x0C, 0x0C, 0x0E, 0x1C, 0x0C,
0x0C, 0x18, 0x06, 0x0C, 0x0C, 0x1C, 0x06, 0x0C, 0x0C, 0x1C, 0x0E, 0x0C, 0x0C, 0x1C, 0x0E, 0x0C, 0x0C, 0x0C, 0x06, 0x0C,
0x08, 0x00, 0x00, 0x06, 0x18, 0x02, 0x10, 0x06, 0x10, 0x0C, 0x0C, 0x03, 0x30, 0xF8, 0x07, 0x03, 0x60, 0xE0, 0x80, 0x01,
0xC0, 0x00, 0xC0, 0x00, 0x80, 0x01, 0x70, 0x00, 0x00, 0x06, 0x1C, 0x00, 0x00, 0xF0, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00,
#define mute_symbol_width 8
#define mute_symbol_height 8
const uint8_t mute_symbol[] PROGMEM = {
0b00011001, // █
0b00100110, // █
0b00100100, // ████
0b01001010, // █ █ █
0b01010010, // █ █ █
0b01100010, // ████████
0b11111111, // █ █
0b10011000, // █
};
#define heart_height 30
#define heart_width 30
static unsigned char heart[] PROGMEM = {
0x00, 0x00, 0x00, 0x00, 0xC0, 0x03, 0xF0, 0x00, 0xF8, 0x0F, 0xFC, 0x07, 0xFC, 0x1F, 0x06, 0x0E, 0xFE, 0x3F, 0x03, 0x18,
0xFE, 0xFF, 0x7F, 0x10, 0xFF, 0xFF, 0xFF, 0x31, 0xFF, 0xFF, 0xFF, 0x33, 0xFF, 0xFF, 0xFF, 0x37, 0xFF, 0xFF, 0xFF, 0x37,
0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xFF, 0x3F, 0xFE, 0xFF, 0xFF, 0x1F, 0xFE, 0xFF, 0xFF, 0x1F,
0xFC, 0xFF, 0xFF, 0x0F, 0xFC, 0xFF, 0xFF, 0x0F, 0xF8, 0xFF, 0xFF, 0x07, 0xF0, 0xFF, 0xFF, 0x03, 0xF0, 0xFF, 0xFF, 0x03,
0xE0, 0xFF, 0xFF, 0x01, 0xC0, 0xFF, 0xFF, 0x00, 0x80, 0xFF, 0x7F, 0x00, 0x00, 0xFF, 0x3F, 0x00, 0x00, 0xFE, 0x1F, 0x00,
0x00, 0xFC, 0x0F, 0x00, 0x00, 0xF8, 0x07, 0x00, 0x00, 0xF0, 0x03, 0x00, 0x00, 0xE0, 0x01, 0x00, 0x00, 0x80, 0x00, 0x00,
#define mute_symbol_big_width 16
#define mute_symbol_big_height 16
const uint8_t mute_symbol_big[] PROGMEM = {0b00000001, 0b00000000, 0b11000010, 0b00000011, 0b00110100, 0b00001100, 0b00011000,
0b00001000, 0b00011000, 0b00010000, 0b00101000, 0b00010000, 0b01001000, 0b00010000,
0b10001000, 0b00010000, 0b00001000, 0b00010001, 0b00001000, 0b00010010, 0b00001000,
0b00010100, 0b00000100, 0b00101000, 0b11111100, 0b00111111, 0b01000000, 0b00100010,
0b10000000, 0b01000001, 0b00000000, 0b10000000};
// Bell icon for Alert Message
#define bell_alert_width 8
#define bell_alert_height 8
const unsigned char bell_alert[] PROGMEM = {0b00011000, 0b00100100, 0b00100100, 0b01000010,
0b01000010, 0b01000010, 0b11111111, 0b00011000};
#define key_symbol_width 8
#define key_symbol_height 8
const uint8_t key_symbol[] PROGMEM = {0b00000000, 0b00000000, 0b00000110, 0b11111001,
0b10101001, 0b10000110, 0b00000000, 0b00000000};
#define placeholder_width 8
#define placeholder_height 8
const uint8_t placeholder[] PROGMEM = {0b11111111, 0b11111111, 0b11111111, 0b11111111,
0b11111111, 0b11111111, 0b11111111, 0b11111111};
#define icon_node_width 8
#define icon_node_height 8
static const uint8_t icon_node[] PROGMEM = {
0x10, // #
0x10, // # ← antenna
0x10, // #
0xFE, // ####### ← device top
0x82, // # #
0xAA, // # # # # ← body with pattern
0x92, // # # #
0xFE // ####### ← device base
};
#define poo_width 30
#define poo_height 30
static unsigned char poo[] PROGMEM = {
0x00, 0x1C, 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x00, 0xEC, 0x01, 0x00, 0x00, 0x8C, 0x07, 0x00, 0x00, 0x0C, 0x06, 0x00,
0x00, 0x24, 0x0C, 0x00, 0x00, 0x34, 0x08, 0x00, 0x00, 0x1F, 0x08, 0x00, 0xC0, 0x0F, 0x08, 0x00, 0xC0, 0x00, 0x3C, 0x00,
0x60, 0x00, 0x7C, 0x00, 0x60, 0x00, 0xC6, 0x00, 0x20, 0x00, 0xCB, 0x00, 0xA0, 0xC7, 0xFF, 0x00, 0xE0, 0x7F, 0xF7, 0x00,
0xF0, 0x18, 0xE3, 0x03, 0x78, 0x18, 0x41, 0x03, 0x6C, 0x9B, 0x5D, 0x06, 0x64, 0x9B, 0x5D, 0x04, 0x44, 0x1A, 0x41, 0x04,
0x4C, 0xD8, 0x63, 0x06, 0xF8, 0xFC, 0x36, 0x06, 0xFE, 0x0F, 0x9C, 0x1F, 0x07, 0x03, 0xC0, 0x30, 0x03, 0x00, 0x78, 0x20,
0x01, 0x00, 0x1F, 0x20, 0x03, 0xE0, 0x03, 0x20, 0x07, 0x7E, 0x04, 0x30, 0xFE, 0x0F, 0xFC, 0x1F, 0xF0, 0x00, 0xF0, 0x0F,
};
#endif
#define bluetoothdisabled_width 8
#define bluetoothdisabled_height 8
const uint8_t bluetoothdisabled[] PROGMEM = {0b11101100, 0b01010100, 0b01001100, 0b01010100,
0b01001100, 0b00000000, 0b00000000, 0b00000000};
#define smallbulletpoint_width 8
#define smallbulletpoint_height 8
const uint8_t smallbulletpoint[] PROGMEM = {0b00000011, 0b00000011, 0b00000000, 0b00000000,
0b00000000, 0b00000000, 0b00000000, 0b00000000};
#include "img/icon.xbm"
static_assert(sizeof(icon_bits) >= 0, "Silence unused variable warning");

View File

@@ -19,6 +19,7 @@
#define INPUT_BROKER_MSG_FN_SYMBOL_ON 0xf1
#define INPUT_BROKER_MSG_FN_SYMBOL_OFF 0xf2
#define INPUT_BROKER_MSG_BLUETOOTH_TOGGLE 0xAA
#define INPUT_BROKER_MSG_TAB 0x09
typedef struct _InputEvent {
const char *source;

View File

@@ -84,6 +84,7 @@ int32_t ScanAndSelectInput::runOnce()
// Dismiss the alert screen several seconds after it appears
if (!Throttle::isWithinTimespanMs(alertingSinceMs, durationAlertMs)) {
alertingNoMessage = false;
if (screen)
screen->endAlert();
}
}
@@ -183,6 +184,7 @@ void ScanAndSelectInput::alertNoMessage()
alertingSinceMs = millis();
// Graphics code: the alert frame to show on screen
if (screen) {
screen->startAlert([](OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) -> void {
display->setTextAlignment(TEXT_ALIGN_CENTER_BOTH);
display->setFont(FONT_SMALL);
@@ -191,6 +193,7 @@ void ScanAndSelectInput::alertNoMessage()
display->drawString(textX + x, textY + y, "No Canned Messages");
});
}
}
// Remove the canned message frame from screen
// Used to dismiss the module frame when user button pressed

View File

@@ -372,11 +372,9 @@ void setup()
SPISettings spiSettings(4000000, MSBFIRST, SPI_MODE0);
#endif
#if !HAS_TFT
meshtastic_Config_DisplayConfig_OledType screen_model =
meshtastic_Config_DisplayConfig_OledType::meshtastic_Config_DisplayConfig_OledType_OLED_AUTO;
OLEDDISPLAY_GEOMETRY screen_geometry = GEOMETRY_128_64;
#endif
#ifdef USE_SEGGER
auto mode = false ? SEGGER_RTT_MODE_BLOCK_IF_FIFO_FULL : SEGGER_RTT_MODE_NO_BLOCK_TRIM;
@@ -539,10 +537,6 @@ void setup()
digitalWrite(AQ_SET_PIN, HIGH);
#endif
#if HAS_TFT
tftSetup();
#endif
// Currently only the tbeam has a PMU
// PMU initialization needs to be placed before i2c scanning
power = new Power();
@@ -605,7 +599,6 @@ void setup()
}
#endif
#if !HAS_TFT
auto screenInfo = i2cScanner->firstScreen();
screen_found = screenInfo.type != ScanI2C::DeviceType::NONE ? screenInfo.address : ScanI2C::ADDRESS_NONE;
@@ -623,7 +616,6 @@ void setup()
screen_model = meshtastic_Config_DisplayConfig_OledType::meshtastic_Config_DisplayConfig_OledType_OLED_AUTO;
}
}
#endif
#define UPDATE_FROM_SCANNER(FIND_FN)
@@ -770,6 +762,12 @@ void setup()
// but we need to do this after main cpu init (esp32setup), because we need the random seed set
nodeDB = new NodeDB;
#if HAS_TFT
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_COLOR) {
tftSetup();
}
#endif
// If we're taking on the repeater role, use NextHopRouter and turn off 3V3_S rail because peripherals are not needed
if (config.device.role == meshtastic_Config_DeviceConfig_Role_REPEATER) {
router = new NextHopRouter();
@@ -792,11 +790,9 @@ void setup()
else
playStartMelody();
#if !HAS_TFT
// fixed screen override?
if (config.display.oled != meshtastic_Config_DisplayConfig_OledType_OLED_AUTO)
screen_model = config.display.oled;
#endif
#if defined(USE_SH1107)
screen_model = meshtastic_Config_DisplayConfig_OledType_OLED_SH1107; // set dimension of 128x128
@@ -866,7 +862,9 @@ void setup()
// Initialize the screen first so we can show the logo while we start up everything else.
#if HAS_SCREEN
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_COLOR) {
screen = new graphics::Screen(screen_found, screen_model, screen_geometry);
}
#endif
// setup TZ prior to time actions.
#if !MESHTASTIC_EXCLUDE_TZ
@@ -956,18 +954,21 @@ void setup()
// the current region name)
#if defined(ST7701_CS) || defined(ST7735_CS) || defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) || \
defined(ST7789_CS) || defined(HX8357_CS) || defined(USE_ST7789) || defined(ILI9488_CS)
if (screen)
screen->setup();
#elif defined(ARCH_PORTDUINO)
if (screen_found.port != ScanI2C::I2CPort::NO_I2C || settingsMap[displayPanel]) {
if ((screen_found.port != ScanI2C::I2CPort::NO_I2C || settingsMap[displayPanel]) &&
config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_COLOR) {
screen->setup();
}
#else
if (screen_found.port != ScanI2C::I2CPort::NO_I2C)
if (screen_found.port != ScanI2C::I2CPort::NO_I2C && screen)
screen->setup();
#endif
#endif
if (screen) {
screen->print("Started...\n");
}
#ifdef PIN_PWR_DELAY_MS
// This may be required to give the peripherals time to power up.
@@ -1227,9 +1228,12 @@ void setup()
LOG_WARN("LoRa chip does not support 2.4GHz. Revert to unset");
config.lora.region = meshtastic_Config_LoRaConfig_RegionCode_UNSET;
nodeDB->saveToDisk(SEGMENT_CONFIG);
if (!rIf->reconfigure()) {
LOG_WARN("Reconfigure failed, rebooting");
screen->startAlert("Rebooting...");
if (screen) {
screen->showOverlayBanner("Rebooting...");
}
rebootAtMsec = millis() + 5000;
}
}

View File

@@ -499,6 +499,9 @@ void NodeDB::installDefaultConfig(bool preserveKey = false)
true; // FIXME: maybe false in the future, and setting region to enable it. (unset region forces it off)
config.lora.override_duty_cycle = false;
config.lora.config_ok_to_mqtt = false;
#if HAS_TFT // For the devices that support MUI, default to that
config.display.displaymode = meshtastic_Config_DisplayConfig_DisplayMode_COLOR;
#endif
#ifdef USERPREFS_CONFIG_LORA_REGION
config.lora.region = USERPREFS_CONFIG_LORA_REGION;
#else

View File

@@ -64,7 +64,9 @@ static int32_t reconnectETH()
}
#if !MESHTASTIC_EXCLUDE_SOCKETAPI
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_COLOR) {
initApiServer();
}
#endif
ethStartupComplete = true;

View File

@@ -903,6 +903,7 @@ void handleBlinkLED(HTTPRequest *req, HTTPResponse *res)
}
} else {
#if HAS_SCREEN
if (screen)
screen->blink();
#endif
}

View File

@@ -154,6 +154,7 @@ void createSSLCert()
esp_task_wdt_reset();
#if HAS_SCREEN
if (millis() / 1000 >= 3) {
if (screen)
screen->setSSLFrames();
}
#endif

View File

@@ -124,10 +124,14 @@ static void onNetworkConnected()
}
#if defined(ARCH_ESP32) && !MESHTASTIC_EXCLUDE_WEBSERVER
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_COLOR) {
initWebServer();
}
#endif
#if !MESHTASTIC_EXCLUDE_SOCKETAPI
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_COLOR) {
initApiServer();
}
#endif
APStartupComplete = true;
}

View File

@@ -200,6 +200,7 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
#if defined(ARCH_ESP32)
#if !MESHTASTIC_EXCLUDE_BLUETOOTH
if (!BleOta::getOtaAppVersion().isEmpty()) {
if (screen)
screen->startFirmwareUpdateScreen();
BleOta::switchToOtaApp();
LOG_INFO("Rebooting to BLE OTA");
@@ -207,6 +208,7 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
#endif
#if !MESHTASTIC_EXCLUDE_WIFI
if (WiFiOTA::trySwitchToOTA()) {
if (screen)
screen->startFirmwareUpdateScreen();
WiFiOTA::saveConfig(&config.network);
LOG_INFO("Rebooting to WiFi OTA");
@@ -297,6 +299,8 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
if (node != NULL) {
node->is_favorite = true;
saveChanges(SEGMENT_NODEDATABASE, false);
if (screen)
screen->setFrames(graphics::Screen::FOCUS_PRESERVE); // <-- Rebuild screens
}
break;
}
@@ -306,6 +310,8 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
if (node != NULL) {
node->is_favorite = false;
saveChanges(SEGMENT_NODEDATABASE, false);
if (screen)
screen->setFrames(graphics::Screen::FOCUS_PRESERVE); // <-- Rebuild screens
}
break;
}
@@ -620,8 +626,12 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c)
config.has_display = true;
if (config.display.screen_on_secs == c.payload_variant.display.screen_on_secs &&
config.display.flip_screen == c.payload_variant.display.flip_screen &&
config.display.oled == c.payload_variant.display.oled) {
config.display.oled == c.payload_variant.display.oled &&
config.display.displaymode == c.payload_variant.display.displaymode) {
requiresReboot = false;
} else if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_COLOR &&
c.payload_variant.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_COLOR) {
config.bluetooth.enabled = false;
}
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
if (config.display.wake_on_tap_or_motion == false && c.payload_variant.display.wake_on_tap_or_motion == true &&
@@ -1111,7 +1121,8 @@ void AdminModule::handleGetDeviceUIConfig(const meshtastic_MeshPacket &req)
void AdminModule::reboot(int32_t seconds)
{
LOG_INFO("Reboot in %d seconds", seconds);
screen->startAlert("Rebooting...");
if (screen)
screen->showOverlayBanner("Rebooting...", 0); // stays on screen
rebootAtMsec = (seconds < 0) ? 0 : (millis() + seconds * 1000);
}

File diff suppressed because it is too large Load Diff

View File

@@ -3,27 +3,42 @@
#include "ProtobufModule.h"
#include "input/InputBroker.h"
// ============================
// Enums & Defines
// ============================
enum cannedMessageModuleRunState {
CANNED_MESSAGE_RUN_STATE_DISABLED,
CANNED_MESSAGE_RUN_STATE_INACTIVE,
CANNED_MESSAGE_RUN_STATE_ACTIVE,
CANNED_MESSAGE_RUN_STATE_FREETEXT,
CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE,
CANNED_MESSAGE_RUN_STATE_ACK_NACK_RECEIVED,
CANNED_MESSAGE_RUN_STATE_MESSAGE,
CANNED_MESSAGE_RUN_STATE_ACTION_SELECT,
CANNED_MESSAGE_RUN_STATE_ACTION_UP,
CANNED_MESSAGE_RUN_STATE_ACTION_DOWN,
CANNED_MESSAGE_RUN_STATE_DESTINATION_SELECTION,
CANNED_MESSAGE_RUN_STATE_FREETEXT,
CANNED_MESSAGE_RUN_STATE_MESSAGE_SELECTION
};
enum cannedMessageDestinationType {
CANNED_MESSAGE_DESTINATION_TYPE_NONE,
CANNED_MESSAGE_DESTINATION_TYPE_NODE,
CANNED_MESSAGE_DESTINATION_TYPE_CHANNEL
};
enum CannedMessageModuleIconType { shift, backspace, space, enter };
#define CANNED_MESSAGE_MODULE_MESSAGE_MAX_COUNT 50
#define CANNED_MESSAGE_MODULE_MESSAGES_SIZE 800
#ifndef CANNED_MESSAGE_MODULE_ENABLE
#define CANNED_MESSAGE_MODULE_ENABLE 0
#endif
// ============================
// Data Structures
// ============================
struct Letter {
String character;
float width;
@@ -33,71 +48,62 @@ struct Letter {
int rectHeight;
};
#define CANNED_MESSAGE_MODULE_MESSAGE_MAX_COUNT 50
/**
* Sum of CannedMessageModuleConfig part sizes.
*/
#define CANNED_MESSAGE_MODULE_MESSAGES_SIZE 800
struct NodeEntry {
meshtastic_NodeInfoLite *node;
uint32_t lastHeard;
};
#ifndef CANNED_MESSAGE_MODULE_ENABLE
#define CANNED_MESSAGE_MODULE_ENABLE 0
#endif
// ============================
// Main Class
// ============================
class CannedMessageModule : public SinglePortModule, public Observable<const UIFrameEvent *>, private concurrency::OSThread
{
CallbackObserver<CannedMessageModule, const InputEvent *> inputObserver =
CallbackObserver<CannedMessageModule, const InputEvent *>(this, &CannedMessageModule::handleInputEvent);
public:
CannedMessageModule();
// === Message navigation ===
const char *getCurrentMessage();
const char *getPrevMessage();
const char *getNextMessage();
const char *getMessageByIndex(int index);
const char *getNodeName(NodeNum node);
// === State/UI ===
bool shouldDraw();
bool hasMessages();
// void eventUp();
// void eventDown();
// void eventSelect();
void showTemporaryMessage(const String &message);
void resetSearch();
void updateFilteredNodes();
bool isInterceptingAndFocused();
bool isCharInputAllowed() const;
String drawWithCursor(String text, int cursor);
// === Admin Handlers ===
void handleGetCannedMessageModuleMessages(const meshtastic_MeshPacket &req, meshtastic_AdminMessage *response);
void handleSetCannedMessageModuleMessages(const char *from_msg);
void showTemporaryMessage(const String &message);
String drawWithCursor(String text, int cursor);
#ifdef RAK14014
cannedMessageModuleRunState getRunState() const { return runState; }
#endif
/*
-Override the wantPacket method. We need the Routing Messages to look for ACKs.
*/
// === Packet Interest Filter ===
virtual bool wantPacket(const meshtastic_MeshPacket *p) override
{
if (p->rx_rssi != 0) {
this->lastRxRssi = p->rx_rssi;
}
if (p->rx_snr > 0) {
this->lastRxSnr = p->rx_snr;
}
switch (p->decoded.portnum) {
case meshtastic_PortNum_ROUTING_APP:
return waitingForAck;
default:
return false;
}
if (p->rx_rssi != 0)
lastRxRssi = p->rx_rssi;
if (p->rx_snr > 0)
lastRxSnr = p->rx_snr;
return (p->decoded.portnum == meshtastic_PortNum_ROUTING_APP) ? waitingForAck : false;
}
protected:
// === Thread Entry Point ===
virtual int32_t runOnce() override;
// === Transmission ===
void sendText(NodeNum dest, ChannelIndex channel, const char *message, bool wantReplies);
void drawHeader(OLEDDisplay *display, int16_t x, int16_t y, char *buffer);
int splitConfiguredMessages();
int getNextIndex();
int getPrevIndex();
@@ -105,58 +111,85 @@ class CannedMessageModule : public SinglePortModule, public Observable<const UIF
#if defined(USE_VIRTUAL_KEYBOARD)
void drawKeyboard(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
String keyForCoordinates(uint x, uint y);
bool shift = false;
int charSet = 0;
void drawShiftIcon(OLEDDisplay *display, int x, int y, float scale = 1);
void drawBackspaceIcon(OLEDDisplay *display, int x, int y, float scale = 1);
void drawEnterIcon(OLEDDisplay *display, int x, int y, float scale = 1);
#endif
char highlight = 0x00;
// === Input Handling ===
int handleInputEvent(const InputEvent *event);
virtual bool wantUIFrame() override { return this->shouldDraw(); }
virtual bool wantUIFrame() override { return shouldDraw(); }
virtual Observable<const UIFrameEvent *> *getUIFrameObservable() override { return this; }
virtual bool interceptingKeyboardInput() override;
#if !HAS_TFT
virtual void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) override;
#endif
virtual AdminMessageHandleResult handleAdminMessageForModule(const meshtastic_MeshPacket &mp,
meshtastic_AdminMessage *request,
meshtastic_AdminMessage *response) override;
/** Called to handle a particular incoming message
* @return ProcessMessage::STOP if you've guaranteed you've handled this message and no other handlers should be considered
* for it
*/
virtual ProcessMessage handleReceived(const meshtastic_MeshPacket &mp) override;
void loadProtoForModule();
bool saveProtoForModule();
void installDefaultCannedMessageModuleConfig();
int currentMessageIndex = -1;
cannedMessageModuleRunState runState = CANNED_MESSAGE_RUN_STATE_INACTIVE;
char payload = 0x00;
unsigned int cursor = 0;
String freetext = ""; // Text Buffer for Freetext Editor
NodeNum dest = NODENUM_BROADCAST;
ChannelIndex channel = 0;
cannedMessageDestinationType destSelect = CANNED_MESSAGE_DESTINATION_TYPE_NONE;
uint8_t numChannels = 0;
ChannelIndex indexChannels[MAX_NUM_CHANNELS] = {0};
NodeNum incoming = NODENUM_BROADCAST;
bool ack = false; // True means ACK, false means NAK (error_reason != NONE)
bool waitingForAck = false; // Are currently interested in routing packets?
float lastRxSnr = 0;
int32_t lastRxRssi = 0;
private:
// === Input Observers ===
CallbackObserver<CannedMessageModule, const InputEvent *> inputObserver =
CallbackObserver<CannedMessageModule, const InputEvent *>(this, &CannedMessageModule::handleInputEvent);
// === Display and UI ===
int displayHeight = 64;
int destIndex = 0;
int scrollIndex = 0;
int visibleRows = 0;
bool needsUpdate = true;
bool shouldRedraw = false;
unsigned long lastUpdateMillis = 0;
String searchQuery;
String nodeSelectionInput;
String freetext;
String temporaryMessage;
// === Message Storage ===
char messageStore[CANNED_MESSAGE_MODULE_MESSAGES_SIZE + 1];
char *messages[CANNED_MESSAGE_MODULE_MESSAGE_MAX_COUNT];
int messagesCount = 0;
int currentMessageIndex = -1;
// === Routing & Acknowledgment ===
NodeNum dest = NODENUM_BROADCAST; // Destination node for outgoing messages (default: broadcast)
NodeNum incoming = NODENUM_BROADCAST; // Source node from which last ACK/NACK was received
NodeNum lastSentNode = 0; // Tracks the most recent node we sent a message to (for UI display)
ChannelIndex channel = 0; // Channel index used when sending a message
bool ack = false; // True = ACK received, False = NACK or failed
bool waitingForAck = false; // True if we're expecting an ACK and should monitor routing packets
bool lastAckWasRelayed = false; // True if the ACK was relayed through intermediate nodes
uint8_t lastAckHopStart = 0; // Hop start value from the received ACK packet
uint8_t lastAckHopLimit = 0; // Hop limit value from the received ACK packet
float lastRxSnr = 0; // SNR from last received ACK (used for diagnostics/UI)
int32_t lastRxRssi = 0; // RSSI from last received ACK (used for diagnostics/UI)
// === State Tracking ===
cannedMessageModuleRunState runState = CANNED_MESSAGE_RUN_STATE_INACTIVE;
cannedMessageDestinationType destSelect = CANNED_MESSAGE_DESTINATION_TYPE_NONE;
char highlight = 0x00;
char payload = 0x00;
unsigned int cursor = 0;
unsigned long lastTouchMillis = 0;
String temporaryMessage;
std::vector<uint8_t> activeChannelIndices;
std::vector<NodeEntry> filteredNodes;
bool isInputSourceAllowed(const InputEvent *event);
bool isUpEvent(const InputEvent *event);
bool isDownEvent(const InputEvent *event);
bool isSelectEvent(const InputEvent *event);
bool handleTabSwitch(const InputEvent *event);
int handleDestinationSelectionInput(const InputEvent *event, bool isUp, bool isDown, bool isSelect);
bool handleMessageSelectorInput(const InputEvent *event, bool isUp, bool isDown, bool isSelect);
bool handleFreeTextInput(const InputEvent *event);
bool handleSystemCommandInput(const InputEvent *event);
#if defined(USE_VIRTUAL_KEYBOARD)
Letter keyboard[2][4][10] = {{{{"Q", 20, 0, 0, 0, 0},

View File

@@ -0,0 +1,302 @@
#if !MESHTASTIC_EXCLUDE_PKI
#include "KeyVerificationModule.h"
#include "MeshService.h"
#include "RTC.h"
#include "main.h"
#include "modules/AdminModule.h"
#include <SHA256.h>
KeyVerificationModule *keyVerificationModule;
KeyVerificationModule::KeyVerificationModule()
: ProtobufModule("KeyVerification", meshtastic_PortNum_KEY_VERIFICATION_APP, &meshtastic_KeyVerification_msg)
{
ourPortNum = meshtastic_PortNum_KEY_VERIFICATION_APP;
}
AdminMessageHandleResult KeyVerificationModule::handleAdminMessageForModule(const meshtastic_MeshPacket &mp,
meshtastic_AdminMessage *request,
meshtastic_AdminMessage *response)
{
updateState();
if (request->which_payload_variant == meshtastic_AdminMessage_key_verification_tag && mp.from == 0) {
LOG_WARN("Handling Key Verification Admin Message type %u", request->key_verification.message_type);
if (request->key_verification.message_type == meshtastic_KeyVerificationAdmin_MessageType_INITIATE_VERIFICATION &&
currentState == KEY_VERIFICATION_IDLE) {
sendInitialRequest(request->key_verification.remote_nodenum);
} else if (request->key_verification.message_type ==
meshtastic_KeyVerificationAdmin_MessageType_PROVIDE_SECURITY_NUMBER &&
request->key_verification.has_security_number && currentState == KEY_VERIFICATION_SENDER_AWAITING_NUMBER &&
request->key_verification.nonce == currentNonce) {
processSecurityNumber(request->key_verification.security_number);
} else if (request->key_verification.message_type == meshtastic_KeyVerificationAdmin_MessageType_DO_VERIFY &&
request->key_verification.nonce == currentNonce) {
auto remoteNodePtr = nodeDB->getMeshNode(currentRemoteNode);
remoteNodePtr->bitfield |= NODEINFO_BITFIELD_IS_KEY_MANUALLY_VERIFIED_MASK;
resetToIdle();
} else if (request->key_verification.message_type == meshtastic_KeyVerificationAdmin_MessageType_DO_NOT_VERIFY) {
resetToIdle();
}
return AdminMessageHandleResult::HANDLED;
}
return AdminMessageHandleResult::NOT_HANDLED;
}
bool KeyVerificationModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_KeyVerification *r)
{
updateState();
if (mp.pki_encrypted == false)
return false;
if (mp.from != currentRemoteNode) // because the inital connection request is handled in allocReply()
return false;
if (currentState == KEY_VERIFICATION_IDLE) {
return false; // if we're idle, the only acceptable message is an init, which should be handled by allocReply()
} else if (currentState == KEY_VERIFICATION_SENDER_HAS_INITIATED && r->nonce == currentNonce && r->hash2.size == 32 &&
r->hash1.size == 0) {
memcpy(hash2, r->hash2.bytes, 32);
if (screen)
screen->showOverlayBanner("Enter Security Number", 15000);
meshtastic_ClientNotification *cn = clientNotificationPool.allocZeroed();
cn->level = meshtastic_LogRecord_Level_WARNING;
sprintf(cn->message, "Enter Security Number for Key Verification");
cn->which_payload_variant = meshtastic_ClientNotification_key_verification_number_request_tag;
cn->payload_variant.key_verification_number_request.nonce = currentNonce;
strncpy(cn->payload_variant.key_verification_number_request.remote_longname, // should really check for nulls, etc
nodeDB->getMeshNode(currentRemoteNode)->user.long_name,
sizeof(cn->payload_variant.key_verification_number_request.remote_longname));
service->sendClientNotification(cn);
LOG_INFO("Received hash2");
currentState = KEY_VERIFICATION_SENDER_AWAITING_NUMBER;
return true;
} else if (currentState == KEY_VERIFICATION_RECEIVER_AWAITING_HASH1 && r->hash1.size == 32 && r->nonce == currentNonce) {
if (memcmp(hash1, r->hash1.bytes, 32) == 0) {
memset(message, 0, sizeof(message));
sprintf(message, "Verification: \n");
generateVerificationCode(message + 15);
LOG_INFO("Hash1 matches!");
if (screen) {
screen->showOverlayBanner(message, 15000);
}
meshtastic_ClientNotification *cn = clientNotificationPool.allocZeroed();
cn->level = meshtastic_LogRecord_Level_WARNING;
sprintf(cn->message, "Final confirmation for incoming manual key verification %s", message);
cn->which_payload_variant = meshtastic_ClientNotification_key_verification_final_tag;
cn->payload_variant.key_verification_final.nonce = currentNonce;
strncpy(cn->payload_variant.key_verification_final.remote_longname, // should really check for nulls, etc
nodeDB->getMeshNode(currentRemoteNode)->user.long_name,
sizeof(cn->payload_variant.key_verification_final.remote_longname));
cn->payload_variant.key_verification_final.isSender = false;
service->sendClientNotification(cn);
currentState = KEY_VERIFICATION_RECEIVER_AWAITING_USER;
return true;
}
}
return false;
}
bool KeyVerificationModule::sendInitialRequest(NodeNum remoteNode)
{
LOG_DEBUG("keyVerification start");
// generate nonce
updateState();
if (currentState != KEY_VERIFICATION_IDLE) {
return false;
}
currentNonce = random();
currentNonceTimestamp = getTime();
currentRemoteNode = remoteNode;
meshtastic_KeyVerification KeyVerification = meshtastic_KeyVerification_init_zero;
KeyVerification.nonce = currentNonce;
KeyVerification.hash2.size = 0;
KeyVerification.hash1.size = 0;
meshtastic_MeshPacket *p = allocDataProtobuf(KeyVerification);
p->to = remoteNode;
p->channel = 0;
p->pki_encrypted = true;
p->decoded.want_response = true;
p->priority = meshtastic_MeshPacket_Priority_HIGH;
service->sendToMesh(p, RX_SRC_LOCAL, true);
currentState = KEY_VERIFICATION_SENDER_HAS_INITIATED;
return true;
}
meshtastic_MeshPacket *KeyVerificationModule::allocReply()
{
SHA256 hash;
NodeNum ourNodeNum = nodeDB->getNodeNum();
updateState();
if (currentState != KEY_VERIFICATION_IDLE) { // TODO: cooldown period
LOG_WARN("Key Verification requested, but already in a request");
return nullptr;
} else if (!currentRequest->pki_encrypted) {
LOG_WARN("Key Verification requested, but not in a PKI packet");
return nullptr;
}
currentState = KEY_VERIFICATION_RECEIVER_AWAITING_HASH1;
auto req = *currentRequest;
const auto &p = req.decoded;
meshtastic_KeyVerification scratch;
meshtastic_KeyVerification response;
meshtastic_MeshPacket *responsePacket = nullptr;
pb_decode_from_bytes(p.payload.bytes, p.payload.size, &meshtastic_KeyVerification_msg, &scratch);
currentNonce = scratch.nonce;
response.nonce = scratch.nonce;
currentRemoteNode = req.from;
currentNonceTimestamp = getTime();
currentSecurityNumber = random(1, 999999);
// generate hash1
hash.reset();
hash.update(&currentSecurityNumber, sizeof(currentSecurityNumber));
hash.update(&currentNonce, sizeof(currentNonce));
hash.update(&currentRemoteNode, sizeof(currentRemoteNode));
hash.update(&ourNodeNum, sizeof(ourNodeNum));
hash.update(currentRequest->public_key.bytes, currentRequest->public_key.size);
hash.update(owner.public_key.bytes, owner.public_key.size);
hash.finalize(hash1, 32);
// generate hash2
hash.reset();
hash.update(&currentNonce, sizeof(currentNonce));
hash.update(hash1, 32);
hash.finalize(hash2, 32);
response.hash1.size = 0;
response.hash2.size = 32;
memcpy(response.hash2.bytes, hash2, 32);
responsePacket = allocDataProtobuf(response);
responsePacket->pki_encrypted = true;
if (screen) {
snprintf(message, 25, "Security Number \n%03u %03u", currentSecurityNumber / 1000, currentSecurityNumber % 1000);
screen->showOverlayBanner(message, 15000);
LOG_WARN("%s", message);
}
meshtastic_ClientNotification *cn = clientNotificationPool.allocZeroed();
cn->level = meshtastic_LogRecord_Level_WARNING;
sprintf(cn->message, "Incoming Key Verification.\nSecurity Number\n%03u %03u", currentSecurityNumber / 1000,
currentSecurityNumber % 1000);
cn->which_payload_variant = meshtastic_ClientNotification_key_verification_number_inform_tag;
cn->payload_variant.key_verification_number_inform.nonce = currentNonce;
strncpy(cn->payload_variant.key_verification_number_inform.remote_longname, // should really check for nulls, etc
nodeDB->getMeshNode(currentRemoteNode)->user.long_name,
sizeof(cn->payload_variant.key_verification_number_inform.remote_longname));
cn->payload_variant.key_verification_number_inform.security_number = currentSecurityNumber;
service->sendClientNotification(cn);
LOG_WARN("Security Number %04u", currentSecurityNumber);
return responsePacket;
}
void KeyVerificationModule::processSecurityNumber(uint32_t incomingNumber)
{
SHA256 hash;
NodeNum ourNodeNum = nodeDB->getNodeNum();
uint8_t scratch_hash[32] = {0};
LOG_WARN("received security number: %u", incomingNumber);
meshtastic_NodeInfoLite *remoteNodePtr = nullptr;
remoteNodePtr = nodeDB->getMeshNode(currentRemoteNode);
if (remoteNodePtr == nullptr || !remoteNodePtr->has_user || remoteNodePtr->user.public_key.size != 32) {
currentState = KEY_VERIFICATION_IDLE;
return; // should we throw an error here?
}
LOG_WARN("hashing ");
// calculate hash1
hash.reset();
hash.update(&incomingNumber, sizeof(incomingNumber));
hash.update(&currentNonce, sizeof(currentNonce));
hash.update(&ourNodeNum, sizeof(ourNodeNum));
hash.update(&currentRemoteNode, sizeof(currentRemoteNode));
hash.update(owner.public_key.bytes, owner.public_key.size);
hash.update(remoteNodePtr->user.public_key.bytes, remoteNodePtr->user.public_key.size);
hash.finalize(hash1, 32);
hash.reset();
hash.update(&currentNonce, sizeof(currentNonce));
hash.update(hash1, 32);
hash.finalize(scratch_hash, 32);
if (memcmp(scratch_hash, hash2, 32) != 0) {
LOG_WARN("Hash2 did not match");
return; // should probably throw an error of some sort
}
currentSecurityNumber = incomingNumber;
meshtastic_KeyVerification KeyVerification = meshtastic_KeyVerification_init_zero;
KeyVerification.nonce = currentNonce;
KeyVerification.hash2.size = 0;
KeyVerification.hash1.size = 32;
memcpy(KeyVerification.hash1.bytes, hash1, 32);
meshtastic_MeshPacket *p = allocDataProtobuf(KeyVerification);
p->to = currentRemoteNode;
p->channel = 0;
p->pki_encrypted = true;
p->decoded.want_response = true;
p->priority = meshtastic_MeshPacket_Priority_HIGH;
service->sendToMesh(p, RX_SRC_LOCAL, true);
currentState = KEY_VERIFICATION_SENDER_AWAITING_USER;
memset(message, 0, sizeof(message));
sprintf(message, "Verification: \n");
generateVerificationCode(message + 15); // send the toPhone packet
if (screen) {
screen->showOverlayBanner(message, 15000);
}
meshtastic_ClientNotification *cn = clientNotificationPool.allocZeroed();
cn->level = meshtastic_LogRecord_Level_WARNING;
sprintf(cn->message, "Final confirmation for outgoing manual key verification %s", message);
cn->which_payload_variant = meshtastic_ClientNotification_key_verification_final_tag;
cn->payload_variant.key_verification_final.nonce = currentNonce;
strncpy(cn->payload_variant.key_verification_final.remote_longname, // should really check for nulls, etc
nodeDB->getMeshNode(currentRemoteNode)->user.long_name,
sizeof(cn->payload_variant.key_verification_final.remote_longname));
cn->payload_variant.key_verification_final.isSender = true;
service->sendClientNotification(cn);
LOG_INFO(message);
return;
}
void KeyVerificationModule::updateState()
{
if (currentState != KEY_VERIFICATION_IDLE) {
// check for the 30 second timeout
if (currentNonceTimestamp < getTime() - 30) {
resetToIdle();
}
}
}
void KeyVerificationModule::resetToIdle()
{
memset(hash1, 0, 32);
memset(hash2, 0, 32);
currentNonce = 0;
currentNonceTimestamp = 0;
currentSecurityNumber = 0;
currentRemoteNode = 0;
currentState = KEY_VERIFICATION_IDLE;
}
void KeyVerificationModule::generateVerificationCode(char *readableCode)
{
for (int i = 0; i < 4; i++) {
// drop the two highest significance bits, then encode as a base64
readableCode[i] = (hash1[i] >> 2) + 48; // not a standardized base64, but workable and avoids having a dictionary.
}
readableCode[4] = ' ';
for (int i = 5; i < 9; i++) {
// drop the two highest significance bits, then encode as a base64
readableCode[i] = (hash1[i] >> 2) + 48; // not a standardized base64, but workable and avoids having a dictionary.
}
}
#endif

View File

@@ -0,0 +1,64 @@
#pragma once
#include "ProtobufModule.h"
#include "SinglePortModule.h"
enum KeyVerificationState {
KEY_VERIFICATION_IDLE,
KEY_VERIFICATION_SENDER_HAS_INITIATED,
KEY_VERIFICATION_SENDER_AWAITING_NUMBER,
KEY_VERIFICATION_SENDER_AWAITING_USER,
KEY_VERIFICATION_RECEIVER_AWAITING_USER,
KEY_VERIFICATION_RECEIVER_AWAITING_HASH1,
};
class KeyVerificationModule : public ProtobufModule<meshtastic_KeyVerification> //, private concurrency::OSThread //
{
// CallbackObserver<KeyVerificationModule, const meshtastic::Status *> nodeStatusObserver =
// CallbackObserver<KeyVerificationModule, const meshtastic::Status *>(this, &KeyVerificationModule::handleStatusUpdate);
public:
KeyVerificationModule();
/* : concurrency::OSThread("KeyVerification"),
ProtobufModule("KeyVerification", meshtastic_PortNum_KEY_VERIFICATION_APP, &meshtastic_KeyVerification_msg)
{
nodeStatusObserver.observe(&nodeStatus->onNewStatus);
setIntervalFromNow(setStartDelay()); // Wait until NodeInfo is sent
}*/
virtual bool wantUIFrame() { return false; };
bool sendInitialRequest(NodeNum remoteNode);
protected:
/* Called to handle a particular incoming message
@return true if you've guaranteed you've handled this message and no other handlers should be considered for it
*/
virtual bool handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_KeyVerification *p);
// virtual meshtastic_MeshPacket *allocReply() override;
// rather than add to the craziness that is the admin module, just handle those requests here.
virtual AdminMessageHandleResult handleAdminMessageForModule(const meshtastic_MeshPacket &mp,
meshtastic_AdminMessage *request,
meshtastic_AdminMessage *response) override;
/*
* Send our Telemetry into the mesh
*/
bool sendMetrics();
virtual meshtastic_MeshPacket *allocReply() override;
private:
uint64_t currentNonce = 0;
uint32_t currentNonceTimestamp = 0;
NodeNum currentRemoteNode = 0;
uint32_t currentSecurityNumber = 0;
KeyVerificationState currentState = KEY_VERIFICATION_IDLE;
uint8_t hash1[32] = {0}; //
uint8_t hash2[32] = {0}; //
char message[26] = {0};
void processSecurityNumber(uint32_t);
void updateState(); // check the timeouts and maybe reset the state to idle
void resetToIdle(); // Zero out module state
void generateVerificationCode(char *); // fills char with the user readable verification code
};
extern KeyVerificationModule *keyVerificationModule;

View File

@@ -12,6 +12,9 @@
#endif
#include "input/kbMatrixImpl.h"
#endif
#if !MESHTASTIC_EXCLUDE_PKI
#include "KeyVerificationModule.h"
#endif
#if !MESHTASTIC_EXCLUDE_ADMIN
#include "modules/AdminModule.h"
#endif
@@ -62,6 +65,7 @@
#include "modules/Telemetry/AirQualityTelemetry.h"
#include "modules/Telemetry/EnvironmentTelemetry.h"
#include "modules/Telemetry/HealthTelemetry.h"
#include "modules/Telemetry/Sensor/TelemetrySensor.h"
#endif
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_POWER_TELEMETRY
#include "modules/Telemetry/PowerTelemetry.h"
@@ -104,7 +108,9 @@ void setupModules()
{
if (config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER) {
#if (HAS_BUTTON || ARCH_PORTDUINO) && !MESHTASTIC_EXCLUDE_INPUTBROKER
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_COLOR) {
inputBroker = new InputBroker();
}
#endif
#if !MESHTASTIC_EXCLUDE_ADMIN
adminModule = new AdminModule();
@@ -133,7 +139,9 @@ void setupModules()
#if !MESHTASTIC_EXCLUDE_ATAK
atakPluginModule = new AtakPluginModule();
#endif
#if !MESHTASTIC_EXCLUDE_PKI
keyVerificationModule = new KeyVerificationModule();
#endif
#if !MESHTASTIC_EXCLUDE_DROPZONE
dropzoneModule = new DropzoneModule();
#endif
@@ -152,6 +160,8 @@ void setupModules()
// Example: Put your module here
// new ReplyModule();
#if (HAS_BUTTON || ARCH_PORTDUINO) && !MESHTASTIC_EXCLUDE_INPUTBROKER
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_COLOR) {
rotaryEncoderInterruptImpl1 = new RotaryEncoderInterruptImpl1();
if (!rotaryEncoderInterruptImpl1->init()) {
delete rotaryEncoderInterruptImpl1;
@@ -164,7 +174,8 @@ void setupModules()
}
#if HAS_SCREEN
// In order to have the user button dismiss the canned message frame, this class lightly interacts with the Screen class
// In order to have the user button dismiss the canned message frame, this class lightly interacts with the Screen
// class
scanAndSelectInput = new ScanAndSelectInput();
if (!scanAndSelectInput->init()) {
delete scanAndSelectInput;
@@ -182,20 +193,28 @@ void setupModules()
aSerialKeyboardImpl = new SerialKeyboardImpl();
aSerialKeyboardImpl->init();
#endif // INPUTBROKER_MATRIX_TYPE
}
#endif // HAS_BUTTON
#if ARCH_PORTDUINO && !HAS_TFT
#if ARCH_PORTDUINO
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_COLOR) {
aLinuxInputImpl = new LinuxInputImpl();
aLinuxInputImpl->init();
}
#endif
#if HAS_TRACKBALL && !MESHTASTIC_EXCLUDE_INPUTBROKER
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_COLOR) {
trackballInterruptImpl1 = new TrackballInterruptImpl1();
trackballInterruptImpl1->init();
}
#endif
LOG_DEBUG("location5");
#ifdef INPUTBROKER_EXPRESSLRSFIVEWAY_TYPE
expressLRSFiveWayInput = new ExpressLRSFiveWay();
#endif
#if HAS_SCREEN && !MESHTASTIC_EXCLUDE_CANNEDMESSAGES
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_COLOR) {
cannedMessageModule = new CannedMessageModule();
}
#endif
#if ARCH_PORTDUINO
new HostMetricsModule();
@@ -221,7 +240,9 @@ void setupModules()
#if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)) && !defined(CONFIG_IDF_TARGET_ESP32S2) && \
!defined(CONFIG_IDF_TARGET_ESP32C3)
#if !MESHTASTIC_EXCLUDE_SERIAL
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_COLOR) {
new SerialModule();
}
#endif
#endif
#ifdef ARCH_ESP32

View File

@@ -21,13 +21,6 @@ bool NodeInfoModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes
bool wasBroadcast = isBroadcast(mp.to);
// Show new nodes on LCD screen
if (wasBroadcast) {
String lcd = String("Joined: ") + p.long_name + "\n";
if (screen)
screen->print(lcd.c_str());
}
// if user has changed while packet was not for us, inform phone
if (hasChanged && !wasBroadcast && !isToUs(&mp))
service->sendToPhone(packetPool.allocCopy(mp));

View File

@@ -328,7 +328,13 @@ void PositionModule::sendOurPosition()
// If we changed channels, ask everyone else for their latest info
LOG_INFO("Send pos@%x:6 to mesh (wantReplies=%d)", localPosition.timestamp, requestReplies);
sendOurPosition(NODENUM_BROADCAST, requestReplies);
for (uint8_t channelNum = 0; channelNum < 8; channelNum++) {
if (channels.getByIndex(channelNum).settings.has_module_settings &&
channels.getByIndex(channelNum).settings.module_settings.position_precision != 0) {
sendOurPosition(NODENUM_BROADCAST, requestReplies, channelNum);
return;
}
}
}
void PositionModule::sendOurPosition(NodeNum dest, bool wantReplies, uint8_t channel)
@@ -340,11 +346,6 @@ void PositionModule::sendOurPosition(NodeNum dest, bool wantReplies, uint8_t cha
// Set's the class precision value for this particular packet
if (channels.getByIndex(channel).settings.has_module_settings) {
precision = channels.getByIndex(channel).settings.module_settings.position_precision;
} else if (channels.getByIndex(channel).role == meshtastic_Channel_Role_PRIMARY) {
// backwards compatibility for Primary channels created before position_precision was set by default
precision = 13;
} else {
precision = 0;
}
meshtastic_MeshPacket *p = allocPositionPacket();

View File

@@ -84,6 +84,7 @@ bool RemoteHardwareModule::handleReceivedProtobuf(const meshtastic_MeshPacket &r
switch (p.type) {
case meshtastic_HardwareMessage_Type_WRITE_GPIOS: {
// Print notification to LCD screen
if (screen)
screen->print("Write GPIOs\n");
pinModes(p.gpio_mask, OUTPUT, availablePins);

View File

@@ -14,7 +14,7 @@ meshtastic_MeshPacket *ReplyModule::allocReply()
// The incoming message is in p.payload
LOG_INFO("Received message from=0x%0x, id=%d, msg=%.*s", req.from, req.id, p.payload.size, p.payload.bytes);
#endif
if (screen)
screen->print("Send reply\n");
const char *replyStr = "Message Received";

View File

@@ -341,7 +341,7 @@ ProcessMessage SerialModuleRadio::handleReceived(const meshtastic_MeshPacket &mp
serialPrint->write(p.payload.bytes, p.payload.size);
} else if (moduleConfig.serial.mode == meshtastic_ModuleConfig_SerialConfig_Serial_Mode_TEXTMSG) {
meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(getFrom(&mp));
String sender = (node && node->has_user) ? node->user.short_name : "???";
const char *sender = (node && node->has_user) ? node->user.short_name : "???";
serialPrint->println();
serialPrint->printf("%s: %s", sender, p.payload.bytes);
serialPrint->println();
@@ -410,8 +410,8 @@ uint32_t SerialModule::getBaudRate()
// Add this structure to help with parsing WindGust = 24.4 serial lines.
struct ParsedLine {
String name;
String value;
char name[64];
char value[128];
};
/**
@@ -438,16 +438,30 @@ ParsedLine parseLine(const char *line)
strncpy(nameBuf, line, nameLen);
nameBuf[nameLen] = '\0';
// Create trimmed name string
String name = String(nameBuf);
name.trim();
// Trim whitespace from name
char *nameStart = nameBuf;
while (*nameStart && isspace(*nameStart))
nameStart++;
char *nameEnd = nameStart + strlen(nameStart) - 1;
while (nameEnd > nameStart && isspace(*nameEnd))
*nameEnd-- = '\0';
// Extract value after equals sign
String value = String(equals + 1);
value.trim();
// Copy trimmed name
strncpy(result.name, nameStart, sizeof(result.name) - 1);
result.name[sizeof(result.name) - 1] = '\0';
// Extract value part (after equals)
const char *valueStart = equals + 1;
while (*valueStart && isspace(*valueStart))
valueStart++;
strncpy(result.value, valueStart, sizeof(result.value) - 1);
result.value[sizeof(result.value) - 1] = '\0';
// Trim trailing whitespace from value
char *valueEnd = result.value + strlen(result.value) - 1;
while (valueEnd > result.value && isspace(*valueEnd))
*valueEnd-- = '\0';
result.name = name;
result.value = value;
return result;
}
@@ -517,16 +531,16 @@ void SerialModule::processWXSerial()
memcpy(line, &serialBytes[lineStart], lineEnd - lineStart);
ParsedLine parsed = parseLine(line);
if (parsed.name.length() > 0) {
if (parsed.name == "WindDir") {
strlcpy(windDir, parsed.value.c_str(), sizeof(windDir));
if (strlen(parsed.name) > 0) {
if (strcmp(parsed.name, "WindDir") == 0) {
strlcpy(windDir, parsed.value, sizeof(windDir));
double radians = GeoCoord::toRadians(strtof(windDir, nullptr));
dir_sum_sin += sin(radians);
dir_sum_cos += cos(radians);
dirCount++;
gotwind = true;
} else if (parsed.name == "WindSpeed") {
strlcpy(windVel, parsed.value.c_str(), sizeof(windVel));
} else if (strcmp(parsed.name, "WindSpeed") == 0) {
strlcpy(windVel, parsed.value, sizeof(windVel));
float newv = strtof(windVel, nullptr);
velSum += newv;
velCount++;
@@ -534,28 +548,28 @@ void SerialModule::processWXSerial()
lull = newv;
}
gotwind = true;
} else if (parsed.name == "WindGust") {
strlcpy(windGust, parsed.value.c_str(), sizeof(windGust));
} else if (strcmp(parsed.name, "WindGust") == 0) {
strlcpy(windGust, parsed.value, sizeof(windGust));
float newg = strtof(windGust, nullptr);
if (newg > gust) {
gust = newg;
}
gotwind = true;
} else if (parsed.name == "BatVoltage") {
strlcpy(batVoltage, parsed.value.c_str(), sizeof(batVoltage));
} else if (strcmp(parsed.name, "BatVoltage") == 0) {
strlcpy(batVoltage, parsed.value, sizeof(batVoltage));
batVoltageF = strtof(batVoltage, nullptr);
break; // last possible data we want so break
} else if (parsed.name == "CapVoltage") {
strlcpy(capVoltage, parsed.value.c_str(), sizeof(capVoltage));
} else if (strcmp(parsed.name, "CapVoltage") == 0) {
strlcpy(capVoltage, parsed.value, sizeof(capVoltage));
capVoltageF = strtof(capVoltage, nullptr);
} else if (parsed.name == "GXTS04Temp" || parsed.name == "Temperature") {
strlcpy(temperature, parsed.value.c_str(), sizeof(temperature));
} else if (strcmp(parsed.name, "GXTS04Temp") == 0 || strcmp(parsed.name, "Temperature") == 0) {
strlcpy(temperature, parsed.value, sizeof(temperature));
temperatureF = strtof(temperature, nullptr);
} else if (parsed.name == "RainIntSum") {
strlcpy(rainStr, parsed.value.c_str(), sizeof(rainStr));
} else if (strcmp(parsed.name, "RainIntSum") == 0) {
strlcpy(rainStr, parsed.value, sizeof(rainStr));
rainSum = int(strtof(rainStr, nullptr));
} else if (parsed.name == "Rain") {
strlcpy(rainStr, parsed.value.c_str(), sizeof(rainStr));
} else if (strcmp(parsed.name, "Rain") == 0) {
strlcpy(rainStr, parsed.value, sizeof(rainStr));
rain = strtof(rainStr, nullptr);
}
}

View File

@@ -1,6 +1,6 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && __has_include("Adafruit_PM25AQI.h")
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && __has_include("Adafruit_PM25AQI.h")
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "AirQualityTelemetry.h"

View File

@@ -1,6 +1,6 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "Default.h"
@@ -11,7 +11,11 @@
#include "RTC.h"
#include "Router.h"
#include "UnitConversions.h"
#include "buzz.h"
#include "graphics/SharedUIDisplay.h"
#include "graphics/images.h"
#include "main.h"
#include "modules/ExternalNotificationModule.h"
#include "power.h"
#include "sleep.h"
#include "target_specific.h"
@@ -19,12 +23,17 @@
#include <OLEDDisplayUi.h>
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR_EXTERNAL
// Sensors
#include "Sensor/CGRadSensSensor.h"
#include "Sensor/RCWL9620Sensor.h"
#include "Sensor/nullSensor.h"
namespace graphics
{
extern void drawCommonHeader(OLEDDisplay *display, int16_t x, int16_t y);
}
#if __has_include(<Adafruit_AHTX0.h>)
#include "Sensor/AHT10.h"
AHT10Sensor aht10Sensor;
@@ -330,119 +339,167 @@ bool EnvironmentTelemetryModule::wantUIFrame()
void EnvironmentTelemetryModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
display->setTextAlignment(TEXT_ALIGN_LEFT);
// === Setup display ===
display->clear();
display->setFont(FONT_SMALL);
display->setTextAlignment(TEXT_ALIGN_LEFT);
if (lastMeasurementPacket == nullptr) {
// If there's no valid packet, display "Environment"
display->drawString(x, y, "Environment");
display->drawString(x, y += _fontHeight(FONT_SMALL), "No measurement");
// Draw shared header bar (battery, time, etc.)
graphics::drawCommonHeader(display, x, y);
// === Draw Title (Centered under header) ===
const int highlightHeight = FONT_HEIGHT_SMALL - 1;
const int titleY = y + 1 + (highlightHeight - FONT_HEIGHT_SMALL) / 2;
const char *titleStr = (SCREEN_WIDTH > 128) ? "Environment" : "Env.";
const int centerX = x + SCREEN_WIDTH / 2;
// Use black text on white background if in inverted mode
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_INVERTED)
display->setColor(BLACK);
display->setTextAlignment(TEXT_ALIGN_CENTER);
display->drawString(centerX, titleY, titleStr); // Centered title
if (config.display.heading_bold)
display->drawString(centerX + 1, titleY, titleStr); // Bold effect via 1px offset
// Restore text color & alignment
display->setColor(WHITE);
display->setTextAlignment(TEXT_ALIGN_LEFT);
// === Row spacing setup ===
const int rowHeight = FONT_HEIGHT_SMALL - 4;
int currentY = compactFirstLine;
// === Show "No Telemetry" if no data available ===
if (!lastMeasurementPacket) {
display->drawString(x, currentY, "No Telemetry");
return;
}
// Decode the last measurement packet
meshtastic_Telemetry lastMeasurement;
uint32_t agoSecs = service->GetTimeSinceMeshPacket(lastMeasurementPacket);
const char *lastSender = getSenderShortName(*lastMeasurementPacket);
// Decode the telemetry message from the latest received packet
const meshtastic_Data &p = lastMeasurementPacket->decoded;
if (!pb_decode_from_bytes(p.payload.bytes, p.payload.size, &meshtastic_Telemetry_msg, &lastMeasurement)) {
display->drawString(x, y, "Measurement Error");
LOG_ERROR("Unable to decode last packet");
meshtastic_Telemetry telemetry;
if (!pb_decode_from_bytes(p.payload.bytes, p.payload.size, &meshtastic_Telemetry_msg, &telemetry)) {
display->drawString(x, currentY, "No Telemetry");
return;
}
// Display "Env. From: ..." on its own
display->drawString(x, y, "Env. From: " + String(lastSender) + " (" + String(agoSecs) + "s)");
const auto &m = telemetry.variant.environment_metrics;
// Prepare sensor data strings
String sensorData[10];
int sensorCount = 0;
// Check if any telemetry field has valid data
bool hasAny = m.has_temperature || m.has_relative_humidity || m.barometric_pressure != 0 || m.iaq != 0 || m.voltage != 0 ||
m.current != 0 || m.lux != 0 || m.white_lux != 0 || m.weight != 0 || m.distance != 0 || m.radiation != 0;
if (lastMeasurement.variant.environment_metrics.has_temperature ||
lastMeasurement.variant.environment_metrics.has_relative_humidity) {
String last_temp = String(lastMeasurement.variant.environment_metrics.temperature, 0) + "°C";
if (moduleConfig.telemetry.environment_display_fahrenheit) {
last_temp =
String(UnitConversions::CelsiusToFahrenheit(lastMeasurement.variant.environment_metrics.temperature), 0) + "°F";
if (!hasAny) {
display->drawString(x, currentY, "No Telemetry");
return;
}
sensorData[sensorCount++] =
"Temp/Hum: " + last_temp + " / " + String(lastMeasurement.variant.environment_metrics.relative_humidity, 0) + "%";
}
// === First line: Show sender name + time since received (left), and first metric (right) ===
const char *sender = getSenderShortName(*lastMeasurementPacket);
uint32_t agoSecs = service->GetTimeSinceMeshPacket(lastMeasurementPacket);
String agoStr = (agoSecs > 864000) ? "?"
: (agoSecs > 3600) ? String(agoSecs / 3600) + "h"
: (agoSecs > 60) ? String(agoSecs / 60) + "m"
: String(agoSecs) + "s";
if (lastMeasurement.variant.environment_metrics.barometric_pressure != 0) {
sensorData[sensorCount++] =
"Press: " + String(lastMeasurement.variant.environment_metrics.barometric_pressure, 0) + "hPA";
}
String leftStr = String(sender) + " (" + agoStr + ")";
display->drawString(x, currentY, leftStr); // Left side: who and when
if (lastMeasurement.variant.environment_metrics.voltage != 0) {
sensorData[sensorCount++] = "Volt/Cur: " + String(lastMeasurement.variant.environment_metrics.voltage, 0) + "V / " +
String(lastMeasurement.variant.environment_metrics.current, 0) + "mA";
}
// === Collect sensor readings as label strings (no icons) ===
std::vector<String> entries;
if (lastMeasurement.variant.environment_metrics.iaq != 0) {
sensorData[sensorCount++] = "IAQ: " + String(lastMeasurement.variant.environment_metrics.iaq);
if (m.has_temperature) {
String tempStr = moduleConfig.telemetry.environment_display_fahrenheit
? "Tmp: " + String(UnitConversions::CelsiusToFahrenheit(m.temperature), 1) + "°F"
: "Tmp: " + String(m.temperature, 1) + "°C";
entries.push_back(tempStr);
}
if (m.has_relative_humidity)
entries.push_back("Hum: " + String(m.relative_humidity, 0) + "%");
if (m.barometric_pressure != 0)
entries.push_back("Prss: " + String(m.barometric_pressure, 0) + " hPa");
if (m.iaq != 0) {
String aqi = "IAQ: " + String(m.iaq);
const char *bannerMsg = nullptr; // Default: no banner
if (lastMeasurement.variant.environment_metrics.distance != 0) {
sensorData[sensorCount++] = "Water Level: " + String(lastMeasurement.variant.environment_metrics.distance, 0) + "mm";
}
if (lastMeasurement.variant.environment_metrics.weight != 0) {
sensorData[sensorCount++] = "Weight: " + String(lastMeasurement.variant.environment_metrics.weight, 0) + "kg";
}
if (lastMeasurement.variant.environment_metrics.radiation != 0) {
sensorData[sensorCount++] = "Rad: " + String(lastMeasurement.variant.environment_metrics.radiation, 2) + "µR/h";
}
if (lastMeasurement.variant.environment_metrics.lux != 0) {
sensorData[sensorCount++] = "Illuminance: " + String(lastMeasurement.variant.environment_metrics.lux, 2) + "lx";
}
if (lastMeasurement.variant.environment_metrics.white_lux != 0) {
sensorData[sensorCount++] = "W_Lux: " + String(lastMeasurement.variant.environment_metrics.white_lux, 2) + "lx";
}
static int scrollOffset = 0;
static bool scrollingDown = true;
static uint32_t lastScrollTime = millis();
// Determine how many lines we can fit on display
// Calculated once only: display dimensions don't change during runtime.
static int maxLines = 0;
if (!maxLines) {
const int16_t paddingTop = _fontHeight(FONT_SMALL); // Heading text
const int16_t paddingBottom = 8; // Indicator dots
maxLines = (display->getHeight() - paddingTop - paddingBottom) / _fontHeight(FONT_SMALL);
assert(maxLines > 0);
}
// Draw as many lines of data as we can fit
int linesToShow = min(maxLines, sensorCount);
for (int i = 0; i < linesToShow; i++) {
int index = (scrollOffset + i) % sensorCount;
display->drawString(x, y += _fontHeight(FONT_SMALL), sensorData[index]);
}
// Only scroll if there are more than 3 sensor data lines
if (sensorCount > 3) {
// Update scroll offset every 5 seconds
if (millis() - lastScrollTime > 5000) {
if (scrollingDown) {
scrollOffset++;
if (scrollOffset + linesToShow >= sensorCount) {
scrollingDown = false;
}
if (m.iaq <= 25)
aqi += " (Excellent)";
else if (m.iaq <= 50)
aqi += " (Good)";
else if (m.iaq <= 100)
aqi += " (Moderate)";
else if (m.iaq <= 150)
aqi += " (Poor)";
else if (m.iaq <= 200) {
aqi += " (Unhealthy)";
bannerMsg = "Unhealthy IAQ";
} else if (m.iaq <= 300) {
aqi += " (Very Unhealthy)";
bannerMsg = "Very Unhealthy IAQ";
} else {
scrollOffset--;
if (scrollOffset <= 0) {
scrollingDown = true;
aqi += " (Hazardous)";
bannerMsg = "Hazardous IAQ";
}
entries.push_back(aqi);
// === IAQ alert logic ===
static uint32_t lastAlertTime = 0;
uint32_t now = millis();
bool isOwnTelemetry = lastMeasurementPacket->from == nodeDB->getNodeNum();
bool isCooldownOver = (now - lastAlertTime > 60000);
if (isOwnTelemetry && bannerMsg && isCooldownOver) {
LOG_INFO("drawFrame: IAQ %d (own) — showing banner: %s", m.iaq, bannerMsg);
screen->showOverlayBanner(bannerMsg, 3000);
// Only buzz if IAQ is over 200
if (m.iaq > 200 && moduleConfig.external_notification.enabled && !externalNotificationModule->getMute()) {
playLongBeep();
}
lastAlertTime = now;
}
}
lastScrollTime = millis();
if (m.voltage != 0 || m.current != 0)
entries.push_back(String(m.voltage, 1) + "V / " + String(m.current, 0) + "mA");
if (m.lux != 0)
entries.push_back("Light: " + String(m.lux, 0) + "lx");
if (m.white_lux != 0)
entries.push_back("White: " + String(m.white_lux, 0) + "lx");
if (m.weight != 0)
entries.push_back("Weight: " + String(m.weight, 0) + "kg");
if (m.distance != 0)
entries.push_back("Level: " + String(m.distance, 0) + "mm");
if (m.radiation != 0)
entries.push_back("Rad: " + String(m.radiation, 2) + " µR/h");
// === Show first available metric on top-right of first line ===
if (!entries.empty()) {
String valueStr = entries.front();
int rightX = SCREEN_WIDTH - display->getStringWidth(valueStr);
display->drawString(rightX, currentY, valueStr);
entries.erase(entries.begin()); // Remove from queue
}
// === Advance to next line for remaining telemetry entries ===
currentY += rowHeight;
// === Draw remaining entries in 2-column format (left and right) ===
for (size_t i = 0; i < entries.size(); i += 2) {
// Left column
display->drawString(x, currentY, entries[i]);
// Right column if it exists
if (i + 1 < entries.size()) {
int rightX = SCREEN_WIDTH / 2;
display->drawString(rightX, currentY, entries[i + 1]);
}
currentY += rowHeight;
}
}

View File

@@ -118,22 +118,31 @@ void HealthTelemetryModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *
}
// Display "Health From: ..." on its own
display->drawString(x, y, "Health From: " + String(lastSender) + "(" + String(agoSecs) + "s)");
char headerStr[64];
snprintf(headerStr, sizeof(headerStr), "Health From: %s(%ds)", lastSender, (int)agoSecs);
display->drawString(x, y, headerStr);
String last_temp = String(lastMeasurement.variant.health_metrics.temperature, 0) + "°C";
char last_temp[16];
if (moduleConfig.telemetry.environment_display_fahrenheit) {
last_temp = String(UnitConversions::CelsiusToFahrenheit(lastMeasurement.variant.health_metrics.temperature), 0) + "°F";
snprintf(last_temp, sizeof(last_temp), "%.0f°F",
UnitConversions::CelsiusToFahrenheit(lastMeasurement.variant.health_metrics.temperature));
} else {
snprintf(last_temp, sizeof(last_temp), "%.0f°C", lastMeasurement.variant.health_metrics.temperature);
}
// Continue with the remaining details
display->drawString(x, y += _fontHeight(FONT_SMALL), "Temp: " + last_temp);
char tempStr[32];
snprintf(tempStr, sizeof(tempStr), "Temp: %s", last_temp);
display->drawString(x, y += _fontHeight(FONT_SMALL), tempStr);
if (lastMeasurement.variant.health_metrics.has_heart_bpm) {
display->drawString(x, y += _fontHeight(FONT_SMALL),
"Heart Rate: " + String(lastMeasurement.variant.health_metrics.heart_bpm, 0) + " bpm");
char heartStr[32];
snprintf(heartStr, sizeof(heartStr), "Heart Rate: %.0f bpm", lastMeasurement.variant.health_metrics.heart_bpm);
display->drawString(x, y += _fontHeight(FONT_SMALL), heartStr);
}
if (lastMeasurement.variant.health_metrics.has_spO2) {
display->drawString(x, y += _fontHeight(FONT_SMALL),
"spO2: " + String(lastMeasurement.variant.health_metrics.spO2, 0) + " %");
char spo2Str[32];
snprintf(spo2Str, sizeof(spo2Str), "spO2: %.0f %%", lastMeasurement.variant.health_metrics.spO2);
display->drawString(x, y += _fontHeight(FONT_SMALL), spo2Str);
}
}

View File

@@ -10,6 +10,7 @@
#include "PowerTelemetry.h"
#include "RTC.h"
#include "Router.h"
#include "graphics/SharedUIDisplay.h"
#include "main.h"
#include "power.h"
#include "sleep.h"
@@ -21,6 +22,11 @@
#include "graphics/ScreenFonts.h"
#include <Throttle.h>
namespace graphics
{
extern void drawCommonHeader(OLEDDisplay *display, int16_t x, int16_t y);
}
int32_t PowerTelemetryModule::runOnce()
{
if (sleepOnNextExecution == true) {
@@ -103,13 +109,33 @@ bool PowerTelemetryModule::wantUIFrame()
void PowerTelemetryModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
display->clear();
display->setTextAlignment(TEXT_ALIGN_LEFT);
display->setFont(FONT_SMALL);
graphics::drawCommonHeader(display, x, y); // Shared UI header
// === Draw title (aligned with header baseline) ===
const int highlightHeight = FONT_HEIGHT_SMALL - 1;
const int textY = y + 1 + (highlightHeight - FONT_HEIGHT_SMALL) / 2;
const char *titleStr = (SCREEN_WIDTH > 128) ? "Power Telem." : "Power";
const int centerX = x + SCREEN_WIDTH / 2;
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_INVERTED) {
display->setColor(BLACK);
}
display->setTextAlignment(TEXT_ALIGN_CENTER);
display->drawString(centerX, textY, titleStr);
if (config.display.heading_bold) {
display->drawString(centerX + 1, textY, titleStr);
}
display->setColor(WHITE);
display->setTextAlignment(TEXT_ALIGN_LEFT);
if (lastMeasurementPacket == nullptr) {
// In case of no valid packet, display "Power Telemetry", "No measurement"
display->drawString(x, y, "Power Telemetry");
display->drawString(x, y += _fontHeight(FONT_SMALL), "No measurement");
display->drawString(x, compactFirstLine, "No measurement");
return;
}
@@ -120,29 +146,35 @@ void PowerTelemetryModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *s
const meshtastic_Data &p = lastMeasurementPacket->decoded;
if (!pb_decode_from_bytes(p.payload.bytes, p.payload.size, &meshtastic_Telemetry_msg, &lastMeasurement)) {
display->drawString(x, y, "Measurement Error");
display->drawString(x, compactFirstLine, "Measurement Error");
LOG_ERROR("Unable to decode last packet");
return;
}
// Display "Pow. From: ..."
display->drawString(x, y, "Pow. From: " + String(lastSender) + "(" + String(agoSecs) + "s)");
char fromStr[64];
snprintf(fromStr, sizeof(fromStr), "Pow. From: %s (%ds)", lastSender, agoSecs);
display->drawString(x, compactFirstLine, fromStr);
// Display current and voltage based on ...power_metrics.has_[channel/voltage/current]... flags
if (lastMeasurement.variant.power_metrics.has_ch1_voltage || lastMeasurement.variant.power_metrics.has_ch1_current) {
display->drawString(x, y += _fontHeight(FONT_SMALL),
"Ch1: " + String(lastMeasurement.variant.power_metrics.ch1_voltage, 2) + "V " +
String(lastMeasurement.variant.power_metrics.ch1_current, 0) + "mA");
const auto &m = lastMeasurement.variant.power_metrics;
int lineY = compactSecondLine;
auto drawLine = [&](const char *label, float voltage, float current) {
char lineStr[64];
snprintf(lineStr, sizeof(lineStr), "%s: %.2fV %.0fmA", label, voltage, current);
display->drawString(x, lineY, lineStr);
lineY += _fontHeight(FONT_SMALL);
};
if (m.has_ch1_voltage || m.has_ch1_current) {
drawLine("Ch1", m.ch1_voltage, m.ch1_current);
}
if (lastMeasurement.variant.power_metrics.has_ch2_voltage || lastMeasurement.variant.power_metrics.has_ch2_current) {
display->drawString(x, y += _fontHeight(FONT_SMALL),
"Ch2: " + String(lastMeasurement.variant.power_metrics.ch2_voltage, 2) + "V " +
String(lastMeasurement.variant.power_metrics.ch2_current, 0) + "mA");
if (m.has_ch2_voltage || m.has_ch2_current) {
drawLine("Ch2", m.ch2_voltage, m.ch2_current);
}
if (lastMeasurement.variant.power_metrics.has_ch3_voltage || lastMeasurement.variant.power_metrics.has_ch3_current) {
display->drawString(x, y += _fontHeight(FONT_SMALL),
"Ch3: " + String(lastMeasurement.variant.power_metrics.ch3_voltage, 2) + "V " +
String(lastMeasurement.variant.power_metrics.ch3_current, 0) + "mA");
if (m.has_ch3_voltage || m.has_ch3_current) {
drawLine("Ch3", m.ch3_voltage, m.ch3_current);
}
}

View File

@@ -137,17 +137,17 @@ void BME680Sensor::updateState()
#endif
}
void BME680Sensor::checkStatus(String functionName)
void BME680Sensor::checkStatus(const char *functionName)
{
if (bme680.status < BSEC_OK)
LOG_ERROR("%s BSEC2 code: %s", functionName.c_str(), String(bme680.status).c_str());
LOG_ERROR("%s BSEC2 code: %d", functionName, bme680.status);
else if (bme680.status > BSEC_OK)
LOG_WARN("%s BSEC2 code: %s", functionName.c_str(), String(bme680.status).c_str());
LOG_WARN("%s BSEC2 code: %d", functionName, bme680.status);
if (bme680.sensor.status < BME68X_OK)
LOG_ERROR("%s BME68X code: %s", functionName.c_str(), String(bme680.sensor.status).c_str());
LOG_ERROR("%s BME68X code: %d", functionName, bme680.sensor.status);
else if (bme680.sensor.status > BME68X_OK)
LOG_WARN("%s BME68X code: %s", functionName.c_str(), String(bme680.sensor.status).c_str());
LOG_WARN("%s BME68X code: %d", functionName, bme680.sensor.status);
}
#endif

View File

@@ -34,7 +34,7 @@ class BME680Sensor : public TelemetrySensor
BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_HUMIDITY};
void loadState();
void updateState();
void checkStatus(String functionName);
void checkStatus(const char *functionName);
public:
BME680Sensor();

View File

@@ -2,9 +2,12 @@
#include "NodeDB.h"
#include "PowerFSM.h"
#include "configuration.h"
#include "graphics/draw/CompassRenderer.h"
#if HAS_SCREEN
#include "gps/RTC.h"
#include "graphics/Screen.h"
#include "graphics/draw/NodeListRenderer.h"
#include "main.h"
#endif
@@ -48,6 +51,8 @@ ProcessMessage WaypointModule::handleReceived(const meshtastic_MeshPacket &mp)
bool WaypointModule::shouldDraw()
{
#if !MESHTASTIC_EXCLUDE_WAYPOINT
if (screen == nullptr)
return false;
// If no waypoint to show
if (!devicestate.has_rx_waypoint)
return false;
@@ -79,13 +84,15 @@ bool WaypointModule::shouldDraw()
/// Draw the last waypoint we received
void WaypointModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
if (screen == nullptr)
return;
// Prepare to draw
display->setFont(FONT_SMALL);
display->setTextAlignment(TEXT_ALIGN_LEFT);
// Handle inverted display
// Unsure of expected behavior: for now, copy drawNodeInfo
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_INVERTED)
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_INVERTED)
display->fillRect(0 + x, 0 + y, x + display->getWidth(), y + FONT_HEIGHT_SMALL);
// Decode the waypoint
@@ -115,7 +122,7 @@ void WaypointModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state,
// Dimensions / co-ordinates for the compass/circle
int16_t compassX = 0, compassY = 0;
uint16_t compassDiam = graphics::Screen::getCompassDiam(display->getWidth(), display->getHeight());
uint16_t compassDiam = graphics::CompassRenderer::getCompassDiam(display->getWidth(), display->getHeight());
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_DEFAULT) {
compassX = x + display->getWidth() - compassDiam / 2 - 5;
@@ -133,7 +140,7 @@ void WaypointModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state,
myHeading = (screen->getHeading()) * PI / 180; // gotta convert compass degrees to Radians
else
myHeading = screen->estimatedHeading(DegD(op.latitude_i), DegD(op.longitude_i));
screen->drawCompassNorth(display, compassX, compassY, myHeading);
graphics::CompassRenderer::drawCompassNorth(display, compassX, compassY, myHeading);
// Compass bearing to waypoint
float bearingToOther =
@@ -142,7 +149,7 @@ void WaypointModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state,
// If the top of the compass is not a static north we need adjust bearingToOther based on heading
if (!config.display.compass_north_top)
bearingToOther -= myHeading;
screen->drawNodeHeading(display, compassX, compassY, compassDiam, bearingToOther);
graphics::CompassRenderer::drawNodeHeading(display, compassX, compassY, compassDiam, bearingToOther);
float bearingToOtherDegrees = (bearingToOther < 0) ? bearingToOther + 2 * PI : bearingToOther;
bearingToOtherDegrees = bearingToOtherDegrees * 180 / PI;
@@ -180,11 +187,11 @@ void WaypointModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state,
// Undo color-inversion, if set prior to drawing header
// Unsure of expected behavior? For now: copy drawNodeInfo
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_INVERTED) {
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_INVERTED) {
display->setColor(BLACK);
}
// Must be after distStr is populated
screen->drawColumns(display, x, y, fields);
graphics::NodeListRenderer::drawColumns(display, x, y, fields);
}
#endif

View File

@@ -37,6 +37,7 @@ int32_t BMX160Sensor::runOnce()
if (!showingScreen) {
powerFSM.trigger(EVENT_PRESS); // keep screen alive during calibration
showingScreen = true;
if (screen)
screen->startAlert((FrameCallback)drawFrameCalibration);
}
@@ -58,6 +59,7 @@ int32_t BMX160Sensor::runOnce()
doCalibration = false;
endCalibrationAt = 0;
showingScreen = false;
if (screen)
screen->endAlert();
}
@@ -103,7 +105,7 @@ int32_t BMX160Sensor::runOnce()
heading += 270;
break;
}
if (screen)
screen->setHeading(heading);
#endif
@@ -118,6 +120,7 @@ void BMX160Sensor::calibrate(uint16_t forSeconds)
doCalibration = true;
uint16_t calibrateFor = forSeconds * 1000; // calibrate for seconds provided
endCalibrationAt = millis() + calibrateFor;
if (screen)
screen->setEndCalibration(endCalibrationAt);
#endif
}

View File

@@ -60,6 +60,7 @@ int32_t ICM20948Sensor::runOnce()
if (!showingScreen) {
powerFSM.trigger(EVENT_PRESS); // keep screen alive during calibration
showingScreen = true;
if (screen)
screen->startAlert((FrameCallback)drawFrameCalibration);
}
@@ -81,6 +82,7 @@ int32_t ICM20948Sensor::runOnce()
doCalibration = false;
endCalibrationAt = 0;
showingScreen = false;
if (screen)
screen->endAlert();
}
@@ -124,7 +126,7 @@ int32_t ICM20948Sensor::runOnce()
heading += 270;
break;
}
if (screen)
screen->setHeading(heading);
#endif
@@ -159,6 +161,7 @@ void ICM20948Sensor::calibrate(uint16_t forSeconds)
doCalibration = true;
uint16_t calibrateFor = forSeconds * 1000; // calibrate for seconds provided
endCalibrationAt = millis() + calibrateFor;
if (screen)
screen->setEndCalibration(endCalibrationAt);
#endif
}

View File

@@ -1,4 +1,5 @@
#include "MotionSensor.h"
#include "graphics/draw/CompassRenderer.h"
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
@@ -34,6 +35,8 @@ ScanI2C::I2CPort MotionSensor::devicePort()
#if !defined(MESHTASTIC_EXCLUDE_SCREEN) && HAS_SCREEN
void MotionSensor::drawFrameCalibration(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
if (screen == nullptr)
return;
// int x_offset = display->width() / 2;
// int y_offset = display->height() <= 80 ? 0 : 32;
display->setTextAlignment(TEXT_ALIGN_LEFT);
@@ -46,7 +49,7 @@ void MotionSensor::drawFrameCalibration(OLEDDisplay *display, OLEDDisplayUiState
display->drawString(x, y + 40, timeRemainingBuffer);
int16_t compassX = 0, compassY = 0;
uint16_t compassDiam = graphics::Screen::getCompassDiam(display->getWidth(), display->getHeight());
uint16_t compassDiam = graphics::CompassRenderer::getCompassDiam(display->getWidth(), display->getHeight());
// coordinates for the center of the compass/circle
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_DEFAULT) {
@@ -57,7 +60,7 @@ void MotionSensor::drawFrameCalibration(OLEDDisplay *display, OLEDDisplayUiState
compassY = y + FONT_HEIGHT_SMALL + (display->getHeight() - FONT_HEIGHT_SMALL) / 2;
}
display->drawCircle(compassX, compassY, compassDiam / 2);
screen->drawCompassNorth(display, compassX, compassY, screen->getHeading() * PI / 180);
graphics::CompassRenderer::drawCompassNorth(display, compassX, compassY, screen->getHeading() * PI / 180);
}
#endif

View File

@@ -94,6 +94,7 @@ class NimbleBluetoothServerCallback : public NimBLEServerCallbacks
bluetoothStatus->updateStatus(new meshtastic::BluetoothStatus(std::to_string(passkey)));
#if HAS_SCREEN // Todo: migrate this display code back into Screen class, and observe bluetoothStatus
if (screen) {
screen->startAlert([passkey](OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) -> void {
char btPIN[16] = "888888";
snprintf(btPIN, sizeof(btPIN), "%06u", passkey);
@@ -108,17 +109,18 @@ class NimbleBluetoothServerCallback : public NimBLEServerCallbacks
display->drawString(x_offset + x, y_offset + y, "Enter this code");
display->setFont(FONT_LARGE);
String displayPin(btPIN);
String pin = displayPin.substring(0, 3) + " " + displayPin.substring(3, 6);
char pin[8];
snprintf(pin, sizeof(pin), "%.3s %.3s", btPIN, btPIN + 3);
y_offset = display->height() == 64 ? y_offset + FONT_HEIGHT_SMALL - 5 : y_offset + FONT_HEIGHT_SMALL + 5;
display->drawString(x_offset + x, y_offset + y, pin);
display->setFont(FONT_SMALL);
String deviceName = "Name: ";
deviceName.concat(getDeviceName());
char deviceName[64];
snprintf(deviceName, sizeof(deviceName), "Name: %s", getDeviceName());
y_offset = display->height() == 64 ? y_offset + FONT_HEIGHT_LARGE - 6 : y_offset + FONT_HEIGHT_LARGE + 5;
display->drawString(x_offset + x, y_offset + y, deviceName);
});
}
#endif
passkeyShowing = true;
@@ -134,6 +136,7 @@ class NimbleBluetoothServerCallback : public NimBLEServerCallbacks
// Todo: migrate this display code back into Screen class, and observe bluetoothStatus
if (passkeyShowing) {
passkeyShowing = false;
if (screen)
screen->endAlert();
}
}

View File

@@ -80,13 +80,13 @@ bool trySwitchToOTA()
return true;
}
String getVersion()
const char *getVersion()
{
const esp_partition_t *part = getAppPartition();
esp_app_desc_t app_desc;
static esp_app_desc_t app_desc;
if (!getAppDesc(part, &app_desc))
return String();
return String(app_desc.version);
return "";
return app_desc.version;
}
} // namespace WiFiOTA

View File

@@ -12,7 +12,7 @@ bool isUpdated();
void recoverConfig(meshtastic_Config_NetworkConfig *network);
void saveConfig(meshtastic_Config_NetworkConfig *network);
bool trySwitchToOTA();
String getVersion();
const char *getVersion();
} // namespace WiFiOTA
#endif // WIFIOTA_H

View File

@@ -78,8 +78,8 @@ extern NullSensor ina3221Sensor;
#endif
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_STM32WL)
#include "modules/Telemetry/Sensor/MAX17048Sensor.h"
#if __has_include(<Adafruit_MAX1704X.h>)
#include "modules/Telemetry/Sensor/MAX17048Sensor.h"
extern MAX17048Sensor max17048Sensor;
#else
extern NullSensor max17048Sensor;

View File

@@ -41,8 +41,8 @@ void powerCommandsCheck()
}
#if defined(ARCH_ESP32) || defined(ARCH_NRF52)
if (shutdownAtMsec) {
screen->startAlert("Shutting down...");
if (shutdownAtMsec && screen) {
screen->showOverlayBanner("Shutting Down...", 0); // stays on screen
}
#endif

View File

@@ -221,7 +221,7 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false, bool skipSaveN
#endif
powerMon->setState(meshtastic_PowerMon_State_CPU_DeepSleep);
if (screen)
screen->doDeepSleep(); // datasheet says this will draw only 10ua
if (!skipSaveNodeDb) {

View File

@@ -56,6 +56,7 @@ extern "C" {
#define TFT_WIDTH 240
#define TFT_OFFSET_X 0
#define TFT_OFFSET_Y 0
// #define TFT_OFFSET_ROTATION 0
// #define SCREEN_ROTATE
// #define SCREEN_TRANSITION_FRAMERATE 5

View File

@@ -1,3 +1,4 @@
#ifndef HAS_TFT
#define BUTTON_PIN 0
#define BUTTON_PIN_SECONDARY 21 // Second built-in button
#define BUTTON_SECONDARY_CANNEDMESSAGES // By default, use the secondary button as canned message input
@@ -69,3 +70,4 @@
#define SX126X_DIO2_AS_RF_SWITCH
#define SX126X_DIO3_TCXO_VOLTAGE 1.8
#endif // HAS_TFT

View File

@@ -26,18 +26,12 @@ extends = env:picomputer-s3
build_flags =
${env:picomputer-s3.build_flags}
-D MESHTASTIC_EXCLUDE_CANNEDMESSAGES=1
-D MESHTASTIC_EXCLUDE_INPUTBROKER=1
-D MESHTASTIC_EXCLUDE_BLUETOOTH=1
-D MESHTASTIC_EXCLUDE_WEBSERVER=1
-D MESHTASTIC_EXCLUDE_SERIAL=1
-D MESHTASTIC_EXCLUDE_SOCKETAPI=1
-D INPUTDRIVER_MATRIX_TYPE=1
-D USE_PIN_BUZZER=PIN_BUZZER
-D USE_SX127x
-D HAS_SCREEN=0
-D HAS_SCREEN=1
-D HAS_TFT=1
-D RAM_SIZE=1024
-D RAM_SIZE=1560
-D LV_LVGL_H_INCLUDE_SIMPLE
-D LV_CONF_INCLUDE_SIMPLE
-D LV_COMP_CONF_INCLUDE_SIMPLE

View File

@@ -26,7 +26,8 @@ build_flags = ${native_base.build_flags} -Os -lX11 -linput -lxkbcommon -ffunctio
-D RAM_SIZE=16384
-D USE_X11=1
-D HAS_TFT=1
-D HAS_SCREEN=0
-D HAS_SCREEN=1
-D LV_CACHE_DEF_SIZE=6291456
-D LV_BUILD_TEST=0
-D LV_USE_LIBINPUT=1
@@ -41,7 +42,6 @@ build_flags = ${native_base.build_flags} -Os -lX11 -linput -lxkbcommon -ffunctio
!pkg-config --libs openssl --silence-errors || :
build_src_filter =
${native_base.build_src_filter}
-<graphics/TFTDisplay.cpp>
[env:native-fb]
extends = native_base
@@ -56,7 +56,7 @@ build_flags = ${native_base.build_flags} -Os -ffunction-sections -fdata-sections
-D USE_FRAMEBUFFER=1
-D LV_COLOR_DEPTH=32
-D HAS_TFT=1
-D HAS_SCREEN=0
-D HAS_SCREEN=1
-D LV_BUILD_TEST=0
-D LV_USE_LOG=0
-D LV_USE_EVDEV=1
@@ -72,7 +72,6 @@ build_flags = ${native_base.build_flags} -Os -ffunction-sections -fdata-sections
!pkg-config --libs openssl --silence-errors || :
build_src_filter =
${native_base.build_src_filter}
-<graphics/TFTDisplay.cpp>
[env:native-tft-debug]
extends = native_base

View File

@@ -36,17 +36,9 @@ upload_speed = 460800
build_flags =
${env:seeed-sensecap-indicator.build_flags}
-D MESHTASTIC_EXCLUDE_CANNEDMESSAGES=1
-D MESHTASTIC_EXCLUDE_INPUTBROKER=1
-D MESHTASTIC_EXCLUDE_SCREEN=1
-D MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR=1
-D MESHTASTIC_EXCLUDE_WEBSERVER=1
-D MESHTASTIC_EXCLUDE_SERIAL=1
-D MESHTASTIC_EXCLUDE_SOCKETAPI=1
-D INPUTDRIVER_BUTTON_TYPE=38
-D HAS_TELEMETRY=0
-D CONFIG_DISABLE_HAL_LOCKS=1
-D HAS_SCREEN=0
-D HAS_SCREEN=1
-D HAS_TFT=1
-D DISPLAY_SET_RESOLUTION
-D RAM_SIZE=4096

View File

@@ -25,11 +25,6 @@ extends = env:t-deck
build_flags =
${env:t-deck.build_flags}
-D CONFIG_DISABLE_HAL_LOCKS=1 ; "feels" to be a bit more stable without locks
-D MESHTASTIC_EXCLUDE_CANNEDMESSAGES=1
-D MESHTASTIC_EXCLUDE_INPUTBROKER=1
-D MESHTASTIC_EXCLUDE_WEBSERVER=1
-D MESHTASTIC_EXCLUDE_SERIAL=1
-D MESHTASTIC_EXCLUDE_SOCKETAPI=1
-D INPUTDRIVER_I2C_KBD_TYPE=0x55
-D INPUTDRIVER_ENCODER_TYPE=3
-D INPUTDRIVER_ENCODER_LEFT=1
@@ -39,7 +34,7 @@ build_flags =
-D INPUTDRIVER_ENCODER_BTN=0
-D INPUTDRIVER_BUTTON_TYPE=0
-D HAS_SDCARD
-D HAS_SCREEN=0
-D HAS_SCREEN=1
-D HAS_TFT=1
-D USE_I2S_BUZZER
-D RAM_SIZE=5120

View File

@@ -1,6 +1,5 @@
#define TFT_CS 12
#ifndef HAS_TFT // for TFT-UI the definitions are in device-ui
#define BUTTON_PIN 0
// ST7789 TFT LCD
@@ -24,7 +23,6 @@
#define SCREEN_ROTATE
#define SCREEN_TRANSITION_FRAMERATE 5
#define BRIGHTNESS_DEFAULT 130 // Medium Low Brightness
#endif
#define HAS_TOUCHSCREEN 1
#define SCREEN_TOUCH_INT 16
@@ -34,10 +32,9 @@
#define USE_POWERSAVE
#define SLEEP_TIME 120
#ifndef HAS_TFT
#define BUTTON_PIN 0
// #define BUTTON_NEED_PULLUP
#endif
#define GPS_DEFAULT_NOT_PRESENT 1
#define GPS_RX_PIN 44
#define GPS_TX_PIN 43

View File

@@ -36,13 +36,8 @@ extends = env:unphone
build_flags =
${env:unphone.build_flags}
-D CONFIG_DISABLE_HAL_LOCKS=1
-D MESHTASTIC_EXCLUDE_CANNEDMESSAGES=1
-D MESHTASTIC_EXCLUDE_INPUTBROKER=1
-D MESHTASTIC_EXCLUDE_WEBSERVER=1
-D MESHTASTIC_EXCLUDE_SERIAL=1
-D MESHTASTIC_EXCLUDE_SOCKETAPI=1
-D INPUTDRIVER_BUTTON_TYPE=21
-D HAS_SCREEN=0
-D HAS_SCREEN=1
-D HAS_TFT=1
-D HAS_SDCARD
-D DISPLAY_SET_RESOLUTION