-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathTEF-Nextion-Multiband.ino
2085 lines (1938 loc) · 59.8 KB
/
TEF-Nextion-Multiband.ino
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#include "soc/soc.h"
#include "soc/rtc_cntl_reg.h"
#include <Wire.h> // Included in Boardmanager
#include <WiFiClient.h> // Included in Boardmanager
#include <EEPROM.h> // Included in Boardmanager
#include <SoftwareSerial.h> // https://github.com/plerup/espsoftwareserial/
#include <EasyNextionLibrary.h> // https://github.com/Seithan/EasyNextionLibrary
#include <Hash.h> // https://github.com/bbx10/Hash_tng
#include <TimeLib.h> // https://github.com/PaulStoffregen/Time
#include "src/constants.h"
#include "src/TEF6686.h"
#include "src/ADF4351.h"
#include "src/WiFiConnect.h"
#include "src/gui.h"
#include "src/comms.h"
#include "src/scanner.h"
#include "src/touch.h"
WiFiConnect wc;
WiFiServer Server(7373);
WiFiUDP Udp;
WiFiClient RemoteClient;
EasyNex Display(Serial2);
TEF6686 radio;
ADF4351 Frontend;
EspSoftwareSerial::UART swSer;
ESP32Time rtc(0);
bool af2show;
bool btconnect;
bool btsetup;
bool BWreset = true;
bool cnvis;
bool ctshow;
bool direction;
bool displayreset;
bool donesearch;
bool dropout;
bool EONold;
bool fullsearchrds;
bool hasCTold;
bool manfreq;
bool memorystore;
bool menu;
bool mlogo_off;
bool mlogo_on;
bool MS;
bool mutelogo_off;
bool mutelogo_on;
bool mutestatus = true;
bool optrot;
bool power;
bool RDSSpy;
bool RDSstatus;
bool RDSstatusold;
bool rotarymode;
bool rtcset;
bool RTPlus;
bool scanfound;
bool seek;
bool setoffset;
bool showrdserrors;
bool showrdsinfo;
bool slogo_off;
bool slogo_on;
bool spec;
bool SQ;
bool Stereostatus;
bool Stereostatusold;
bool StereoToggle = true;
bool store;
bool TA;
bool TAold;
bool TP;
bool TPold;
bool tunereset;
bool UHF;
bool usblogo_off;
bool usblogo_on;
bool USBstatus;
bool wificonnect;
bool wifiretry;
bool XDRGTK;
bool XDRGTKdata;
bool XDRGTKTCP;
bool XDRMute;
byte af_counterold;
byte af_scan;
byte am;
byte band;
byte btselect;
byte BWset;
byte BWsetAM = 2;
byte BWsetOld = 254;
byte change;
byte coaxmode;
byte CoaxSwitch;
byte ContrastSet;
byte demp;
byte displaysize;
byte ECCold;
byte EQset;
byte fm;
byte fmsi;
byte IF;
byte iMSEQ;
byte iMSset;
byte ip1;
byte ip2;
byte ip3;
byte ip4;
byte lf;
byte memory_pos;
byte MSold;
byte OStatusold;
byte scanner_band;
byte scanner_speed;
byte scanner_th;
byte scanner_thenable;
byte scanstatus;
byte scopeview;
byte softmuteam;
byte softmutefm;
byte stationlist;
byte stepsize;
byte TEF;
byte tunemode;
byte uhf1;
byte uhf2;
byte uhf3;
byte uhf4;
byte uhf6;
byte usbmode;
byte wifienable;
byte wifienableold;
char buff[16];
char musicArtistPrevious[48];
char musicTitlePrevious[48];
char programTypePrevious[18];
char radioIdPrevious[5];
char stationEventPrevious[48];
char stationHostPrevious[48];
int AM_att;
int AM_Cochannel;
int AM_NBLevel;
int BlendLevel;
int BlendOffset;
int displayversion;
int HighCutLevel;
int HighCutOffset;
int HighEdgeSet0;
int HighEdgeSet1;
int HighEdgeSet2;
int HighEdgeSet3;
int HighEdgeSet4;
int HighEdgeSet6;
int LevelOffset0;
int LevelOffset1;
int LevelOffset2;
int LevelOffset3;
int LevelOffset4;
int LevelOffset6;
int LowEdgeSet0;
int LowEdgeSet1;
int LowEdgeSet2;
int LowEdgeSet3;
int LowEdgeSet4;
int LowEdgeSet6;
int NBLevel;
int offset;
int rotary;
int scanner_filter;
int Squelch;
int Squelchold;
int SStatusold;
int StereoLevel;
int timeoffset;
int VolSet;
int XDRBWset;
int XDRBWsetold;
int XDRscanner_filter;
int16_t OStatus;
int16_t SAvg;
int16_t SAvg2;
int16_t SAvg3;
int16_t SStatus;
int8_t CN;
int8_t CNold;
IPAddress remoteip;
long rssi;
long rssiold = 1;
String af;
String af2;
String clockPrevious;
String cryptedpassword;
String datePrevious;
String eonstringold;
String MAC[10];
String NAME[10];
String packet;
String password = "12345";
String PIcode;
String PIold;
String programServicePrevious;
String PSold;
String radioTextPrevious;
String rds_clock = "--:--";
String rds_clockold;
String rds_date = "----------";
String RDSSPYRDSold;
String RTContent1old;
String RTContent2old;
String RTold;
String salt;
String saltkey = " ";
String showsoftwareversion;
String XDRGTKRDSold;
uint16_t BW;
uint16_t highcut;
uint16_t minutesold;
uint16_t MStatus;
uint16_t stereo;
uint16_t sthiblend;
uint16_t USN;
uint16_t WAM;
uint8_t af_counter;
uint8_t buff_pos = 0;
uint8_t RDSerrorsold;
uint8_t stband_1;
uint8_t stband_2;
uint8_t stband_3;
uint8_t stband_4;
unsigned int BWOld;
unsigned int converteroffset;
unsigned int fmsi_11;
unsigned int fmsi_12;
unsigned int fmsi_21;
unsigned int fmsi_22;
unsigned int fmsi_31;
unsigned int fmsi_32;
unsigned int fmsi_41;
unsigned int fmsi_42;
unsigned int fmsi_attack;
unsigned int fmsi_release;
unsigned int freq;
unsigned int freq_scan;
unsigned int freqtemp;
unsigned int frequency0;
unsigned int frequency0old;
unsigned int frequency1;
unsigned int frequency1old;
unsigned int frequency2;
unsigned int frequency2old;
unsigned int frequency3;
unsigned int frequency3old;
unsigned int frequency4;
unsigned int frequency4old;
unsigned int frequency5;
unsigned int frequency5old;
unsigned int frequency6;
unsigned int frequency6old;
unsigned int memory[30];
unsigned int scanner_end;
unsigned int scanner_found;
unsigned int scanner_start;
unsigned int scanner_vbw;
unsigned int XDRfreq_scan;
unsigned int XDRscanner_end;
unsigned int XDRscanner_old;
unsigned int XDRscanner_start;
unsigned int XDRscanner_step;
unsigned long BWTimer;
unsigned long CNTimer;
unsigned long showmillis;
unsigned long signalstatustimer;
unsigned long stlmillis;
unsigned long time_now;
unsigned long XDRshowmillis;
unsigned long tuneresetcounter;
void setup(void) {
WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0);
gpio_set_drive_capability((gpio_num_t) 21, GPIO_DRIVE_CAP_0);
gpio_set_drive_capability((gpio_num_t) 22, GPIO_DRIVE_CAP_0);
swSer.begin(9600, EspSoftwareSerial::SWSERIAL_8N1, 13, 14, false, 95);
btStop();
Display.begin(38400);
delay(500);
pinMode(SMETERPIN, OUTPUT);
pinMode(MODEBUTTON, INPUT);
pinMode(BAND, INPUT_PULLUP);
pinMode(BWBUTTON, INPUT);
pinMode(ROTARY_BUTTON, INPUT);
pinMode(ROTARY_PIN_A, INPUT);
pinMode(ROTARY_PIN_B, INPUT);
pinMode(RFA, OUTPUT);
pinMode(RFB, OUTPUT);
pinMode(RFC, OUTPUT);
attachInterrupt(digitalPinToInterrupt(ROTARY_PIN_A), read_encoder, CHANGE);
attachInterrupt(digitalPinToInterrupt(ROTARY_PIN_B), read_encoder, CHANGE);
analogWrite(SMETERPIN, 0);
Display.writeNum("sleep", 0);
delay(500);
EEPROM.begin(EE_TOTAL);
if (EEPROM.readByte(EE_UINT8T_VERSIONCHECK) != EE_VERSIONCOUNTER) FactoryDefaults();
if (digitalRead(ROTARY_BUTTON) == LOW && digitalRead(MODEBUTTON) == HIGH && digitalRead(BWBUTTON) == HIGH) {
optrot = EEPROM.readByte(EE_UINT8T_OPTROT);
if (optrot) {
optrot = false;
Display.writeStr("version2.txt", "standard encoder");
} else {
optrot = true;
Display.writeStr("version2.txt", "optical encoder");
}
EEPROM.writeByte(EE_UINT8T_OPTROT, optrot);
EEPROM.commit();
Display.writeStr("version.txt", "Changed to: ");
delay(2000);
Display.writeStr("version.txt", "Please release");
Display.writeStr("version2.txt", "the button!");
while (digitalRead(ROTARY_BUTTON) == LOW) delay(10);
}
if (digitalRead(MODEBUTTON) == LOW && digitalRead(ROTARY_BUTTON) == HIGH && digitalRead(BWBUTTON) == HIGH) {
CoaxSwitch = EEPROM.readByte(EE_UINT8T_COAXSWITCH);
if (CoaxSwitch == 1) CoaxSwitch = 0; else CoaxSwitch = 1;
EEPROM.writeByte(EE_UINT8T_COAXSWITCH, CoaxSwitch);
EEPROM.commit();
Display.writeStr("version.txt", "Coax switch");
Display.writeStr("version2.txt", "changed!");
delay(2000);
Display.writeStr("version.txt", "Please release");
Display.writeStr("version2.txt", "the button!");
while (digitalRead(MODEBUTTON) == LOW) delay(10);
}
if (digitalRead(BWBUTTON) == LOW && digitalRead(ROTARY_BUTTON) == HIGH && digitalRead(MODEBUTTON) == HIGH) {
rotarymode = EEPROM.readByte(EE_UINT8T_ROTARYMODE);
if (!rotarymode) rotarymode = true; else rotarymode = false;
EEPROM.writeByte(EE_UINT8T_ROTARYMODE, rotarymode);
EEPROM.commit();
Display.writeStr("version.txt", "Rotary direc-");
Display.writeStr("version2.txt", "tion changed");
delay(2000);
Display.writeStr("version.txt", "Please release");
Display.writeStr("version2.txt", "the button!");
while (digitalRead(BWBUTTON) == LOW) delay(10);
}
if (digitalRead(BWBUTTON) == LOW && digitalRead(ROTARY_BUTTON) == LOW && digitalRead(MODEBUTTON) == HIGH) {
FactoryDefaults();
Display.writeStr("version.txt", "Tuner back to");
Display.writeStr("version2.txt", "default values");
delay(2000);
Display.writeStr("version.txt", "Please release");
Display.writeStr("version2.txt", "the buttons!");
while (digitalRead(BWBUTTON) == LOW && digitalRead(ROTARY_BUTTON) == LOW) delay(10);
}
if (digitalRead(BWBUTTON) == HIGH && digitalRead(ROTARY_BUTTON) == LOW && digitalRead(MODEBUTTON) == LOW) {
Display.writeStr("version.txt", "Calibrate s-meter");
Display.writeStr("version2.txt", "");
delay(2000);
Display.writeStr("version.txt", "Release buttons");
Display.writeStr("version2.txt", "when ready!");
while (digitalRead(MODEBUTTON) == LOW && digitalRead(ROTARY_BUTTON) == LOW) delay(10);
}
String displayversionext;
String softwareversionext;
displayversion = Display.readNumber("versie");
if (displayversion % 10 < 10 && displayversion % 10 > 0) {
displayversionext = ".0" + String (displayversion % 10);
} else if (displayversion % 10 == 0) {
displayversionext = ".00";
} else {
displayversionext = "." + String (displayversion % 10);
}
if (SOFTWAREVER % 10 < 10 && SOFTWAREVER % 10 > 0) {
softwareversionext = ".0" + String (SOFTWAREVER % 10);
} else if (SOFTWAREVER % 10 == 0) {
softwareversionext = ".00";
} else {
softwareversionext = "." + String (SOFTWAREVER % 10);
}
showsoftwareversion = String ("v" + String (SOFTWAREVER / 100) + String(softwareversionext));
if (BETA > 0) showsoftwareversion += String(" beta ");
if (BETA > 1) showsoftwareversion += String(BETA);
String showdisplayversion = String ("Display v" + String (displayversion / 100) + String(displayversionext));
Display.writeStr("page 0");
Display.writeStr("version.txt", "Version " + String(showsoftwareversion));
Display.writeStr("version2.txt", showdisplayversion);
if (displayversion < DISPLAYVER) {
Display.writeStr("page 0");
Display.writeStr("version.txt", "Incompatible display version");
Display.writeStr("version2.txt", "Update display to v" + String (DISPLAYVER / 100) + ".0" + String (DISPLAYVER % 10) + "!");
for (;;);
}
TEF = EEPROM.readByte(EE_UINT8T_TEF);
if (TEF != 101 && TEF != 102 && TEF != 205) SetTunerPatch();
Frontend.Init(5, 25000000);
radio.init(TEF);
uint16_t device;
uint16_t hw;
uint16_t sw;
radio.getIdentification(device, hw, sw);
if (TEF != (highByte(hw) * 100 + highByte(sw))) SetTunerPatch();
radio.power(0);
radio.setMute();
radio.getStatus(SStatus, USN, WAM, OStatus, BW, MStatus, CN);
if (lowByte(device) != 0) {
Display.writeNum("TEF.pco", NEXTION_COLOR_GREEN);
if (lowByte(device) == 14) {
Display.writeStr("TEF.txt", "TEF6686 detected!");
} else if (lowByte(device) == 1) {
Display.writeStr("TEF.txt", "TEF6687 detected!");
Display.writeNum("fmsienable", 1);
fullsearchrds = true;
} else if (lowByte(device) == 9) {
Display.writeStr("TEF.txt", "TEF6688 detected!");
} else if (lowByte(device) == 3) {
Display.writeStr("TEF.txt", "TEF6689 detected!");
Display.writeNum("fmsienable", 1);
fullsearchrds = true;
}
} else {
Display.writeNum("TEF.pco", NEXTION_COLOR_RED);
Display.writeStr("TEF.txt", "Tuner NOT detected!");
}
if (digitalRead(BAND) == LOW) {
Display.writeNum("UHF.pco", NEXTION_COLOR_GREEN);
Display.writeStr("UHF.txt", "UHF Board detected!");
Display.writeNum("uhf", 1);
UHF = true;
} else {
Display.writeNum("UHF.pco", NEXTION_COLOR_RED);
Display.writeStr("UHF.txt", "UHF Board NOT detected!");
UHF = false;
}
swSer.print("AT+STATUS");
delay(100);
if (swSer.available()) {
Display.writeNum("BT.pco", NEXTION_COLOR_GREEN);
Display.writeStr("BT.txt", "Bluetooth detected!");
Display.writeNum("btenable", 1);
}
Frontend.SetFreq(100000, offset);
delay(400);
EEpromReadData();
if (usbmode == 1) Serial.begin(19200); else Serial.begin(115200);
Display.writeNum("smeterold", 0);
if (iMSset == 1 && EQset == 1) iMSEQ = 2;
if (iMSset == 0 && EQset == 1) iMSEQ = 3;
if (iMSset == 1 && EQset == 0) iMSEQ = 4;
if (iMSset == 0 && EQset == 0) iMSEQ = 1;
if (wifienable == 2) tryWiFi(); else WiFi.mode(WIFI_OFF);
radio.setVolume(VolSet);
radio.setMute();
radio.setStereoLevel(StereoLevel);
radio.setHighCutLevel(HighCutLevel);
radio.setHighCutOffset(HighCutOffset);
radio.setStHiBlendLevel(BlendLevel);
radio.setStHiBlendOffset(BlendOffset);
radio.setDeemphasis(demp);
radio.setAudio(lf);
radio.setFMNoiseBlanker(NBLevel);
radio.setAMCoChannel(AM_Cochannel);
radio.setAMNoiseBlanker(AM_NBLevel);
radio.setAMAttenuation(AM_att);
radio.setFMSI(fmsi);
radio.setFMSI_Time(fmsi_attack, fmsi_release);
radio.setFMSI_Gain(fmsi_11, fmsi_21, fmsi_31, fmsi_41);
radio.setFMSI_Bias(fmsi_12, fmsi_22, fmsi_32, fmsi_42);
radio.rds.rtbuffer = true;
radio.underscore = false;
radio.rds.filter = false;
radio.rds.pierrors = true;
radio.rds.sortaf = true;
radio.rds.fastps = true;
Display.writeStr("page 1");
switch (band) {
case 0: RF(0); break;
case 1: RF(1); break;
case 2: RF(2); break;
case 3: RF(3); break;
case 4: RF(4); break;
case 5: RF(5); break;
case 6: RF(6); break;
}
ShowFreq();
ShowStepSize();
ShowiMS();
ShowEQ();
ShowTuneMode();
}
void loop(void) {
Display.NextionListen();
Communication();
if (setoffset) {
radio.getStatus(SStatus, USN, WAM, OStatus, BW, MStatus, CN);
Display.writeNum("offsetvalue.val", OStatus);
ShowOffset();
} else {
if (seek) Seek(direction);
if (spec) scan_loop();
if (menu) {
radio.getProcessing(highcut, stereo, sthiblend, stband_1, stband_2, stband_3, stband_4);
Display.writeNum("highcut", highcut);
Display.writeNum("stereol", stereo);
Display.writeNum("sthiblend", sthiblend);
Display.writeNum("stband_1", stband_1);
Display.writeNum("stband_2", stband_2);
Display.writeNum("stband_3", stband_3);
Display.writeNum("stband_4", stband_4);
}
if (!menu && !manfreq && !spec) {
if (band == 5) radio.getStatusAM(SStatus, USN, WAM, OStatus, BW, MStatus, CN); else radio.getStatus(SStatus, USN, WAM, OStatus, BW, MStatus, CN);
readRds();
if (XDRGTKTCP || XDRGTK) {
if (millis() > XDRshowmillis + 70) {
if (WAM > 150 && millis() > showmillis + 250) {
ShowBW();
ShowStereoStatus();
if (band != 5) {
if (RDSstatus) Display.writeNum("rdslogo.pic", NEXTION_RDSLOGO); else Display.writeNum("rdslogo.pic", NEXTION_RDSLOGO_GREYOUT);
}
ShowOffset();
showmillis = millis();
}
if (WAM <= 150) {
ShowBW();
ShowStereoStatus();
if (band != 5) {
if (RDSstatus) Display.writeNum("rdslogo.pic", NEXTION_RDSLOGO); else Display.writeNum("rdslogo.pic", NEXTION_RDSLOGO_GREYOUT);
}
ShowOffset();
}
ShowSignalLevel();
ShowModLevel();
ShowUSBstatus();
ShowRSSI();
doSquelch();
XDRshowmillis = millis();
}
} else {
if (WAM > 150 && millis() > showmillis + 250) {
ShowBW();
ShowStereoStatus();
if (band != 5) {
if (RDSstatus) Display.writeNum("rdslogo.pic", NEXTION_RDSLOGO); else Display.writeNum("rdslogo.pic", NEXTION_RDSLOGO_GREYOUT);
}
ShowOffset();
showmillis = millis();
}
if (WAM <= 150) {
ShowBW();
ShowStereoStatus();
if (band != 5) {
if (RDSstatus) Display.writeNum("rdslogo.pic", NEXTION_RDSLOGO); else Display.writeNum("rdslogo.pic", NEXTION_RDSLOGO_GREYOUT);
}
ShowOffset();
}
ShowSignalLevel();
ShowModLevel();
ShowUSBstatus();
ShowRSSI();
doSquelch();
}
doEEpromWrite();
displayreset = false;
if (rotary == -1) KeyUp();
if (rotary == 1) KeyDown();
if (digitalRead(ROTARY_BUTTON) == LOW) ButtonPress();
if (digitalRead(MODEBUTTON) == LOW) ModeButtonPress();
if (digitalRead(BWBUTTON) == LOW) BWButtonPress();
if (digitalRead(BAND) == LOW) BandSet();
}
}
}
void BandSet(void) {
unsigned long counterold = millis();
unsigned long counter = millis();
while (digitalRead(BAND) == LOW && counter - counterold <= 1000) counter = millis();
if (counter - counterold < 1000 || power) {
if (power) {
Display.writeNum("sleep", 0);
Display.writeStr("page 0");
ESP.restart();
}
seek = false;
tunemode = 0;
ShowTuneMode();
if (UHF) {
band ++;
if (band > 5) band = 0;
switch (band) {
case 0: RF(0); break;
case 1: RF(1); break;
case 2: RF(2); break;
case 3: RF(3); break;
case 4: RF(4); break;
case 5: RF(5); break;
}
} else {
band ++;
if (band > 6) band = 0;
if (band == 1) band = 5;
if (band == 0) RF(0);
if (band == 5) RF(5);
if (band == 6) RF(6);
}
EEPROM.writeByte(EE_UINT8T_BAND, band);
EEPROM.commit();
ShowFreq();
} else if (!XDRGTK && !XDRGTKTCP) {
power = true;
Display.writeNum("sleep", 1);
Frontend.Power(0);
radio.power(1);
analogWrite(SMETERPIN, 0);
if (wifienable == 1) {
Server.end();
Udp.stop();
WiFi.mode(WIFI_OFF);
}
}
while (digitalRead(BAND) == LOW) delay(10);
}
void RF(byte RFset) {
if (!spec && !manfreq) {
Display.writeNum("outlimit.en", 0);
Display.writeStr("vis outoflimit,0");
}
if (RFset == 0 && fm == 0) {
band ++;
RFset ++;
}
if (RFset == 1 && uhf1 == 0) {
band ++;
RFset ++;
}
if (RFset == 2 && uhf2 == 0) {
band ++;
RFset ++;
}
if (RFset == 3 && uhf3 == 0) {
band ++;
RFset ++;
}
if (RFset == 4 && uhf4 == 0) {
band ++;
RFset ++;
}
if (RFset == 5 && am == 0) {
if (UHF) {
band = 0;
RFset = 0;
} else {
band ++;
RFset ++;
}
}
if (RFset == 6 && uhf6 == 0) {
band = 0;
RFset = 0;
}
if (RFset == 5) {
if (showrdsinfo && !manfreq) {
Display.writeStr("page 1");
showrdsinfo = false;
}
if (!manfreq) {
Display.writeStr("vis m0,0");
}
if (!showrdsinfo && !scopeview && !manfreq) {
Display.writeStr("vis U_disp,0");
Display.writeStr("vis W_disp,0");
Display.writeNum("tm4.en", 0);
Display.writeStr("vis m1,0");
Display.writeStr("vis signalform,1");
Display.writeStr("vis modpos,1");
Display.writeNum("scopeview", 1);
}
if (!manfreq) {
if (!showrdsinfo) {
Display.writeNum("autobwlogo.pic", NEXTION_AUTOBWLOGO_GREYOUT);
Display.writeNum("imslogo.pic", NEXTION_IMSLOGO_GREYOUT);
Display.writeNum("eqlogo.pic", NEXTION_EQLOGO_GREYOUT);
}
Display.writeNum("BW.pco", NEXTION_COLOR_YELLOW);
Display.writeNum("stereo.pic", NEXTION_STEREOLOGO_GREYOUT);
Display.writeNum("ber.pic", NEXTION_RDSBAR_0);
Display.writeNum("t4.pco", NEXTION_COLOR_GREY);
Display.writeNum("t5.pco", NEXTION_COLOR_GREY);
Display.writeNum("t6.pco", NEXTION_COLOR_GREY);
Display.writeNum("t7.pco", NEXTION_COLOR_GREY);
String count = String(frequency5, DEC);
if (count.length() > 3) {
Display.writeNum("freq.vvs1", 3);
if (!showrdsinfo) Display.writeStr("t2.txt", "MHz");
} else {
Display.writeNum("freq.vvs1", 0);
if (!showrdsinfo) Display.writeStr("t2.txt", "kHz");
}
}
} else {
if (!spec && !manfreq) {
ShowiMS();
ShowEQ();
Display.writeStr("vis m0,1");
if (!showrdsinfo) {
if (!scopeview) {
Display.writeStr("vis U_disp,1");
Display.writeStr("vis W_disp,1");
Display.writeNum("tm4.en", 1);
Display.writeStr("vis m1,1");
Display.writeStr("vis signalform,0");
Display.writeStr("vis modpos,0");
Display.writeNum("scopeview", 0);
}
Display.writeStr("t2.txt", "MHz");
}
Display.writeNum("freq.vvs1", 2);
Display.writeNum("t4.pco", NEXTION_COLOR_WHITE);
Display.writeNum("t5.pco", NEXTION_COLOR_WHITE);
Display.writeNum("t6.pco", NEXTION_COLOR_WHITE);
Display.writeNum("t7.pco", NEXTION_COLOR_WHITE);
ShowBW();
}
}
switch (RFset) {
case 0:
if (CoaxSwitch == 1) digitalWrite(RFC, LOW); else digitalWrite(RFC, HIGH);
digitalWrite(RFA, HIGH);
digitalWrite(RFB, HIGH);
radio.power(0);
delay(50);
radio.SetFreq(frequency0);
if (!displayreset) radio.clearRDS(fullsearchrds);
radio.setOffset(LevelOffset0);
Frontend.Power(0);
if (!spec && !manfreq) {
Display.writeNum("offsettouch", 0);
}
break;
case 1:
if (CoaxSwitch == 1) digitalWrite(RFC, HIGH); else digitalWrite(RFC, LOW);
digitalWrite(RFA, LOW);
digitalWrite(RFB, LOW);
radio.power(0);
delay(50);
radio.SetFreq(IF * 100);
if (!displayreset) radio.clearRDS(fullsearchrds);
radio.setOffset(LevelOffset1 - 7);
Frontend.Power(1);
Frontend.SetFreq(frequency1 - (IF * 100), offset);
Display.writeNum("offsettouch", 1);
break;
case 2:
if (CoaxSwitch == 1) digitalWrite(RFC, HIGH); else digitalWrite(RFC, LOW);
digitalWrite(RFA, HIGH);
digitalWrite(RFB, LOW);
radio.power(0);
delay(50);
radio.SetFreq(IF * 100);
if (!displayreset) radio.clearRDS(fullsearchrds);
radio.setOffset(LevelOffset2 - 4);
Frontend.SetFreq(frequency2 - (IF * 100), offset);
Display.writeNum("offsettouch", 1);
break;
case 3:
if (CoaxSwitch == 1) digitalWrite(RFC, HIGH); else digitalWrite(RFC, LOW);
digitalWrite(RFA, LOW);
digitalWrite(RFB, HIGH);
radio.power(0);
delay(50);
radio.SetFreq(IF * 100);
if (!displayreset) radio.clearRDS(fullsearchrds);
radio.setOffset(LevelOffset3);
Frontend.SetFreq(frequency3 - (IF * 100), offset);
Display.writeNum("offsettouch", 1);
break;
case 4:
if (CoaxSwitch == 1) digitalWrite(RFC, HIGH); else digitalWrite(RFC, LOW);
digitalWrite(RFA, HIGH);
digitalWrite(RFB, HIGH);
radio.power(0);
delay(50);
radio.SetFreq(IF * 100);
if (!displayreset) radio.clearRDS(fullsearchrds);
radio.setOffset(LevelOffset4 + 2);
Frontend.SetFreq(frequency4 - (IF * 100), offset);
Display.writeNum("offsettouch", 1);
break;
case 5:
if (CoaxSwitch == 1) {
if (coaxmode && !UHF) digitalWrite(RFC, HIGH); else digitalWrite(RFC, LOW);
} else {
if (coaxmode && !UHF) digitalWrite(RFC, LOW); else digitalWrite(RFC, HIGH);
}
digitalWrite(RFA, HIGH);
digitalWrite(RFB, HIGH);
if (!displayreset) radio.clearRDS(fullsearchrds);
radio.SetFreqAM(frequency5);
Frontend.Power(0);
Display.writeNum("offsettouch", 0);
break;
case 6:
if (CoaxSwitch == 1) {
if (!coaxmode) digitalWrite(RFC, HIGH); else digitalWrite(RFC, LOW);
} else {
if (!coaxmode) digitalWrite(RFC, LOW); else digitalWrite(RFC, HIGH);
}
digitalWrite(RFA, HIGH);
digitalWrite(RFB, HIGH);
radio.power(0);
delay(50);
radio.SetFreq(frequency6 - converteroffset * 100);
radio.setOffset(LevelOffset6);
Display.writeNum("offsettouch", 0);
Wire.beginTransmission(0x12);
Wire.write(converteroffset >> 8);
Wire.write(converteroffset & (0xFF));
Wire.endTransmission();
if (!displayreset) radio.clearRDS(fullsearchrds);
break;
}
OStatusold = 0;
BWreset = true;
if (band == 5) radio.setSoftmuteAM(softmuteam); else radio.setSoftmuteFM(softmutefm);
}
void readRds(void) {
if (band == 5) RDSstatus = false; else radio.readRDS(showrdserrors ? 3 : 1);
RDSstatus = radio.rds.hasRDS;
ShowRDS();
if (RDSSpy && RDSstatus && band != 5) {
String RDSSPYRDS;
RDSSPYRDS = "G:\r\n";
if (radio.rds.rdsAerror) RDSSPYRDS += "----"; else RDSSPYRDS += String(((radio.rds.rdsA >> 8) >> 4) & 0xF, HEX) + String((radio.rds.rdsA >> 8) & 0xF, HEX) + String(((radio.rds.rdsA) >> 4) & 0xF, HEX) + String((radio.rds.rdsA) & 0xF, HEX);
if (radio.rds.rdsBerror) RDSSPYRDS += "----"; else RDSSPYRDS += String(((radio.rds.rdsB >> 8) >> 4) & 0xF, HEX) + String((radio.rds.rdsB >> 8) & 0xF, HEX) + String(((radio.rds.rdsB) >> 4) & 0xF, HEX) + String((radio.rds.rdsB) & 0xF, HEX);
if (radio.rds.rdsCerror) RDSSPYRDS += "----"; else RDSSPYRDS += String(((radio.rds.rdsC >> 8) >> 4) & 0xF, HEX) + String((radio.rds.rdsC >> 8) & 0xF, HEX) + String(((radio.rds.rdsC) >> 4) & 0xF, HEX) + String((radio.rds.rdsC) & 0xF, HEX);
if (radio.rds.rdsDerror) RDSSPYRDS += "----"; else RDSSPYRDS += String(((radio.rds.rdsD >> 8) >> 4) & 0xF, HEX) + String((radio.rds.rdsD >> 8) & 0xF, HEX) + String(((radio.rds.rdsD) >> 4) & 0xF, HEX) + String((radio.rds.rdsD) & 0xF, HEX);
RDSSPYRDS += "\r\n\r\n";
if (RDSSPYRDS != RDSSPYRDSold) {
RDSSPYRDSold = RDSSPYRDS;
if (wificonnect) RemoteClient.print(RDSSPYRDS); else Serial.print(RDSSPYRDS);
}
}
if ((XDRGTKTCP || XDRGTK) && RDSstatus && band != 5) {
String XDRGTKRDS;
XDRGTKRDS = "R";
XDRGTKRDS += String(((radio.rds.rdsB >> 8) >> 4) & 0xF, HEX) + String((radio.rds.rdsB >> 8) & 0xF, HEX);
XDRGTKRDS += String(((radio.rds.rdsB) >> 4) & 0xF, HEX) + String((radio.rds.rdsB) & 0xF, HEX);
XDRGTKRDS += String(((radio.rds.rdsC >> 8) >> 4) & 0xF, HEX) + String((radio.rds.rdsC >> 8) & 0xF, HEX);
XDRGTKRDS += String(((radio.rds.rdsC) >> 4) & 0xF, HEX) + String((radio.rds.rdsC) & 0xF, HEX);
XDRGTKRDS += String(((radio.rds.rdsD >> 8) >> 4) & 0xF, HEX) + String((radio.rds.rdsD >> 8) & 0xF, HEX);
XDRGTKRDS += String(((radio.rds.rdsD) >> 4) & 0xF, HEX) + String((radio.rds.rdsD) & 0xF, HEX);
uint8_t erroutput = 0;
erroutput |= ((radio.rds.rdsErr >> 8) & B00110000) >> 4;
erroutput |= ((radio.rds.rdsErr >> 8) & B00001100);
erroutput |= ((radio.rds.rdsErr >> 8) & B00000011) << 4;
XDRGTKRDS += String((erroutput >> 4) & 0xF, HEX);
XDRGTKRDS += String(erroutput & 0xF, HEX);
XDRGTKRDS += "\n";
if (XDRGTKRDS != XDRGTKRDSold) {
uint8_t piError = radio.rds.rdsErr >> 14;
if (piError < 3) {
uint8_t piState = radio.rds.piBuffer.add(radio.rds.rdsA, piError);
if (piState != RdsPiBuffer::STATE_INVALID) {
if (XDRGTKTCP) RemoteClient.print("P");
if (XDRGTK) Serial.print("P");
String PIcodeToSend;
PIcodeToSend = String(((radio.rds.rdsA >> 8) >> 4) & 0xF, HEX) + String((radio.rds.rdsA >> 8) & 0xF, HEX) + String(((radio.rds.rdsA) >> 4) & 0xF, HEX) + String((radio.rds.rdsA) & 0xF, HEX);
PIcodeToSend.toUpperCase();
if (XDRGTKTCP) RemoteClient.print(PIcodeToSend);
if (XDRGTK) Serial.print(PIcodeToSend);
while (piState != 0) {
if (XDRGTKTCP) RemoteClient.print("?");
if (XDRGTK) Serial.print("?");
piState--;
}
if (XDRGTKTCP) RemoteClient.print("\n");
if (XDRGTK) Serial.print("\n");
}
}
XDRGTKRDSold = XDRGTKRDS;
XDRGTKRDS.toUpperCase();
if (XDRGTKTCP) RemoteClient.print(XDRGTKRDS);
if (XDRGTK) Serial.print(XDRGTKRDS);
}
}
}
void doStepSize(void) {
stepsize++;
if (stepsize > 4) stepsize = 0;
ShowStepSize();
EEPROM.writeByte(EE_UINT8T_STEPSIZE, stepsize);
EEPROM.commit();
if (stepsize == 0) {
RoundStep();
ShowFreq();
}
}
void doTuneMode(void) {
tunemode++;
if (tunemode > 2) tunemode = 0;
ShowTuneMode();
if (stepsize != 0) {
stepsize = 0;
RoundStep();
ShowStepSize();
ShowFreq();
}
}
void doFilter(void) {
switch (iMSEQ) {
case 0:
iMSset = 1;
EQset = 0;
ShowiMS();
ShowEQ();
iMSEQ = 1;
break;
case 1:
iMSset = 0;
EQset = 1;
ShowiMS();
ShowEQ();
iMSEQ = 2;
break;
case 2:
iMSset = 1;
EQset = 1;
ShowiMS();