Welcome to mirror list, hosted at ThFree Co, Russian Federation.

TemperatureSensor.cpp « Heating « src - github.com/Duet3D/RepRapFirmware.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
blob: 74a9c3999e54688f80a838306e4f0667206554f9 (plain)
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
#include "TemperatureSensor.h"
#include "Platform.h"
#include "RepRap.h"

// MAX31855 thermocouple chip
//
// The MAX31855 continuously samples a Type K thermocouple.  When the MAX31855
// is selected via its chip select (CS) pin, it unconditionally writes a 32 bit
// sequence onto the bus.  This sequence is designed such that we need only
// interpret the high 16 bits in order to ascertain the temperature reading and
// whether there a fault condition exists.  The low 16 bits provide the
// MAX31855's cold junction temperature (and thus the board temperature) as
// well as finer detail on any existing fault condition.
//
// The temperature read from the chip is a signed, two's-complement integer.
// As it is a 14 bit value (in units of one-quarter degrees Celsius), we
// convert it to a proper signed 16 bit value by adding two high bits.  The
// high bits added should both be zero if the value is positive (highest bit
// of the 14 bit value is zero), or both be one if the value is negative
// (highest bit of the 14 bit value is one).
//
// Note Bene: there's a Arduino Due sketch floating about the internet which
// gets this wrong and for negative temperatures generates incorrect values.
// E.g, -2047C for what should be -1C; -1798C for what should be -250C.  The
// values of -1C and -250C are shown as examples in Table 4 of the datasheet
// for the MAX21855.)  The incorrect Arduino Due sketch appears in, and may be
// from, the book Arduino Sketches: Tools and Techniques for Programming
// Wizardry, James A. Langbridge, January 12, 2015, John Wiley & Sons.

// Bits  -- Interpretation
// -----    -----------------------------------------------------------------
// 31:18 -- 14 bit, signed thermocouple temperature data.  Units of 0.25 C
//    17 -- Reserved
//    16 -- Fault indicator (1 if fault detected; 0 otherwise)
// 15:04 -- 12 bit, signed cold junction temperature data.  Units of 0.0625 C
//    03 -- Reserved
//    02 -- SCV fault; reads 1 if the thermocouple is shorted to Vcc
//    01 -- SCG fault; reads 1 if the thermocouple is shorted to ground
//    00 --  OC fault; reads 1 if the thermocouple is not connected (open)

// For purposes of setting bit transfer widths and timings, we need to use a
// Peripheral Channel Select (PCS).  Use channel #3 as it is unlikely to be
// used by anything else as the Arduino Due leaves pin 78 unconnected.
//
// No warranty given or implied, use at your own risk.
// dan.newman@mtbaldy.us
// GPL v3

const uint32_t MAX31855_Frequency = 4000000;	// maximum for MAX31855 is 5MHz
const uint32_t MAX31865_Frequency = 4000000;	// maximum for MAX31865 is also 5MHz
const uint32_t MCP3204_Frequency = 1000000;		// maximum for MCP3204 is 1MHz @ 2.7V, will be slightly higher at 3.3V

// SPI modes:
// If the inactive state of SCL is LOW (CPOL = 0) (in the case of the MAX31865, this is sampled on the falling edge of CS):
// The MAX31855 sets up the first data bit after the falling edge of CLK, and changes the data on each falling clock edge.
// So the SAM needs to sample data on the rising clock edge. This requires NCPHA = 1.
// The MAX31865 changes data after the rising edge of CLK, and samples input data on the falling edge.
// This requires NCPHA = 0.
// The MCP3204 samples input data on the rising edge and changes the output data on the rising edge.

const uint8_t MAX31855_SpiMode = SPI_MODE_0;
const uint8_t MAX31865_SpiMode = SPI_MODE_1;
const uint8_t MCP3204_SpiMode = SPI_MODE_0;

// Define the minimum interval between readings. The MAX31865 needs 62.5ms in 50Hz filter mode.
const uint32_t MinimumReadInterval = 100;		// minimum interval between reads, in milliseconds

// Table of temperature vs. MAX31865 result for PT100 thermistor, from the MAX31865 datasheet
struct TempTableEntry
{
	int16_t temperature;
	uint16_t adcReading;
};

