aboutsummaryrefslogtreecommitdiffstats
diff options
context:
space:
mode:
-rw-r--r--config/example-extras.cfg32
-rw-r--r--config/example.cfg5
-rw-r--r--klippy/extras/spi_temperature.py350
-rw-r--r--klippy/heater.py1
-rw-r--r--src/Makefile2
-rw-r--r--src/spicmds.c9
-rw-r--r--src/spicmds.h10
-rw-r--r--src/thermocouple.c178
8 files changed, 583 insertions, 4 deletions
diff --git a/config/example-extras.cfg b/config/example-extras.cfg
index e6c0adae..285006e4 100644
--- a/config/example-extras.cfg
+++ b/config/example-extras.cfg
@@ -631,6 +631,38 @@
# measurements must be provided.
+# MAXxxxxx serial peripheral interface (SPI) temperature based
+# sensors. The following parameters are available in heater sections
+# that use one of these sensor types.
+#[extruder]
+# See the "extruder" section in example.cfg for a description of
+# heater parameters. The parameters below describe sensor parameters.
+#sensor_type:
+# One of "MAX6675", "MAX31855", "MAX31856", or "MAX31865".
+#spi_mode:
+# The SPI mode to use when communicating with the chip. This
+# parameter must be provided.
+#spi_speed:
+# The SPI speed (in hz) to use when communicating with the chip.
+# This parameter must be provided.
+#sensor_pin:
+# The chip select line for the sensor chip. This parameter must be
+# provided.
+#tc_type: K
+#tc_use_50Hz_filter: False
+#tc_averaging_count: 1
+# The above parameters control the sensor parameters of MAX31856
+# chips. The defaults for each parameter are next to the parameter
+# name in the above list.
+#rtd_nominal_r: 100
+#rtd_reference_r: 430
+#rtd_num_of_wires: 2
+#rtd_use_50Hz_filter: False
+# The above parameters control the sensor parameters of MAX31865
+# chips. The defaults for each parameter are next to the parameter
+# name in the above list.
+
+
# G-Code macros (one may define any number of sections with a
# "gcode_macro" prefix).
#[gcode_macro my_cmd]
diff --git a/config/example.cfg b/config/example.cfg
index 025f6b71..636b1095 100644
--- a/config/example.cfg
+++ b/config/example.cfg
@@ -147,8 +147,9 @@ heater_pin: ar10
sensor_type: EPCOS 100K B57560G104F
# Type of sensor - this may be "EPCOS 100K B57560G104F", "ATC
# Semitec 104GT-2", "NTC 100K beta 3950", "Honeywell 100K
-# 135-104LAG-J01", "NTC 100K MGB18-104F39050L32", "AD595", or "PT100
-# INA826". Additional sensor types may be available - see the
+# 135-104LAG-J01", "NTC 100K MGB18-104F39050L32", "AD595", "PT100
+# INA826", "MAX6675", "MAX31855", "MAX31856", or "MAX31865".
+# Additional sensor types may be available - see the
# example-extras.cfg file for details. This parameter must be
# provided.
sensor_pin: analog13
diff --git a/klippy/extras/spi_temperature.py b/klippy/extras/spi_temperature.py
new file mode 100644
index 00000000..96b2d1f6
--- /dev/null
+++ b/klippy/extras/spi_temperature.py
@@ -0,0 +1,350 @@
+# Support for common SPI based thermocouple and RTD temperature sensors
+#
+# Copyright (C) 2018 Petri Honkala <cruwaller@gmail.com>
+#
+# This file may be distributed under the terms of the GNU GPLv3 license.
+import math
+
+
+######################################################################
+# SensorBase
+######################################################################
+
+SAMPLE_TIME_DEFAULT = 0.001
+SAMPLE_COUNT_DEFAULT = 8
+REPORT_TIME_DEFAULT = 0.300
+
+VALID_SPI_SENSORS = {
+ 'MAX6675' : 1, 'MAX31855' : 1,
+ 'MAX31856' : 2,
+ 'MAX31865' : 4
+}
+
+class error(Exception):
+ pass
+
+class SensorBase(object):
+ error = error
+ def __init__(self,
+ config,
+ is_spi = False,
+ sample_time = SAMPLE_TIME_DEFAULT,
+ sample_count = SAMPLE_COUNT_DEFAULT,
+ report_time = REPORT_TIME_DEFAULT):
+ self.is_spi = is_spi
+ self.sample_time = sample_time
+ self.sample_count = sample_count
+ self.report_time = report_time
+ self.min_temp = config.getfloat('min_temp', minval=0., default=0.)
+ self.max_temp = config.getfloat('max_temp', above=self.min_temp)
+ self._callback = None
+ sensor_pin = config.get('sensor_pin')
+ adc_range = [self.calc_adc(self.min_temp),
+ self.calc_adc(self.max_temp)]
+ self.min_sample_value = min(adc_range)
+ self.max_sample_value = max(adc_range)
+ self._report_clock = 0
+ ppins = config.get_printer().lookup_object('pins')
+ if is_spi:
+ pin_params = ppins.lookup_pin('digital_out', sensor_pin)
+ self.mcu = mcu = pin_params['chip']
+ pin = pin_params['pin']
+ # SPI bus configuration
+ spi_oid = mcu.create_oid()
+ spi_mode = config.getint('spi_mode', minval=0, maxval=3)
+ spi_speed = config.getint('spi_speed', minval=0)
+ mcu.add_config_cmd(
+ "config_spi oid=%u bus=%u pin=%s"
+ " mode=%u rate=%u shutdown_msg=" % (
+ spi_oid, 0, pin, spi_mode, spi_speed))
+ config_cmd = "".join("%02x" % b for b in self.get_configs())
+ mcu.add_config_cmd("spi_send oid=%u data=%s" % (
+ spi_oid, config_cmd), is_init=True)
+ # Reader chip configuration
+ self.oid = oid = mcu.create_oid()
+ mcu.add_config_cmd(
+ "config_thermocouple oid=%u spi_oid=%u chip_type=%u" % (
+ oid, spi_oid, VALID_SPI_SENSORS[self.chip_type]))
+ mcu.register_msg(self._handle_spi_response,
+ "thermocouple_result", oid)
+ mcu.add_config_object(self)
+ else:
+ self.mcu = ppins.setup_pin('adc', sensor_pin)
+ self.mcu.setup_minmax(
+ sample_time, sample_count,
+ minval=min(adc_range), maxval=max(adc_range))
+ def setup_minmax(self, min_temp, max_temp):
+ pass
+ def setup_callback(self, cb):
+ if self.is_spi:
+ self._callback = cb
+ else:
+ self.mcu.setup_callback(self.report_time, cb)
+ def get_report_time_delta(self):
+ return self.report_time
+ def build_config(self):
+ clock = self.mcu.get_query_slot(self.oid)
+ self._report_clock = self.mcu.seconds_to_clock(self.report_time)
+ self.mcu.add_config_cmd(
+ "query_thermocouple oid=%u clock=%u rest_ticks=%u"
+ " min_value=%u max_value=%u" % (
+ self.oid, clock, self._report_clock,
+ self.min_sample_value, self.max_sample_value))
+ def _handle_spi_response(self, params):
+ last_value = params['value']
+ next_clock = self.mcu.clock32_to_clock64(params['next_clock'])
+ last_read_clock = next_clock - self._report_clock
+ last_read_time = self.mcu.clock_to_print_time(last_read_clock)
+ temp = self.calc_temp(last_value)
+ self.check_faults(params['fault'])
+ if self._callback is not None:
+ self._callback(last_read_time, temp)
+
+
+######################################################################
+# Thermocouples
+######################################################################
+
+MAX31856_CR0_REG = 0x00
+MAX31856_CR0_AUTOCONVERT = 0x80
+MAX31856_CR0_1SHOT = 0x40
+MAX31856_CR0_OCFAULT1 = 0x20
+MAX31856_CR0_OCFAULT0 = 0x10
+MAX31856_CR0_CJ = 0x08
+MAX31856_CR0_FAULT = 0x04
+MAX31856_CR0_FAULTCLR = 0x02
+MAX31856_CR0_FILT50HZ = 0x01
+MAX31856_CR0_FILT60HZ = 0x00
+
+MAX31856_CR1_REG = 0x01
+MAX31856_CR1_AVGSEL1 = 0x00
+MAX31856_CR1_AVGSEL2 = 0x10
+MAX31856_CR1_AVGSEL4 = 0x20
+MAX31856_CR1_AVGSEL8 = 0x30
+MAX31856_CR1_AVGSEL16 = 0x70
+
+MAX31856_MASK_REG = 0x02
+MAX31856_MASK_COLD_JUNCTION_HIGH_FAULT = 0x20
+MAX31856_MASK_COLD_JUNCTION_LOW_FAULT = 0x10
+MAX31856_MASK_THERMOCOUPLE_HIGH_FAULT = 0x08
+MAX31856_MASK_THERMOCOUPLE_LOW_FAULT = 0x04
+MAX31856_MASK_VOLTAGE_UNDER_OVER_FAULT = 0x02
+MAX31856_MASK_THERMOCOUPLE_OPEN_FAULT = 0x01
+
+MAX31856_CJHF_REG = 0x03
+MAX31856_CJLF_REG = 0x04
+MAX31856_LTHFTH_REG = 0x05
+MAX31856_LTHFTL_REG = 0x06
+MAX31856_LTLFTH_REG = 0x07
+MAX31856_LTLFTL_REG = 0x08
+MAX31856_CJTO_REG = 0x09
+MAX31856_CJTH_REG = 0x0A
+MAX31856_CJTL_REG = 0x0B
+MAX31856_LTCBH_REG = 0x0C
+MAX31856_LTCBM_REG = 0x0D
+MAX31856_LTCBL_REG = 0x0E
+
+MAX31856_SR_REG = 0x0F
+MAX31856_FAULT_CJRANGE = 0x80 # Cold Junction out of range
+MAX31856_FAULT_TCRANGE = 0x40 # Thermocouple out of range
+MAX31856_FAULT_CJHIGH = 0x20 # Cold Junction High
+MAX31856_FAULT_CJLOW = 0x10 # Cold Junction Low
+MAX31856_FAULT_TCHIGH = 0x08 # Thermocouple Low
+MAX31856_FAULT_TCLOW = 0x04 # Thermocouple Low
+MAX31856_FAULT_OVUV = 0x02 # Under Over Voltage
+MAX31856_FAULT_OPEN = 0x01
+
+class Thermocouple(SensorBase):
+ def __init__(self, config):
+ self.chip_type = chip_type = config.get('sensor_type')
+ types = {
+ "B" : 0b0000,
+ "E" : 0b0001,
+ "J" : 0b0010,
+ "K" : 0b0011,
+ "N" : 0b0100,
+ "R" : 0b0101,
+ "S" : 0b0110,
+ "T" : 0b0111,
+ }
+ self.tc_type = config.getchoice('tc_type', types, default="K")
+ self.use_50Hz_filter = config.getboolean('tc_use_50Hz_filter', False)
+ averages = {
+ "1" : MAX31856_CR1_AVGSEL1,
+ "2" : MAX31856_CR1_AVGSEL2,
+ "4" : MAX31856_CR1_AVGSEL4,
+ "8" : MAX31856_CR1_AVGSEL8,
+ "16" : MAX31856_CR1_AVGSEL16
+ }
+ self.average_count = config.getchoice('tc_averaging_count', averages, "1")
+ if chip_type == "MAX31856":
+ self.val_a = 0.0078125
+ self.scale = 5
+ else:
+ self.val_a = 0.25
+ self.scale = 18
+ SensorBase.__init__(self, config, is_spi = True, sample_count = 1)
+ def _check_faults_simple(self, val):
+ if not self.chip_type == "MAX31856":
+ if val & 0x1:
+ raise self.error("MAX6675/MAX31855 : Open Circuit")
+ if val & 0x2:
+ raise self.error("MAX6675/MAX31855 : Short to GND")
+ if val & 0x4:
+ raise self.error("MAX6675/MAX31855 : Short to Vcc")
+ def check_faults(self, fault):
+ if self.chip_type == "MAX31856":
+ if fault & MAX31856_FAULT_CJRANGE:
+ raise self.error("Max31856: Cold Junction Range Fault")
+ if fault & MAX31856_FAULT_TCRANGE:
+ raise self.error("Max31856: Thermocouple Range Fault")
+ if fault & MAX31856_FAULT_CJHIGH:
+ raise self.error("Max31856: Cold Junction High Fault")
+ if fault & MAX31856_FAULT_CJLOW:
+ raise self.error("Max31856: Cold Junction Low Fault")
+ if fault & MAX31856_FAULT_TCHIGH:
+ raise self.error("Max31856: Thermocouple High Fault")
+ if fault & MAX31856_FAULT_TCLOW:
+ raise self.error("Max31856: Thermocouple Low Fault")
+ if fault & MAX31856_FAULT_OVUV:
+ raise self.error("Max31856: Over/Under Voltage Fault")
+ if fault & MAX31856_FAULT_OPEN:
+ raise self.error("Max31856: Thermocouple Open Fault")
+ def calc_temp(self, adc):
+ self._check_faults_simple(adc)
+ adc = adc >> self.scale
+ # Fix sign bit:
+ if self.chip_type == "MAX31856":
+ if adc & 0x40000:
+ adc = ((adc & 0x3FFFF) + 1) * -1
+ else:
+ if adc & 0x2000:
+ adc = ((adc & 0x1FFF) + 1) * -1
+ temp = self.val_a * adc
+ return temp
+ def calc_adc(self, temp):
+ adc = int ( ( temp / self.val_a ) + 0.5 ) # convert to ADC value
+ adc = adc << self.scale
+ return adc
+ def get_configs(self):
+ cmds = []
+ if self.chip_type == "MAX31856":
+ value = MAX31856_CR0_AUTOCONVERT
+ if self.use_50Hz_filter:
+ value |= MAX31856_CR0_FILT50HZ
+ cmds.append(0x80 + MAX31856_CR0_REG)
+ cmds.append(value)
+
+ value = self.tc_type
+ value |= self.average_count
+ cmds.append(0x80 + MAX31856_CR1_REG)
+ cmds.append(value)
+
+ value = (MAX31856_MASK_VOLTAGE_UNDER_OVER_FAULT |
+ MAX31856_MASK_THERMOCOUPLE_OPEN_FAULT)
+ cmds.append(0x80 + MAX31856_MASK_REG)
+ cmds.append(value)
+ return cmds
+
+
+######################################################################
+# MAX31865 (RTD sensor)
+######################################################################
+
+MAX31865_CONFIG_REG = 0x00
+MAX31865_RTDMSB_REG = 0x01
+MAX31865_RTDLSB_REG = 0x02
+MAX31865_HFAULTMSB_REG = 0x03
+MAX31865_HFAULTLSB_REG = 0x04
+MAX31865_LFAULTMSB_REG = 0x05
+MAX31865_LFAULTLSB_REG = 0x06
+MAX31865_FAULTSTAT_REG = 0x07
+
+MAX31865_CONFIG_BIAS = 0x80
+MAX31865_CONFIG_MODEAUTO = 0x40
+MAX31865_CONFIG_1SHOT = 0x20
+MAX31865_CONFIG_3WIRE = 0x10
+MAX31865_CONFIG_FAULTCLEAR = 0x02
+MAX31865_CONFIG_FILT50HZ = 0x01
+
+MAX31865_FAULT_HIGHTHRESH = 0x80
+MAX31865_FAULT_LOWTHRESH = 0x40
+MAX31865_FAULT_REFINLOW = 0x20
+MAX31865_FAULT_REFINHIGH = 0x10
+MAX31865_FAULT_RTDINLOW = 0x08
+MAX31865_FAULT_OVUV = 0x04
+
+VAL_A = 0.00390830
+VAL_B = 0.0000005775
+VAL_C = -0.00000000000418301
+VAL_ADC_MAX = 32768.0 # 2^15
+
+class RTD(SensorBase):
+ def __init__(self, config):
+ self.chip_type = config.get('sensor_type')
+ self.rtd_nominal_r = config.getint('rtd_nominal_r', 100)
+ self.reference_r = config.getfloat('rtd_reference_r', 430., above=0.)
+ self.num_wires = config.getint('rtd_num_of_wires', 2)
+ self.use_50Hz_filter = config.getboolean('rtd_use_50Hz_filter', False)
+ SensorBase.__init__(self, config, is_spi = True, sample_count = 1)
+ def check_faults(self, fault):
+ if fault & 0x80:
+ raise self.error("Max31865 RTD input is disconnected")
+ if fault & 0x40:
+ raise self.error("Max31865 RTD input is shorted")
+ if fault & 0x20:
+ raise self.error("Max31865 VREF- is greater than 0.85 * VBIAS, FORCE- open")
+ if fault & 0x10:
+ raise self.error("Max31865 VREF- is less than 0.85 * VBIAS, FORCE- open")
+ if fault & 0x08:
+ raise self.error("Max31865 VRTD- is less than 0.85 * VBIAS, FORCE- open")
+ if fault & 0x04:
+ raise self.error("Max31865 Overvoltage or undervoltage fault")
+ if fault & 0x03:
+ raise self.error("Max31865 Unspecified error")
+ def calc_temp(self, adc):
+ adc = adc >> 1 # remove fault bit
+ R_rtd = (self.reference_r * adc) / VAL_ADC_MAX
+ temp = (
+ (( ( -1 * self.rtd_nominal_r ) * VAL_A ) +
+ math.sqrt( ( self.rtd_nominal_r * self.rtd_nominal_r * VAL_A * VAL_A ) -
+ ( 4 * self.rtd_nominal_r * VAL_B * ( self.rtd_nominal_r - R_rtd ) )))
+ / (2 * self.rtd_nominal_r * VAL_B))
+ return temp
+ def calc_adc(self, temp):
+ R_rtd = temp * ( 2 * self.rtd_nominal_r * VAL_B )
+ R_rtd = math.pow( ( R_rtd + ( self.rtd_nominal_r * VAL_A ) ), 2)
+ R_rtd = -1 * ( R_rtd - ( self.rtd_nominal_r * self.rtd_nominal_r * VAL_A * VAL_A ) )
+ R_rtd = R_rtd / ( 4 * self.rtd_nominal_r * VAL_B )
+ R_rtd = ( -1 * R_rtd ) + self.rtd_nominal_r
+ adc = int ( ( ( R_rtd * VAL_ADC_MAX ) / self.reference_r) + 0.5 )
+ adc = adc << 1 # Add fault bit
+ return adc
+ def get_configs(self):
+ value = (MAX31865_CONFIG_BIAS |
+ MAX31865_CONFIG_MODEAUTO |
+ MAX31865_CONFIG_FAULTCLEAR)
+ if self.use_50Hz_filter:
+ value |= MAX31865_CONFIG_FILT50HZ
+ if self.num_wires == 3:
+ value |= MAX31865_CONFIG_3WIRE
+ cmd = 0x80 + MAX31865_CONFIG_REG
+ return [cmd, value]
+
+
+######################################################################
+# Sensor registration
+######################################################################
+
+Sensors = {
+ "MAX6675": Thermocouple,
+ "MAX31855": Thermocouple,
+ "MAX31856": Thermocouple,
+ "MAX31865": RTD,
+}
+
+def load_config(config):
+ # Register sensors
+ pheater = config.get_printer().lookup_object("heater")
+ for name, klass in Sensors.items():
+ pheater.add_sensor(name, klass)
diff --git a/klippy/heater.py b/klippy/heater.py
index 919e1088..ee27f72e 100644
--- a/klippy/heater.py
+++ b/klippy/heater.py
@@ -243,6 +243,7 @@ class PrinterHeaters:
def setup_sensor(self, config):
self.printer.try_load_module(config, "thermistor")
self.printer.try_load_module(config, "adc_temperature")
+ self.printer.try_load_module(config, "spi_temperature")
sensor_type = config.get('sensor_type')
if sensor_type not in self.sensors:
raise self.printer.config_error("Unknown temperature sensor '%s'" % (
diff --git a/src/Makefile b/src/Makefile
index 22db35ea..f74b303a 100644
--- a/src/Makefile
+++ b/src/Makefile
@@ -3,6 +3,6 @@
src-y += sched.c command.c basecmd.c debugcmds.c
src-$(CONFIG_HAVE_GPIO) += gpiocmds.c stepper.c endstop.c
src-$(CONFIG_HAVE_GPIO_ADC) += adccmds.c
-src-$(CONFIG_HAVE_GPIO_SPI) += spicmds.c
+src-$(CONFIG_HAVE_GPIO_SPI) += spicmds.c thermocouple.c
src-$(CONFIG_HAVE_GPIO_HARD_PWM) += pwmcmds.c
src-$(CONFIG_HAVE_USER_INTERFACE) += lcd_st7920.c lcd_hd44780.c buttons.c
diff --git a/src/spicmds.c b/src/spicmds.c
index ebbe8a87..5af6dafc 100644
--- a/src/spicmds.c
+++ b/src/spicmds.c
@@ -9,6 +9,7 @@
#include "basecmd.h" // oid_alloc
#include "command.h" // DECL_COMMAND
#include "sched.h" // DECL_SHUTDOWN
+#include "spicmds.h" // spidev_transfer
struct spidev_s {
struct spi_config spi_config;
@@ -53,7 +54,13 @@ DECL_COMMAND(command_config_spi_without_cs,
"config_spi_without_cs oid=%c bus=%u mode=%u rate=%u"
" shutdown_msg=%*s");
-static void
+struct spidev_s *
+spidev_oid_lookup(uint8_t oid)
+{
+ return oid_lookup(oid, command_config_spi);
+}
+
+void
spidev_transfer(struct spidev_s *spi, uint8_t receive_data
, uint8_t data_len, uint8_t *data)
{
diff --git a/src/spicmds.h b/src/spicmds.h
new file mode 100644
index 00000000..dee50665
--- /dev/null
+++ b/src/spicmds.h
@@ -0,0 +1,10 @@
+#ifndef __SPICMDS_H
+#define __SPICMDS_H
+
+#include <stdint.h> // uint8_t
+
+struct spidev_s *spidev_oid_lookup(uint8_t oid);
+void spidev_transfer(struct spidev_s *spi, uint8_t receive_data
+ , uint8_t data_len, uint8_t *data);
+
+#endif // stepper.h
diff --git a/src/thermocouple.c b/src/thermocouple.c
new file mode 100644
index 00000000..5f4f7bb6
--- /dev/null
+++ b/src/thermocouple.c
@@ -0,0 +1,178 @@
+// Basic support for common SPI controlled thermocouple chips
+//
+// Copyright (C) 2018 Petri Honkala <cruwaller@gmail.com>
+// Copyright (C) 2018 Kevin O'Connor <kevin@koconnor.net>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include <string.h> // memcpy
+#include "board/irq.h" // irq_disable
+#include "basecmd.h" // oid_alloc
+#include "byteorder.h" // be32_to_cpu
+#include "command.h" // DECL_COMMAND
+#include "sched.h" // DECL_TASK
+#include "spicmds.h" // spidev_transfer
+
+enum {
+ TS_CHIP_MAX31855 = 1 << 0,
+ TS_CHIP_MAX31856 = 1 << 1,
+ TS_CHIP_MAX31865 = 1 << 2
+};
+
+struct thermocouple_spi {
+ struct timer timer;
+ uint32_t rest_time;
+ uint32_t min_value; // Min allowed ADC value
+ uint32_t max_value; // Max allowed ADC value
+ struct spidev_s *spi;
+ uint8_t chip_type, flags;
+};
+
+enum {
+ TS_PENDING = 1,
+};
+
+static struct task_wake thermocouple_wake;
+
+static uint_fast8_t thermocouple_event(struct timer *timer) {
+ struct thermocouple_spi *spi = container_of(
+ timer, struct thermocouple_spi, timer);
+ // Trigger task to read and send results
+ sched_wake_task(&thermocouple_wake);
+ spi->flags |= TS_PENDING;
+ spi->timer.waketime += spi->rest_time;
+ return SF_RESCHEDULE;
+}
+
+void
+command_config_thermocouple(uint32_t *args)
+{
+ uint8_t chip_type = args[2];
+ if (chip_type > TS_CHIP_MAX31865 || !chip_type)
+ shutdown("Invalid thermocouple chip type");
+ struct thermocouple_spi *spi = oid_alloc(
+ args[0], command_config_thermocouple, sizeof(*spi));
+ spi->timer.func = thermocouple_event;
+ spi->spi = spidev_oid_lookup(args[1]);
+ spi->chip_type = chip_type;
+}
+DECL_COMMAND(command_config_thermocouple,
+ "config_thermocouple oid=%c spi_oid=%c chip_type=%c");
+
+void
+command_query_thermocouple(uint32_t *args)
+{
+ struct thermocouple_spi *spi = oid_lookup(
+ args[0], command_config_thermocouple);
+
+ sched_del_timer(&spi->timer);
+ spi->timer.waketime = args[1];
+ if (! spi->timer.waketime)
+ return;
+ spi->rest_time = args[2];
+ spi->min_value = args[3];
+ spi->max_value = args[4];
+ sched_add_timer(&spi->timer);
+}
+DECL_COMMAND(command_query_thermocouple,
+ "query_thermocouple oid=%c clock=%u rest_ticks=%u"
+ " min_value=%u max_value=%u");
+
+static void
+thermocouple_respond(struct thermocouple_spi *spi, uint32_t next_begin_time
+ , uint32_t value, uint8_t fault, uint8_t oid)
+{
+ /* check the result and stop if below or above allowed range */
+ if (value < spi->min_value || value > spi->max_value) {
+ try_shutdown("Thermocouple ADC out of range");
+ }
+ sendf("thermocouple_result oid=%c next_clock=%u value=%u fault=%c",
+ oid, next_begin_time, value, fault);
+}
+
+/* Logic of thermocouple K readers MAX6675 and MAX31855 are same */
+static void
+thermocouple_handle_max31855(struct thermocouple_spi *spi
+ , uint32_t next_begin_time, uint8_t oid)
+{
+ uint8_t msg[4] = { 0x00, 0x00, 0x00, 0x00 };
+ spidev_transfer(spi->spi, 1, sizeof(msg), msg);
+ uint32_t value;
+ memcpy(&value, msg, sizeof(value));
+ value = be32_to_cpu(value);
+ thermocouple_respond(spi, next_begin_time, value, 0, oid);
+ // Kill after data send, host decode an error
+ if (value & 0x04)
+ try_shutdown("Thermocouple reader fault");
+}
+
+#define MAX31856_LTCBH_REG 0x0C
+#define MAX31856_SR_REG 0x0F
+
+static void
+thermocouple_handle_max31856(struct thermocouple_spi *spi
+ , uint32_t next_begin_time, uint8_t oid)
+{
+ uint8_t msg[4] = { MAX31856_LTCBH_REG, 0x00, 0x00, 0x00 };
+ spidev_transfer(spi->spi, 1, sizeof(msg), msg);
+ uint32_t value;
+ memcpy(&value, msg, sizeof(value));
+ value = be32_to_cpu(value) & 0x00ffffff;
+ // Read faults
+ msg[0] = MAX31856_SR_REG;
+ msg[1] = 0x00;
+ spidev_transfer(spi->spi, 1, 2, msg);
+ thermocouple_respond(spi, next_begin_time, value, msg[1], oid);
+}
+
+#define MAX31865_RTDMSB_REG 0x01
+#define MAX31865_FAULTSTAT_REG 0x07
+
+static void
+thermocouple_handle_max31865(struct thermocouple_spi *spi
+ , uint32_t next_begin_time, uint8_t oid)
+{
+ uint8_t msg[4] = { MAX31865_RTDMSB_REG, 0x00, 0x00, 0x00 };
+ spidev_transfer(spi->spi, 1, 3, msg);
+ uint32_t value;
+ memcpy(&value, msg, sizeof(value));
+ value = (be32_to_cpu(value) >> 8) & 0xffff;
+ // Read faults
+ msg[0] = MAX31865_FAULTSTAT_REG;
+ msg[1] = 0x00;
+ spidev_transfer(spi->spi, 1, 2, msg);
+ thermocouple_respond(spi, next_begin_time, value, msg[1], oid);
+ // Kill after data send, host decode an error
+ if (value & 0x0001)
+ try_shutdown("Thermocouple reader fault");
+}
+
+// task to read thermocouple and send response
+void
+thermocouple_task(void)
+{
+ if (!sched_check_wake(&thermocouple_wake))
+ return;
+ uint8_t oid;
+ struct thermocouple_spi *spi;
+ foreach_oid(oid, spi, command_config_thermocouple) {
+ if (!(spi->flags & TS_PENDING))
+ continue;
+ irq_disable();
+ uint32_t next_begin_time = spi->timer.waketime;
+ spi->flags &= ~TS_PENDING;
+ irq_enable();
+ switch (spi->chip_type) {
+ case TS_CHIP_MAX31855:
+ thermocouple_handle_max31855(spi, next_begin_time, oid);
+ break;
+ case TS_CHIP_MAX31856:
+ thermocouple_handle_max31856(spi, next_begin_time, oid);
+ break;
+ case TS_CHIP_MAX31865:
+ thermocouple_handle_max31865(spi, next_begin_time, oid);
+ break;
+ }
+ }
+}
+DECL_TASK(thermocouple_task);