forked from reprappro/RepRapFirmware
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Platform.cpp
2363 lines (2061 loc) · 58.8 KB
/
Platform.cpp
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
/****************************************************************************************************
RepRapFirmware - Platform: RepRapPro Ormerod with Arduino Due controller
Platform contains all the code and definitions to deal with machine-dependent things such as control
pins, bed area, number of extruders, tolerable accelerations and speeds and so on.
-----------------------------------------------------------------------------------------------------
Version 0.1
18 November 2012
Adrian Bowyer
RepRap Professional Ltd
http://reprappro.com
Licence: GPL
****************************************************************************************************/
#include "RepRapFirmware.h"
#include "DueFlashStorage.h"
extern char _end;
extern "C" char *sbrk(int i);
const uint8_t memPattern = 0xA5;
static uint32_t fanInterruptCount = 0; // accessed only in ISR, so no need to declare it volatile
const uint32_t fanMaxInterruptCount = 32; // number of fan interrupts that we average over
static volatile uint32_t fanLastResetTime = 0; // time (microseconds) at which we last reset the interrupt count, accessed inside and outside ISR
static volatile uint32_t fanInterval = 0; // written by ISR, read outside the ISR
// Arduino initialise and loop functions
// Put nothing in these other than calls to the RepRap equivalents
void setup()
{
// Fill the free memory with a pattern so that we can check for stack usage and memory corruption
char* heapend = sbrk(0);
register const char * stack_ptr asm ("sp");
while (heapend + 16 < stack_ptr)
{
*heapend++ = memPattern;
}
reprap.Init();
}
void loop()
{
reprap.Spin();
}
extern "C"
{
// This intercepts the 1ms system tick. It must return 'false', otherwise the Arduino core tick handler will be bypassed.
int sysTickHook()
{
reprap.Tick();
return 0;
}
}
//*************************************************************************************************
// PidParameters class
bool PidParameters::UsePID() const
{
return kP >= 0;
}
float PidParameters::GetThermistorR25() const
{
return thermistorInfR * exp(thermistorBeta / (25.0 - ABS_ZERO));
}
void PidParameters::SetThermistorR25AndBeta(float r25, float beta)
{
thermistorInfR = r25 * exp(-beta / (25.0 - ABS_ZERO));
thermistorBeta = beta;
}
bool PidParameters::operator==(const PidParameters& other) const
{
return kI == other.kI && kD == other.kD && kP == other.kP && kT == other.kT && kS == other.kS
&& fullBand == other.fullBand && pidMin == other.pidMin
&& pidMax == other.pidMax && thermistorBeta == other.thermistorBeta && thermistorInfR == other.thermistorInfR
&& thermistorSeriesR == other.thermistorSeriesR && adcLowOffset == other.adcLowOffset
&& adcHighOffset == other.adcHighOffset;
}
//*************************************************************************************************
// Platform class
Platform::Platform() :
tickState(0), fileStructureInitialised(false), active(false), errorCodeBits(0), debugCode(0),
messageString(messageStringBuffer, ARRAY_SIZE(messageStringBuffer)), autoSaveEnabled(false)
{
line = new Line(SerialUSB);
aux = new Line(Serial);
// Files
massStorage = new MassStorage(this);
for(size_t i = 0; i < MAX_FILES; i++)
{
files[i] = new FileStore(this);
}
}
//*******************************************************************************************************************
void Platform::Init()
{
digitalWrite(atxPowerPin, LOW); // ensure ATX power is off by default
pinMode(atxPowerPin, OUTPUT);
idleCurrentFactor = DEFAULT_IDLE_CURRENT_FACTOR;
baudRates[0] = BAUD_RATE;
baudRates[1] = AUX_BAUD_RATE;
commsParams[0] = 0;
commsParams[1] = 1; // by default we require a checksum on data from the aux port, to guard against overrun errors
SerialUSB.begin(baudRates[0]);
Serial.begin(baudRates[1]); // this can't be done in the constructor because the Arduino port initialisation isn't complete at that point
static_assert(sizeof(FlashData) + sizeof(SoftwareResetData) <= 1024, "NVData too large");
ResetNvData();
line->Init();
aux->Init();
messageIndent = 0;
addToTime = 0.0;
lastTimeCall = 0;
lastTime = Time();
longWait = lastTime;
massStorage->Init();
for (size_t file = 0; file < MAX_FILES; file++)
{
files[file]->Init();
}
fileStructureInitialised = true;
mcpDuet.begin(); //only call begin once in the entire execution, this begins the I2C comms on that channel for all objects
mcpExpansion.setMCP4461Address(0x2E); //not required for mcpDuet, as this uses the default address
sysDir = SYS_DIR;
configFile = CONFIG_FILE;
defaultFile = DEFAULT_FILE;
// DRIVES
ARRAY_INIT(stepPins, STEP_PINS);
ARRAY_INIT(directionPins, DIRECTION_PINS);
ARRAY_INIT(directions, DIRECTIONS);
ARRAY_INIT(enablePins, ENABLE_PINS);
//ARRAY_INIT(disableDrives, DISABLE_DRIVES); // not currently used
ARRAY_INIT(lowStopPins, LOW_STOP_PINS);
ARRAY_INIT(highStopPins, HIGH_STOP_PINS);
ARRAY_INIT(maxFeedrates, MAX_FEEDRATES);
ARRAY_INIT(accelerations, ACCELERATIONS);
ARRAY_INIT(driveStepsPerUnit, DRIVE_STEPS_PER_UNIT);
ARRAY_INIT(instantDvs, INSTANT_DVS);
ARRAY_INIT(potWipes, POT_WIPES);
senseResistor = SENSE_RESISTOR;
maxStepperDigipotVoltage = MAX_STEPPER_DIGIPOT_VOLTAGE;
//numMixingDrives = NUM_MIXING_DRIVES;
// Z PROBE
zProbePin = Z_PROBE_PIN;
zProbeModulationPin = Z_PROBE_MOD_PIN;
zProbeAdcChannel = PinToAdcChannel(zProbePin);
InitZProbe();
// AXES
ARRAY_INIT(axisMaxima, AXIS_MAXIMA);
ARRAY_INIT(axisMinima, AXIS_MINIMA);
ARRAY_INIT(homeFeedrates, HOME_FEEDRATES);
SetSlowestDrive();
// HEATERS - Bed is assumed to be the first
ARRAY_INIT(tempSensePins, TEMP_SENSE_PINS);
ARRAY_INIT(heatOnPins, HEAT_ON_PINS);
ARRAY_INIT(standbyTemperatures, STANDBY_TEMPERATURES);
ARRAY_INIT(activeTemperatures, ACTIVE_TEMPERATURES);
heatSampleTime = HEAT_SAMPLE_TIME;
coolingFanValue = 0.0;
coolingFanPin = COOLING_FAN_PIN;
coolingFanRpmPin = COOLING_FAN_RPM_PIN;
timeToHot = TIME_TO_HOT;
lastRpmResetTime = 0.0;
webDir = WEB_DIR;
gcodeDir = GCODE_DIR;
tempDir = TEMP_DIR;
for (size_t drive = 0; drive < DRIVES; drive++)
{
if (stepPins[drive] >= 0)
{
pinMode(stepPins[drive], OUTPUT);
}
if (directionPins[drive] >= 0)
{
pinMode(directionPins[drive], OUTPUT);
}
if (enablePins[drive] >= 0)
{
pinMode(enablePins[drive], OUTPUT);
}
if (lowStopPins[drive] >= 0)
{
pinMode(lowStopPins[drive], INPUT_PULLUP);
}
if (highStopPins[drive] >= 0)
{
pinMode(highStopPins[drive], INPUT_PULLUP);
}
motorCurrents[drive] = 0.0;
DisableDrive(drive);
driveState[drive] = DriveStatus::disabled;
}
extrusionAncilliaryPWM = 0.0;
for (size_t heater = 0; heater < HEATERS; heater++)
{
if (heatOnPins[heater] >= 0)
{
digitalWrite(heatOnPins[heater], HIGH); // turn the heater off
pinMode(heatOnPins[heater], OUTPUT);
}
analogReadResolution(12);
thermistorFilters[heater].Init(analogRead(tempSensePins[heater]));
heaterAdcChannels[heater] = PinToAdcChannel(tempSensePins[heater]);
// Calculate and store the ADC average sum that corresponds to an overheat condition, so that we can check is quickly in the tick ISR
float thermistorOverheatResistance = nvData.pidParams[heater].GetRInf()
* exp(-nvData.pidParams[heater].GetBeta() / (BAD_HIGH_TEMPERATURE - ABS_ZERO));
float thermistorOverheatAdcValue = (adRangeReal + 1) * thermistorOverheatResistance
/ (thermistorOverheatResistance + nvData.pidParams[heater].thermistorSeriesR);
thermistorOverheatSums[heater] = (uint32_t) (thermistorOverheatAdcValue + 0.9) * numThermistorReadingsAveraged;
}
if (coolingFanPin >= 0)
{
// Inverse logic for Duet v0.6 and later; this turns it off
analogWriteDuet(coolingFanPin, (HEAT_ON == 0) ? 255 : 0, true);
}
if (coolingFanRpmPin >= 0)
{
pinModeDuet(coolingFanRpmPin, INPUT_PULLUP, 1500);
}
InitialiseInterrupts();
lastTime = Time();
longWait = lastTime;
}
// Specify which thermistor channel a particular heater uses
void Platform::SetThermistorNumber(size_t heater, size_t thermistor)
//pre(heater < HEATERS && thermistor < HEATERS)
{
heaterAdcChannels[heater] = PinToAdcChannel(tempSensePins[thermistor]);
}
int Platform::GetThermistorNumber(size_t heater) const
{
for (size_t thermistor = 0; thermistor < HEATERS; ++thermistor)
{
if (heaterAdcChannels[heater] == PinToAdcChannel(tempSensePins[thermistor]))
{
return thermistor;
}
}
return -1;
}
void Platform::SetSlowestDrive()
{
slowestDrive = 0;
for(int8_t drive = 1; drive < DRIVES; drive++)
{
if(InstantDv(drive) < InstantDv(slowestDrive))
slowestDrive = drive;
}
}
void Platform::InitZProbe()
{
zProbeOnFilter.Init(0);
zProbeOffFilter.Init(0);
// zpl-2015-01-15: Don't introduce new Z-probe types for different modulation pin configurations; use 'G31 R' instead
if (nvData.zProbeType >= 1)
{
zProbeModulationPin = (nvData.zProbeChannel == 1) ? Z_PROBE_MOD_PIN07 : Z_PROBE_MOD_PIN;
pinMode(zProbeModulationPin, OUTPUT);
digitalWrite(zProbeModulationPin, (nvData.zProbeType <= 2) ? HIGH : LOW); // enable the IR LED or alternate sensor
}
}
int Platform::GetRawZHeight() const
{
return (nvData.zProbeType != 0) ? analogRead(zProbePin) : 0;
}
// Return the Z probe data.
// The ADC readings are 12 bits, so we convert them to 10-bit readings for compatibility with the old firmware.
int Platform::ZProbe() const
{
if (zProbeOnFilter.IsValid() && zProbeOffFilter.IsValid())
{
switch (nvData.zProbeType)
{
case 1:
case 3:
// Simple IR sensor, or direct-mode ultrasonic sensor
return (int) ((zProbeOnFilter.GetSum() + zProbeOffFilter.GetSum()) / (8 * numZProbeReadingsAveraged));
case 2:
// Modulated IR sensor. We assume that zProbeOnFilter and zprobeOffFilter average the same number of readings.
// Because of noise, it is possible to get a negative reading, so allow for this.
return (int) (((int32_t) zProbeOnFilter.GetSum() - (int32_t) zProbeOffFilter.GetSum())
/ (4 * numZProbeReadingsAveraged));
default:
break;
}
}
return 0; // Z probe not turned on or not initialised yet
}
// Return the Z probe secondary values.
int Platform::GetZProbeSecondaryValues(int& v1, int& v2)
{
if (zProbeOnFilter.IsValid() && zProbeOffFilter.IsValid())
{
switch (nvData.zProbeType)
{
case 2: // modulated IR sensor
v1 = (int) (zProbeOnFilter.GetSum() / (4 * numZProbeReadingsAveraged)); // pass back the reading with IR turned on
return 1;
default:
break;
}
}
return 0;
}
int Platform::GetZProbeType() const
{
return nvData.zProbeType;
}
int Platform::GetZProbeChannel() const
{
return nvData.zProbeChannel;
}
void Platform::SetZProbeAxes(const bool axes[AXES])
{
for(int axis=0; axis<AXES; axis++)
{
nvData.zProbeAxes[axis] = axes[axis];
}
if (autoSaveEnabled)
{
WriteNvData();
}
}
void Platform::GetZProbeAxes(bool (&axes)[AXES])
{
for(int axis=0; axis<AXES; axis++)
{
axes[axis] = nvData.zProbeAxes[axis];
}
}
float Platform::ZProbeStopHeight() const
{
switch (nvData.zProbeType)
{
case 0:
return nvData.switchZProbeParameters.GetStopHeight(GetTemperature(0));
case 1:
case 2:
return nvData.irZProbeParameters.GetStopHeight(GetTemperature(0));
case 3:
return nvData.alternateZProbeParameters.GetStopHeight(GetTemperature(0));
default:
return 0;
}
}
void Platform::SetZProbeType(int pt)
{
int newZProbeType = (pt >= 0 && pt <= 3) ? pt : 0;
if (newZProbeType != nvData.zProbeType)
{
nvData.zProbeType = newZProbeType;
if (autoSaveEnabled)
{
WriteNvData();
}
}
InitZProbe();
}
void Platform::SetZProbeChannel(int channel)
{
switch (channel)
{
case 1:
zProbeModulationPin = Z_PROBE_MOD_PIN07;
break;
default:
zProbeModulationPin = Z_PROBE_MOD_PIN;
channel = 0;
}
if (channel != nvData.zProbeChannel)
{
nvData.zProbeChannel = channel;
if (autoSaveEnabled)
{
WriteNvData();
}
}
}
bool Platform::GetZProbeParameters(struct ZProbeParameters& params) const
{
switch (nvData.zProbeType)
{
case 0:
params = nvData.switchZProbeParameters;
return true;
case 1:
case 2:
params = nvData.irZProbeParameters;
return true;
case 3:
params = nvData.alternateZProbeParameters;
return true;
default:
return false;
}
}
bool Platform::SetZProbeParameters(const struct ZProbeParameters& params)
{
switch (nvData.zProbeType)
{
case 0:
if (nvData.switchZProbeParameters != params)
{
nvData.switchZProbeParameters = params;
if (autoSaveEnabled)
{
WriteNvData();
}
}
return true;
case 1:
case 2:
if (nvData.irZProbeParameters != params)
{
nvData.irZProbeParameters = params;
if (autoSaveEnabled)
{
WriteNvData();
}
}
return true;
case 3:
if (nvData.alternateZProbeParameters != params)
{
nvData.alternateZProbeParameters = params;
if (autoSaveEnabled)
{
WriteNvData();
}
}
return true;
default:
return false;
}
}
// Return true if we must home X and Y before we home Z (i.e. we are using a bed probe)
bool Platform::MustHomeXYBeforeZ() const
{
return nvData.zProbeType != 0;
}
void Platform::ResetNvData()
{
nvData.compatibility = me;
ARRAY_INIT(nvData.ipAddress, IP_ADDRESS);
ARRAY_INIT(nvData.netMask, NET_MASK);
ARRAY_INIT(nvData.gateWay, GATE_WAY);
ARRAY_INIT(nvData.macAddress, MAC_ADDRESS);
nvData.zProbeType = 0; // Default is to use the switch
nvData.zProbeChannel = 0; // Ormerods are usually shipped with a Duet v0.6
ARRAY_INIT(nvData.zProbeAxes, Z_PROBE_AXES);
nvData.switchZProbeParameters.Init(0.0);
nvData.irZProbeParameters.Init(Z_PROBE_STOP_HEIGHT);
nvData.alternateZProbeParameters.Init(Z_PROBE_STOP_HEIGHT);
for (size_t i = 0; i < HEATERS; ++i)
{
PidParameters& pp = nvData.pidParams[i];
pp.thermistorSeriesR = defaultThermistorSeriesRs[i];
pp.SetThermistorR25AndBeta(defaultThermistor25RS[i], defaultThermistorBetas[i]);
pp.kI = defaultPidKis[i];
pp.kD = defaultPidKds[i];
pp.kP = defaultPidKps[i];
pp.kT = defaultPidKts[i];
pp.kS = defaultPidKss[i];
pp.fullBand = defaultFullBands[i];
pp.pidMin = defaultPidMins[i];
pp.pidMax = defaultPidMaxes[i];
pp.adcLowOffset = pp.adcHighOffset = 0.0;
}
#ifdef FLASH_SAVE_ENABLED
nvData.magic = FlashData::magicValue;
#endif
}
void Platform::ReadNvData()
{
#ifdef FLASH_SAVE_ENABLED
DueFlashStorage::read(FlashData::nvAddress, &nvData, sizeof(nvData));
if (nvData.magic != FlashData::magicValue)
{
// Nonvolatile data has not been initialized since the firmware was last written, so set up default values
ResetNvData();
// No point in writing it back here
}
#else
Message(BOTH_ERROR_MESSAGE, "Cannot load non-volatile data, because Flash support has been disabled!\n");
#endif
}
void Platform::WriteNvData()
{
#ifdef FLASH_SAVE_ENABLED
DueFlashStorage::write(FlashData::nvAddress, &nvData, sizeof(nvData));
#else
Message(BOTH_ERROR_MESSAGE, "Cannot write non-volatile data, because Flash support has been disabled!\n");
#endif
}
void Platform::SetAutoSave(bool enabled)
{
#ifdef FLASH_SAVE_ENABLED
autoSaveEnabled = enabled;
#else
Message(BOTH_ERROR_MESSAGE, "Cannot enable auto-save, because Flash support has been disabled!\n");
#endif
}
// AUX device
void Platform::Beep(int freq, int ms)
{
// Send the beep command to the aux channel. There is no flow control on this port, so it can't block for long.
scratchString.printf("{\"beep_freq\":%d,\"beep_length\":%d}\n", freq, ms);
aux->Write(scratchString.Pointer(), true);
}
// Note: the use of floating point time will cause the resolution to degrade over time.
// For example, 1ms time resolution will only be available for about half an hour from startup.
// Personally, I (dc42) would rather just maintain and provide the time in milliseconds in a uint32_t.
// This would wrap round after about 49 days, but that isn't difficult to handle.
float Platform::Time()
{
unsigned long now = micros();
if (now < lastTimeCall) // Has timer overflowed?
{
addToTime += ((float) ULONG_MAX) * TIME_FROM_REPRAP;
}
lastTimeCall = now;
return addToTime + TIME_FROM_REPRAP * (float) now;
}
void Platform::Exit()
{
Message(BOTH_MESSAGE, "Platform class exited.\n");
active = false;
}
Compatibility Platform::Emulating() const
{
if (nvData.compatibility == reprapFirmware)
return me;
return nvData.compatibility;
}
void Platform::SetEmulating(Compatibility c)
{
if (c != me && c != reprapFirmware && c != marlin)
{
Message(BOTH_ERROR_MESSAGE, "Attempt to emulate unsupported firmware.\n");
return;
}
if (c == reprapFirmware)
{
c = me;
}
if (c != nvData.compatibility)
{
nvData.compatibility = c;
if (autoSaveEnabled)
{
WriteNvData();
}
}
}
void Platform::UpdateNetworkAddress(byte dst[4], const byte src[4])
{
bool changed = false;
for (uint8_t i = 0; i < 4; i++)
{
if (dst[i] != src[i])
{
dst[i] = src[i];
changed = true;
}
}
if (changed && autoSaveEnabled)
{
WriteNvData();
}
}
void Platform::SetIPAddress(byte ip[])
{
UpdateNetworkAddress(nvData.ipAddress, ip);
}
void Platform::SetGateWay(byte gw[])
{
UpdateNetworkAddress(nvData.gateWay, gw);
}
void Platform::SetNetMask(byte nm[])
{
UpdateNetworkAddress(nvData.netMask, nm);
}
void Platform::Spin()
{
if (!active)
return;
if (debugCode == DiagnosticTest::TestSpinLockup)
{
for (;;) {}
}
line->Spin();
aux->Spin();
ClassReport(longWait);
}
void Platform::SoftwareReset(uint16_t reason)
{
if (reason != SoftwareResetReason::user)
{
if (line->inWrite)
{
reason |= SoftwareResetReason::inUsbOutput; // if we are resetting because we are stuck in a Spin function, record whether we are trying to send to USB
}
if (reprap.GetNetwork()->InLwip())
{
reason |= SoftwareResetReason::inLwipSpin;
}
if (aux->inWrite)
{
reason |= SoftwareResetReason::inAuxOutput; // if we are resetting because we are stuck in a Spin function, record whether we are trying to send to aux
}
}
reason |= reprap.GetSpinningModule();
// Record the reason for the software reset
SoftwareResetData temp;
temp.magic = SoftwareResetData::magicValue;
temp.resetReason = reason;
GetStackUsage(NULL, NULL, &temp.neverUsedRam);
// zpl fork usually includes the last-known message as it might provide debug info
if (reason != SoftwareResetReason::user)
{
strncpy(temp.lastMessage, messageString.Pointer(), sizeof(temp.lastMessage) - 1);
temp.lastMessage[sizeof(temp.lastMessage) - 1] = 0;
}
else
{
temp.lastMessage[0] = 0;
}
// Save diagnostics data to Flash and reset the software
DueFlashStorage::write(SoftwareResetData::nvAddress, &temp, sizeof(SoftwareResetData));
rstc_start_software_reset(RSTC);
for(;;) {}
}
//*****************************************************************************************************************
// Interrupts
void TC3_Handler()
{
TC_GetStatus(TC1, 0);
reprap.Interrupt();
}
void TC4_Handler()
{
TC_GetStatus(TC1, 1);
reprap.GetNetwork()->Interrupt();
}
void FanInterrupt()
{
++fanInterruptCount;
if (fanInterruptCount == fanMaxInterruptCount)
{
uint32_t now = micros();
fanInterval = now - fanLastResetTime;
fanLastResetTime = now;
fanInterruptCount = 0;
}
}
void Platform::InitialiseInterrupts()
{
// Timer interrupt for stepper motors
pmc_set_writeprotect(false);
pmc_enable_periph_clk((uint32_t) TC3_IRQn);
TC_Configure(TC1, 0, TC_CMR_WAVE | TC_CMR_WAVSEL_UP_RC | TC_CMR_TCCLKS_TIMER_CLOCK4);
TC1 ->TC_CHANNEL[0].TC_IER = TC_IER_CPCS;
TC1 ->TC_CHANNEL[0].TC_IDR = ~TC_IER_CPCS;
SetInterrupt(STANDBY_INTERRUPT_RATE);
// Timer interrupt to keep the networking timers running (called at 16Hz)
pmc_enable_periph_clk((uint32_t) TC4_IRQn);
TC_Configure(TC1, 1, TC_CMR_WAVE | TC_CMR_WAVSEL_UP_RC | TC_CMR_TCCLKS_TIMER_CLOCK2);
uint32_t rc = VARIANT_MCK/8/16; // 8 because we selected TIMER_CLOCK2 above
TC_SetRA(TC1, 1, rc/2); // 50% high, 50% low
TC_SetRC(TC1, 1, rc);
TC_Start(TC1, 1);
TC1 ->TC_CHANNEL[1].TC_IER = TC_IER_CPCS;
TC1 ->TC_CHANNEL[1].TC_IDR = ~TC_IER_CPCS;
NVIC_EnableIRQ(TC4_IRQn);
// Interrupt for 4-pin PWM fan sense line
attachInterrupt(coolingFanRpmPin, FanInterrupt, FALLING);
// Tick interrupt for ADC conversions
tickState = 0;
currentHeater = 0;
active = true; // this enables the tick interrupt, which keeps the watchdog happy
}
void Platform::SetInterrupt(float s) // Seconds
{
if (s <= 0.0)
{
//NVIC_DisableIRQ(TC3_IRQn);
Message(BOTH_ERROR_MESSAGE, "Negative interrupt!\n");
s = STANDBY_INTERRUPT_RATE;
}
uint32_t rc = (uint32_t)( (((long)(TIME_TO_REPRAP*s))*84l)/128l );
TC_SetRA(TC1, 0, rc/2); //50% high, 50% low
TC_SetRC(TC1, 0, rc);
TC_Start(TC1, 0);
NVIC_EnableIRQ(TC3_IRQn);
}
//void Platform::DisableInterrupts()
//{
// NVIC_DisableIRQ(TC3_IRQn);
/// NVIC_DisableIRQ(TC4_IRQn);
//}
// Process a 1ms tick interrupt
// This function must be kept fast so as not to disturb the stepper timing, so don't do any floating point maths in here.
// This is what we need to do:
// 0. Kick the watchdog.
// 1. Kick off a new ADC conversion.
// 2. Fetch and process the result of the last ADC conversion.
// 3a. If the last ADC conversion was for the Z probe, toggle the modulation output if using a modulated IR sensor.
// 3b. If the last ADC reading was a thermistor reading, check for an over-temperature situation and turn off the heater if necessary.
// We do this here because the usual polling loop sometimes gets stuck trying to send data to the USB port.
//#define TIME_TICK_ISR 1 // define this to store the tick ISR time in errorCodeBits
void Platform::Tick()
{
#ifdef TIME_TICK_ISR
uint32_t now = micros();
#endif
switch (tickState)
{
case 1: // last conversion started was a thermistor
case 3:
{
ThermistorAveragingFilter& currentFilter = const_cast<ThermistorAveragingFilter&>(thermistorFilters[currentHeater]);
currentFilter.ProcessReading(GetAdcReading(heaterAdcChannels[currentHeater]));
StartAdcConversion(zProbeAdcChannel);
if (currentFilter.IsValid())
{
uint32_t sum = currentFilter.GetSum();
if (sum < thermistorOverheatSums[currentHeater] || sum >= adDisconnectedReal * numThermistorReadingsAveraged)
{
// We have an over-temperature or bad reading from this thermistor, so turn off the heater
// NB - the SetHeater function we call does floating point maths, but this is an exceptional situation so we allow it
SetHeater(currentHeater, 0.0);
errorCodeBits |= ErrorBadTemp;
}
}
++currentHeater;
if (currentHeater == HEATERS)
{
currentHeater = 0;
}
}
++tickState;
break;
case 2: // last conversion started was the Z probe, with IR LED on
const_cast<ZProbeAveragingFilter&>(zProbeOnFilter).ProcessReading(GetAdcReading(zProbeAdcChannel));
StartAdcConversion(heaterAdcChannels[currentHeater]); // read a thermistor
if (nvData.zProbeType == 2) // if using a modulated IR sensor
{
digitalWrite(zProbeModulationPin, LOW); // turn off the IR emitter
}
++tickState;
break;
case 4: // last conversion started was the Z probe, with IR LED off if modulation is enabled
const_cast<ZProbeAveragingFilter&>(zProbeOffFilter).ProcessReading(GetAdcReading(zProbeAdcChannel));
// no break
case 0: // this is the state after initialisation, no conversion has been started
default:
{
StartAdcConversion(heaterAdcChannels[currentHeater]); // read a thermistor
if (nvData.zProbeType == 2) // if using a modulated IR sensor
{
digitalWrite(zProbeModulationPin, HIGH); // turn on the IR emitter
}
}
tickState = 1;
break;
}
#ifdef TIME_TICK_ISR
uint32_t now2 = micros();
if (now2 - now > errorCodeBits)
{
errorCodeBits = now2 - now;
}
#endif
}
/*static*/uint16_t Platform::GetAdcReading(adc_channel_num_t chan)
{
uint16_t rslt = (uint16_t) adc_get_channel_value(ADC, chan);
adc_disable_channel(ADC, chan);
return rslt;
}
/*static*/void Platform::StartAdcConversion(adc_channel_num_t chan)
{
adc_enable_channel(ADC, chan);
adc_start(ADC );
}
// Convert an Arduino Due pin number to the corresponding ADC channel number
/*static*/adc_channel_num_t Platform::PinToAdcChannel(int pin)
{
if (pin < A0)
{
pin += A0;
}
return (adc_channel_num_t) (int) g_APinDescription[pin].ulADCChannelNumber;
}
//*************************************************************************************************
// This diagnostics function is the first to be called, so it calls Message to start with.
// All other messages generated by this and other diagnostics functions must call AppendMessage.
void Platform::Diagnostics()
{
Message(BOTH_MESSAGE, "Platform Diagnostics:\n");
// Print memory stats and error codes to USB and copy them to the current webserver reply
const char *ramstart = (char *) 0x20070000;
const struct mallinfo mi = mallinfo();
AppendMessage(BOTH_MESSAGE, "Memory usage:\n");
AppendMessage(BOTH_MESSAGE, "Program static ram used: %d\n", &_end - ramstart);
AppendMessage(BOTH_MESSAGE, "Dynamic ram used: %d\n", mi.uordblks);
AppendMessage(BOTH_MESSAGE, "Recycled dynamic ram: %d\n", mi.fordblks);
size_t currentStack, maxStack, neverUsed;
GetStackUsage(¤tStack, &maxStack, &neverUsed);
AppendMessage(BOTH_MESSAGE, "Current stack ram used: %d\n", currentStack);
AppendMessage(BOTH_MESSAGE, "Maximum stack ram used: %d\n", maxStack);
AppendMessage(BOTH_MESSAGE, "Never used ram: %d\n", neverUsed);
// Show the up time and reason for the last reset
const uint32_t now = (uint32_t)Time(); // get up time in seconds
const char* resetReasons[8] = { "power up", "backup", "watchdog", "software", "external", "?", "?", "?" };
AppendMessage(BOTH_MESSAGE, "Last reset %02d:%02d:%02d ago, cause: %s\n",
(unsigned int)(now/3600), (unsigned int)((now % 3600)/60), (unsigned int)(now % 60),
resetReasons[(REG_RSTC_SR & RSTC_SR_RSTTYP_Msk) >> RSTC_SR_RSTTYP_Pos]);
// Show the error code stored at the last software reset
{
SoftwareResetData temp;
temp.magic = 0;
DueFlashStorage::read(SoftwareResetData::nvAddress, &temp, sizeof(SoftwareResetData));
if (temp.magic == SoftwareResetData::magicValue)
{
AppendMessage(BOTH_MESSAGE, "Last software reset code & available RAM: 0x%04x, %u\n", temp.resetReason, temp.neverUsedRam);
AppendMessage(BOTH_MESSAGE, "Spinning module during software reset: %s\n", moduleName[temp.resetReason & 0x0F]);
if (temp.lastMessage[0])
{
AppendMessage(BOTH_MESSAGE, "Last message before reset: %s", temp.lastMessage); // usually ends with NL
}
}
}
// Show the current error codes
AppendMessage(BOTH_MESSAGE, "Error status: %u\n", errorCodeBits);
// Show the current probe position heights
AppendMessage(BOTH_MESSAGE, "Bed probe heights:");
for (size_t i = 0; i < NUMBER_OF_PROBE_POINTS; ++i)
{
AppendMessage(BOTH_MESSAGE, " %.3f", reprap.GetMove()->ZBedProbePoint(i));
}
AppendMessage(BOTH_MESSAGE, "\n");
// Show the number of free entries in the file table
unsigned int numFreeFiles = 0;
for (size_t i = 0; i < MAX_FILES; i++)
{
if (!files[i]->inUse)
{
++numFreeFiles;
}
}
AppendMessage(BOTH_MESSAGE, "Free file entries: %u\n", numFreeFiles);
// Show the longest write time
AppendMessage(BOTH_MESSAGE, "Longest block write time: %.1fms\n", FileStore::GetAndClearLongestWriteTime());
reprap.Timing();
}
void Platform::DiagnosticTest(int d)
{
switch (d)
{
case DiagnosticTest::TestWatchdog:
SysTick ->CTRL &= ~(SysTick_CTRL_TICKINT_Msk); // disable the system tick interrupt so that we get a watchdog timeout reset
break;
case DiagnosticTest::TestSpinLockup:
debugCode = d; // tell the Spin function to loop
break;
case DiagnosticTest::TestSerialBlock: // write an arbitrary message via debugPrintf()