static const TempTableEntry tempTable[] =
{
	{-30,	7227},
	{-20,	7550},
	{-10,	7871},
	{0,		8192},
	{10,	8512},
	{20,	8830},
	{30,	9148},
	{40,	9465},
	{50,	9781},
	{60,	10096},
	{70,	10410},
	{80,	10723},
	{90,	11035},
	{100,	11346},
	{110,	11657},
	{120,	11966},
	{130,	12274},
	{140,	12582},
	{150,	12888},
	{160,	13194},
	{170,	13498},
	{180,	13802},
	{190,	14104},
	{200,	14406},
	{225,	15156},
	{250,	15901},
	{275,	16639},
	{300,	17371},
	{325,	18098},
	{350,	18818},
	{375,	19533},
	{400,	20242},
	{425,	20945},
	{450,	21642},
	{475,	22333},
	{500,	23018},
	{525,	23697},
	{550,	24370}
};

const size_t NumTempTableEntries = sizeof(tempTable)/sizeof(tempTable[0]);

// Perform the actual hardware initialization for attaching and using this device on the SPI hardware bus.
void TemperatureSensor::InitThermocouple(uint8_t cs)
{
	device.csPin = cs;
	device.spiMode = MAX31855_SpiMode;
	device.clockFrequency = MAX31855_Frequency;
	sspi_master_init(&device, 8);

	lastReadingTime = millis();
	lastResult = TemperatureError::success;
	lastTemperature = 0.0;
}

// Perform the actual hardware initialization for attaching and using this device on the SPI hardware bus.
void TemperatureSensor::InitRtd(uint8_t cs)
{
	device.csPin = cs;
	device.spiMode = MAX31865_SpiMode;
	device.clockFrequency = MAX31865_Frequency;
	sspi_master_init(&device, 8);

	TemperatureError rslt;
	for (unsigned int i = 0; i < 3; ++i)		// try 3 times
	{
		rslt = TryInitRtd();
		if (rslt == TemperatureError::success)
		{
			break;
		}
		delay(MinimumReadInterval);
	}

	lastReadingTime = millis();
	lastResult = rslt;
	lastTemperature = 0.0;

	if (rslt != TemperatureError::success)
	{
		reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "Error: failed to initialise RTD: %s\n", TemperatureErrorString(rslt));
	}
}

// Try to initialise the RTD
TemperatureError TemperatureSensor::TryInitRtd() const
{
	// Note that to get the MAX31865 to do continuous conversions, we need to set the bias bit as well as the continuous-conversion bit
	static const uint8_t modeData[2] = { 0x80, 0xC3 };		// write register 0, bias on, auto conversion, clear errors, 50Hz
	uint32_t rawVal;
	TemperatureError sts = DoSpiTransaction(modeData, 2, rawVal);

	if (sts == TemperatureError::success)
	{
		static const uint8_t readData[2] = { 0x00, 0x00 };		// read register 0
		sts = DoSpiTransaction(readData, 2, rawVal);
	}

	//debugPrintf("Status %d data %04x\n", (int)sts, rawVal);
	return (sts == TemperatureError::success && (uint8_t)rawVal != 0xC1)
				? TemperatureError::badResponse
				: sts;
}

// Initialise the linear ADC
void TemperatureSensor::InitLinearAdc(uint8_t cs)
{
	device.csPin = cs;
	device.spiMode = MCP3204_SpiMode;
	device.clockFrequency = MCP3204_Frequency;
	sspi_master_init(&device, 8);

	for (unsigned int i = 0; i < 3; ++i)		// try 3 times
	{
		TryGetLinearAdcTemperature();
		if (lastResult == TemperatureError::success)
		{
			break;
		}
		delay(MinimumReadInterval);
	}

	lastReadingTime = millis();

	if (lastResult != TemperatureError::success)
	{
		reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "Error: failed to initialise daughter board ADC: %s\n", TemperatureErrorString(lastResult));
	}

}

