Skip to content

Commit

Permalink
Merge pull request #15 from lebuni/beta
Browse files Browse the repository at this point in the history
Beta
  • Loading branch information
lebuni authored Nov 18, 2021
2 parents c72f2b5 + d79447c commit 6f5b00c
Show file tree
Hide file tree
Showing 7 changed files with 190 additions and 187 deletions.
22 changes: 10 additions & 12 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,9 @@

Arduino Library to read the ZACwire protocol, wich is used by TSic temperature sensors 206, 306 and 506 on their signal pin.

`ZACwire<int pin> obj(int Sensor)` tells the library which input pin of the controller (eg. 2) and type of sensor (eg. 306) it should use. Please pay attention that the selected pin supports external interrupts!
`ZACwire obj(int pin, int Sensor)` tells the library which input pin of the controller (eg. 2) and type of sensor (eg. 306) it should use. Please pay attention that the selected pin supports external interrupts!

`.begin()` returns true if a signal is detected on the specific pin and starts the reading via ISRs. It should be started at least 120ms before the first .getTemp().
`.begin()` returns true if a signal is detected on the specific pin and starts the reading via ISRs. It should be started at least 2ms before the first .getTemp().

`.getTemp()` returns the temperature in °C and gets usually updated every 100ms. In case of a failed reading, it returns `222`. In case of no incoming signal it returns `221`.

Expand All @@ -19,7 +19,7 @@ Arduino Library to read the ZACwire protocol, wich is used by TSic temperature s
- saves a lot of controller time, because no delay() is used and calculations are done by bit manipulation
- low memory consumption
- misreading rate lower than 0.001%
- reading an unlimited number of TSic simultaneously
- reading an unlimited number of TSic simultaneously (except AVR boards)
- higher accuracy (0.1°C offset corrected)
- simple use

Expand All @@ -33,15 +33,15 @@ Arduino Library to read the ZACwire protocol, wich is used by TSic temperature s

#include <ZACwire.h>

ZACwire<2> Sensor(306); // set pin "2" to receive signal from the TSic "306"
ZACwire Sensor(2, 306); // set pin "2" to receive signal from the TSic "306"

void setup() {
Serial.begin(500000);

if (Sensor.begin() == true) { //check if a sensor is connected to the pin
Serial.println("Signal found on pin 2");
}
delay(120);
delay(2);
}

