Moved Blue Wire Comms to a separate task

This commit is contained in:
Ray Jones 2020-04-25 09:23:16 +10:00
parent 28bfb28ff6
commit 5cdc5c95a5
16 changed files with 958 additions and 585 deletions

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,478 @@
/*
* This file is part of the "bluetoothheater" distribution
* (https://gitlab.com/mrjones.id.au/bluetoothheater)
*
* Copyright (C) 2018 Ray Jones <ray@mrjones.id.au>
* Copyright (C) 2018 James Clark
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "BlueWireTask.h"
#include "../cfg/BTCConfig.h"
#include "../cfg/pins.h"
#include "Protocol.h"
#include "TxManage.h"
// #include "SmartError.h"
#include "../Utility/UtilClasses.h"
#include "../Utility/DataFilter.h"
#include "../Utility/FuelGauge.h"
#include "../Utility/HourMeter.h"
#include "../Utility/macros.h"
// Setup Serial Port Definitions
#if defined(__arm__)
// Required for Arduino Due, UARTclass is derived from HardwareSerial
static UARTClass& BlueWireSerial(Serial1);
#else
// for ESP32, Mega
// HardwareSerial is it for these boards
static HardwareSerial& BlueWireSerial(Serial1);
#endif
#define RX_DATA_TIMOUT 50
CommStates CommState;
CTxManage TxManage(TxEnbPin, BlueWireSerial);
CProtocol DefaultBTCParams(CProtocol::CtrlMode); // defines the default parameters, used in case of no OEM controller
CModeratedFrame OEMCtrlFrame; // data packet received from heater in response to OEM controller packet
CModeratedFrame HeaterFrame1; // data packet received from heater in response to OEM controller packet
CProtocol HeaterFrame2; // data packet received from heater in response to our packet
// CSmartError SmartError;
CProtocolPackage reportHeaterData;
CProtocolPackage primaryHeaterData;
static bool bHasOEMController = false;
static bool bHasOEMLCDController = false;
static bool bHasHtrData = false;
extern bool bReportRecyleEvents;
extern bool bReportOEMresync;
extern bool bReportBlueWireData;
extern sFilteredData FilteredSamples;
QueueHandle_t BlueWireMsgBuf = NULL; // cannot use general Serial.print etc from this task without causing conflicts
QueueHandle_t BlueWireRxQueue = NULL; // queue to pass down heater receive data
QueueHandle_t BlueWireTxQueue = NULL; // queue to pass down heater transmit data
SemaphoreHandle_t BlueWireSemaphore = NULL; // flag to indicate completion of heater data exchange
bool validateFrame(const CProtocol& frame, const char* name);
void DebugReportFrame(const char* hdr, const CProtocol& Frame, const char* ftr, char* msg);
// void updateFilteredData();
void initBlueWireSerial();
void pushDebugMsg(const char* msg) {
if(BlueWireMsgBuf)
xQueueSend(BlueWireMsgBuf, msg, 0);
}
void BlueWireTask(void*) {
//////////////////////////////////////////////////////////////////////////////////////
// Blue wire data reception
// Reads data from the "blue wire" Serial port, (to/from heater)
// If an OEM controller exists we will also see it's data frames
// Note that the data is read now, then held for later use in the state machine
//
static unsigned long lastRxTime = 0; // used to observe inter character delays
static unsigned long moderator = 50;
bool isBTCmaster = false;
BlueWireMsgBuf = xQueueCreate(4, BLUEWIRE_MSGQUEUESIZE);
BlueWireRxQueue = xQueueCreate(4, BLUEWIRE_DATAQUEUESIZE);
BlueWireTxQueue = xQueueCreate(4, BLUEWIRE_DATAQUEUESIZE);
BlueWireSemaphore = xSemaphoreCreateBinary();
TxManage.begin(); // ensure Tx enable pin is setup
// define defaults should OEM controller be missing
DefaultBTCParams.setHeaterDemand(23);
DefaultBTCParams.setTemperature_Actual(22);
DefaultBTCParams.setSystemVoltage(12.0);
DefaultBTCParams.setPump_Min(1.6f);
DefaultBTCParams.setPump_Max(5.5f);
DefaultBTCParams.setFan_Min(1680);
DefaultBTCParams.setFan_Max(4500);
DefaultBTCParams.Controller.FanSensor = 1;
initBlueWireSerial();
CommState.setCallback(pushDebugMsg);
TxManage.setCallback(pushDebugMsg);
for(;;) {
sRxData BlueWireRxData;
unsigned long timenow = millis();
// calc elapsed time since last rxd byte
// used to detect no OEM controller, or the start of an OEM frame sequence
unsigned long RxTimeElapsed = timenow - lastRxTime;
if (BlueWireSerial.available()) {
// Data is available, read and store it now, use it later
// Note that if not in a recognised data receive frame state, the data
// will be deliberately lost!
BlueWireRxData.setValue(BlueWireSerial.read()); // read hex byte, store for later use
lastRxTime = timenow; // tickle last rx time, for rx data timeout purposes
}
// precautionary state machine action if all 24 bytes were not received
// whilst expecting a frame from the blue wire
if(RxTimeElapsed > RX_DATA_TIMOUT) {
if( CommState.is(CommStates::OEMCtrlRx) ||
CommState.is(CommStates::HeaterRx1) ||
CommState.is(CommStates::HeaterRx2) ) {
if(RxTimeElapsed >= moderator) {
moderator += 10;
if(bReportRecyleEvents) {
char msg[32];
sprintf(msg, "%ldms - ", RxTimeElapsed);
pushDebugMsg(msg);
}
if(CommState.is(CommStates::OEMCtrlRx)) {
bHasOEMController = false;
bHasOEMLCDController = false;
if(bReportRecyleEvents) {
pushDebugMsg("Timeout collecting OEM controller data, returning to Idle State\r\n");
}
}
else if(CommState.is(CommStates::HeaterRx1)) {
bHasHtrData = false;
if(bReportRecyleEvents) {
pushDebugMsg("Timeout collecting OEM heater response data, returning to Idle State\r\n");
}
}
else {
bHasHtrData = false;
if(bReportRecyleEvents) {
pushDebugMsg("Timeout collecting BTC heater response data, returning to Idle State\r\n");
}
}
}
if(bReportRecyleEvents) {
pushDebugMsg("Recycling blue wire serial interface\r\n");
}
#ifdef REBOOT_BLUEWIRE
initBlueWireSerial();
#endif
CommState.set(CommStates::ExchangeComplete); // revert to idle mode, after passing thru exchange complete mode
}
}
///////////////////////////////////////////////////////////////////////////////////////////
// do our state machine to track the reception and delivery of blue wire data
switch(CommState.get()) {
case CommStates::Idle:
moderator = 50;
digitalWrite(LED_Pin, LOW);
// Detect the possible start of a new frame sequence from an OEM controller
// This will be the first activity for considerable period on the blue wire
// The heater always responds to a controller frame, but otherwise never by itself
if(RxTimeElapsed >= (NVstore.getUserSettings().FrameRate - 60)) { // compensate for the time spent just doing things in this state machine
// have not seen any receive data for a second (typ.).
// OEM controller is probably not connected.
// Skip state machine immediately to BTC_Tx, sending our own settings.
bHasHtrData = false;
bHasOEMController = false;
bHasOEMLCDController = false;
isBTCmaster = true;
TxManage.PrepareFrame(DefaultBTCParams, isBTCmaster); // use our parameters, and mix in NV storage values
TxManage.Start(timenow);
CommState.set(CommStates::TxStart);
break;
}
if(BlueWireRxData.available() && (RxTimeElapsed > (RX_DATA_TIMOUT+10))) {
if(bReportOEMresync) {
char msg[64];
sprintf(msg, "Re-sync'd with OEM Controller. %ldms Idle time.\r\n", RxTimeElapsed);
pushDebugMsg(msg);
}
bHasHtrData = false;
bHasOEMController = true;
CommState.set(CommStates::OEMCtrlRx); // we must add this new byte!
//
// ** IMPORTANT - we must drop through to OEMCtrlRx *NOW* (skipping break) **
// ** otherwise the first byte will be lost! **
//
}
else {
break; // only break if we fail all Idle state tests
}
case CommStates::OEMCtrlRx:
digitalWrite(LED_Pin, HIGH);
// collect OEM controller frame
if(BlueWireRxData.available()) {
if(CommState.collectData(OEMCtrlFrame, BlueWireRxData.getValue()) ) {
CommState.set(CommStates::OEMCtrlValidate); // collected 24 bytes, move on!
}
}
break;
case CommStates::OEMCtrlValidate:
digitalWrite(LED_Pin, LOW);
// test for valid CRC, abort and restarts Serial1 if invalid
if(!validateFrame(OEMCtrlFrame, "OEM")) {
break;
}
// filled OEM controller frame
OEMCtrlFrame.setTime();
// LCD controllers use 0x76 as first byte, rotary knobs use 0x78
bHasOEMLCDController = (OEMCtrlFrame.Controller.Byte0 != 0x78);
// xQueueSend(BlueWireTxQueue, OEMCtrlFrame.Data, 0);
CommState.set(CommStates::HeaterRx1);
break;
case CommStates::HeaterRx1:
digitalWrite(LED_Pin, HIGH);
// collect heater frame, always in response to an OEM controller frame
if(BlueWireRxData.available()) {
if( CommState.collectData(HeaterFrame1, BlueWireRxData.getValue()) ) {
CommState.set(CommStates::HeaterValidate1);
}
}
break;
case CommStates::HeaterValidate1:
digitalWrite(LED_Pin, LOW);
// test for valid CRC, abort and restarts Serial1 if invalid
if(!validateFrame(HeaterFrame1, "RX1")) {
bHasHtrData = false;
break;
}
bHasHtrData = true;
HeaterFrame1.setTime();
while(BlueWireSerial.available()) {
pushDebugMsg("DUMPED ROGUE RX DATA\r\n");
BlueWireSerial.read();
}
BlueWireSerial.flush();
// received heater frame (after controller message), report
primaryHeaterData.set(HeaterFrame1, OEMCtrlFrame); // OEM is always *the* controller
if(bReportBlueWireData) {
primaryHeaterData.reportFrames(true, pushDebugMsg);
}
isBTCmaster = false;
TxManage.PrepareFrame(OEMCtrlFrame, isBTCmaster); // parrot OEM parameters, but block NV modes
CommState.set(CommStates::TxStart);
break;
case CommStates::TxStart:
xQueueSend(BlueWireTxQueue, TxManage.getFrame().Data, 0);
TxManage.Start(timenow);
CommState.set(CommStates::TxInterval);
break;
case CommStates::TxInterval:
// Handle time interval where we send data to the blue wire
lastRxTime = timenow; // *we* are pumping onto blue wire, track this activity!
if(TxManage.CheckTx(timenow) ) { // monitor progress of our data delivery
CommState.set(CommStates::HeaterRx2); // then await heater repsonse
}
break;
case CommStates::HeaterRx2:
digitalWrite(LED_Pin, HIGH);
// collect heater frame, in response to our control frame
if(BlueWireRxData.available()) {
#ifdef BADSTARTCHECK
if(!CommState.checkValidStart(BlueWireData.getValue())) {
DebugPort.println("***** Invalid start of frame - restarting Serial port *****");
initBlueWireSerial();
CommState.set(CommStates::Idle);
}
else {
if( CommState.collectData(HeaterFrame2, BlueWireData.getValue()) ) {
CommState.set(CommStates::HeaterValidate2);
}
}
#else
if( CommState.collectData(HeaterFrame2, BlueWireRxData.getValue()) ) {
CommState.set(CommStates::HeaterValidate2);
}
#endif
}
break;
case CommStates::HeaterValidate2:
digitalWrite(LED_Pin, LOW);
// test for valid CRC, abort and restart Serial1 if invalid
if(!validateFrame(HeaterFrame2, "RX2")) {
bHasHtrData = false;
break;
}
bHasHtrData = true;
// received heater frame (after our control message), report
xQueueSend(BlueWireRxQueue, HeaterFrame2.Data, 0);
// do some monitoring of the heater state variables
// if abnormal transitions, introduce a smart error!
// SmartError.monitor(HeaterFrame2);
if(!bHasOEMController) // no OEM controller - BTC is *the* controller
primaryHeaterData.set(HeaterFrame2, TxManage.getFrame());
if(bReportBlueWireData) { // debug or investigation purposes
reportHeaterData.set(HeaterFrame2, TxManage.getFrame());
reportHeaterData.reportFrames(false, pushDebugMsg);
}
CommState.set(CommStates::ExchangeComplete);
break;
case CommStates::ExchangeComplete:
xSemaphoreGive(BlueWireSemaphore);
CommState.set(CommStates::Idle);
break;
} // switch(CommState)
vTaskDelay(1);
}
}
bool validateFrame(const CProtocol& frame, const char* name)
{
if(!frame.verifyCRC(pushDebugMsg)) {
// Bad CRC - restart blue wire Serial port
char msg[128];
sprintf(msg, "\007Bad CRC detected for %s frame - restarting blue wire's serial port\r\n", name);
pushDebugMsg(msg);
msg[0] = 0; // empty string
DebugReportFrame("BAD CRC:", frame, "\r\n", msg);
pushDebugMsg(msg);
#ifdef REBOOT_BLUEWIRE
initBlueWireSerial();
#endif
CommState.set(CommStates::ExchangeComplete);
return false;
}
return true;
}
void DebugReportFrame(const char* hdr, const CProtocol& Frame, const char* ftr, char* msg)
{
strcat(msg, hdr); // header
for(int i=0; i<24; i++) {
char str[16];
sprintf(str, " %02X", Frame.Data[i]); // build 2 dig hex values
strcat(msg, str); // and print
}
strcat(msg, ftr); // footer
}
bool hasOEMcontroller()
{
return bHasOEMController;
}
bool hasOEMLCDcontroller()
{
return bHasOEMLCDController;
}
bool hasHtrData()
{
return bHasHtrData;
}
void initBlueWireSerial()
{
// initialize serial port to interact with the "blue wire"
// 25000 baud, Tx and Rx channels of Chinese heater comms interface:
// Tx/Rx data to/from heater,
// Note special baud rate for Chinese heater controllers
#if defined(__arm__) || defined(__AVR__)
BlueWireSerial.begin(25000);
pinMode(Rx1Pin, INPUT_PULLUP); // required for MUX to work properly
#elif ESP32
// ESP32
BlueWireSerial.begin(25000, SERIAL_8N1, Rx1Pin, Tx1Pin); // need to explicitly specify pins for pin multiplexer!
pinMode(Rx1Pin, INPUT_PULLUP); // required for MUX to work properly
#endif
}
// 0x00 - Normal: BTC, with heater responding
// 0x01 - Error: BTC, heater not responding
// 0x02 - Special: OEM controller & heater responding
// 0x03 - Error: OEM controller, heater not responding
int getBlueWireStat()
{
int stat = 0;
if(!bHasHtrData) {
stat |= 0x01;
}
if(bHasOEMController) {
stat |= 0x02;
}
return stat;
}
const char* getBlueWireStatStr()
{
static const char* BlueWireStates[] = { "BTC,Htr", "BTC", "OEM,Htr", "OEM" };
return BlueWireStates[getBlueWireStat()];
}
void reqPumpPrime(bool on)
{
DefaultBTCParams.setPump_Prime(on);
}

View File

@ -0,0 +1,40 @@
/*
* This file is part of the "bluetoothheater" distribution
* (https://gitlab.com/mrjones.id.au/bluetoothheater)
*
* Copyright (C) 2018 Ray Jones <ray@mrjones.id.au>
* Copyright (C) 2018 James Clark
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#ifndef __BLUEWIRETASK_H__
#define __BLUEWIRETASK_H__
#include <FreeRTOS.h>
#include "../Utility/UtilClasses.h"
extern QueueHandle_t BlueWireMsgBuf; // cannot use general Serial.print etc from this task without causing conflicts
extern QueueHandle_t BlueWireRxQueue; // queue to pass down heater receive data
extern QueueHandle_t BlueWireTxQueue; // queue to pass down heater transmit data
extern SemaphoreHandle_t BlueWireSemaphore; // flag to indicate completion of heater data exchange
const int BLUEWIRE_MSGQUEUESIZE = 192;
const int BLUEWIRE_DATAQUEUESIZE = 24;
extern void BlueWireTask(void*);
extern CommStates CommState;
#endif

View File

@ -54,15 +54,17 @@ CProtocol::getCRC() const
// return true for CRC match
bool
CProtocol::verifyCRC(bool bSilent) const
CProtocol::verifyCRC(std::function<void(const char*)> pushMsg) const
{
char errmsg[32];
CModBusCRC16 CRCengine;
uint16_t CRC = CRCengine.process(22, Data); // calculate CRC based on first 22 bytes of our data buffer
uint16_t FrameCRC = getCRC();
bool bOK = (FrameCRC == CRC);
if(!bOK && !bSilent) {
DebugPort.printf("verifyCRC FAILED: calc: %04X data: %04X\r\n", CRC, FrameCRC);
if(!bOK) {
sprintf(errmsg, "verifyCRC FAILED: calc: %04X data: %04X\r\n", CRC, FrameCRC);
pushMsg(errmsg);
}
return bOK; // does it match the stored values?
}
@ -430,16 +432,19 @@ CProtocolPackage::setRefTime()
}*/
void
CProtocolPackage::reportFrames(bool isOEM)
CProtocolPackage::reportFrames(bool isOEM, std::function<void(const char*)> pushMsg)
{
_timeStamp.report(); // absolute time
char msg[192];
msg[0] = 0;
_timeStamp.report(msg); // absolute time
if(isOEM) {
DebugReportFrame("OEM:", Controller, TERMINATE_OEM_LINE ? "\r\n" : " ");
DebugReportFrame("OEM:", Controller, TERMINATE_OEM_LINE ? "\r\n" : " ", msg);
}
else {
DebugReportFrame("BTC:", Controller, TERMINATE_BTC_LINE ? "\r\n" : " ");
DebugReportFrame("BTC:", Controller, TERMINATE_BTC_LINE ? "\r\n" : " ", msg);
}
DebugReportFrame("HTR:", Heater, "\r\n");
DebugReportFrame("HTR:", Heater, "\r\n", msg);
pushMsg(msg);
}
int