TemperatureError TemperatureSensor::GetThermocoupleTemperature(float& t)
{
	if (inInterrupt() || millis() - lastReadingTime < MinimumReadInterval)
	{
		t = lastTemperature;
	}
	else
	{
		uint32_t rawVal;
		TemperatureError sts = DoSpiTransaction(nullptr, 4, rawVal);
		if (sts != TemperatureError::success)
		{
			lastResult = sts;
		}
		else
		{
			lastReadingTime = millis();

			if ((rawVal & 0x00020008) != 0)
			{
				// These two bits should always read 0. Likely the entire read was 0xFF 0xFF which is not uncommon when first powering up
				lastResult = TemperatureError::ioError;
			}
			else if ((rawVal & 0x00010007) != 0)		// check the fault bits
			{
				// Check for three more types of bad reads as we set the response code:
				//   1. A read in which the fault indicator bit (16) is set but the fault reason bits (0:2) are all clear;
				//   2. A read in which the fault indicator bit (16) is clear, but one or more of the fault reason bits (0:2) are set; and,
				//   3. A read in which more than one of the fault reason bits (0:1) are set.
				if ((rawVal & 0x00010000) == 0)
				{
					// One or more fault reason bits are set but the fault indicator bit is clear
					lastResult = TemperatureError::ioError;
				}
				else
				{
					// At this point we are assured that bit 16 (fault indicator) is set and that at least one of the fault reason bits (0:2) are set.
					// We now need to ensure that only one fault reason bit is set.
					uint8_t nbits = 0;
					if (rawVal & 0x01)
					{
						// Open Circuit
						++nbits;
						lastResult = TemperatureError::openCircuit;
					}
					if (rawVal & 0x02)
					{
						// Short to ground;
						++nbits;
						lastResult = TemperatureError::shortToGround;
					}
					if (rawVal && 0x04)
					{
						// Short to Vcc
						++nbits;
						lastResult = TemperatureError::shortToVcc;
					}

					if (nbits != 1)
					{
						// Fault indicator was set but a fault reason was not set (nbits == 0) or too many fault reason bits were set (nbits > 1).
						// Assume that a communication error with the MAX31855 has occurred.
						lastResult = TemperatureError::ioError;
					}
				}
			}
			else
			{
				rawVal >>= 18;							// shift the 14-bit temperature data to the bottom of the word
				rawVal |= (0 - (rawVal & 0x2000));		// sign-extend the sign bit

				// And convert to from units of 1/4C to 1C
				t = lastTemperature = (float)(0.25 * (float)(int32_t)rawVal);
				lastResult = TemperatureError::success;
			}
		}
	}
	return lastResult;
}

TemperatureError TemperatureSensor::GetRtdTemperature(float& t)
{
	if (inInterrupt() || millis() - lastReadingTime < MinimumReadInterval)
	{
		t = lastTemperature;
	}
	else
	{
		static const uint8_t dataOut[4] = {0, 55, 55, 55};		// read registers 0 (control), 1 (MSB) and 2 (LSB)
		uint32_t rawVal;
		TemperatureError sts = DoSpiTransaction(dataOut, 4, rawVal);

		if (sts != TemperatureError::success)
		{
			lastResult = sts;
		}
		else
		{
			lastReadingTime = millis();
			if (((rawVal & 0x00C10000) != 0xC10000)
#if 0
					// We no longer check the error status bit, because it seems to be impossible to clear it once it has been set.
					// Perhaps we would need to exit continuous reading mode to do so, and then re-enable it afterwards. But this would
					// take to long.
#else
					|| (rawVal & 1) != 0
#endif
					)
			{
				// Either the continuous conversion bit has got cleared, or the fault bit has been set
				TryInitRtd();
				lastResult = TemperatureError::hardwareError;
			}
			else
			{
				uint16_t adcVal = (rawVal >> 1) & 0x7FFF;

				// Formally-verified binary search routine, adapted from one of the eCv examples
				size_t low = 0u, high = NumTempTableEntries;
				while (high > low)
				keep(low <= high; high <= NumTempTableEntries)
				keep(low == 0u || tempTable[low - 1u].adcReading < adcVal)
				keep(high == NumTempTableEntries || adcVal <= tempTable[high].adcReading)
				decrease(high - low)
				{
					size_t mid = (high - low)/2u + low;			// get the mid point, avoiding arithmetic overflow
					if (adcVal <= tempTable[mid].adcReading)
					{
						high = mid;
					}
					else
					{
						low = mid + 1u;
					}
				}
				assert(low <= NumTempTableEntries);
				assert(low == 0 || tempTable[low - 1] < adcVal);
				assert(low == NumTempTableEntries || adcVal <= tempTable[low]);

				if (low == 0)									// if off the bottom of the table
				{
					lastResult = TemperatureError::shortCircuit;
				}
				else  if (low >= NumTempTableEntries)					// if off the top of the table
				{
					lastResult = TemperatureError::openCircuit;
				}
				else
				{
					const float interpolationFraction = (float)(adcVal - tempTable[low - 1].adcReading)/(float)(tempTable[low].adcReading - tempTable[low - 1].adcReading);
					t = lastTemperature = ((float)(tempTable[low].temperature - tempTable[low - 1].temperature) * interpolationFraction)
							+ (float)tempTable[low - 1].temperature;
					//debugPrintf("raw %u low %u interp %f temp %f\n", adcVal, low, interpolationFraction, *t);
					lastResult = TemperatureError::success;
				}
			}
		}
	}
	return lastResult;
}

