From c3b64760d482edd3f4a4250547779d3c4de2bcab Mon Sep 17 00:00:00 2001 From: budulinek Date: Thu, 5 Oct 2023 00:25:58 +0200 Subject: [PATCH] non-blocking --- Adafruit_MAX31865.cpp | 371 ------------------ Adafruit_MAX31865.h | 116 ------ MAX31865_NonBlocking.cpp | 241 ++++++++++++ MAX31865_NonBlocking.h | 325 +++++++++++++++ README.md | 30 +- .../MAX31865_Continuous.ino | 87 ++++ examples/MAX31865_Single/MAX31865_Single.ino | 140 +++++++ examples/max31865/max31865.ino | 74 ---- library.properties | 10 - 9 files changed, 816 insertions(+), 578 deletions(-) delete mode 100644 Adafruit_MAX31865.cpp delete mode 100644 Adafruit_MAX31865.h create mode 100644 MAX31865_NonBlocking.cpp create mode 100644 MAX31865_NonBlocking.h create mode 100644 examples/MAX31865_Continuous/MAX31865_Continuous.ino create mode 100644 examples/MAX31865_Single/MAX31865_Single.ino delete mode 100644 examples/max31865/max31865.ino delete mode 100644 library.properties diff --git a/Adafruit_MAX31865.cpp b/Adafruit_MAX31865.cpp deleted file mode 100644 index c663ceb..0000000 --- a/Adafruit_MAX31865.cpp +++ /dev/null @@ -1,371 +0,0 @@ -/*************************************************** - This is a library for the Adafruit PT100/P1000 RTD Sensor w/MAX31865 - - Designed specifically to work with the Adafruit RTD Sensor - ----> https://www.adafruit.com/products/3328 - - This sensor uses SPI to communicate, 4 pins are required to - interface - Adafruit invests time and resources providing this open source code, - please support Adafruit and open-source hardware by purchasing - products from Adafruit! - - Written by Limor Fried/Ladyada for Adafruit Industries. - BSD license, all text above must be included in any redistribution - ****************************************************/ - -#include "Adafruit_MAX31865.h" -#ifdef __AVR -#include -#elif defined(ESP8266) -#include -#endif - -#include - -/**************************************************************************/ -/*! - @brief Create the interface object using software (bitbang) SPI - @param spi_cs the SPI CS pin to use - @param spi_mosi the SPI MOSI pin to use - @param spi_miso the SPI MISO pin to use - @param spi_clk the SPI clock pin to use -*/ -/**************************************************************************/ -// -Adafruit_MAX31865::Adafruit_MAX31865(int8_t spi_cs, int8_t spi_mosi, - int8_t spi_miso, int8_t spi_clk) - : spi_dev(spi_cs, spi_clk, spi_miso, spi_mosi, 1000000, - SPI_BITORDER_MSBFIRST, SPI_MODE1) {} - -/**************************************************************************/ -/*! - @brief Create the interface object using hardware SPI - @param spi_cs the SPI chip select pin to use - @param theSPI the SPI device to use, default is SPI -*/ -/**************************************************************************/ -Adafruit_MAX31865::Adafruit_MAX31865(int8_t spi_cs, SPIClass *theSPI) - : spi_dev(spi_cs, 1000000, SPI_BITORDER_MSBFIRST, SPI_MODE1, theSPI) {} - -/**************************************************************************/ -/*! - @brief Initialize the SPI interface and set the number of RTD wires used - @param wires The number of wires in enum format. Can be MAX31865_2WIRE, - MAX31865_3WIRE, or MAX31865_4WIRE - @return True -*/ -/**************************************************************************/ -bool Adafruit_MAX31865::begin(max31865_numwires_t wires) { - spi_dev.begin(); - - setWires(wires); - enableBias(false); - autoConvert(false); - setThresholds(0, 0xFFFF); - clearFault(); - - // Serial.print("config: "); - // Serial.println(readRegister8(MAX31865_CONFIG_REG), HEX); - return true; -} - -/**************************************************************************/ -/*! - @brief Read the raw 8-bit FAULTSTAT register - @param fault_cycle The fault cycle type to run. Can be MAX31865_FAULT_NONE, - MAX31865_FAULT_AUTO, MAX31865_FAULT_MANUAL_RUN, or - MAX31865_FAULT_MANUAL_FINISH - @return The raw unsigned 8-bit FAULT status register -*/ -/**************************************************************************/ -uint8_t Adafruit_MAX31865::readFault(max31865_fault_cycle_t fault_cycle) { - if (fault_cycle) { - uint8_t cfg_reg = readRegister8(MAX31865_CONFIG_REG); - cfg_reg &= 0x11; // mask out wire and filter bits - switch (fault_cycle) { - case MAX31865_FAULT_AUTO: - writeRegister8(MAX31865_CONFIG_REG, (cfg_reg | 0b10000100)); - delay(1); - break; - case MAX31865_FAULT_MANUAL_RUN: - writeRegister8(MAX31865_CONFIG_REG, (cfg_reg | 0b10001000)); - return 0; - case MAX31865_FAULT_MANUAL_FINISH: - writeRegister8(MAX31865_CONFIG_REG, (cfg_reg | 0b10001100)); - return 0; - case MAX31865_FAULT_NONE: - default: - break; - } - } - return readRegister8(MAX31865_FAULTSTAT_REG); -} - -/**************************************************************************/ -/*! - @brief Clear all faults in FAULTSTAT -*/ -/**************************************************************************/ -void Adafruit_MAX31865::clearFault(void) { - uint8_t t = readRegister8(MAX31865_CONFIG_REG); - t &= ~0x2C; - t |= MAX31865_CONFIG_FAULTSTAT; - writeRegister8(MAX31865_CONFIG_REG, t); -} - -/**************************************************************************/ -/*! - @brief Enable the bias voltage on the RTD sensor between readings - @param b If true bias is enabled between readings, else disabled -*/ -/**************************************************************************/ -void Adafruit_MAX31865::enableBias(bool b) { - uint8_t t = readRegister8(MAX31865_CONFIG_REG); - if (b) { - t |= MAX31865_CONFIG_BIAS; // enable bias - } else { - t &= ~MAX31865_CONFIG_BIAS; // disable bias - } - writeRegister8(MAX31865_CONFIG_REG, t); - bias = b; -} - -/**************************************************************************/ -/*! - @brief Whether we want to have continuous conversions (50/60 Hz) - @param b If true, continuous conversion is enabled -*/ -/**************************************************************************/ -void Adafruit_MAX31865::autoConvert(bool b) { - uint8_t t = readRegister8(MAX31865_CONFIG_REG); - if (b) { - t |= MAX31865_CONFIG_MODEAUTO; // enable continuous conversion - } else { - t &= ~MAX31865_CONFIG_MODEAUTO; // disable continuous conversion - } - writeRegister8(MAX31865_CONFIG_REG, t); - if (b && !continuous) { - if (filter50Hz) { - delay(70); - } else { - delay(60); - } - } - continuous = b; -} - -/**************************************************************************/ -/*! - @brief Whether we want filter out 50Hz noise or 60Hz noise - @param b If true, 50Hz noise is filtered, else 60Hz(default) -*/ -/**************************************************************************/ - -void Adafruit_MAX31865::enable50Hz(bool b) { - uint8_t t = readRegister8(MAX31865_CONFIG_REG); - if (b) { - t |= MAX31865_CONFIG_FILT50HZ; - } else { - t &= ~MAX31865_CONFIG_FILT50HZ; - } - writeRegister8(MAX31865_CONFIG_REG, t); - filter50Hz = b; -} - -/**************************************************************************/ -/*! - @brief Write the lower and upper values into the threshold fault - register to values as returned by readRTD() - @param lower raw lower threshold - @param upper raw upper threshold -*/ -/**************************************************************************/ -void Adafruit_MAX31865::setThresholds(uint16_t lower, uint16_t upper) { - writeRegister8(MAX31865_LFAULTLSB_REG, lower & 0xFF); - writeRegister8(MAX31865_LFAULTMSB_REG, lower >> 8); - writeRegister8(MAX31865_HFAULTLSB_REG, upper & 0xFF); - writeRegister8(MAX31865_HFAULTMSB_REG, upper >> 8); -} - -/**************************************************************************/ -/*! - @brief Read the raw 16-bit lower threshold value - @return The raw unsigned 16-bit value, NOT temperature! -*/ -/**************************************************************************/ -uint16_t Adafruit_MAX31865::getLowerThreshold(void) { - return readRegister16(MAX31865_LFAULTMSB_REG); -} - -/**************************************************************************/ -/*! - @brief Read the raw 16-bit lower threshold value - @return The raw unsigned 16-bit value, NOT temperature! -*/ -/**************************************************************************/ -uint16_t Adafruit_MAX31865::getUpperThreshold(void) { - return readRegister16(MAX31865_HFAULTMSB_REG); -} - -/**************************************************************************/ -/*! - @brief How many wires we have in our RTD setup, can be MAX31865_2WIRE, - MAX31865_3WIRE, or MAX31865_4WIRE - @param wires The number of wires in enum format -*/ -/**************************************************************************/ -void Adafruit_MAX31865::setWires(max31865_numwires_t wires) { - uint8_t t = readRegister8(MAX31865_CONFIG_REG); - if (wires == MAX31865_3WIRE) { - t |= MAX31865_CONFIG_3WIRE; - } else { - // 2 or 4 wire - t &= ~MAX31865_CONFIG_3WIRE; - } - writeRegister8(MAX31865_CONFIG_REG, t); -} - -/**************************************************************************/ -/*! - @brief Read the temperature in C from the RTD through calculation of the - resistance. Uses - http://www.analog.com/media/en/technical-documentation/application-notes/AN709_0.pdf - technique - @param RTDnominal The 'nominal' resistance of the RTD sensor, usually 100 - or 1000 - @param refResistor The value of the matching reference resistor, usually - 430 or 4300 - @returns Temperature in C -*/ -/**************************************************************************/ -float Adafruit_MAX31865::temperature(float RTDnominal, float refResistor) { - return calculateTemperature(readRTD(), RTDnominal, refResistor); -} -/**************************************************************************/ -/*! - @brief Calculate the temperature in C from the RTD through calculation of - the resistance. Uses - http://www.analog.com/media/en/technical-documentation/application-notes/AN709_0.pdf - technique - @param RTDraw The raw 16-bit value from the RTD_REG - @param RTDnominal The 'nominal' resistance of the RTD sensor, usually 100 - or 1000 - @param refResistor The value of the matching reference resistor, usually - 430 or 4300 - @returns Temperature in C -*/ -/**************************************************************************/ -float Adafruit_MAX31865::calculateTemperature(uint16_t RTDraw, float RTDnominal, - float refResistor) { - float Z1, Z2, Z3, Z4, Rt, temp; - - Rt = RTDraw; - Rt /= 32768; - Rt *= refResistor; - - // Serial.print("\nResistance: "); Serial.println(Rt, 8); - - Z1 = -RTD_A; - Z2 = RTD_A * RTD_A - (4 * RTD_B); - Z3 = (4 * RTD_B) / RTDnominal; - Z4 = 2 * RTD_B; - - temp = Z2 + (Z3 * Rt); - temp = (sqrt(temp) + Z1) / Z4; - - if (temp >= 0) - return temp; - - // ugh. - Rt /= RTDnominal; - Rt *= 100; // normalize to 100 ohm - - float rpoly = Rt; - - temp = -242.02; - temp += 2.2228 * rpoly; - rpoly *= Rt; // square - temp += 2.5859e-3 * rpoly; - rpoly *= Rt; // ^3 - temp -= 4.8260e-6 * rpoly; - rpoly *= Rt; // ^4 - temp -= 2.8183e-8 * rpoly; - rpoly *= Rt; // ^5 - temp += 1.5243e-10 * rpoly; - - return temp; -} - -/**************************************************************************/ -/*! - @brief Read the raw 16-bit value from the RTD_REG in one shot mode - @return The raw unsigned 16-bit value, NOT temperature! -*/ -/**************************************************************************/ -uint16_t Adafruit_MAX31865::readRTD(void) { - clearFault(); - if (!continuous) { - if (!bias) { - uint8_t t = readRegister8(MAX31865_CONFIG_REG); - t |= MAX31865_CONFIG_BIAS; // enable bias - writeRegister8(MAX31865_CONFIG_REG, t); - delay(10); - } - uint8_t t = readRegister8(MAX31865_CONFIG_REG); - t |= MAX31865_CONFIG_1SHOT; - writeRegister8(MAX31865_CONFIG_REG, t); - if (filter50Hz) { - delay(70); - } else { - delay(60); - } - } - - uint16_t rtd = readRegister16(MAX31865_RTDMSB_REG); - - if (!bias) { - uint8_t t = readRegister8(MAX31865_CONFIG_REG); - t &= ~MAX31865_CONFIG_BIAS; // disable bias - writeRegister8(MAX31865_CONFIG_REG, t); - } - - // remove fault - rtd >>= 1; - - return rtd; -} - -/**********************************************/ - -uint8_t Adafruit_MAX31865::readRegister8(uint8_t addr) { - uint8_t ret = 0; - readRegisterN(addr, &ret, 1); - - return ret; -} - -uint16_t Adafruit_MAX31865::readRegister16(uint8_t addr) { - uint8_t buffer[2] = {0, 0}; - readRegisterN(addr, buffer, 2); - - uint16_t ret = buffer[0]; - ret <<= 8; - ret |= buffer[1]; - - return ret; -} - -void Adafruit_MAX31865::readRegisterN(uint8_t addr, uint8_t buffer[], - uint8_t n) { - addr &= 0x7F; // make sure top bit is not set - - spi_dev.write_then_read(&addr, 1, buffer, n); -} - -void Adafruit_MAX31865::writeRegister8(uint8_t addr, uint8_t data) { - addr |= 0x80; // make sure top bit is set - - uint8_t buffer[2] = {addr, data}; - spi_dev.write(buffer, 2); -} diff --git a/Adafruit_MAX31865.h b/Adafruit_MAX31865.h deleted file mode 100644 index 1acc69d..0000000 --- a/Adafruit_MAX31865.h +++ /dev/null @@ -1,116 +0,0 @@ -/*************************************************** - This is a library for the Adafruit PT100/P1000 RTD Sensor w/MAX31865 - - Designed specifically to work with the Adafruit RTD Sensor - ----> https://www.adafruit.com/products/3328 - - This sensor uses SPI to communicate, 4 pins are required to - interface - Adafruit invests time and resources providing this open source code, - please support Adafruit and open-source hardware by purchasing - products from Adafruit! - - Written by Limor Fried/Ladyada for Adafruit Industries. - BSD license, all text above must be included in any redistribution - ****************************************************/ - -#ifndef ADAFRUIT_MAX31865_H -#define ADAFRUIT_MAX31865_H - -#define MAX31865_CONFIG_REG 0x00 -#define MAX31865_CONFIG_BIAS 0x80 -#define MAX31865_CONFIG_MODEAUTO 0x40 -#define MAX31865_CONFIG_MODEOFF 0x00 -#define MAX31865_CONFIG_1SHOT 0x20 -#define MAX31865_CONFIG_3WIRE 0x10 -#define MAX31865_CONFIG_24WIRE 0x00 -#define MAX31865_CONFIG_FAULTSTAT 0x02 -#define MAX31865_CONFIG_FILT50HZ 0x01 -#define MAX31865_CONFIG_FILT60HZ 0x00 - -#define MAX31865_RTDMSB_REG 0x01 -#define MAX31865_RTDLSB_REG 0x02 -#define MAX31865_HFAULTMSB_REG 0x03 -#define MAX31865_HFAULTLSB_REG 0x04 -#define MAX31865_LFAULTMSB_REG 0x05 -#define MAX31865_LFAULTLSB_REG 0x06 -#define MAX31865_FAULTSTAT_REG 0x07 - -#define MAX31865_FAULT_HIGHTHRESH 0x80 -#define MAX31865_FAULT_LOWTHRESH 0x40 -#define MAX31865_FAULT_REFINLOW 0x20 -#define MAX31865_FAULT_REFINHIGH 0x10 -#define MAX31865_FAULT_RTDINLOW 0x08 -#define MAX31865_FAULT_OVUV 0x04 - -#define RTD_A 3.9083e-3 -#define RTD_B -5.775e-7 - -#if (ARDUINO >= 100) -#include "Arduino.h" -#else -#include "WProgram.h" -#endif - -#include - -typedef enum max31865_numwires { - MAX31865_2WIRE = 0, - MAX31865_3WIRE = 1, - MAX31865_4WIRE = 0 -} max31865_numwires_t; - -typedef enum { - MAX31865_FAULT_NONE = 0, - MAX31865_FAULT_AUTO, - MAX31865_FAULT_MANUAL_RUN, - MAX31865_FAULT_MANUAL_FINISH -} max31865_fault_cycle_t; - -/*! Interface class for the MAX31865 RTD Sensor reader */ -class Adafruit_MAX31865 { -public: - Adafruit_MAX31865(int8_t spi_cs, int8_t spi_mosi, int8_t spi_miso, - int8_t spi_clk); - Adafruit_MAX31865(int8_t spi_cs, SPIClass *theSPI = &SPI); - - bool begin(max31865_numwires_t x = MAX31865_2WIRE); - - uint8_t readFault(max31865_fault_cycle_t fault_cycle = MAX31865_FAULT_AUTO); - void clearFault(void); - uint16_t readRTD(); - - void setThresholds(uint16_t lower, uint16_t upper); - uint16_t getLowerThreshold(void); - uint16_t getUpperThreshold(void); - - void setWires(max31865_numwires_t wires); - void autoConvert(bool b); - void enable50Hz(bool b); - void enableBias(bool b); - - float temperature(float RTDnominal, float refResistor); - float calculateTemperature(uint16_t RTDraw, float RTDnominal, - float refResistor); - -private: - Adafruit_SPIDevice spi_dev; - - void readRegisterN(uint8_t addr, uint8_t buffer[], uint8_t n); - - uint8_t readRegister8(uint8_t addr); - uint16_t readRegister16(uint8_t addr); - - void writeRegister8(uint8_t addr, uint8_t reg); - - // bias voltage - bool bias; - - // continuous conversion - bool continuous; - - // 50Hz filter - bool filter50Hz; -}; - -#endif diff --git a/MAX31865_NonBlocking.cpp b/MAX31865_NonBlocking.cpp new file mode 100644 index 0000000..3959a5c --- /dev/null +++ b/MAX31865_NonBlocking.cpp @@ -0,0 +1,241 @@ +/*************************************************** + This is a library for the Adafruit PT100/P1000 RTD Sensor w/MAX31865 + + Designed specifically to work with the Adafruit RTD Sensor + ----> https://www.adafruit.com/products/3328 + + This sensor uses SPI to communicate, 4 pins are required to + interface + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + Written by Limor Fried/Ladyada for Adafruit Industries. + Modified by budulinek for everyone. + + BSD license, all text above must be included in any redistribution + ****************************************************/ + +#include "MAX31865_NonBlocking.h" +#ifdef __AVR +#include +#elif defined(ESP8266) +#include +#endif + +#include + +void MAX31865::begin(RtdWire wires, FilterFreq filter) { + _spi->begin(); + pinMode(_cs, OUTPUT); + + setThresholds(0, 0xFFFF); + clearFault(); + setConfig(0x00); + + setWires(wires); + setFilter(filter); + + + // Serial.print("config: "); + // Serial.println(readRegister8(CONFIG_ADDR), HEX); +} + +uint8_t MAX31865::getFault(FaultCycle fault_cycle) { + if (fault_cycle) { + uint8_t cfg_reg = getConfig(); + cfg_reg &= 0x11; // mask out wire and filter bits + switch (fault_cycle) { + case FAULT_AUTO: + setConfig(cfg_reg | 0b10000100); + // delay(1); // TODO: ?? + break; + case FAULT_MANUAL_RUN: + setConfig(cfg_reg | 0b10001000); + return 0; + case FAULT_MANUAL_FINISH: + setConfig(cfg_reg | 0b10001100); + return 0; + case FAULT_NONE: + default: + break; + } + } + return readRegister8(FAULT_STATUS_ADDR); +} + +void MAX31865::clearFault(void) { + uint8_t t = getConfig(); + t &= ~0x2C; + t |= CONFIG_FAULT_STATUS_BIT; + setConfig(t); +} + +void MAX31865::setConfig(uint8_t cfg_reg) { + writeRegister8(CONFIG_ADDR, cfg_reg); +} + +uint8_t MAX31865::getConfig() { + return readRegister8(CONFIG_ADDR); +} + +void MAX31865::setWires(RtdWire wires) { + uint8_t t = getConfig(); + if (wires == RTD_3WIRE) { + t |= CONFIG_3WIRE_RTD_BIT; + } else { + // 2 or 4 wire + t &= ~CONFIG_3WIRE_RTD_BIT; + } + setConfig(t); +} + +MAX31865::RtdWire MAX31865::getWires(void) { + return (MAX31865::RtdWire(getConfig() & CONFIG_3WIRE_RTD_BIT)); +} + +void MAX31865::setFilter(const FilterFreq filter) { + uint8_t t = getConfig(); + if (t & CONFIG_CONVERSION_MODE_BIT) return; + if (filter == FILTER_50HZ) { + t |= CONFIG_FILTER_BIT; + } else { + t &= ~CONFIG_FILTER_BIT; + } + setConfig(t); +} + +MAX31865::FilterFreq MAX31865::getFilter(void) { + return (MAX31865::FilterFreq(getConfig() & CONFIG_FILTER_BIT)); +} + +void MAX31865::enableBias(bool b) { + uint8_t t = getConfig(); + if (b) { + t |= CONFIG_VBIAS_BIT; // enable bias + } else { + t &= ~CONFIG_VBIAS_BIT; // disable bias + } + setConfig(t); +} + +void MAX31865::autoConvert(bool b) { + uint8_t t = getConfig(); + if (b) { + t |= CONFIG_CONVERSION_MODE_BIT; // enable continuous conversion + } else { + t &= ~CONFIG_CONVERSION_MODE_BIT; // disable continuous conversion + } + setConfig(t); +} + +void MAX31865::singleConvert(void) { + uint8_t t = getConfig(); + t |= CONFIG_1SHOT_BIT; + setConfig(t); +} + + +void MAX31865::setThresholds(uint16_t lower, uint16_t upper) { + writeRegister8(LOW_FAULT_THRESH_LSB_ADDR, lower & 0xFF); + writeRegister8(LOW_FAULT_THRESH_MSB_ADDR, lower >> 8); + writeRegister8(HIGH_FAULT_THRESH_LSB_ADDR, upper & 0xFF); + writeRegister8(HIGH_FAULT_THRESH_MSB_ADDR, upper >> 8); +} + +uint16_t MAX31865::getLowerThreshold(void) { + return readRegister16(LOW_FAULT_THRESH_MSB_ADDR); +} + +uint16_t MAX31865::getUpperThreshold(void) { + return readRegister16(HIGH_FAULT_THRESH_MSB_ADDR); +} + +uint16_t MAX31865::getRTD(void) { + clearFault(); + uint16_t rtd = readRegister16(RTD_MSB_ADDR); + _fault = rtd & 0x0001; + // remove fault + rtd >>= 1; + return rtd; +} + +float MAX31865::getTemp(uint16_t rNominal, uint16_t rReference) { + return calculateTemperature(getRTD(), rNominal, rReference); +} + +float MAX31865::calculateTemperature(uint16_t rtdRaw, uint16_t rNominal, + uint16_t rReference) { + float Z1, Z2, Z3, Z4, Rt, temp; + + Z1 = -RTD_A; + Z2 = RTD_A * RTD_A - (4 * RTD_B); + Z3 = (4 * RTD_B) / static_cast(rNominal); + Z4 = 2 * RTD_B; + + /* Measured resistance */ + Rt = static_cast(rReference) * static_cast(rtdRaw) / RTD_MAX_VAL; + /* Convert resistance to temperature */ + temp = (Z1 + sqrtf(Z2 + (Z3 * Rt))) / Z4; + // if (temp < -12.5f) { + // Rt /= static_cast(rNominal); + // Rt *= 100.0f; + // temp = -242.97f + 2.2838f * Rt + 1.4727e-3f * Rt * Rt; + // } + + return temp; +} + +/**********************************************/ + +uint8_t MAX31865::readRegister8(const uint8_t addr) { + uint8_t ret = 0; + readRegisterN(addr, &ret, 1); + return ret; +} + +uint16_t MAX31865::readRegister16(const uint8_t addr) { + uint8_t buffer[2] = { 0, 0 }; + readRegisterN(addr, buffer, 2); + uint16_t ret = buffer[0]; + ret <<= 8; + ret |= buffer[1]; + return ret; +} + +void MAX31865::readRegisterN(uint8_t addr, uint8_t *const data, + const uint8_t count) { + addr &= 0x7F; // make sure top bit is not set + _spi->beginTransaction(SPI_MAX31865_SETTINGS); +#if defined(TEENSYDUINO) + digitalWriteFast(_cs, LOW); +#else + digitalWrite(_cs, LOW); +#endif + _spi->transfer(addr); + _spi->transfer(data, count); +#if defined(TEENSYDUINO) + digitalWriteFast(_cs, HIGH); +#else + digitalWrite(_cs, HIGH); +#endif + _spi->endTransaction(); +} + +void MAX31865::writeRegister8(uint8_t addr, const uint8_t data) { + addr |= 0x80; // make sure top bit is set + _spi->beginTransaction(SPI_MAX31865_SETTINGS); +#if defined(TEENSYDUINO) + digitalWriteFast(_cs, LOW); +#else + digitalWrite(_cs, LOW); +#endif + _spi->transfer(addr); + _spi->transfer(data); +#if defined(TEENSYDUINO) + digitalWriteFast(_cs, HIGH); +#else + digitalWrite(_cs, HIGH); +#endif + _spi->endTransaction(); +} diff --git a/MAX31865_NonBlocking.h b/MAX31865_NonBlocking.h new file mode 100644 index 0000000..5a41385 --- /dev/null +++ b/MAX31865_NonBlocking.h @@ -0,0 +1,325 @@ +/*************************************************** + This is a library for the Adafruit PT100/P1000 RTD Sensor w/MAX31865 + + Designed specifically to work with the Adafruit RTD Sensor + ----> https://www.adafruit.com/products/3328 + + This sensor uses SPI to communicate, 4 pins are required to + interface + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + Written by Limor Fried/Ladyada for Adafruit Industries. + Modified by budulinek for everyone. + + BSD license, all text above must be included in any redistribution + ****************************************************/ + +#ifndef MAX31865_NONBLOCKING_H +#define MAX31865_NONBLOCKING_H + +#if defined(ARDUINO) +#include +#include "SPI.h" +#else +#include +#include +#include "core/core.h" +#endif + +#define SPI_MAX31865_SETTINGS SPISettings(5000000, MSBFIRST, SPI_MODE1) + +/*! Interface class for the MAX31865 RTD Sensor reader */ +class MAX31865 { +public: + /* Fault Status Masks */ + + /** RTD High Threshold */ + static constexpr uint8_t FAULT_HIGHTHRESH_BIT = 0x80; + /** RTD Low Threshold */ + static constexpr uint8_t FAULT_LOWTHRESH_BIT = 0x40; + /** REFIN- > 0.85 x Bias */ + static constexpr uint8_t FAULT_REFINLOW_BIT = 0x20; + /** REFIN- < 0.85 x Bias - FORCE- open */ + static constexpr uint8_t FAULT_REFINHIGH_BIT = 0x10; + /** RTDIN- < 0.85 x Bias - FORCE- open */ + static constexpr uint8_t FAULT_RTDINLOW_BIT = 0x08; + /** Under/Over voltage */ + static constexpr uint8_t FAULT_OVUV_BIT = 0x04; + + /**************************************************************************/ + /*! + Number of wires we have in our RTD setup + */ + /**************************************************************************/ + typedef enum { + RTD_2WIRE = 0, + RTD_3WIRE = 1, + RTD_4WIRE = 0 + } RtdWire; + + /**************************************************************************/ + /*! + Notch frequency for the noise rejection filter. + Choose 50Hz or 60Hz depending on the frequency of your power sources. + */ + /**************************************************************************/ + typedef enum { + /** Filter out 60Hz noise and its harmonics */ + FILTER_60HZ = 0, + /** Filter out 50Hz noise and its harmonics */ + FILTER_50HZ = 1 + } FilterFreq; + + /**************************************************************************/ + /*! + Fault Detection Cycle Control + */ + /**************************************************************************/ + typedef enum { + /** No action */ + FAULT_NONE, + /** Fault detection with automatic delay */ + FAULT_AUTO, + /** Run fault detection with manual delay */ + FAULT_MANUAL_RUN, + /** Finish fault detection with manual delay */ + FAULT_MANUAL_FINISH + } FaultCycle; + + MAX31865() {} + + /**************************************************************************/ + /*! + @brief Create the interface object using hardware SPI + @param cs the SPI chip select pin to use + @param spi the SPI device to use, default is SPI + */ + /**************************************************************************/ + MAX31865(const uint8_t cs, SPIClass *spi = &SPI) + : _spi(spi), _cs(cs) {} + + /**************************************************************************/ + /*! + @brief Initialize the SPI interface and set the number of RTD wires used + @param wires Number of wires in enum format. Can be RTD_2WIRE, + RTD_3WIRE, or RTD_4WIRE + @param filter Notch frequency for the noise rejection filter. + Can be FILTER_50HZ or FILTER_60HZ + */ + /**************************************************************************/ + void begin(RtdWire wires = RTD_2WIRE, FilterFreq filter = FILTER_50HZ); + + /**************************************************************************/ + /*! + @brief Read the raw 8-bit FAULTSTAT register and set the fault detection + cycle type + @param fault_cycle The fault cycle type to run. Can be FAULT_NONE, + FAULT_AUTO, FAULT_MANUAL_RUN, or FAULT_MANUAL_FINISH + @return The raw unsigned 8-bit FAULT status register + */ + /**************************************************************************/ + uint8_t getFault(FaultCycle fault_cycle = FAULT_AUTO); + + /**************************************************************************/ + /*! + @brief Clear all faults in FAULTSTAT + */ + /**************************************************************************/ + void clearFault(void); + + /**************************************************************************/ + /*! + @brief Fault bit that indicates whether any RTD faults have been detected. + @return True if RTD faults have been detected. + */ + /**************************************************************************/ + inline bool fault() const { + return _fault; + } + + /**************************************************************************/ + /*! + @brief Set the raw 8-bit CONFIG register + @param cfg_reg raw 8-bit CONFIG value + */ + /**************************************************************************/ + void setConfig(uint8_t cfg_reg); + + /**************************************************************************/ + /*! + @brief Read the raw 8-bit CONFIG register + @return The raw unsigned 8-bit CONFIG register + */ + /**************************************************************************/ + uint8_t getConfig(void); + + /**************************************************************************/ + /*! + @brief How many wires we have in our RTD setup. + @param wires Number of wires in enum format, can be RTD_2WIRE, + RTD_3WIRE, or RTD_4WIRE + */ + /**************************************************************************/ + void setWires(RtdWire wires); + + /**************************************************************************/ + /*! + @brief Reads number of configured wires. + @return Selected number of wires, can be RTD_2WIRE, RTD_3WIRE, or RTD_4WIRE + */ + /**************************************************************************/ + RtdWire getWires(void); + + /**************************************************************************/ + /*! + @brief Choose notch frequency for the noise rejection filter. + Do not change the notch frequency while in auto conversion mode. + @param filter Notch frequency for the noise rejection filter. + Can be FILTER_50HZ or FILTER_60HZ + */ + /**************************************************************************/ + void setFilter(FilterFreq filter); + + /**************************************************************************/ + /*! + @brief Reads notch frequency for the noise rejection filter. + @return Selected notch frequency for the noise rejection filter. + Can be FILTER_50HZ or FILTER_60HZ + */ + /**************************************************************************/ + FilterFreq getFilter(void); + + /**************************************************************************/ + /*! + @brief Enable the bias voltage on the RTD sensor before beginning + a single (1-Shot) conversion. + Disable bias voltage to reduce power dissipation (self-heating of RTD sensor) + @param b If true bias voltage is enabled, else disabled + */ + /**************************************************************************/ + void enableBias(bool b); + + /**************************************************************************/ + /*! + @brief Enable automatic conversion mode, in which conversions occur continuously. + When automatic conversion mode is selected, bias voltage remains on continuously. + Therefore, auto conversion mode leads to self-heating of the RTD sensor. + @param b If true, continuous conversion is enabled + */ + /**************************************************************************/ + void autoConvert(bool b); + + /**************************************************************************/ + /*! + @brief Trigger single resistance conversion. Use when autoConvert is disabled. + Enable bias voltage and wait cca 10ms before initiating the conversion. + A single conversion requires approximately 52ms in 60Hz filter mode + or 62.5ms in 50Hz filter mode to complete. + */ + /**************************************************************************/ + void singleConvert(void); + + /**************************************************************************/ + /*! + @brief Write the lower and upper values into the threshold fault + register to values as returned by getRTD() + @param lower raw lower threshold + @param upper raw upper threshold + */ + /**************************************************************************/ + void setThresholds(uint16_t lower, uint16_t upper); + + /**************************************************************************/ + /*! + @brief Read the raw 16-bit lower threshold value + @return The raw unsigned 16-bit value, NOT temperature! + */ + /**************************************************************************/ + uint16_t getLowerThreshold(void); + + /**************************************************************************/ + /*! + @brief Read the raw 16-bit lower threshold value + @return The raw unsigned 16-bit value, NOT temperature! + */ + /**************************************************************************/ + uint16_t getUpperThreshold(void); + + /**************************************************************************/ + /*! + @brief Read the raw 16-bit value from the RTD_REG + @return The raw unsigned 16-bit value, NOT temperature! + */ + /**************************************************************************/ + uint16_t getRTD(); + + /**************************************************************************/ + /*! + @brief Read the temperature in C from the RTD through calculation of the + resistance. Uses + http://www.analog.com/media/en/technical-documentation/application-notes/AN709_0.pdf + technique + @param rNominal Nominal resistance of the RTD sensor at 0°C, usually 100 + or 1000 + @param rReference Resistance of the reference resistor, usually + 430 or 4300 + @returns Temperature in °C + */ + /**************************************************************************/ + float getTemp(uint16_t rNominal, uint16_t rReference); + +private: + /* Communication */ + SPIClass *_spi; + uint8_t _cs; + /* Data */ + bool _fault; + static constexpr float RTD_MAX_VAL = 32768.0f; + static constexpr float RTD_A = 3.9083e-3; + static constexpr float RTD_B = -5.775e-7; + /* Registers */ + static constexpr uint8_t CONFIG_ADDR = 0x00; + static constexpr uint8_t RTD_MSB_ADDR = 0x01; + static constexpr uint8_t RTD_LSB_ADDR = 0x02; + static constexpr uint8_t HIGH_FAULT_THRESH_MSB_ADDR = 0x03; + static constexpr uint8_t HIGH_FAULT_THRESH_LSB_ADDR = 0x04; + static constexpr uint8_t LOW_FAULT_THRESH_MSB_ADDR = 0x05; + static constexpr uint8_t LOW_FAULT_THRESH_LSB_ADDR = 0x06; + static constexpr uint8_t FAULT_STATUS_ADDR = 0x07; + /* Config Masks */ + static constexpr uint8_t CONFIG_VBIAS_BIT = 0x80; + static constexpr uint8_t CONFIG_CONVERSION_MODE_BIT = 0x40; + static constexpr uint8_t CONFIG_1SHOT_BIT = 0x20; + static constexpr uint8_t CONFIG_3WIRE_RTD_BIT = 0x10; + static constexpr uint8_t CONFIG_FAULT_DET_MASK_ = 0x0C; + static constexpr uint8_t CONFIG_FAULT_STATUS_BIT = 0x02; + static constexpr uint8_t CONFIG_FILTER_BIT = 0x01; + + /**************************************************************************/ + /*! + @brief Calculate the temperature in C from the RTD through calculation of + the resistance. Uses + http://www.analog.com/media/en/technical-documentation/application-notes/AN709_0.pdf + technique + @param rtdRaw The raw 16-bit value from the RTD_REG + @param rNominal Nominal resistance of the RTD sensor at 0°C, usually 100 + or 1000 + @param rReference Resistance of the reference resistor, usually + 430 or 4300 + @returns Temperature in °C + */ + /**************************************************************************/ + float calculateTemperature(uint16_t rtdRaw, uint16_t rNominal, + uint16_t rReference); + + void readRegisterN(const uint8_t addr, uint8_t *const data, const uint8_t count); + + uint8_t readRegister8(const uint8_t addr); + uint16_t readRegister16(const uint8_t addr); + + void writeRegister8(const uint8_t addr, const uint8_t data); +}; + +#endif diff --git a/README.md b/README.md index d692db4..2a95a0e 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ -# Adafruit MAX31865 [![Build Status](https://github.com/adafruit/Adafruit_MAX31865/workflows/Arduino%20Library%20CI/badge.svg)](https://github.com/adafruit/Adafruit_MAX31865/actions) +# MAX31865 NonBlocking [![Build Status](https://github.com/adafruit/Adafruit_MAX31865/workflows/Arduino%20Library%20CI/badge.svg)](https://github.com/adafruit/Adafruit_MAX31865/actions) This is the Adafruit MAX31865 Arduino Library @@ -7,13 +7,29 @@ This is the Adafruit MAX31865 Arduino Library Tested and works great with the Adafruit Thermocouple Breakout w/MAX31865 * http://www.adafruit.com/products/3328 -These sensors use SPI to communicate, 4 pins are required to -interface +These sensors use SPI to communicate, 4 pins are required to interface -Adafruit invests time and resources providing this open source code, -please support Adafruit and open-source hardware by purchasing -products from Adafruit! +Adafruit invests time and resources providing this open source code, please support Adafruit and open-source hardware by purchasing products from Adafruit! + +Written by Limor Fried/Ladyada for Adafruit Industries. + +Modified by budulinek for everyone. + +### Changes to the original Adafruit library: +- non-blocking automatic conversion mode +- non-blocking single shot conversion mode +- no software (bitbang) SPI, only hardware SPI +- uses standard SPI.h library +- modified API (function names), check source files for usage comments +- simplified temperature calculation (provides accurate results from -60°C up to 850°C) + +For **single shot measurements**, follow these steps (see examples): +1. **enableBias(true)** Enable bias voltage. +2. Wait cca 10 ms ("10x the input time constant plus 1ms" according to specs). +3. **singleConvert()** Trigger single shot measurement. +4. Wait 65 ms. +5. **getTemp()** Read temperature in °C. +6. **enableBias(false)** Disable bias voltage. -Written by Limor Fried/Ladyada for Adafruit Industries. BSD license, check license.txt for more information All text above must be included in any redistribution diff --git a/examples/MAX31865_Continuous/MAX31865_Continuous.ino b/examples/MAX31865_Continuous/MAX31865_Continuous.ino new file mode 100644 index 0000000..f913f3c --- /dev/null +++ b/examples/MAX31865_Continuous/MAX31865_Continuous.ino @@ -0,0 +1,87 @@ +/*************************************************** + This is a library for the Adafruit PT100/P1000 RTD Sensor w/MAX31865 + + Designed specifically to work with the Adafruit RTD Sensor + ----> https://www.adafruit.com/products/3328 + + This sensor uses SPI to communicate, 4 pins are required to + interface + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + Written by Limor Fried/Ladyada for Adafruit Industries. + Modified by budulinek for everyone. + + BSD license, all text above must be included in any redistribution + ****************************************************/ + +#include "MAX31865_NonBlocking.h" + +// uses hardware SPI, just pass in the CS pin (mandatory) and SPI bus (optional) +// MAX31865 rtd(5, &SPI); +MAX31865 rtd(5); + +// Resistance of the reference resistor. Check Rref resistor value on your module, +// should be 430 for PT100 and 4300 for PT1000 +#define RREF 4300 +// Nominal resistance of the RTD sensor at 0°C, +// use 100 for PT100, 1000 for PT1000 +#define RNOMINAL 1000 + +void setup() { + Serial.begin(115200); + Serial.println("MAX31865 PT1000 Sensor Test!"); + + rtd.begin(MAX31865::RTD_3WIRE, MAX31865::FILTER_50HZ); + rtd.autoConvert(true); +} + +void loop() { + // Read and print temperature and faults (non-blocking) + readRtd(); + + delay(1000); +} + +void readRtd() { + uint16_t rtdVal = rtd.getRTD(); + + Serial.print("RTD value: "); + Serial.println(rtdVal); + float ratio = rtdVal; + ratio /= 32768; + Serial.print("Ratio = "); + Serial.println(ratio, 8); + Serial.print("Resistance = "); + Serial.println(RREF * ratio, 8); + Serial.print("Temperature = "); + Serial.println(rtd.getTemp(RNOMINAL, RREF)); + + // Check and print any faults + uint8_t fault = rtd.getFault(); + if (fault) { + Serial.print("Fault 0x"); + Serial.println(fault, HEX); + if (fault & MAX31865::FAULT_HIGHTHRESH_BIT) { + Serial.println("RTD High Threshold"); + } + if (fault & MAX31865::FAULT_LOWTHRESH_BIT) { + Serial.println("RTD Low Threshold"); + } + if (fault & MAX31865::FAULT_REFINLOW_BIT) { + Serial.println("REFIN- > 0.85 x Bias"); + } + if (fault & MAX31865::FAULT_REFINHIGH_BIT) { + Serial.println("REFIN- < 0.85 x Bias - FORCE- open"); + } + if (fault & MAX31865::FAULT_RTDINLOW_BIT) { + Serial.println("RTDIN- < 0.85 x Bias - FORCE- open"); + } + if (fault & MAX31865::FAULT_OVUV_BIT) { + Serial.println("Under/Over voltage"); + } + rtd.clearFault(); + } + Serial.println(); +} diff --git a/examples/MAX31865_Single/MAX31865_Single.ino b/examples/MAX31865_Single/MAX31865_Single.ino new file mode 100644 index 0000000..4ba0c8d --- /dev/null +++ b/examples/MAX31865_Single/MAX31865_Single.ino @@ -0,0 +1,140 @@ +/*************************************************** + This is a library for the Adafruit PT100/P1000 RTD Sensor w/MAX31865 + + Designed specifically to work with the Adafruit RTD Sensor + ----> https://www.adafruit.com/products/3328 + + This sensor uses SPI to communicate, 4 pins are required to + interface + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + Written by Limor Fried/Ladyada for Adafruit Industries. + Modified by budulinek for everyone. + + BSD license, all text above must be included in any redistribution + ****************************************************/ + +#include "MAX31865_NonBlocking.h" + +// uses hardware SPI, just pass in the CS pin (mandatory) and SPI bus (optional) +// MAX31865 rtd(5, &SPI); +MAX31865 rtd(5); + +// Resistance of the reference resistor. Check Rref resistor value on your module, +// should be 430 for PT100 and 4300 for PT1000 +#define RREF 4300 +// Nominal resistance of the RTD sensor at 0°C, +// use 100 for PT100, 1000 for PT1000 +#define RNOMINAL 1000 + +// state machine +byte state; + +// Timer class for non-blocking delays +class Timer { +private: + uint32_t timestampLastHitMs; + uint32_t sleepTimeMs; +public: + boolean isOver(); + void sleep(uint32_t sleepTimeMs); +}; +boolean Timer::isOver() { + if ((uint32_t)(millis() - timestampLastHitMs) > sleepTimeMs) { + return true; + } + return false; +} +void Timer::sleep(uint32_t sleepTimeMs) { + this->sleepTimeMs = sleepTimeMs; + timestampLastHitMs = millis(); +} +Timer rtdTimer; + +void setup() { + Serial.begin(115200); + Serial.println("MAX31865 PT1000 Sensor Test!"); + + rtd.begin(MAX31865::RTD_3WIRE, MAX31865::FILTER_50HZ); +} + +void loop() { + // Read and print temperature and faults (non-blocking) + readRtd(); + + // Place your other functions here... + +} + +void readRtd() { + if (rtdTimer.isOver() == false) { + return; + } + switch (state) { + case 0: + { + rtd.enableBias(true); // enable bias voltage + rtdTimer.sleep(10); // and wait 10 ms + state++; + } + break; + case 1: + { + rtd.singleConvert(); // trigger single resistance conversion + rtdTimer.sleep(65); // and wait 65 ms + state++; + } + break; + case 2: + { + uint16_t rtdVal = rtd.getRTD(); + + Serial.print("RTD value: "); + Serial.println(rtdVal); + float ratio = rtdVal; + ratio /= 32768; + Serial.print("Ratio = "); + Serial.println(ratio, 8); + Serial.print("Resistance = "); + Serial.println(RREF * ratio, 8); + Serial.print("Temperature = "); + Serial.println(rtd.getTemp(RNOMINAL, RREF)); + + // Check and print any faults + uint8_t fault = rtd.getFault(); + if (fault) { + Serial.print("Fault 0x"); + Serial.println(fault, HEX); + if (fault & MAX31865::FAULT_HIGHTHRESH_BIT) { + Serial.println("RTD High Threshold"); + } + if (fault & MAX31865::FAULT_LOWTHRESH_BIT) { + Serial.println("RTD Low Threshold"); + } + if (fault & MAX31865::FAULT_REFINLOW_BIT) { + Serial.println("REFIN- > 0.85 x Bias"); + } + if (fault & MAX31865::FAULT_REFINHIGH_BIT) { + Serial.println("REFIN- < 0.85 x Bias - FORCE- open"); + } + if (fault & MAX31865::FAULT_RTDINLOW_BIT) { + Serial.println("RTDIN- < 0.85 x Bias - FORCE- open"); + } + if (fault & MAX31865::FAULT_OVUV_BIT) { + Serial.println("Under/Over voltage"); + } + rtd.clearFault(); + } + Serial.println(); + + rtd.enableBias(false); // disable bias voltage + rtdTimer.sleep(1000); + state = 0; + } + break; + default: + break; + } +} diff --git a/examples/max31865/max31865.ino b/examples/max31865/max31865.ino deleted file mode 100644 index 40f0578..0000000 --- a/examples/max31865/max31865.ino +++ /dev/null @@ -1,74 +0,0 @@ -/*************************************************** - This is a library for the Adafruit PT100/P1000 RTD Sensor w/MAX31865 - - Designed specifically to work with the Adafruit RTD Sensor - ----> https://www.adafruit.com/products/3328 - - This sensor uses SPI to communicate, 4 pins are required to - interface - Adafruit invests time and resources providing this open source code, - please support Adafruit and open-source hardware by purchasing - products from Adafruit! - - Written by Limor Fried/Ladyada for Adafruit Industries. - BSD license, all text above must be included in any redistribution - ****************************************************/ - -#include - -// Use software SPI: CS, DI, DO, CLK -Adafruit_MAX31865 thermo = Adafruit_MAX31865(10, 11, 12, 13); -// use hardware SPI, just pass in the CS pin -//Adafruit_MAX31865 thermo = Adafruit_MAX31865(10); - -// The value of the Rref resistor. Use 430.0 for PT100 and 4300.0 for PT1000 -#define RREF 430.0 -// The 'nominal' 0-degrees-C resistance of the sensor -// 100.0 for PT100, 1000.0 for PT1000 -#define RNOMINAL 100.0 - -void setup() { - Serial.begin(115200); - Serial.println("Adafruit MAX31865 PT100 Sensor Test!"); - - thermo.begin(MAX31865_3WIRE); // set to 2WIRE or 4WIRE as necessary -} - - -void loop() { - uint16_t rtd = thermo.readRTD(); - - Serial.print("RTD value: "); Serial.println(rtd); - float ratio = rtd; - ratio /= 32768; - Serial.print("Ratio = "); Serial.println(ratio,8); - Serial.print("Resistance = "); Serial.println(RREF*ratio,8); - Serial.print("Temperature = "); Serial.println(thermo.temperature(RNOMINAL, RREF)); - - // Check and print any faults - uint8_t fault = thermo.readFault(); - if (fault) { - Serial.print("Fault 0x"); Serial.println(fault, HEX); - if (fault & MAX31865_FAULT_HIGHTHRESH) { - Serial.println("RTD High Threshold"); - } - if (fault & MAX31865_FAULT_LOWTHRESH) { - Serial.println("RTD Low Threshold"); - } - if (fault & MAX31865_FAULT_REFINLOW) { - Serial.println("REFIN- > 0.85 x Bias"); - } - if (fault & MAX31865_FAULT_REFINHIGH) { - Serial.println("REFIN- < 0.85 x Bias - FORCE- open"); - } - if (fault & MAX31865_FAULT_RTDINLOW) { - Serial.println("RTDIN- < 0.85 x Bias - FORCE- open"); - } - if (fault & MAX31865_FAULT_OVUV) { - Serial.println("Under/Over voltage"); - } - thermo.clearFault(); - } - Serial.println(); - delay(1000); -} diff --git a/library.properties b/library.properties deleted file mode 100644 index 9eb768f..0000000 --- a/library.properties +++ /dev/null @@ -1,10 +0,0 @@ -name=Adafruit MAX31865 library -version=1.6.0 -author=Adafruit -maintainer=Adafruit -sentence=Library for the Adafruit RTD Amplifier breakout with MAX31865 -paragraph=Library for the Adafruit RTD Amplifier breakout with MAX31865 -category=Sensors -url=https://github.com/adafruit/Adafruit_MAX31865 -architectures=* -depends=Adafruit BusIO