-
Notifications
You must be signed in to change notification settings - Fork 16
/
Copy pathCHPC_firmware.ino
2438 lines (2208 loc) · 74.7 KB
/
CHPC_firmware.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
/*
Cheap Heat Pump Controller (CHPC) firmware.
Copyright (C) 2018-2019 Gonzho ([email protected])
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/>.
See https://github.com/gonzho000/chpc/ for more details
*/
//-----------------------USER OPTIONS-----------------------
#define BOARD_TYPE_G //Type "G", PCB from github.com/gonzho000/chpc/
//#define BOARD_TYPE_F //Type "F"
//#define BOARD_TYPE_G9 //Type "G9" or "G-MAX", current testing
//#define DISPLAY_096 1 //1st tests, support WILL BE DROPPED OUT SOON! small OLEDs support
#define DISPLAY_1602 2 //if only 1st character appears: patch 1602 library "inline size_t LiquidCrystal_I2C::write(uint8_t value)" "return 1" instead of "return 0"
//#define DISPLAY_NONE -1
#define INPUTS_AS_BUTTONS 1 //pulldown resistors required
//#define RS485_PYTHON 1
#define RS485_HUMAN 2
//#define RS485_NONE 3
#define EEV_SUPPORT
//#define EEV_ONLY //NO target, no relays. Oly EEV, Tae, Tbe, current sensor and may be additional T sensors
#define HUMAN_AUTOINFO 10000 //print stats to console
#define WATCHDOG //only if u know what to do
//-----------------------TEMPERATURES-----------------------
#define T_SETPOINT_MAX 45.0; //defines max temperature that ordinary user can set
#define T_HOTCIRCLE_DELTA_MIN 2.0; //useful for "water heater vith intermediate heat exchanger" scheme, Target == sensor in water, hot side CP will be switched on if "target - hot_out > T_HOTCIRCLE_DELTA_MIN"
#define T_SUMP_MIN 9.0; //HP will not start if T lower
#define T_SUMP_MAX 110.0; //HP will stop if T higher
#define T_SUMP_HEAT_THRESHOLD 16.0; //sump heater will be powered on if T lower
#define T_BEFORE_CONDENSER_MAX 108.0; //discharge MAX, system stops if discharge higher
#define T_AFTER_EVAPORATOR_MIN -7.0; //suction MIN, HP stops if lower, anti-freeze and anti-liquid at suction protection
#define T_COLD_MIN -8.0; //cold loop anti-freeze: stop if inlet or outlet temperature lower
#define T_HOTOUT_MAX 50.0; //hot loop: stop if outlet temperature higher than this
#define T_WORKINGOK_SUMP_MIN 30.0; //compressor MIN temperature, HP stops if it lower after 5 minutes of pumping, need to be not very high to normal start after deep freeze
//-----------------------TUNING OPTIONS -----------------------
#define MAX_WATTS 1170.0 //user for power protection
#define DEFFERED_STOP_HOTCIRCLE 3000000 //50 mins
#define POWERON_PAUSE 300000 //5 mins
#define MINCYCLE_POWEROFF 300000 //5 mins
#define MINCYCLE_POWERON 3600000 //60 mins
#define POWERON_HIGHTIME 10000 //10 sec, defines time after start when power consumption can be 2 times greater than normal
//EEV
#define EEV_MAXPULSES 480
#define EEV_PULSE_FCLOSE_MILLIS 20 //fast close, set waiting pos., close on danger
#define EEV_PULSE_CLOSE_MILLIS 50000 //precise close
#define EEV_PULSE_WOPEN_MILLIS 20 //waiting pos. set
#define EEV_PULSE_FOPEN_MILLIS 1300 //fast open, fast search
#define EEV_PULSE_OPEN_MILLIS 60000 //precise open
#define EEV_STOP_HOLD 500 //0.1..1sec for Sanhua
#define EEV_CLOSE_ADD_PULSES 8 //read below, close algo
#define EEV_OPEN_AFTER_CLOSE 47 //0 - close to zero position, than close on EEV_CLOSE_ADD_PULSES (close insurance, read EEV manuals for this value)
//N - close to zero position, than close on EEV_CLOSE_ADD_PULSES, than open on EEV_OPEN_AFTER_CLOSE pulses
//i.e. it is "waiting position" while HP not working
#define EEV_MINWORKPOS 52 //position will be not less during normal work, set after compressor start
#define EEV_PRECISE_START 8.6 //T difference, threshold: make slower pulses if (real_diff-target_diff) less than this value. Used for fine auto-tuning.
#define EEV_EMERG_DIFF 2.5 //if dangerous condition: real_diff =< (target_diff - EEV_EMERG_DIFF) occured then EEV will be closed to min. work position //Ex: EEV_EMERG_DIFF = 2.0, target diff 5.0, if real_diff =< (5.0 - 2.0) than EEV will be closed
#define EEV_HYSTERESIS 0.6 //must be less than EEV_PRECISE_START, ex: target difference = 4.0, hysteresis = 0.1, when difference in range 4.0..4.1 no EEV pulses will be done;
#define EEV_CLOSEEVERY 86400000 //86400000: EEV will be closed (calibrated) every 24 hours, done while HP is NOT working
#define EEV_TARGET_TEMP_DIFF 4.0 //target difference between Before Evaporator and After Evaporator, the head of whole algo
//#define EEV_DEBUG //debug, usefull during system fine tuning, "RS485_HUMAN" only
#define MAGIC 0x55 //change if u want to reinit T sensors
//-----------------------USER OPTIONS END -----------------------
//#define INPUTS_AS_INPUTS 2 //
//#define RS485_MACHINE 3 //?? or part of Python?
//-----------------------changelog-----------------------
/*
v1.0:
- Displays support
- define TYPE F/G and rearrange ports
- multi-DS18b20 support on lane
- skip non-important DS18B20 during init
- rewrite Main Cycle to unification: some sensors can be absent, ex: T_hot_out can be absent because i'ts used as target
- 2 on-board buttons support: +/- aim
- DISPLAY: indication: real and aim
- RS485_HUMAN: remote commands +,-,G,0x20/?/Enter
- buttons: < > increase_decrease t
- simpliest thermostat scheme: only T target
- rename all procs
- RS485_PYTHON: print to console inspite of mode diring init proc
- faster wattage overload processing
- write aim value to EE if needed, period: 15 mins (eq. 1041 days)
- deferred stop of hot side circle
- 80 microseconds at 9600
v1.1, 15 Apr 2019:
- HUMAN_AUTOINFO time
- EEV_ONLY mode
- EEV_Support
- EEV auto poweron/poweroff every 10 sec
- EEV_recalibration_time to stop HP and recalibrate EEV from zero level ex: every 24 hours
v1.2, 16 Apr 2019:
- "Type F" support
v1.3, 30 Apr 2019:
- EEV changed "overheating" to "delta T"
- EEV algo v1.1
v1.4, 02 Jun 2019:
- minor fixes
- EEV more asyncy
- T options to header
v1.5, 01 Jul 2019:
- prototyping 9
v1.6, 30 Apr 2021:
- sensors init issue fix
//TODO:
- 0.0 to -127 fix: only 2 attempts than pass 0.0
- poss. DoS: infinite read to nowhere, fix it, set finite counter (ex: 200)
- Dev and Host ID to header
- add speaker and err code for ""ERR: no Tae or Tbe for EEV!""
- min_user_t/max_user_t to header
- rs485_modbus
- full relays halification
? wclose and fclose to EEV
- liquid ref. protection: start cold circle and sump heater if tsump =< tco/tci+1, add option to header
- periodical start of hot side circle
- valve_4way
- inputs support
- ? emergency jumper support
- ? rewite re-init proc from MAGIC to emergency jumper removal at board start
- ? EEV target to EEPROM
- ? list T and other things on screen with buttons
- ? EEV define maximum working position
- ? few devices at same lane for RS485_HUMAN
*/
//-----------------------changelog END-----------------------
// DS18B20 pins: GND DATA VDD
//Connections:
//DS18B20 Pinout (Left to Right, pins down, flat side toward you)
//- Left = Ground
//- Center = Signal (Pin N of arduino): (with 3.3K to 4.7K resistor to +5 or 3.3 )
//- Right = +5 or +3.3 V
//
//
// high volume scheme: +---- +5V (12V not tested)
// |
// +----+
// 1MOhm piezo
// +----+
// |(C)
// pin -> 1.6 kOhms -> (B) 2n2222 < front here
// |(E)
// +--- GND
//
/*
scheme SCT-013-000:
2 pins used: tip and sleeve, center (ring) not used http://cms.35g.tw/coding/wp-content/uploads/2014/09/SCT-013-000_UNO-1.jpg
pins are interchangeable due to AC
32 Ohms (22+10) between sensor pins (35 == ideal)
Pin1:
- via elect. cap. to GND
- via ~10K..470K resistor to GND
- via ~10K..470K resistor to +5 (same as prev.)
if 10K+10K used: current is 25mA
use 100K+100K for 3 phases
Pin2:
- to analog pin
- via 32..35 Ohms resistor to Pin1
+5 -------------------------+
|
|
# R1 10K+
|
|
|~2.5 at this point
+---------------+--------------------------------------+----+
| | | |
#_ elect. cap. # R2 10K+ (same as R1) SCT-013-000 $ # R3 = 35 Ohms (ideal case), 32 used
| | | |
GND --------+---------------+ +----+--------> to Analog pin
WARNING: calibrate 3 sensors together, from different sellers, due to case of incorrectly worked 1 of 3 sensor
P(watts)=220*220/R(Ohms)
*/
//
//MAX 485 voltage - 5V
//
// use resistor at RS-485 GND
// 1st test: 10k result lot of issues
// 2nd test: 1k, issues
// 3rd test: 100, see discussions
//16-ch Multiplexer EN pin: active LOW, connect to GND
//used pins:
//!!! ACTUALISE
//2: Z
//3: S3
//4: S2
//5: S1
//6: S0
//7: relay 2
//8: relay 3
//9: speaker
//10: relay 4
//11-13: rs485
//A0: relay 1
//A1: power monitor
/*
relay 1: heat pump
relay 2: hot side pump
relay 3: cold side pump
relay 4: (future) heatpump sump heater
t0: room
t1: heatpump sump
t2: cold in
t3: cold out
t4: hot in
t5: hot out
t6: before condenser
t7: condenser-evaporator
t8: after evaporator
t9: outer
tA: warm floor
wattage1
*/
String fw_version = "1.6";
#ifdef DISPLAY_096
#define DISPLAY DISPLAY_096
#include <Wire.h>
#include "SSD1306Ascii.h"
#include "SSD1306AsciiWire.h"
#define I2C_ADDRESS 0x3C
SSD1306AsciiWire oled;
#endif
#ifdef DISPLAY_1602
#define DISPLAY DISPLAY_1602
#include <Wire.h>
#include "LiquidCrystal_I2C.h"
LiquidCrystal_I2C lcd(0x3f,16,2); // set the LCD address to 0x27 for a 16 chars and 2 line display
#endif
#ifdef DISPLAY_NONE
#define DISPLAY DISPLAY_NONE
#endif
#ifndef DISPLAY
#define DISPLAY -1
#endif
//
#ifdef INPUTS_AS_BUTTONS
#define INPUTS INPUTS_AS_BUTTONS
#endif
#ifdef INPUTS_AS_INPUTS
#define INPUTS INPUTS_AS_INPUTS
#endif
//
#ifdef RS485_PYTHON
#define RS485 RS485_PYTHON
char ishuman = 0;
#endif
#ifdef RS485_HUMAN
#define RS485 RS485_HUMAN
char ishuman = 1;
#endif
#ifdef RS485_NONE
char ishuman = 0;
#endif
//hardware resources
#define OW_BUS_ALLTSENSORS 12
#define SerialTxControl 13 //RS485 Direction control DE and RE to this pin
#define speakerOut 6
#define em_pin1 A6
#define EMERGENCY_PIN A7
#ifdef BOARD_TYPE_G
String hw_version = "Type G v1.x";
#define RELAY_HEATPUMP 8
#define RELAY_HOTSIDE_CIRCLE 9
#define RELAY_COLDSIDE_CIRCLE 7
#define RELAY_SUMP_HEATER 10
#define RELAY_4WAY_VALVE 11
#ifdef INPUTS_AS_BUTTONS
#define BUT_RIGHT A3
#define BUT_LEFT A2
#endif
#ifdef EEV_SUPPORT
#define EEV_1 2
#define EEV_2 4
#define EEV_3 3
#define EEV_4 5
#endif
#endif
#ifdef BOARD_TYPE_F
String hw_version = "Type F v1.x";
#define RELAY_HEATPUMP 7
#define RELAY_COLDSIDE_CIRCLE 8
#define LATCH_595 10
#define CLK_595 11
#define DATA_595 9
//595.0: relay 3 RELAY_HOTSIDE_CIRCLE, 595.1: relay 4 RELAY_SUMP_HEATER, 595.2: relay 5 RELAY_4WAY_VALVE, 595.3: uln 6, 595.4: uln 7, 595.5: uln 8, 595.6: uln 9, 595.7: uln 10
#ifdef EEV_SUPPORT
#define EEV_1 5
#define EEV_2 3
#define EEV_3 4
#define EEV_4 2
#endif
#ifdef INPUTS_AS_BUTTONS //not sure
#define BUT_RIGHT A3
#define BUT_LEFT A2
#endif
#endif
#ifdef BOARD_TYPE_G9
String hw_version = "Type G9 v1.x";
#define RELAY_4WAY_VALVE 8
#define RELAY_SUMP_HEATER 7
#define LATCH_595 10
#define CLK_595 9
#define DATA_595 11
#define OE_595 A1
/*
595.0: relay 10(not used)
595.1: relay 8
595.2: relay 9
595.3: relay 5 RELAY_HEATPUMP
595.4: relay 4 RELAY_COLDSIDE_CIRCLE
595.5: relay 3 RELAY_HOTSIDE_CIRCLE
595.6: relay 6
595.7: relay 7
*/
#ifdef EEV_SUPPORT
#define EEV_1 2
#define EEV_2 4
#define EEV_3 3
#define EEV_4 5
#endif
#endif
//---------------------------memory debug
#ifdef __arm__
// should use uinstd.h to define sbrk but Due causes a conflict
extern "C" char* sbrk(int incr);
#else // __ARM__
extern char *__brkval;
#endif // __arm__
int freeMemory() {
char top;
#ifdef __arm__
return &top - reinterpret_cast<char*>(sbrk(0));
#elif defined(CORE_TEENSY) || (ARDUINO > 103 && ARDUINO != 151)
return &top - __brkval;
#else // __arm__
return __brkval ? &top - __brkval : &top - __malloc_heap_start;
#endif // __arm__
}
//---------------------------memory debug END
#include <avr/wdt.h>
#include <EEPROM.h>
//#include <FastCRC.h>
/*FastCRC16 CRC16;
union _crc {
unsigned int integer;
char bytes[2];
} crc;
*/
#include <SoftwareSerial.h>
#define SerialRX 0 //RX connected to RO - Receiver Output
#define SerialTX 1 //TX connected to DI - Driver Output Pin
#define RS485Transmit HIGH
#define RS485Receive LOW
const char devID = 0x41;
const char hostID = 0x30;
SoftwareSerial RS485Serial(SerialRX, SerialTX); // RX, TX
#include <OneWire.h>
#include <DallasTemperature.h>
//library's DEVICE_DISCONNECTED_C -127.0
OneWire ow_ALLTSENSORS(OW_BUS_ALLTSENSORS);
DallasTemperature s_allTsensors(&ow_ALLTSENSORS);
typedef struct {
DeviceAddress addr;
bool e; //enabled
double T;
} st_tsens;
DeviceAddress dev_addr; //temp
st_tsens Tae ;
st_tsens Tbe ;
st_tsens Ttarget;
st_tsens Tsump ;
st_tsens Tci ;
st_tsens Tco ;
st_tsens Thi ;
st_tsens Tho ;
st_tsens Tbc ;
st_tsens Tac ;
st_tsens Touter ;
st_tsens Ts1 ;
st_tsens Ts2 ;
#define BIT_Tae 0
#define BIT_Tbe 1
#define BIT_Ttarget 2
#define BIT_Tsump 3
#define BIT_Tci 4
#define BIT_Tco 5
#define BIT_Thi 6
#define BIT_Tho 7
#define BIT_Tbc 8
#define BIT_Tac 9
#define BIT_Touter 10
#define BIT_Ts1 11
#define BIT_Ts2 12
unsigned int used_sensors = 0 ; //bit array
double T_setpoint = 26.5;
double T_setpoint_lastsaved = T_setpoint;
double T_EEV_setpoint = EEV_TARGET_TEMP_DIFF;
double T_EEV_dt = 0.0; //real, used during run
const double cT_setpoint_max = T_SETPOINT_MAX;
const double cT_hotcircle_delta_min = T_HOTCIRCLE_DELTA_MIN;
const double cT_sump_min = T_SUMP_MIN;
const double cT_sump_max = T_SUMP_MAX;
const double cT_sump_heat_threshold = T_SUMP_HEAT_THRESHOLD;
//const double cT_sump_outerT_threshold = 18.0; //?? seems to be not useful
const double cT_before_condenser_max = T_BEFORE_CONDENSER_MAX;
const double cT_after_evaporator_min = T_AFTER_EVAPORATOR_MIN; // working evaporation presure ~= -10, it is constant due to large evaporator volume // waterhouse v1: -12 is too high
const double cT_cold_min = T_COLD_MIN;
const double cT_hotout_max = T_HOTOUT_MAX;
//const double cT_workingOK_cold_delta_min = 0.5; // 0.7 - 1st try, 2nd try 0.5
//const double cT_workingOK_hot_delta_min = 0.5;
const double cT_workingOK_sump_min = T_WORKINGOK_SUMP_MIN; //need to be not very high to normal start after deep freeze
const double c_wattage_max = MAX_WATTS; //FUNAI: 1000W seems to be normal working wattage INCLUDING 1(one) CR25/4 at 3rd speed
//PH165X1CY : 920 Watts, 4.2 A
const double c_workingOK_wattage_min = c_wattage_max/2.5; //
bool heatpump_state = 0;
bool hotside_circle_state = 0;
bool coldside_circle_state = 0;
bool sump_heater_state = 0;
bool valve4w_state = 0;
bool relay6_state = 0;
bool relay7_state = 0;
bool relay8_state = 0;
bool relay9_state = 0;
const long poweron_pause = POWERON_PAUSE ; //default 5 mins
const long mincycle_poweroff = MINCYCLE_POWEROFF; //default 5 mins
const long mincycle_poweron = MINCYCLE_POWERON ; //default 60 mins
bool _1st_start_sleeped = 0;
//??? TODO: periodical start ?
//const long floor_circle_maxhalted = 6000000; //circle NOT works max 100 minutes
const long deffered_stop_hotcircle = DEFFERED_STOP_HOTCIRCLE;
int EEV_cur_pos = 0;
int EEV_apulses = 0; //for async
bool EEV_adonotcare = 0;
const unsigned char EEV_steps[4] = {0b1010, 0b0110, 0b0101, 0b1001};
char EEV_cur_step = 0;
bool EEV_fast = 0;
//main cycle vars
unsigned long millis_prev = 0;
unsigned long millis_now = 0;
unsigned long millis_cycle = 1000;
unsigned long millis_last_heatpump_on = 0;
unsigned long millis_last_heatpump_off = 0;
unsigned long millis_notification = 0;
unsigned long millis_notification_interval = 33000;
unsigned long millis_displ_update = 0;
unsigned long millis_displ_update_interval = 10000;
unsigned long millis_escinput = 0;
unsigned long millis_charinput = 0;
unsigned long millis_lasteesave = 0;
unsigned long millis_last_printstats = 0;
unsigned long millis_eev_last_close = 0;
unsigned long millis_eev_last_on = 0;
unsigned long millis_eev_last_step = 0;
int skipchars = 0;
#define ERR_HZ 2500
char inData[50]; // Allocate some space for the string, do not change that size!
char inChar= -1; // space to store the character read
byte index = 0; // Index into array; where to store the character
//-------------temporary variables
char temp[10];
int i = 0;
int z = 0;
int x = 0;
int y = 0;
double tempdouble = 0.0;
int tempint = 0;
String outString;
//-------------EEPROM
int eeprom_magic_read = 0x00;
int eeprom_addr = 0x00;
//initial values, saved to EEPROM and can be modified later
//CHANGE eeprom_magic after correction!
const int eeprom_magic = MAGIC;
//-------------ERROR states
#define ERR_OK 0
#define ERR_T_SENSOR 1
#define ERR_HOT_PUMP 2
#define ERR_COLD_PUMP 3
#define ERR_HEATPUMP 4
#define ERR_WATTAGE 5
int errorcode = 0;
//--------------------------- for wattage
#define ADC_BITS 10 //10 fo regular arduino
#define ADC_COUNTS (1<<ADC_BITS)
float em_calibration = 62.5;
int em_samplesnum = 2960; // Calculate Irms only 1480 == full 14 periods for 50Hz
//double Irms = 0; //for tests with original procedure
int supply_voltage = 0;
int em_i = 0;
//phase 1
int sampleI_1 = 0;
double filteredI_1 = 0;
double offsetI_1 = ADC_COUNTS>>1; //Low-pass filter output
double sqI_1,sumI_1 = 0; //sq = squared, sum = Sum, inst = instantaneous
double async_Irms_1 = 0;
double async_wattage = 0;
//--------------------------- for wattage END
//--------------------------- functions
long ReadVcc() {
// Read 1.1V reference against AVcc
// set the reference to Vcc and the measurement to the internal 1.1V reference
#if defined(__AVR_ATmega32U4__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
ADMUX = _BV(REFS0) | _BV(MUX4) | _BV(MUX3) | _BV(MUX2) | _BV(MUX1);
#elif defined (__AVR_ATtiny24__) || defined(__AVR_ATtiny44__) || defined(__AVR_ATtiny84__)
ADMUX = _BV(MUX5) | _BV(MUX0);
#elif defined (__AVR_ATtiny25__) || defined(__AVR_ATtiny45__) || defined(__AVR_ATtiny85__)
ADMUX = _BV(MUX3) | _BV(MUX2);
#else
ADMUX = _BV(REFS0) | _BV(MUX3) | _BV(MUX2) | _BV(MUX1);
#endif
delay(2); // Wait for Vref to settle
ADCSRA |= _BV(ADSC); // Start conversion
while (bit_is_set(ADCSRA,ADSC)); // measuring
uint8_t low = ADCL; // must read ADCL first - it then locks ADCH
uint8_t high = ADCH; // unlocks both
long result = (high<<8) | low;
//constant NOT same as in battery controller!
result = 1126400L / result; // Calculate Vcc (in mV); (me: !!) 1125300 (!!) = 1.1*1023*1000
return result; // Vcc in millivolts
}
char CheckAddrExists(void) {
for (i = 0; i < 8; i++) { if (dev_addr[i] != Tae.addr[i]) break; }
if (i == 8) return 1;
for (i = 0; i < 8; i++) { if (dev_addr[i] != Tbe.addr[i]) break; }
if (i == 8) return 1;
for (i = 0; i < 8; i++) { if (dev_addr[i] != Ttarget.addr[i]) break;}
if (i == 8) return 1;
for (i = 0; i < 8; i++) { if (dev_addr[i] != Tsump.addr[i]) break;}
if (i == 8) return 1;
for (i = 0; i < 8; i++) { if (dev_addr[i] != Tci.addr[i]) break;}
if (i == 8) return 1;
for (i = 0; i < 8; i++) { if (dev_addr[i] != Tco.addr[i]) break;}
if (i == 8) return 1;
for (i = 0; i < 8; i++) { if (dev_addr[i] != Thi.addr[i]) break;}
if (i == 8) return 1;
for (i = 0; i < 8; i++) { if (dev_addr[i] != Tho.addr[i]) break;}
if (i == 8) return 1;
for (i = 0; i < 8; i++) { if (dev_addr[i] != Tbc.addr[i]) break;}
if (i == 8) return 1;
for (i = 0; i < 8; i++) { if (dev_addr[i] != Tac.addr[i]) break;}
if (i == 8) return 1;
for (i = 0; i < 8; i++) { if (dev_addr[i] != Touter.addr[i]) break;}
if (i == 8) return 1;
for (i = 0; i < 8; i++) { if (dev_addr[i] != Ts1.addr[i]) break;}
if (i == 8) return 1;
for (i = 0; i < 8; i++) { if (dev_addr[i] != Ts2.addr[i]) break;}
if (i == 8) return 1;
return 0;
/*
//incorrect way: 0.06 % chance for 13 sensors to false positive, calculated for true random.
for (i = 0; i < 8; i++) {
if ( (dev_addr[i] != Tae.addr[i]) &&
(dev_addr[i] != Tbe.addr[i]) &&
(dev_addr[i] != Ttarget.addr[i]) &&
(dev_addr[i] != Tsump.addr[i]) &&
(dev_addr[i] != Tci.addr[i]) &&
(dev_addr[i] != Tco.addr[i]) &&
(dev_addr[i] != Thi.addr[i]) &&
(dev_addr[i] != Tho.addr[i]) &&
(dev_addr[i] != Tbc.addr[i]) &&
(dev_addr[i] != Tac.addr[i]) &&
(dev_addr[i] != Touter.addr[i]) &&
(dev_addr[i] != Ts1.addr[i]) &&
(dev_addr[i] != Ts2.addr[i])
)
break;
}
if (i == 8) return 1;
return 0;
*/
}
void InitS_and_D(void) {
#ifdef DISPLAY_096
Wire.begin();
oled.begin(&Adafruit128x64, I2C_ADDRESS);
oled.setFont(Adafruit5x7);
#endif
#ifdef DISPLAY_1602
lcd.init(); // initialize the lcd
lcd.backlight(); // not really needed
#endif
RS485Serial.begin(9600);
}
void PrintS (String str) {
#ifdef RS485_HUMAN
char *outChar=&str[0];
digitalWrite(SerialTxControl, RS485Transmit);
delay(1);
RS485Serial.print(outChar);
RS485Serial.println();
RS485Serial.flush();
digitalWrite(SerialTxControl, RS485Receive);
#endif
}
void PrintS_and_D (String str, int printSerial = 1) {
char *outChar=&str[0];
//#ifdef RS485_HUMAN
if (ishuman != 0) {
if (printSerial == 1) {
digitalWrite(SerialTxControl, RS485Transmit);
delay(1);
RS485Serial.print(outChar);
RS485Serial.println();
RS485Serial.flush();
digitalWrite(SerialTxControl, RS485Receive);
}
}
//#endif
if (str == "") {
return;
}
#ifdef DISPLAY_096
oled.clear();
oled.println(str);
#endif
#ifdef DISPLAY_1602
lcd.backlight();
lcd.clear();
lcd.print(str);
#endif
}
void Print_D2 () {
#ifdef DISPLAY_1602
lcd.setCursor(0, 1);
lcd.print(outString);
#endif
}
void _PrintHelp(void) {
PrintS( "CHPC, https://github.com/gonzho000/chpc/ fw: " + fw_version + " board: "+ hw_version);
PrintS(F("Commands: \n (?) help\n (+) increase aim T\n (-) decrease aim T\n \n"));
#ifdef EEV_SUPPORT
PrintS(F("(<) decrease EEV T diff \n(>) increase EEV T diff"));
#endif
PrintS(F("(G) get stats"));
}
void PrintS_and_D_double (double double_to_print) {
dtostrf(double_to_print,1,2,temp);
PrintS_and_D(temp);
}
int Inc_T (void) {
if (T_setpoint + 0.5 > cT_setpoint_max) {
PrintS_and_D(F("Max!"));
delay (200);
return 0;
}
T_setpoint += 0.5;
PrintS_and_D_double(T_setpoint);
return 1;
}
int Dec_T (void) {
if (T_setpoint - 0.5 < 1.0) {
PrintS_and_D(F("Min!"));
delay (200);
return 0;
}
T_setpoint -= 0.5;
PrintS_and_D_double(T_setpoint);
return 1;
}
int Inc_E (void) { ///!!!!!! unprotected
T_EEV_setpoint += 0.25;
PrintS_and_D_double(T_EEV_setpoint);
return 1;
}
int Dec_E (void) { ///!!!!!! unprotected
T_EEV_setpoint -= 0.25;
PrintS_and_D_double(T_EEV_setpoint);
return 1;
}
void print_Serial_SaD (double num) { //global string + double
RS485Serial.print(outString);
RS485Serial.println(num);
}
void PrintStats_Serial (void) {
#ifdef RS485_HUMAN
digitalWrite(SerialTxControl, RS485Transmit);
delay(1);
if (Tae.e == 1) {outString = "Tae: " ; print_Serial_SaD(Tae.T); }
if (Tbe.e == 1) {outString= "Tbe: " ; print_Serial_SaD(Tbe.T); }
if (Ttarget.e == 1) {outString = "Ttarget: "; print_Serial_SaD(Ttarget.T); }
if (Tsump.e == 1) {outString = "Tsump: " ; print_Serial_SaD(Tsump.T); }
if (Tci.e == 1) {outString = "Tci: " ; print_Serial_SaD(Tci.T); }
if (Tco.e == 1) {outString = "Tco: " ; print_Serial_SaD(Tco.T); }
if (Thi.e == 1) {outString = "Thi: " ; print_Serial_SaD(Thi.T); }
if (Tho.e == 1) {outString = "Tho: " ; print_Serial_SaD(Tho.T); }
if (Tbc.e == 1) {outString = "Tbc: " ; print_Serial_SaD(Tbc.T); }
if (Tac.e == 1) {outString = "Tac: " ; print_Serial_SaD(Tac.T); }
if (Touter.e == 1) {outString = "Touter: " ; print_Serial_SaD(Touter.T); }
if (Ts1.e == 1) {outString = "Ts1: " ; print_Serial_SaD(Ts1.T); }
if (Ts2.e == 1) {outString = "Ts2: " ; print_Serial_SaD(Ts2.T); }
outString = "Err: " + String(errorcode) + "\n\rWatts:" + String(async_wattage) + "\n\rAim: "; print_Serial_SaD(T_setpoint);
#ifdef EEV_SUPPORT
outString = "EEV_pos:" + String (EEV_cur_pos);
RS485Serial.print(outString);
#endif
RS485Serial.println();
RS485Serial.flush();
digitalWrite(SerialTxControl, RS485Receive);
#endif
}
void ReadEECheckAddr(unsigned char *to_addr) {
for (i=0 ; i<8 ; i++) {
to_addr[i] = EEPROM.read(eeprom_addr);
eeprom_addr++;
}
i = 0;
CheckIsInvalidCRCAddr(to_addr);
if (i != 0) {
while (1) {
//PrintAddr(to_addr);
PrintS_and_D(F("Err:EEPROM, reinit!"));
delay(5000);
}
}
}
void CheckIsInvalidCRCAddr(unsigned char *addr) {
if (OneWire::crc8( addr, 7) != addr[7] ) {
i+= 1;
}
}
void CopyAddrStoreEE(unsigned char *addr_to, int bit_offset) { //get result from dev_addr, autoincrement eeprom_addr
//dev_addr and z from globals used
for (i=0 ; i<8 ; i++) { //no matter
if (z == 0) {
dev_addr[i] = 0x00;
}
addr_to[i] = dev_addr[i];
EEPROM.write(eeprom_addr, dev_addr[i]);
eeprom_addr++;
}
bitWrite(used_sensors, bit_offset, z);
}
void WriteFloatEEPROM(int addr, float val) {
byte *x = (byte *)&val;
for(byte u = 0; u < 4; u++) EEPROM.write(u+addr, x[u]);
}
float ReadFloatEEPROM(int addr) {
byte x[4];
for(byte u = 0; u < 4; u++) x[u] = EEPROM.read(u+addr);
float *y = (float *)&x;
return y[0];
}
void SaveSetpointEE(void) {
if( (T_setpoint_lastsaved != T_setpoint) &&
( ((unsigned long)(millis_now - millis_lasteesave) > 15*60*1000 ) || (millis_lasteesave == 0) ) ) {
eeprom_addr = 1;
WriteFloatEEPROM(eeprom_addr, T_setpoint);
millis_lasteesave = millis_now;
T_setpoint_lastsaved = T_setpoint;
}
}
void PrintAddr(unsigned char *str) {
outString = "";
for (i = 0; i < 8; i++) {
if (str[i] < 0x10) outString += "0";
outString += String(str[i], HEX);
}
PrintS_and_D(outString);
}
unsigned char FindAddr(String what, int required = 0) {
i = 1;
while (RS485Serial.available() > 0) {
inChar = RS485Serial.read();
delay(1);
}
inChar = 0x00;
while (1) {
while (!s_allTsensors.getAddress(dev_addr, 0)) {
if (required == 0) {
PrintS_and_D(F("Press > to skip"));
delay(500);
while (RS485Serial.available() > 0) {
inChar = RS485Serial.read();
if (inChar == 0x3E) {
PrintS_and_D("Skipped: " + what);
return 0;
}
}
#ifdef INPUTS_AS_BUTTONS
i = digitalRead(BUT_RIGHT);
if (i == 1) {
PrintS_and_D("Skipped: " + what);
delay(4000);
return 0;
}
#endif
}
PrintS_and_D("Insert " + what);
delay(1000);
}
if ( OneWire::crc8( dev_addr, 7) != dev_addr[7]) {
PrintS_and_D(F("Invalid CRC! Remove and insert same sensor!\n"));
delay(200);
continue;
} else if (CheckAddrExists() == 1) {
PrintS_and_D(F("USED! Remove!"));
delay(1000);
continue;
} else {
break;
}
}
while (1) {
PrintAddr(dev_addr);
delay(1000);
if (s_allTsensors.getAddress(dev_addr, 0)) {
PrintS_and_D("OK! Remove " + what);
delay(1000);
} else {
delay(100);
break;
}
}
return 1;
}
double GetT (unsigned char *str) {
tempdouble = -127.0;
for ( i = 0; i < 8; i++) {
#ifdef WATCHDOG
wdt_reset();
#endif
#ifdef EEV_SUPPORT
eevise();
#endif
tempdouble = s_allTsensors.getTempC(str);
if ( (tempdouble == 85.0) || (tempdouble == -127.0) ) {
if ( tempdouble == 85.0 ) { //initial value in dallas register after poweron
delay (375); //375 actual for 11 bits resolution, 2-3 retries OK for 12-bits resolution
} else {
delay (37);
}
} else {
break;
}
}
return tempdouble;
}
void Get_Temperatures(void) {
if (Tae.e) Tae.T = GetT(Tae.addr);
if (Tbe.e) Tbe.T = GetT(Tbe.addr);
if (Ttarget.e) Ttarget.T = GetT(Ttarget.addr);
if (Tsump.e) Tsump.T = GetT(Tsump.addr);
if (Tci.e) Tci.T = GetT(Tci.addr);
if (Tco.e) Tco.T = GetT(Tco.addr);
if (Thi.e) Thi.T = GetT(Thi.addr);
if (Tho.e) Tho.T = GetT(Tho.addr);
if (Tbc.e) Tbc.T = GetT(Tbc.addr);
if (Tac.e) Tac.T = GetT(Tac.addr);
if (Touter.e) Touter.T = GetT(Touter.addr);
if (Ts1.e) Ts1.T = GetT(Ts1.addr);
if (Ts2.e) Ts2.T = GetT(Ts2.addr);
s_allTsensors.requestTemperatures(); //global request
//---------DEBUG and self-test !!!--------
/*PrintS_and_D("");
PrintS_and_D_double(Tae.T);
PrintS_and_D_double(Tbe.T);
PrintS_and_D_double(Ttarget.T);
PrintS_and_D_double(Tsump.T);
PrintS_and_D("");*/
/*
PrintS_and_D("Sensor 1 ");