TemperatureError TemperatureSensor::GetLinearAdcTemperature(float& t)
{
	if (!inInterrupt() && millis() - lastReadingTime >= MinimumReadInterval)
	{
		TryGetLinearAdcTemperature();
	}

	t = lastTemperature;
	return lastResult;
}

// Try to get a temperature reading from the linear ADC by doing an SPI transaction
void TemperatureSensor::TryGetLinearAdcTemperature()
{
	// The MCP3204 waits for a high input input bit before it does anything. Call this clock 1.
	// The next input bit it high for single-ended operation, low for differential. This is clock 2.
	// The next 3 input bits are the channel selection bits. These are clocks 3..5.
	// Clock 6 produces a null bit on its trailing edge, which is read by the processor on clock 7.
	// Clocks 7..18 produce data bits B11..B0 on their trailing edges, which are read by the MCU on the leading edges of clocks 8-19.
	// If we supply further clocks, then clocks 18..29 are the same data but LSB first, omitting bit 0.
	// Clocks 30 onwards will be zeros.
	// So we need to use at least 19 clocks. We round this up to 24 clocks, and we check that the extra 5 bits we receive are the 5 least significant data bits in reverse order.

	static const uint8_t adcData[] = { 0xC0, 0x00, 0x00 };		// start bit, single ended, channel 0
	uint32_t rawVal;
	lastResult = DoSpiTransaction(adcData, 3, rawVal);
	//debugPrintf("ADC data %u\n", rawVal);

	if (lastResult == TemperatureError::success)
	{
		const uint32_t adcVal1 = (rawVal >> 5) & ((1 << 13) - 1);
		const uint32_t adcVal2 = ((rawVal & 1) << 5) | ((rawVal & 2) << 3) | ((rawVal & 4) << 1) | ((rawVal & 8) >> 1) | ((rawVal & 16) >> 3) | ((rawVal & 32) >> 5);
		if (adcVal1 >= 4096 || adcVal2 != (adcVal1 & ((1 << 6) - 1)))
		{
			lastResult = TemperatureError::badResponse;
		}
		else
		{
			lastTemperature = MinLinearAdcTemp + (LinearAdcDegCPerCount * (float)adcVal1);
		}
	}
}

// Send and receive 1 to 4 bytes of data and return the result as a single 32-bit word
TemperatureError TemperatureSensor::DoSpiTransaction(const uint8_t dataOut[], size_t nbytes, uint32_t& rslt) const
{
	if (!sspi_acquire())
	{
		return TemperatureError::busBusy;
	}

	sspi_master_setup_device(&device);
	delayMicroseconds(1);
	sspi_select_device(&device);
	delayMicroseconds(1);

	uint8_t rawBytes[4];
	spi_status_t sts = sspi_transceive_packet(dataOut, rawBytes, nbytes);

	delayMicroseconds(1);
	sspi_deselect_device(&device);
	delayMicroseconds(1);

	sspi_release();

	if (sts != SPI_OK)
	{
		return TemperatureError::timeout;
	}

	rslt = rawBytes[0];
	for (size_t i = 1; i < nbytes; ++i)
	{
		rslt <<= 8;
		rslt |= rawBytes[i];
	}

	return TemperatureError::success;
}

// End