void loop() {
Expand Down Expand Up @@ -75,15 +75,13 @@ The output of the signal pin switches between GND and V+ to send informations, s
## Fine-Tuning
In case of failed readings, there might be some fine-tuning necessary.
Some optional features, that might be interesting for playing around:
```c++
ZACwire<int pin> obj(int Sensor, byte defaultBitWindow, bool core)
void getTemp(uint8_t maxChangeRate)
```
`uint8_t maxChangeRate` is measured in °C/s and the default value is 10 °C/s. If you have a very stable system, you can lower that value to help the library detecting outliers. If the maxChangeRate is exceeded, a backup value from 100ms before will be used or error 222 will be returned.

`byte defaultBitWindow` is the expected BitWindow in µs. According to the datasheet it should be around 125µs, but it varies with temperature. After some minutes, the code will adjust itself to the precise BitWindow.
Change this, if the **first few readings** of the sensor fail (t = 222°C).
When your system changes temperature really quickly and due to the exceeded maxChangeRate the output of .getTemp() is 222, feel free to increase the value.

`bool core` can only be used on a dual core ESP32. You can decide on which core the ISR should run, default is Core1. Using Core0 might cause some corrupted readings (up to 0.1%), but can be the better option if Core1 is very busy.

If .getTemp() gives you **221** as an output, the library detected an unusual long period above 255ms without new signals. Please check your cables or try using the RC filter, that is mentioned in the [application note of the TSic](https://www.ist-ag.com/sites/default/files/dttsic20x_30x_e.pdf).
If .getTemp() gives you **221** as an output, the library detected an unusual long period above 255ms without new signals. Please check your cables or try using the RC filter, that is mentioned in the [application note of the TSic](https://www.ist-ag.com/sites/default/files/attsic_e.pdf).
132 changes: 132 additions & 0 deletions ZACwire.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,132 @@
/* ZACwire - Library for reading temperature sensors TSIC 206/306/506
created by Adrian Immer in 2020
v2.0.0
*/

#include "ZACwire.h"
#include "Arduino.h"

#if !defined(ESP32) && !defined(ESP8266) //initialize static variables for AVR boards
uint8_t ZACwire::bitThreshold;
uint16_t ZACwire::measuredTimeDiff;
volatile uint8_t ZACwire::bitCounter;
volatile bool ZACwire::backUP;
volatile uint16_t ZACwire::rawData[2];
volatile uint8_t ZACwire::heartbeat;
#endif


ZACwire::ZACwire(uint8_t pin, int16_t sensor) : _pin{pin}, _sensor{sensor} {
bitCounter = 0;
bitThreshold = 0;
}


bool ZACwire::begin() { //start collecting data, needs to be called over 2ms before first getTemp()
pinMode(_pin, INPUT_PULLUP);
for (uint8_t i=20; pulseIn(_pin,LOW,500);) { //wait for time without transmission
if (!--i) return false;
yield();
}
uint8_t strobeTime = pulseIn(_pin, LOW); //check for signal and measure strobeTime
if (!strobeTime) return false; //abort if there is no incoming signal
measuredTimeDiff = micros(); //set timestamp of first rising edge for ISR
bitThreshold = strobeTime * 2.5;

uint8_t isrPin = digitalPinToInterrupt(_pin);
if (isrPin == 255) return false;
#if defined(ESP32) || defined(ESP8266)
attachInterruptArg(isrPin, isrHandler, this, RISING);
#else
attachInterrupt(isrPin, read, RISING);
#endif
return true;
}


float ZACwire::getTemp(uint8_t maxChangeRate, bool useBackup) { //return temperature in °C
if (connectionCheck()) adjustBitThreshold();
else return errorNotConnected;

if (bitCounter != Bit::finished) useBackup = true; //when newer reading is incomplete
uint16_t temp{rawData[backUP^useBackup]}; //get rawData from ISR

if (tempCheck(temp)) {
temp >>= 1; //delete second parity bit
temp = (temp >> 2 & 1792) | (temp & 255); //delete first " "
if (!prevTemp) prevTemp = temp;
int16_t grad = (temp - prevTemp) / (heartbeat|1);//grad is [°C/s]
if (abs(grad) < maxChangeRate) { //limit change rate to detect misreadings
prevTemp = temp;
heartbeat = 0;
if (_sensor < 400) return ((temp * 250L >> 8) - 499) / 10.0; //use different formula for 206&306 or 506
else return ((temp * 175L >> 9) - 99) / 10.0;
}
}
return useBackup ? errorMisreading : getTemp(maxChangeRate,!useBackup); //restart with backUP rawData or return error value 222
}


void ZACwire::end() {
detachInterrupt(digitalPinToInterrupt(_pin));
}


void ZACwire::isrHandler(void* ptr) {
static_cast<ZACwire*>(ptr)->read();
}


void ZACwire::read() { //get called with every rising edge
if (++bitCounter < Bit::lastZero) return; //first 4 bits always =0
uint16_t microtime = micros();
measuredTimeDiff = microtime - measuredTimeDiff; //measure time to previous rising edge
if (measuredTimeDiff >> 10) { //first start bit, so big time difference
if (bitCounter == 20) {
backUP = !backUP; //save backup, if it successfully counted 20 bits
++heartbeat; //give a sign of life to getTemp()
}
bitCounter = 0;
}
else if (bitCounter == Bit::lastZero) {
rawData[backUP] = measuredTimeDiff<<1 | 2; //send measuredTimeDiff for calculating bitThreshold and add prefix "10" to temp
}
else {
if (bitCounter == Bit::afterStop) microtime += bitThreshold>>2; //convert timestamp at stop bit to normal 0 bit
if (~rawData[backUP] & 1) measuredTimeDiff += bitThreshold>>1; //add 1/2 bitThreshold if previous bit was 0 (for normalisation)
rawData[backUP] <<= 1;
if (measuredTimeDiff < bitThreshold) rawData[backUP] |= 1;
}
measuredTimeDiff = microtime;
}


bool ZACwire::connectionCheck() {
if (heartbeat) timeLastHB = 0;
else if (!bitThreshold) { //use bitThreshold to check if begin() was already called
if (begin()) delay(3);
else return false;
}
else if (!timeLastHB) timeLastHB = millis(); //record first missing heartbeat
else if (millis() - timeLastHB > timeout) return false;
return true;
}


void ZACwire::adjustBitThreshold() {
if (bitCounter < Bit::lastZero || bitCounter > Bit::afterStop) return; //adjust bitThreshold only before rawData is used for temperature

uint16_t newBitThreshold = (rawData[backUP] >> (bitCounter - 4));//separate newBitThreshold from temperature bits
newBitThreshold *= 1.25 / 5.25;
bitThreshold < newBitThreshold ? ++bitThreshold : --bitThreshold;
}


bool ZACwire::tempCheck(uint16_t rawTemp) {
if (rawTemp >> 14 != 2 || rawTemp & 512) return false; //check for prefix "10" and stop bit=0

bool parity{true};
for (uint8_t i{0}; i<9; ++i) parity ^= rawTemp & 1 << i;
if (parity) for (uint8_t i{10}; i<14; ++i) parity ^= rawTemp & 1 << i;
return parity;
}
Loading

0 comments on commit 6f5b00c

Please sign in to comment.