View File

@ -95,7 +95,7 @@ public:
void setCRC(); // calculate and set the CRC in the buffer
void setCRC(uint16_t CRC); // set the CRC in the buffer
uint16_t getCRC() const; // extract CRC value from buffer
bool verifyCRC(bool silent=false) const; // return true for CRC match
bool verifyCRC(std::function<void(const char*)> pushMsg) const; // return true for CRC match
void setActiveMode() { Controller.Byte0 = 0x76; }; // this allows heater to save tuning params to EEPROM
void setPassiveMode() { Controller.Byte0 = 0x78; }; // this prevents heater saving tuning params to EEPROM
@ -214,7 +214,7 @@ public:
int getAltitude() const { return Controller.getAltitude(); };
// void setRefTime();
void reportFrames(bool isOEM);
void reportFrames(bool isOEM, std::function<void(const char*)> pushMsg);
};
extern const CProtocolPackage& getHeaterInfo();

View File

@ -59,8 +59,7 @@ CSmartError::inhibit(bool reseterror)
void
CSmartError::monitor(const CProtocol& heaterFrame)
{
bool bSilent = true;
if(heaterFrame.verifyCRC(bSilent)) { // check but don't report dodgy frames to debug
if(heaterFrame.verifyCRC(NULL)) { // check but don't report dodgy frames to debug
// only accept valid heater frames!
monitor(heaterFrame.getRunState());
}

View File

@ -28,8 +28,6 @@
//#define DEBUG_THERMOSTAT
extern void DebugReportFrame(const char* hdr, const CProtocol&, const char* ftr);
// CTxManage is used to send a data frame to the blue wire
//
// As the blue wire is bidirectional, we need to only allow our transmit data
@ -71,6 +69,7 @@ CTxManage::CTxManage(int TxGatePin, HardwareSerial& serial) :
m_nTxGatePin = TxGatePin;
_rawCommand = 0;
m_HWTimer = NULL;
_callback = NULL;
}
// static function used for the tx gate termination
@ -198,7 +197,11 @@ CTxManage::PrepareFrame(const CProtocol& basisFrame, bool isBTCmaster)
float tDelta = tCurrent - tDesired;
float fTemp;
#ifdef DEBUG_THERMOSTAT
DebugPort.printf("Window=%.1f tCurrent=%.1f tDesired=%.1f tDelta=%.1f\r\n", Window, tCurrent, tDesired, tDelta);
if(_callback) {
char msg[80];
sprintf(msg, "Window=%.1f tCurrent=%.1f tDesired=%.1f tDelta=%.1f\r\n", Window, tCurrent, tDesired, tDelta);
_callback(msg);
}
#endif
Window /= 2;
switch(ThermoMode) {
@ -224,7 +227,11 @@ CTxManage::PrepareFrame(const CProtocol& basisFrame, bool isBTCmaster)
s8Temp = (int8_t)(tActual + 0.5);
m_TxFrame.setTemperature_Actual(s8Temp);
#ifdef DEBUG_THERMOSTAT
DebugPort.printf("Conventional thermostat mode: tActual = %d\r\n", u8Temp);
if(_callback) {
char msg[80];
sprintf(msg, "Conventional thermostat mode: tActual = %d\r\n", u8Temp);
_callback(msg);
}
#endif
break;
@ -241,7 +248,11 @@ CTxManage::PrepareFrame(const CProtocol& basisFrame, bool isBTCmaster)
}
m_TxFrame.setTemperature_Actual(s8Temp);
#ifdef DEBUG_THERMOSTAT
DebugPort.printf("Heater controlled windowed thermostat mode: tActual=%d\r\n", u8Temp);
if(_callback) {
char msg[80];
sprintf(msg, "Heater controlled windowed thermostat mode: tActual=%d\r\n", u8Temp);
_callback(msg);
}
#endif
break;
@ -251,7 +262,11 @@ CTxManage::PrepareFrame(const CProtocol& basisFrame, bool isBTCmaster)
// so create a desired "temp" according the the current hystersis
tDelta /= Window; // convert tDelta to fraction of window (CAUTION - may be > +-1 !)
#ifdef DEBUG_THERMOSTAT
DebugPort.printf("Linear window thermostat mode: Fraction=%f", tDelta);
if(_callback) {
char msg[80];
DebugPort.printf("Linear window thermostat mode: Fraction=%f", tDelta);
_callback(msg);
}
#endif
fTemp = (m_TxFrame.getTemperature_Max() + m_TxFrame.getTemperature_Min()) * 0.5; // midpoint - tDelta = 0 hinges here
tDelta *= (m_TxFrame.getTemperature_Max() - fTemp); // linear offset from setpoint
@ -264,8 +279,12 @@ CTxManage::PrepareFrame(const CProtocol& basisFrame, bool isBTCmaster)
m_TxFrame.setHeaterDemand(s8Temp);
m_TxFrame.setThermostatModeProtocol(0); // direct heater to use Hz Mode
m_TxFrame.setTemperature_Actual(0); // must force actual to 0 for Hz mode
#ifdef DEBUG_THERMOSTAT
DebugPort.printf(" tDesired (pseudo Hz demand) = %d\r\n", u8Temp);
#ifdef DEBUG_THERMOSTAT
if(_callback) {
char msg[80];
sprintf(msg, " tDesired (pseudo Hz demand) = %d\r\n", u8Temp);
_callback(msg);
}
#endif
break;
}

