forked from osakechan/notoriousPID
-
Notifications
You must be signed in to change notification settings - Fork 0
/
notoriousPID.ino
1252 lines (1171 loc) · 43.3 KB
/
notoriousPID.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
// Notorious PID Fermentation Temperature Control v 0.9
#include "Arduino.h"
#include <avr/wdt.h>
#include <LiquidCrystal.h>
#include <OneWire.h>
#include <Wire.h>
#include <RTClib.h>
#include <SD.h>
#include <SPI.h>
#include <OneWire.h>
#include <QueueList.h>
#include <EEPROM.h>
#include "PID_v1.h"
#include "probe.h"
#include "EEPROMio.h"
#include "fridge.h"
#include "globals.h"
#define DEBUG true // debug flag for including debugging code
void mainUpdate(); // update sensors, PID output, fridge state, write to log, run profiles
boolean updateProfile(); // update temperature profile
void writeLog(); // write new line to log file
void dateTime(uint16_t* date, uint16_t* time); // date/time callback function for SdFat to timestamp file creation/modification
void initDisplay(); // print static characters to LCD (lables, scrollbar, page names, etc)
void updateDisplay(); // print dynamic characters to LCD (PID/temp values, etc)
void menu(); // change PID and program settings
void mainPIDmode(); // mainPID manual/automatic
void mainPIDsp(); // mainPID setpoint
void heatPIDmode(); // heatPID manual/automatic
void dataLog(); // data logging
void tempProfile(); // temperature profiles
void tempUnit(); // temperature display units C/F
void avrReset(); // restore default settings and reset
void backOut(); // finalize changes and leave menu
void EEPROMReadSettings(); // read saved settings from EEPROM
void EEPROMWriteSettings(); // write current settings to EEPROM
void EEPROMWritePresets(); // write default settings to EEPROM
void encoderChanA(); // manage encoder pin A transitions
void encoderChanB(); // manage encoder pin B transitions
#if DEBUG == true
int freeRAM(); // approximate free SRAM for debugging
#endif
void setup() {
pinMode(chipSelect, OUTPUT); // select pin i/o and enable pullup resistors
pinMode(encoderPinA, INPUT_PULLUP);
pinMode(encoderPinB, INPUT_PULLUP);
pinMode(pushButton, INPUT_PULLUP);
pinMode(relay1, OUTPUT); // configure relay pins and write default HIGH (relay open)
digitalWrite(relay1, HIGH);
pinMode(relay2, OUTPUT);
digitalWrite(relay2, HIGH);
attachInterrupt(0, encoderChanA, CHANGE); // interrupt 0 (pin 2) triggered by change
attachInterrupt(1, encoderChanB, CHANGE); // interrupt 1 (pin 3) triggered by change
encoderPos = 0;
encoderState = 0b000;
encoderChanA(); // call interrupt routines once to init rotary encoder
encoderChanB();
#if DEBUG == true //start serial at 9600 baud for debuging
Serial.begin(9600);
#endif
Wire.begin(); // initialize rtc communication
RTC.begin(); // start real time clock
lcd.createChar(0, (uint8_t*)delta); // create custom characters for LCD (slots 0-7)
lcd.createChar(1, (uint8_t*)rightArrow);
lcd.createChar(2, (uint8_t*)disc);
lcd.createChar(3, (uint8_t*)circle);
lcd.createChar(4, (uint8_t*)dot);
lcd.createChar(5, (uint8_t*)inverted);
lcd.createChar(6, (uint8_t*)degc);
lcd.createChar(7, (uint8_t*)degf);
lcd.begin(20, 4); // initialize lcd display
if (SD.begin(chipSelect, mosi, miso, sck)) lcd.print(F("SDCard Init Success")); // verify and initialize SD card
else lcd.print(F("SDCard Failed/Absent"));
delay(1500);
SdFile::dateTimeCallback(&dateTime);
byte ver;
EEPROMRead(0, &ver, BYTE); // first byte of EEPROM stores a version # for tracking stored settings
#if DEBUG == true
Serial.print(F("Current EEPROM ver:"));
Serial.print(EEPROM_VER);
Serial.print(F(" value read from EEPROM:"));
Serial.println(ver);
#endif
if (ver != EEPROM_VER) { // EEPROM version number != hard coded version number
#if DEBUG == true
Serial.println(F("Outdated or null EEPROM settings. Writing Defaults."));
#endif
EEPROMWritePresets(); // if version # is outdated, write presets
}
EEPROMReadSettings(); // load program settings from EEPROM
#if DEBUG == true
Serial.println(F("Settings loaded from EEPROM:"));
#endif
fridge.init();
beer.init();
mainPID.SetTunings(Kp, Ki, Kd); // set tuning params
mainPID.SetSampleTime(1000); // (ms) matches sample rate (1 hz)
mainPID.SetOutputLimits(0.3, 38); // deg C (~32.5 - ~100 deg F)
if (programState & MAIN_PID_MODE) mainPID.SetMode(AUTOMATIC); // set man/auto
else mainPID.SetMode(MANUAL);
mainPID.setOutputType(FILTERED);
mainPID.setFilterConstant(10);
mainPID.initHistory();
heatPID.SetTunings(heatKp, heatKi, heatKd);
heatPID.SetSampleTime(heatWindow); // sampletime = time proportioning window length
heatPID.SetOutputLimits(0, heatWindow); // heatPID output = duty time per window
if (programState & HEAT_PID_MODE) heatPID.SetMode(AUTOMATIC);
else heatPID.SetMode(MANUAL);
heatPID.initHistory();
encoderPos = 0; // zero rotary encoder position for main loop
wdt_enable(WDTO_8S); // enable watchdog timer with 8 second timeout (max setting)
// wdt will reset the arduino if there is an infinite loop or other hangup; this is a failsafe device
#if DEBUG == true
Serial.print(F("init complete. "));
Serial.print(millis());
Serial.print(F("ms elapsed. "));
Serial.print(freeRAM());
Serial.println(F(" bytes free SRAM remaining"));
#endif
}
void loop() {
wdt_reset(); // reset the watchdog timer (once timer is set/reset, next reset pulse must be sent before timeout or arduino reset will occur)
static char listSize = 4; // for constraining rotary encoder position
static char lastReportedPos = 1; // default to 1 to force display initialze on first iteration
encoderState |= DEBOUNCE; // reset rotary debouncer
if (encoderPos != lastReportedPos) {
encoderPos = (encoderPos + listSize) % listSize; // constrain encoder position
initDisplay(); // re-init display on encoder position change
lastReportedPos = encoderPos;
}
updateDisplay(); // update display data
mainUpdate(); // subroutines manage their own timings, call every loop
if (!digitalRead(pushButton)) menu(); // call menu routine on rotary button-press
}
void mainUpdate() { // call all update subroutines
probe::startConv(); // start conversion for all sensors
if (probe::isReady()) { // update sensors when conversion complete
fridge.update();
beer.update();
Input = beer.getFilter();
}
if (programState & TEMP_PROFILE) updateProfile(); // update main Setpoint if fermentation profile active
mainPID.Compute(); // update main PID
updateFridge(); // update fridge status
if (programState & DATA_LOGGING) writeLog(); // if data capture enabled, run logging routine
}
boolean updateProfile() {
static unsigned int step = 0;
static unsigned long lastStep = 0; // last profile step (ms)
static profileStep Step; // current profile step
if ((millis() >= (unsigned long)(lastStep + Step.duration * 3600000UL)) && !profile.isEmpty()) {
step++; // increment step number
EEPROMWrite(52, step, INT); // write step number to EEPROM
Step = profile.pop(); // pop next step off the queue
Setpoint = Step.temp; // update Setpoint with new temp (deg C)
lastStep = millis();
return true;
}
return false;
}
void writeLog() {
static double LogHz = 1; // datalogging frequency (hz)
static unsigned long lastLog = 0; // millis() at last log
if (millis() >= (unsigned long)(lastLog + 1000/LogHz)) {
#if DEBUG == true
Serial.print(F("logging to file... "));
Serial.print((unsigned long)(millis() - lastLog));
Serial.print(F("ms elapsed. "));
Serial.print(lastLog);
Serial.print(F(" "));
Serial.print(freeRAM());
Serial.println(F(" bytes free SRAM remaining"));
#endif
lastLog = millis();
DateTime time = RTC.now();
LogFile.print(lastLog, DEC);
LogFile.print(F(","));
LogFile.print(time.year(), DEC);
LogFile.print(F("/"));
LogFile.print(time.month(), DEC);
LogFile.print(F("/"));
LogFile.print(time.day(), DEC);
LogFile.print(F(" "));
LogFile.print(time.hour(), DEC);
LogFile.print(F(":"));
LogFile.print(time.minute(), DEC);
LogFile.print(F(":"));
LogFile.print(time.second(), DEC);
LogFile.print(F(","));
LogFile.print(fridge.getTemp(), DEC);
LogFile.print(F(","));
LogFile.print(fridge.getFilter(), DEC);
LogFile.print(F(","));
LogFile.print(beer.getTemp(), DEC);
LogFile.print(F(","));
LogFile.print(beer.getFilter(), DEC);
LogFile.print(F(","));
LogFile.print(Setpoint, DEC);
LogFile.print(F(","));
LogFile.print(Output, DEC);
LogFile.print(F(","));
LogFile.print(heatSetpoint, DEC);
LogFile.print(F(","));
LogFile.print(heatOutput, DEC);
LogFile.print(F(","));
LogFile.print(getPeakEstimator());
LogFile.print(F(","));
LogFile.println(getFridgeState(0));
LogFile.flush();
}
}
void dateTime(uint16_t* date, uint16_t* time) {
DateTime now = RTC.now();
*date = FAT_DATE(now.year(), now.month(), now.day());
*time = FAT_TIME(now.hour(), now.minute(), now.second());
}
void initDisplay() {
lcd.clear();
switch (encoderPos) {
default:
case 0:
lcd.print(F("nPID 1.0"));
lcd.setCursor(1, 1);
lcd.print(F("Tf="));
lcd.setCursor(1, 2);
lcd.print(F("Tb="));
lcd.setCursor(11, 1);
lcd.print(F("SP="));
lcd.setCursor(5, 3);
lcd.write((byte)2);
lcd.write((byte)4);
lcd.write((byte)4);
lcd.write((byte)3);
lcd.write((byte)4);
lcd.write((byte)4);
lcd.write((byte)3);
lcd.write((byte)4);
lcd.write((byte)4);
lcd.write((byte)3);
break;
case 1:
lcd.print(F("main PID"));
lcd.setCursor(1, 1);
lcd.print(F("tP="));
lcd.setCursor(1, 2);
lcd.print(F("tD="));
lcd.setCursor(11, 1);
lcd.print(F("tI="));
lcd.setCursor(11, 2);
lcd.print(F("CO="));
lcd.setCursor(5, 3);
lcd.write((byte)3);
lcd.write((byte)4);
lcd.write((byte)4);
lcd.write((byte)2);
lcd.write((byte)4);
lcd.write((byte)4);
lcd.write((byte)3);
lcd.write((byte)4);
lcd.write((byte)4);
lcd.write((byte)3);
break;
case 2:
lcd.print(F("heat PID"));
lcd.setCursor(1, 1);
lcd.print(F("tP="));
lcd.setCursor(1, 2);
lcd.print(F("tD="));
lcd.setCursor(11, 1);
lcd.print(F("tI="));
lcd.setCursor(11, 2);
lcd.print(F("CO="));
lcd.setCursor(5, 3);
lcd.write((byte)3);
lcd.write((byte)4);
lcd.write((byte)4);
lcd.write((byte)3);
lcd.write((byte)4);
lcd.write((byte)4);
lcd.write((byte)2);
lcd.write((byte)4);
lcd.write((byte)4);
lcd.write((byte)3);
break;
case 3:
lcd.print(F(" fridge "));
lcd.setCursor(1, 2);
lcd.print(F("pE="));
lcd.setCursor(11, 2);
lcd.write((byte)0);
lcd.print(F("t="));
lcd.setCursor(5, 3);
lcd.write((byte)3);
lcd.write((byte)4);
lcd.write((byte)4);
lcd.write((byte)3);
lcd.write((byte)4);
lcd.write((byte)4);
lcd.write((byte)3);
lcd.write((byte)4);
lcd.write((byte)4);
lcd.write((byte)2);
break;
}
}
void updateDisplay() {
lcd.setCursor(9, 0);
if (programState & DISPLAY_UNIT) lcd.write((byte)7);
else lcd.write((byte)6);
if (programState & TEMP_PROFILE) lcd.print(F(" PGM "));
else {
if (programState & MAIN_PID_MODE) lcd.print(F(" A "));
else lcd.print(F(" M "));
if (programState & HEAT_PID_MODE) lcd.print(F("A "));
else lcd.print(F("M "));
}
if (getFridgeState(0) == IDLE) lcd.print(F("I "));
if (getFridgeState(0) == HEAT) lcd.print(F("H "));
if (getFridgeState(0) == COOL) lcd.print(F("C "));
if (programState & DATA_LOGGING) lcd.print(F("SD"));
else { lcd.write((byte)5); lcd.write((byte)5); }
if (!encoderPos) {
DateTime time = RTC.now();
lcd.setCursor(11, 2);
lcd.print((time.hour() - (time.hour() % 10))/10);
lcd.print(time.hour() % 10);
lcd.print(F(":"));
lcd.print(time.minute()/10 % 6);
lcd.print(time.minute() % 10);
lcd.print(F(":"));
lcd.print(time.second()/10 % 6);
lcd.print(time.second() % 10);
}
if (programState & DISPLAY_UNIT) { // temperature units = deg F
switch (encoderPos) { // perform conversion for display
default:
case 0:
lcd.setCursor(4, 1);
lcd.print(probe::tempCtoF(fridge.getTemp()));
lcd.setCursor(4, 2);
lcd.print(probe::tempCtoF(beer.getTemp()));
lcd.setCursor(14, 1);
lcd.print(probe::tempCtoF(Setpoint));
break;
case 1:
lcd.setCursor(4, 1);
lcd.print(mainPID.GetPTerm()*9/5);
lcd.setCursor(4, 2);
lcd.print(mainPID.GetDTerm()*9/5);
lcd.setCursor(14, 1);
lcd.print(mainPID.GetITerm()*9/5);
lcd.setCursor(14, 2);
lcd.print(probe::tempCtoF(Output));
break;
case 2:
lcd.setCursor(4, 1);
lcd.print(heatPID.GetPTerm()/heatWindow);
lcd.print('%');
lcd.setCursor(4, 2);
lcd.print(heatPID.GetDTerm()/heatWindow);
lcd.print('%');
lcd.setCursor(14, 1);
lcd.print(heatPID.GetITerm()/heatWindow);
lcd.print('%');
lcd.setCursor(14, 2);
lcd.print((double)(heatOutput/heatWindow));
lcd.print('%');
break;
case 3:
double elapsed = 0;
lcd.setCursor(0, 1);
switch (getFridgeState(0)) {
case IDLE:
if (getFridgeState(1) == COOL) lcd.print(F(" wait on peak "));
else lcd.print(F(" idling "));
elapsed = (double)(millis() - getStopTime()) / 60000; // time since IDLE start in min
break;
case COOL:
lcd.print(F(" cooling "));
elapsed = (double)(millis() - getStartTime()) / 60000; // time since COOL start in min
break;
case HEAT:
elapsed = millis() - getStartTime(); // time since HEAT window start in ms
if (elapsed < heatOutput) lcd.print(F(" heating "));
else lcd.print(F(" idle on heat "));
elapsed /= 60000; // convert ms to min
break;
}
lcd.setCursor(4, 2);
lcd.print(getPeakEstimator());
lcd.setCursor(14, 2);
lcd.print(elapsed);
break;
}
}
else { // temperature units = deg C
switch (encoderPos) { // no conversion needed
default:
case 0:
lcd.setCursor(4, 1);
lcd.print(fridge.getTemp());
lcd.setCursor(4, 2);
lcd.print(beer.getTemp());
lcd.setCursor(14, 1);
lcd.print(Setpoint);
break;
case 1:
lcd.setCursor(4, 1);
lcd.print(mainPID.GetPTerm());
lcd.setCursor(4, 2);
lcd.print(mainPID.GetDTerm());
lcd.setCursor(14, 1);
lcd.print(mainPID.GetITerm());
lcd.setCursor(14, 2);
lcd.print(Output);
break;
case 2:
lcd.setCursor(4, 1);
lcd.print(heatPID.GetPTerm()/heatWindow);
lcd.print('%');
lcd.setCursor(4, 2);
lcd.print(heatPID.GetDTerm()/heatWindow);
lcd.print('%');
lcd.setCursor(14, 1);
lcd.print(heatPID.GetITerm()/heatWindow);
lcd.print('%');
lcd.setCursor(14, 2);
lcd.print((unsigned int)heatOutput/heatWindow);
lcd.print('%');
break;
case 3:
double elapsed = 0;
lcd.setCursor(0, 1);
switch (getFridgeState(0)) {
case IDLE:
if (getFridgeState(1) == COOL) lcd.print(F(" wait on peak "));
else lcd.print(F(" idling "));
elapsed = (double)(millis() - getStopTime()) / 60000; // time since IDLE start in min
break;
case COOL:
lcd.print(F(" cooling "));
elapsed = (double)(millis() - getStartTime()) / 60000; // time since COOL start in min
break;
case HEAT:
elapsed = millis() - getStartTime(); // time since HEAT window start in ms
if (elapsed < heatOutput) lcd.print(F(" heating "));
else lcd.print(F(" idle on heat "));
elapsed /= 60000; // convert ms to min
break;
}
lcd.setCursor(4, 2);
lcd.print(getPeakEstimator());
lcd.setCursor(14, 2);
lcd.print(elapsed);
break;
}
}
}
void menu() {
#if DEBUG == true
Serial.print(F("control suspended, entering menu... "));
Serial.print(freeRAM());
Serial.println(F(" bytes free SRAM remaining"));
#endif
static char menu_list [8][21] = {"Main PID: Mode", "Main PID: SP", "Heat PID: Mode", "[SD] Logging", "[SD] Profiles", "Display Units", "Restore & Reset", "BACK"};
boolean exit = false;
encoderPos = 0;
do {wdt_reset(); mainUpdate();} while (!digitalRead(pushButton)); // wait for user to let go of button; continue to poll wdt with reset pulse
do { // main menu loop; display current menu option
wdt_reset();
mainUpdate();
static char lastReportedPos = 1;
static char listSize = 8;
encoderState |= DEBOUNCE;
if (lastReportedPos != encoderPos) {
encoderPos = (encoderPos + listSize) % listSize;
lcd.clear();
lcd.setCursor(1, 0);
lcd.print(menu_list[(encoderPos - 1 + listSize) % listSize]);
lcd.setCursor(0, 1);
lcd.write((byte)1);
lcd.print(menu_list[encoderPos]);
lcd.setCursor(1, 2);
lcd.print(menu_list[(encoderPos + 1 + listSize) % listSize]);
lcd.setCursor(1, 3);
lcd.print(menu_list[(encoderPos + 2 + listSize) % listSize]);
lastReportedPos = encoderPos;
}
if (!digitalRead(pushButton)) {
switch (encoderPos) { // main menu switch; run subroutine for current menu option on rotary encoder push
case 0: // main PID operation -- manual / automatic
do {wdt_reset(); mainUpdate();} while (!digitalRead(pushButton));
mainPIDmode();
encoderPos = 0; // return encoder position to current option on the menu
break;
case 1: // main PID Setpoint
do {wdt_reset(); mainUpdate();} while (!digitalRead(pushButton));
mainPIDsp();
encoderPos = 1;
break;
case 2: // heat PID operation -- manual / automatic
do {wdt_reset(); mainUpdate();} while (!digitalRead(pushButton));
heatPIDmode();
encoderPos = 2;
break;
case 3: // data logging operations
do {wdt_reset(); mainUpdate();} while (!digitalRead(pushButton));
dataLog();
encoderPos = 3;
break;
case 4: // fermentation temperature profiles
do {wdt_reset(); mainUpdate();} while (!digitalRead(pushButton));
tempProfile();
encoderPos = 4;
break;
case 5: // temperature units C/F
do {wdt_reset(); mainUpdate();} while (!digitalRead(pushButton));
tempUnit();
encoderPos = 5;
break;
case 6: // reset all settings to defaults and reboot arduino
do {wdt_reset(); mainUpdate();} while (!digitalRead(pushButton));
avrReset();
encoderPos = 6;
break;
case 7: // backOut of the menu and save settings; do file operations if needed
backOut();
exit = true; // exit the menu loop
break;
}
do {wdt_reset(); mainUpdate();} while (!digitalRead(pushButton));
lastReportedPos += 1; // force re-draw of menu list
}
} while (!exit);
encoderPos = 0; // zero encoder position for main display
initDisplay(); // re-initialize main display
}
void mainPIDmode() {
if (programState & TEMP_PROFILE) {
lcd.setCursor(0, 2);
lcd.print(F(" PROFILE IS RUNNING "));
unsigned long start = millis();
do { wdt_reset(); mainUpdate(); } while (millis() <= (unsigned long)(start + 1500)); // wait for 1.5 seconds without hard delay
return;
}
char listSize = 2;
encoderPos = (programState & MAIN_PID_MODE) >> 5;
char lastReportedPos = encoderPos + 1;
lcd.setCursor(0, 2);
lcd.print(F(" "));
lcd.setCursor(2, 2);
lcd.write((byte)1);
do {
wdt_reset();
mainUpdate();
encoderState |= DEBOUNCE;
if (lastReportedPos != encoderPos) {
encoderPos = (encoderPos + listSize) % listSize;
lcd.setCursor(3, 2);
if (encoderPos) lcd.print(F("Automatic"));
else lcd.print(F("Manual "));
lastReportedPos = encoderPos;
}
} while (digitalRead(pushButton));
#if DEBUG == true
if (encoderPos) Serial.print(F("main PID set to automatic. "));
else Serial.print(F("main PID set to manual. "));
Serial.print(freeRAM());
Serial.println(F(" bytes free SRAM remaining"));
#endif
if (encoderPos) {programState |= MAIN_PID_MODE;} // set main PID to automatic mode
else { // set main PID to manual mode; user entry of main Output for manual only
programState &= ~MAIN_PID_MODE;
do {wdt_reset(); mainUpdate();} while (!digitalRead(pushButton));
char listSize = 100;
if (programState & DISPLAY_UNIT) Output = probe::tempCtoF(Output); // if display unit = deg F, convert Output
encoderPos = int(Output);
char lastReportedPos = encoderPos + 1;
lcd.setCursor(3, 2);
lcd.print(F(" "));
do { // coarse-grained ajustment (integers)
wdt_reset();
mainUpdate();
encoderState |= DEBOUNCE;
if (lastReportedPos != encoderPos) {
encoderPos = (encoderPos + listSize) % listSize;
lcd.setCursor(3, 2);
lcd.print(encoderPos + Output - int(Output));
if (programState & DISPLAY_UNIT) lcd.print(F(" \337F"));
else lcd.print(F(" \337C"));
lastReportedPos = encoderPos;
}
lcd.setCursor(4, 2);
lcd.cursor();
} while (digitalRead(pushButton));
lcd.noCursor();
Output = encoderPos + Output - int(Output);
encoderPos = (Output - int(Output)) * 10;
lastReportedPos = encoderPos + 1;
Output = int(Output);
listSize = 10;
do {wdt_reset(); mainUpdate();} while (!digitalRead(pushButton));
do { // fine-grained ajustment (tenths)
wdt_reset();
mainUpdate();
encoderState |= DEBOUNCE;
if (lastReportedPos != encoderPos) {
encoderPos = (encoderPos + listSize) % listSize;
lcd.setCursor(3, 2);
lcd.print(Output + double(encoderPos)/10);
if (programState & DISPLAY_UNIT) lcd.print(F(" \337F"));
else lcd.print(F(" \337C"));
lastReportedPos = encoderPos;
}
lcd.setCursor(6, 2);
lcd.cursor();
} while (digitalRead(pushButton));
lcd.noCursor();
Output = Output + double(encoderPos)/10;
if (programState & DISPLAY_UNIT) Output = probe::tempFtoC(Output); // if display is in deg F, convert user entry back to native deg C
Output = constrain(Output, 0.3, 38); // constrain main PID Output to allowed range 0.3 - 38 deg C (~32.5 - ~100 deg F)
}
#if DEBUG == true
Serial.print(F("main PID Output set to:"));
Serial.print(Output);
Serial.print(F(" "));
Serial.print(freeRAM());
Serial.println(F(" bytes free SRAM remaining"));
#endif
}
void mainPIDsp() {
if (programState & TEMP_PROFILE) {
lcd.setCursor(0, 2);
lcd.print(F(" PROFILE IS RUNNING "));
unsigned long start = millis();
do { wdt_reset(); mainUpdate(); } while (millis() <= (unsigned long)(start + 1500));
return;
}
lcd.setCursor(0, 2);
lcd.print(F(" "));
lcd.setCursor(2, 2);
lcd.write((byte)1);
char listSize = 100;
if (programState & DISPLAY_UNIT) Setpoint = probe::tempCtoF(Setpoint);
encoderPos = int(Setpoint);
char lastReportedPos = encoderPos + 1;
do { // coarse-grained ajustment (integers)
wdt_reset();
mainUpdate();
encoderState |= DEBOUNCE;
if (lastReportedPos != encoderPos) {
encoderPos = (encoderPos + listSize) % listSize;
lcd.setCursor(3, 2);
lcd.print(encoderPos + Setpoint - int(Setpoint));
if (programState & DISPLAY_UNIT) lcd.print(F(" \337F"));
else lcd.print(F(" \337C"));
lastReportedPos = encoderPos;
}
lcd.setCursor(4, 2);
lcd.cursor();
} while (digitalRead(pushButton));
lcd.noCursor();
Setpoint = encoderPos + Setpoint - int(Setpoint);
encoderPos = (Setpoint - int(Setpoint)) * 10;
lastReportedPos = encoderPos + 1;
Setpoint = int(Setpoint);
listSize = 10;
do {wdt_reset(); mainUpdate();} while (!digitalRead(pushButton));
do { // fine-grained ajustment (tenths)
wdt_reset();
mainUpdate();
encoderState |= DEBOUNCE;
if (lastReportedPos != encoderPos) {
encoderPos = (encoderPos + listSize) % listSize;
lcd.setCursor(3, 2);
lcd.print(Setpoint + double(encoderPos)/10);
if (programState & DISPLAY_UNIT) lcd.print(F(" \337F"));
else lcd.print(F(" \337C"));
lastReportedPos = encoderPos;
}
lcd.setCursor(6, 2);
lcd.cursor();
} while (digitalRead(pushButton));
lcd.noCursor();
Setpoint = Setpoint + double(encoderPos)/10;
if (programState & DISPLAY_UNIT) Setpoint = probe::tempFtoC(Setpoint);
#if DEBUG == true
Serial.print(F("main PID Setpoint set to:"));
Serial.print(Setpoint);
Serial.print(F(" "));
Serial.print(freeRAM());
Serial.println(F(" bytes free SRAM remaining"));
#endif
}
void heatPIDmode() {
if (programState & TEMP_PROFILE) {
lcd.setCursor(0, 2);
lcd.print(F(" PROFILE IS RUNNING "));
unsigned long start = millis();
do { wdt_reset(); mainUpdate(); } while (millis() <= (unsigned long)(start + 1500));
return;
}
char listSize = 2;
encoderPos = (programState & HEAT_PID_MODE) >> 4;
char lastReportedPos = encoderPos + 1;
lcd.setCursor(0, 2);
lcd.print(F(" "));
lcd.setCursor(2, 2);
lcd.write((byte)1);
do {
wdt_reset();
mainUpdate();
encoderState |= DEBOUNCE;
if (lastReportedPos != encoderPos) {
encoderPos = (encoderPos + listSize) % listSize;
lcd.setCursor(3, 2);
if (encoderPos) lcd.print(F("Automatic"));
else lcd.print(F("Manual "));
lastReportedPos = encoderPos;
}
} while (digitalRead(pushButton));
#if DEBUG == true
if (encoderPos) Serial.print(F("heat PID set to Automatic. "));
else Serial.print(F("heat PID set to Manual. "));
Serial.print(freeRAM());
Serial.println(F(" bytes free SRAM remaining"));
#endif
if (encoderPos) programState |= HEAT_PID_MODE; // set heat PID to automatic mode
else { // set heat PID to manual mode; user entry of heat Output for manual only
programState &= ~HEAT_PID_MODE;
do {wdt_reset(); mainUpdate();} while (!digitalRead(pushButton));
char listSize = 100;
if (programState & DISPLAY_UNIT) heatSetpoint = probe::tempCtoF(heatSetpoint);
encoderPos = int(heatSetpoint);
char lastReportedPos = encoderPos + 1;
lcd.setCursor(3, 2);
lcd.print(F(" "));
do { // coarse-grained ajustment (integers)
wdt_reset();
mainUpdate();
encoderState |= DEBOUNCE;
if (lastReportedPos != encoderPos) {
encoderPos = (encoderPos + listSize) % listSize;
lcd.setCursor(3, 2);
lcd.print(encoderPos + heatSetpoint - int(heatSetpoint));
if (programState & DISPLAY_UNIT) lcd.print(F(" \337F"));
else lcd.print(F(" \337C"));
lastReportedPos = encoderPos;
}
lcd.setCursor(4, 2);
lcd.cursor();
} while (digitalRead(pushButton));
lcd.noCursor();
heatSetpoint = encoderPos + heatSetpoint - int(heatSetpoint);
encoderPos = (heatSetpoint - int(heatSetpoint)) * 10;
lastReportedPos = encoderPos + 1;
heatSetpoint = int(heatSetpoint);
listSize = 10;
do {wdt_reset(); mainUpdate();} while (!digitalRead(pushButton));
do { // fine-grained ajustment (tenths)
wdt_reset();
mainUpdate();
encoderState |= DEBOUNCE;
if (lastReportedPos != encoderPos) {
encoderPos = (encoderPos + listSize) % listSize;
lcd.setCursor(3, 2);
lcd.print(heatSetpoint + double(encoderPos)/10);
if (programState & DISPLAY_UNIT) lcd.print(F(" \337F"));
else lcd.print(F(" \337C"));
lastReportedPos = encoderPos;
}
lcd.setCursor(6, 2);
lcd.cursor();
} while (digitalRead(pushButton));
lcd.noCursor();
heatSetpoint = heatSetpoint + double(encoderPos)/10;
if (programState & DISPLAY_UNIT) heatSetpoint = probe::tempFtoC(heatSetpoint);
}
#if DEBUG == true
Serial.print(F("heat PID Setpoint set to:"));
Serial.print(heatSetpoint);
Serial.print(F(" "));
Serial.print(freeRAM());
Serial.println(F(" bytes free SRAM remaining"));
#endif
}
void dataLog() {
char listSize = 2;
encoderPos = (programState & DATA_LOGGING) >> 1;
char lastReportedPos = encoderPos + 1;
lcd.setCursor(0, 2);
lcd.print(F(" "));
lcd.setCursor(2, 2);
lcd.write((byte)1);
do {
wdt_reset();
mainUpdate();
encoderState |= DEBOUNCE;
if (lastReportedPos != encoderPos) {
encoderPos = (encoderPos + listSize) % listSize;
lcd.setCursor(3, 2);
if (encoderPos) lcd.print(F("Enabled "));
else lcd.print(F("Disabled"));
lastReportedPos = encoderPos;
}
} while (digitalRead(pushButton));
if (encoderPos) {
if (!(programState & (DATA_LOGGING + FILE_OPS))) {
#if DEBUG == true
Serial.print(F("New logfile pending... "));
Serial.print(freeRAM());
Serial.println(F(" bytes free SRAM remaining"));
#endif
programState += DATA_LOGGING + FILE_OPS; // start new LogFile on menu exit
}
else if ((programState & (DATA_LOGGING + FILE_OPS)) == FILE_OPS) {
#if DEBUG == true
Serial.print(F("Pending close operation canceled... "));
Serial.print(freeRAM());
Serial.println(F(" bytes free SRAM remaining"));
#endif
programState = programState & ~(DATA_LOGGING + FILE_OPS) + DATA_LOGGING; // cancel pending file close and leave log running
}
}
else {
if ((programState & (DATA_LOGGING + FILE_OPS)) == DATA_LOGGING) {
#if DEBUG == true
Serial.print(F("Logfile close pending... "));
Serial.print(freeRAM());
Serial.println(F(" bytes free SRAM remaining"));
#endif
programState = (programState & ~(DATA_LOGGING + FILE_OPS)) + FILE_OPS; // close current LogFile on menu exit
}
else if ((programState & (DATA_LOGGING + FILE_OPS)) == DATA_LOGGING + FILE_OPS) {
#if DEBUG == true
Serial.print(F("Pending new operation canceled... "));
Serial.print(freeRAM());
Serial.println(F(" bytes free SRAM remaining"));
#endif
programState &= ~(DATA_LOGGING + FILE_OPS); // cancel pending file opening
}
}
}
void tempProfile() { // manage SP profiles
if (programState & TEMP_PROFILE) { // if profile already running
char listSize = 2;
encoderPos = 0;
char lastReportedPos = 1;
lcd.setCursor(0, 2);
lcd.print(F(" STOP PROFILE? "));
lcd.setCursor(15, 2);
lcd.write((byte)1);
do {
wdt_reset();
mainUpdate();
encoderState |= DEBOUNCE;
if (lastReportedPos != encoderPos) {
encoderPos = (encoderPos + listSize) % listSize;
lcd.setCursor(16, 2);
if (encoderPos) lcd.print(F("YES"));
else lcd.print(F("NO "));
lastReportedPos = encoderPos;
}
} while (digitalRead(pushButton));
if (encoderPos) { // empty profile queue, reset program flag and return to main menu
programState &= ~TEMP_PROFILE;
while (!profile.isEmpty()) {
wdt_reset();
mainUpdate();
profile.pop();
}
}
encoderPos = 4;
return;
}
encoderPos = 0;
char lastReportedPos = 1;
File root = SD.open("/PROFILES/", FILE_READ); // open root to profile directory
if (!root) { // profile directory does not exist
lcd.setCursor(0, 2);
lcd.print(F(" /PROFILES/ MISSING "));
unsigned long start = millis();
do { wdt_reset(); mainUpdate(); } while (millis() <= (unsigned long)(start + 1500));
return;
}
lcd.setCursor(0, 2);
lcd.print(F(" "));
do {
wdt_reset();
mainUpdate();
encoderState |= DEBOUNCE;
if (lastReportedPos != encoderPos) {
do {
ProFile = root.openNextFile(); // open next file in /profiles/
} while (ProFile.isDirectory()); // ignore directories
if (!ProFile) { // no more files in /profiles/
root.rewindDirectory(); // return to top of /profiles/
lcd.setCursor(2, 2);
lcd.write((byte)1);
lcd.print(F("BACK "));
}
else {
lcd.setCursor(2, 2);
lcd.write((byte)1);
lcd.print(ProFile.name()); // print current filename to LCD
}
lastReportedPos = encoderPos;
}
} while (digitalRead(pushButton));
do {wdt_reset(); mainUpdate();} while (!digitalRead(pushButton));
if (ProFile) {
char filename[12];
for (int i = 0; i++; i < 8) { // store profile name in EEPROM
EEPROMWrite(44 + i, ProFile.name()[i], BYTE);
}
char buff[20]; // char buffer for file data
profileStep Step; // temporary profile step to push to queue
while (ProFile.peek() != -1) { // if not EOF, read temperature,duration one byte at a time
wdt_reset();
mainUpdate();
for (int i = 0; i < 20; i++) { // read step temperature (deg C) into buffer until ',' found
buff[i] = ProFile.read();
if (buff[i] == ',') break;
}
Step.temp = strtod(buff, 0); // convert (char)buffer to double
memset(buff, 0, 20); // reset buffer
for (int i = 0; i < 20; i++) { // read step duration (hours) into buffer until newline found
buff[i] = ProFile.read();
if (buff[i] == '\n') break;
}
Step.duration = strtod(buff, 0);
if (Step.temp || Step.duration) profile.push(Step); // push (non-null) fermentation profile step into queue