View File

@ -27,6 +27,7 @@ class CTxManage
const int m_nFrameTime = 14;
const int m_nFrontPorch = 0;
int m_sysUpdate;
std::function<void(const char*)> _callback;
public:
CTxManage(int TxGatePin, HardwareSerial& serial);
@ -40,6 +41,7 @@ public:
const CProtocol& getFrame() const { return m_TxFrame; };
static void IRAM_ATTR callbackGateTerminate();
void queueSysUpdate(); // use to implant NV settings into heater
void setCallback(std::function<void(const char*)> fn) { _callback = fn; };
private:
HardwareSerial& m_BlueWireSerial;

View File

@ -30,6 +30,6 @@ class CProtocol;
extern ABTelnetSpy DebugPort;
void DebugReportFrame(const char* hdr, const CProtocol& Frame, const char* ftr);
void DebugReportFrame(const char* hdr, const CProtocol& Frame, const char* ftr, char* msg);
#endif // __DEBUGPORT_H__

View File

@ -438,16 +438,22 @@ CBME280Sensor::getTemperature(float& tempReading, bool filtered)
}
bool
CBME280Sensor::getAltitude(float& reading)
CBME280Sensor::getAltitude(float& reading, bool fresh)
{
reading = _bme.readAltitude(1013.25); //use standard atmosphere as reference
if(fresh) {
_fAltitude = _bme.readAltitude(1013.25); //use standard atmosphere as reference
}
reading = _fAltitude;
return true;
}
bool
CBME280Sensor::getHumidity(float& reading)
CBME280Sensor::getHumidity(float& reading, bool fresh)
{
reading = _bme.readHumidity();
if(fresh) {
_fHumidity = _bme.readHumidity();
}
reading = _fHumidity;
return true;
}
@ -489,6 +495,10 @@ CTempSense::startConvert()
bool
CTempSense::readSensors()
{
float fDummy;
getAltitude(fDummy, true);
getHumidity(fDummy, true);
return DS18B20.readSensors();
}
@ -628,19 +638,19 @@ CTempSense::getTemperatureBME280(float& reading)
}
bool
CTempSense::getAltitude(float& reading)
CTempSense::getAltitude(float& reading, bool fresh)
{
if(BME280.getCount())
return BME280.getAltitude(reading);
return BME280.getAltitude(reading, fresh);
else
return false;
}
bool
CTempSense::getHumidity(float& reading)
CTempSense::getHumidity(float& reading, bool fresh)
{
if(BME280.getCount())
return BME280.getHumidity(reading);
return BME280.getHumidity(reading, fresh);
else
return false;
}

View File

@ -89,13 +89,15 @@ public:
class CBME280Sensor : public CSensor {
Adafruit_BME280 _bme; // I2C
long _lastSampleTime;
float _fAltitude;
float _fHumidity;
int _count;
public:
CBME280Sensor();
bool begin(int ID);
bool getTemperature(float& tempReading, bool filtered) ;
bool getAltitude(float& reading);
bool getHumidity(float& reading);
bool getAltitude(float& reading, bool fresh=false);
bool getHumidity(float& reading, bool fresh=false);
const char* getID();
int getCount() const { return _count; };
};
@ -119,8 +121,8 @@ public:
bool getTemperatureBME280(float& tempReading) ; // index is sensor discovery order on one-wire bus
bool getTemperatureDS18B20Idx(int sensIdx, float& tempReading) ; // index is sensor discovery order on one-wire bus
int getNumSensors() const;
bool getAltitude(float& reading);
bool getHumidity(float& reading);
bool getAltitude(float& reading, bool fresh=false);
bool getHumidity(float& reading, bool fresh=false);
CBME280Sensor& getBME280() { return BME280; };
CDS18B20SensorSet& getDS18B20() { return DS18B20; };
static void format(char* msg, float fTemp);

View File

@ -38,13 +38,16 @@ CommStates::set(eCS eState)
{
_State = eState;
_Count = 0;
if(_report) {
if(_report && _callback != NULL) {
static const char* stateNames[] = {
"Idle", "OEMCtrlRx", "OEMCtrlValidate", "HeaterRx1", "HeaterValidate1", "HeaterReport1",
"BTC_Tx", "HeaterRx2", "HeaterValidate2", "HeaterReport2", "TemperatureRead"
"Idle", "OEMCtrlRx", "OEMCtrlValidate", "HeaterRx1", "HeaterValidate1", "TxStart",
"TxInterval", "HeaterRx2", "HeaterValidate2", "ExchangeComplete"
};
if(_State == Idle) DebugPort.println(""); // clear screen
DebugPort.printf("State: %s\r\n", stateNames[_State]);
if(_State == Idle)
_callback("\r\n");
char msg[32];
sprintf(msg, "State: %s\r\n", stateNames[_State]);
_callback(msg);
}
}
@ -54,17 +57,6 @@ CommStates::collectData(CProtocol& Frame, uint8_t val, int limit) { // returns
return _Count >= limit;
}
bool
CommStates::collectDataEx(CProtocol& Frame, uint8_t val, int limit) { // returns true when buffer filled
// guarding against rogue rx kernel buffer stutters....
if((_Count == 0) && (val != 0x76)) {
DebugPort.println("First heater byte not 0x76 - SKIPPING");
return false;
}
Frame.Data[_Count++] = val;
return _Count >= limit;
}
bool
CommStates::checkValidStart(uint8_t val)
{
@ -87,6 +79,8 @@ CommStates::delayExpired()
return(test >= 0);
}
CProfile::CProfile()
{
tStart = millis();
@ -103,6 +97,8 @@ CProfile::elapsed(bool reset/* = false*/)
return retval;
}
void DecodeCmd(const char* cmd, String& payload)
{
int val;

View File

@ -29,11 +29,14 @@
class CProtocol;
// a class to track the blue wire receive / transmit states
#define COMMSTATES_CALLBACK_SIGNATURE std::function<void(char*)> CScallback
class CommStates {
public:
// comms states
enum eCS {
Idle, OEMCtrlRx, OEMCtrlValidate, HeaterRx1, HeaterValidate1, HeaterReport1, BTC_Tx, HeaterRx2, HeaterValidate2, HeaterReport2,TemperatureRead
Idle, OEMCtrlRx, OEMCtrlValidate, HeaterRx1, HeaterValidate1, TxStart, TxInterval, HeaterRx2, HeaterValidate2, ExchangeComplete
};
private:
@ -41,12 +44,14 @@ private:
int _Count;
unsigned long _delay;
bool _report;
std::function<void(const char*)> _callback;
public:
CommStates() {
_State = Idle;
_Count = 0;
_delay = millis();
_report = REPORT_STATE_MACHINE_TRANSITIONS;
_report = false;
_callback = NULL;
}
void set(eCS eState);
eCS get() {
@ -56,7 +61,6 @@ public:
return _State == eState;
}
bool collectData(CProtocol& Frame, uint8_t val, int limit = 24);
bool collectDataEx(CProtocol& Frame, uint8_t val, int limit = 24);
bool checkValidStart(uint8_t val);
void setDelay(int ms);
bool delayExpired();
@ -67,6 +71,7 @@ public:
bool isReporting() {
return _report != 0;
};
void setCallback(std::function<void(const char*)> fn) { _callback = fn; };
};
@ -128,19 +133,29 @@ public:
void setRefTime() {
refTime = millis();
};
void report(bool isDelta) {
void report(bool isDelta, char* msg=NULL) {
if(isDelta) {
long delta = millis() - prevTime;
DebugPort.printf("%+8ldms ", delta);
if(msg)
sprintf(msg, "%+8ldms ", delta);
else
DebugPort.printf("%+8ldms ", delta);
}
else {
prevTime = millis();
DebugPort.printf("%8ldms ", prevTime - refTime);
if(msg)
sprintf(msg, "%8ldms ", prevTime - refTime);
else
DebugPort.printf("%8ldms ", prevTime - refTime);
}
};
void report() {
void report(char* msg = NULL) {
prevTime = millis();
DebugPort.printf("%8ldms ", prevTime - refTime);
if(msg) {
sprintf(msg, "%8ldms ", prevTime - refTime);
}
else
DebugPort.printf("%8ldms ", prevTime - refTime);
};
};

View File

@ -45,6 +45,7 @@ extern void resetFuelGauge();
extern const char* getBlueWireStatStr();
extern bool hasOEMcontroller();
extern bool hasOEMLCDcontroller();
extern bool hasHtrData();
extern int getBlueWireStat();
extern int getSmartError();
extern bool isCyclicActive();
@ -73,8 +74,8 @@ extern CTempSense& getTempSensor() ;
extern void reqHeaterCalUpdate();
void setSSID(const char* name);
void setAPpassword(const char* name);
void setName(const char* name, int type);
void setPassword(const char* name, int type);
extern void ShowOTAScreen(int percent=0, eOTAmodes updateType=eOTAnormal);

View File

@ -150,7 +150,7 @@ bool initWifi()
}
// WiFi.setTxPower(WIFI_POWER_MINUS_1dBm);
// WiFi.setTxPower(WIFI_POWER_19_5dBm);
WiFi.setTxPower(WIFI_POWER_19_5dBm);
return retval;
}

View File

@ -118,9 +118,6 @@ sBrowserUpload::fragment(HTTPUpload& upload)
::SPIFFS.remove(SrcFile.name.c_str()); // remove the bad file from SPIFFS
return -2;
}
#ifdef SSL_SERVER
upload.totalSize += upload.currentSize;
#endif
}
}
else {
@ -130,9 +127,6 @@ sBrowserUpload::fragment(HTTPUpload& upload)
Update.printError(DebugPort);
return -3;
}
#ifdef SSL_SERVER
upload.totalSize += upload.currentSize;
#endif
}
return upload.totalSize;
}