Merge branch 'WebAuth' into SSLtrials

Conflicts resolved:
	src/Afterburner.cpp
	src/WiFi/BTCWebServer.cpp
	src/WiFi/BrowserUpload.cpp
	src/cfg/BTCConfig.h
This commit is contained in:
Ray Jones 2020-04-26 19:52:00 +10:00
commit c74f0a76eb
26 changed files with 1304 additions and 698 deletions

View File

@ -423,6 +423,129 @@ bool Adafruit_BME280::isReadingCalibration(void) {
return (rStatus & (1 << 0)) != 0;
}
/*!
* Pressure and humidity readings require precise temperature for correctness.
* For this reason both readPressure() and readHumidity() call readTemperature() internally,
* which results in 2 SPI/I2C transactions for those readings.
*
* If user code calls a sequence of individual read*() methods to get all sensed values
* it may make sense to replace it with a call to this method
* and get all readings in 3 SPI/I2C transactions, instead of 5.
*
* @brief Returns all environmental values sensed
* @returns 0 on failure, otherwise a bitwise OR of BME280_{T,P,H}_OK flags
* @param readings reference to bme280_readings structure to be filled with data
*/
int Adafruit_BME280::readAll(bme280_readings& readings)
{
int retval = 0;
readings.temperature = readTemperature(); // will set t_fine attribute, for immediate reuse
if (readings.temperature == NAN) // temperature is required for other measurements, abort
{
readings.humidity = NAN;
readings.pressure = NAN;
readings.altitude = NAN;
return retval;
}
retval |= BME280_T_OK; // temperature read OK
// t_fine attribute has just been updated by readTemperature(), proceed
// below code copied almost verbatim from readPressure()
int64_t var1, var2, p;
int32_t adc_P = read24(BME280_REGISTER_PRESSUREDATA);
// less readable code, but reading humidity register could be moved here to minimise
// time before obtaining t_fine and applying it to humidity calculations
// int32_t adc_H = read16(BME280_REGISTER_HUMIDDATA);
if (adc_P == 0x800000) // value in case pressure measurement was disabled
{
readings.pressure = NAN;
}
else
{
adc_P >>= 4;
var1 = ((int64_t)t_fine) - 128000;
var2 = var1 * var1 * (int64_t)_bme280_calib.dig_P6;
var2 = var2 + ((var1 * (int64_t)_bme280_calib.dig_P5) << 17);
var2 = var2 + (((int64_t)_bme280_calib.dig_P4) << 35);
var1 = ((var1 * var1 * (int64_t)_bme280_calib.dig_P3) >> 8) +
((var1 * (int64_t)_bme280_calib.dig_P2) << 12);
var1 = (((((int64_t)1) << 47) + var1)) * ((int64_t)_bme280_calib.dig_P1) >> 33;
if (var1 == 0)
{
readings.pressure = (float) 0.0; // avoid exception caused by division by zero
}
else
{
p = 1048576 - adc_P;
p = (((p << 31) - var2) * 3125) / var1;
var1 = (((int64_t)_bme280_calib.dig_P9) * (p >> 13) * (p >> 13)) >> 25;
var2 = (((int64_t)_bme280_calib.dig_P8) * p) >> 19;
p = ((p + var1 + var2) >> 8) + (((int64_t)_bme280_calib.dig_P7) << 4);
readings.pressure = (float) p / 256;
retval |= BME280_P_OK; // pressure read OK
// calculate altitude ref to std sea level pressure
readings.altitude = readAltitude(1013.25);
}
}
// proceed with reading humidity
// again, code copied almost verbatim from readHumidity()
// t_fine attribute is assumed to be valid
int32_t adc_H = read16(BME280_REGISTER_HUMIDDATA);
if (adc_H == 0x8000)
{ // value in case humidity measurement was disabled
readings.humidity = NAN;
}
else
{
int32_t v_x1_u32r;
v_x1_u32r = (t_fine - ((int32_t)76800));
v_x1_u32r = (((((adc_H << 14) - (((int32_t)_bme280_calib.dig_H4) << 20) -
(((int32_t)_bme280_calib.dig_H5) * v_x1_u32r)) +
((int32_t)16384)) >>
15) *
(((((((v_x1_u32r * ((int32_t)_bme280_calib.dig_H6)) >> 10) *
(((v_x1_u32r * ((int32_t)_bme280_calib.dig_H3)) >> 11) +
((int32_t)32768))) >>
10) +
((int32_t)2097152)) *
((int32_t)_bme280_calib.dig_H2) +
8192) >>
14));
v_x1_u32r = (v_x1_u32r - (((((v_x1_u32r >> 15) * (v_x1_u32r >> 15)) >> 7) *
((int32_t)_bme280_calib.dig_H1)) >>
4));
v_x1_u32r = (v_x1_u32r < 0) ? 0 : v_x1_u32r;
v_x1_u32r = (v_x1_u32r > 419430400) ? 419430400 : v_x1_u32r;
float h = (v_x1_u32r >> 12);
readings.humidity = h / 1024.0;
retval |= BME280_H_OK; // humidity reading OK
}
return retval;
}
/*!
* @brief Returns the temperature from the sensor
* @returns the temperature read from the device

View File

@ -127,13 +127,27 @@ class Adafruit_BME280_Unified : public Adafruit_Sensor
*/
/***********************************************************/
/*!
@brief environment readings combined
*/
/***********************************************************/
typedef struct {
float temperature; // temperature sensed [C]
float humidity; // humidity sensed [%Rh]
float pressure; // pressure sensed [Pa]
float altitude; // [m], referenced to std. sea level pressure
} bme280_readings;
/**************************************************************************/
/*!
@brief Class that stores state and functions for interacting with BME280 IC
*/
/**************************************************************************/
class Adafruit_BME280 {
public:
/*=========================================================*/
/**************************************************************************/
/*!
@brief sampling rates
@ -188,6 +202,19 @@ public:
STANDBY_MS_1000 = 0b101
};
/*******************************************************/
/*!
@brief read status for readAll()
*/
/*******************************************************/
enum read_success {
BME280_T_OK = 0x01,
BME280_P_OK = 0x02,
BME280_H_OK = 0x04
};
// constructors
Adafruit_BME280();
Adafruit_BME280(int8_t cspin, SPIClass *theSPI = &SPI);
@ -214,6 +241,8 @@ public:
float readAltitude(float seaLevel);
float seaLevelForAltitude(float altitude, float pressure);
int readAll(bme280_readings& readings);
uint32_t sensorID(void);
protected:

View File

@ -85,10 +85,10 @@ const int _number_of_closed_slots = CONFIG_LWIP_MAX_ACTIVE_TCP;
static uint32_t _closed_slots[_number_of_closed_slots];
static uint32_t _closed_index = []() {
_slots_lock = xSemaphoreCreateBinary();
xSemaphoreGive(_slots_lock);
for (int i = 0; i < _number_of_closed_slots; ++ i) {
_closed_slots[i] = 1;
_closed_slots[i] = 1; // slot available
}
xSemaphoreGive(_slots_lock);
return 1;
}();
@ -849,21 +849,25 @@ void AsyncClient::_allocate_closed_slot(){
}
}
if (_closed_slot != -1) {
_closed_slots[_closed_slot] = 0;
_closed_slots[_closed_slot] = 0; // slot in use!
}
xSemaphoreGive(_slots_lock);
}
void AsyncClient::_free_closed_slot(){
xSemaphoreTake(_slots_lock, portMAX_DELAY);
if(_closed_slot >= 16 || _closed_slot < -1) {
Serial.printf("CLOSED SLOTS BOUNDS!! free_closed_slot (%d)\r\n", _closed_slot);
xSemaphoreGive(_slots_lock);
return;
}
if (_closed_slot != -1) {
_closed_slots[_closed_slot] = _closed_index;
_closed_slots[_closed_slot] = _closed_index; // slot released by index
_closed_slot = -1;
++ _closed_index;
if(_closed_index == 0) _closed_index = 1;
}
xSemaphoreGive(_slots_lock);
}
/*
@ -888,12 +892,12 @@ int8_t AsyncClient::_connected(void* pcb, int8_t err){
void AsyncClient::_error(int8_t err) {
if(_pcb){
tcp_arg(_pcb, NULL);
if(_pcb->state == LISTEN) {
// if(_pcb->state == LISTEN) {
tcp_sent(_pcb, NULL);
tcp_recv(_pcb, NULL);
tcp_err(_pcb, NULL);
tcp_poll(_pcb, NULL, 0);
}
// }
_pcb = NULL;
}
if(_error_cb) {
@ -911,12 +915,12 @@ int8_t AsyncClient::_lwip_fin(tcp_pcb* pcb, int8_t err) {
return ERR_OK;
}
tcp_arg(_pcb, NULL);
if(_pcb->state == LISTEN) {
// if(_pcb->state == LISTEN) {
tcp_sent(_pcb, NULL);
tcp_recv(_pcb, NULL);
tcp_err(_pcb, NULL);
tcp_poll(_pcb, NULL, 0);
}
// }
if(tcp_close(_pcb) != ERR_OK) {
tcp_abort(_pcb);
}

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

@ -84,7 +84,7 @@ CClock::update()
_currentTime = _rtc.now(); // moderate I2C accesses
Wire.setClock(origClock);
_nextRTCfetch = millis() + 500;
// _checkTimers();
// check timers upon minute rollovers
if(_currentTime.minute() != _prevMinute) {
CTimerManager::manageTime(_currentTime.hour(), _currentTime.minute(), _currentTime.dayOfTheWeek());

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

@ -66,21 +66,30 @@ CGetLine::handle(char rxVal)
if(rxVal < ' ') {
if(_idx == 0) {
if(_pTarget)
strcpy(_buffer, _pTarget);
strcpy(_buffer, _pTarget); // copy buffer if control upon first key, may well be a enter
}
if(rxVal == ('x' & 0x1f)) { // CTRL-X - erase string, return done
memset(_buffer, 0, sizeof(_buffer));
// CTRL-H (backspace)
if(rxVal == ('h' & 0x1f)) {
if(_idx)
_idx--;
}
// CTRL-X
if(rxVal == ('x' & 0x1f)) {
memset(_buffer, 0, sizeof(_buffer)); // erase string, return done
_zeroTarget();
return true;
}
if(rxVal == '\r') // ignore CR
return false;
if(rxVal == '\n') { // accept buffered string upon LF, return done
_copyTarget();
// CR (ala CTRL-M)
if(rxVal == '\r')
return false; // do nothing upon CR
// LF (ala CTRL-J)
if(rxVal == '\n') {
_copyTarget(); // accept buffered string upon LF, return done
return true;
}
if(rxVal == 0x1b) { // abort, no change upon ESC, return done
return true;
// ESC
if(rxVal == 0x1b) {
return true; // abort, no change upon ESC, return done
}
}
else {
@ -89,10 +98,16 @@ CGetLine::handle(char rxVal)
DebugPort.print('*');
else
DebugPort.print(rxVal);
_buffer[_idx++] = rxVal;
if(_idx == _maxlen) {
_copyTarget();
return true;
if(rxVal == 0x7f) { // backspace
if(_idx)
_idx--;
}
else {
_buffer[_idx++] = rxVal;
if(_idx == _maxlen) {
_copyTarget();
return true;
}
}
}
return false;
@ -109,6 +124,11 @@ CGetLine::_doNum(char rxVal)
_Numeric = val;
return true;
}
// CTRL-H (backspace)
if(rxVal == ('h' & 0x1f)) {
if(_idx)
_idx--;
}
if(rxVal == 0x1b) {
return true;
}
@ -125,6 +145,11 @@ CGetLine::_doNum(char rxVal)
}
}
else {
if(rxVal == 0x7f) { // backspace
if(_idx)
_idx--;
return false;
}
return true;
}
return false;

View File

@ -183,3 +183,277 @@ CMQTTsetup::HandleMQTTsetup(char rxVal)
return true;
}
CSecuritySetup::CSecuritySetup()
{
_active = false;
_password.Idx = 0;
_password.State = 0;
}
void
CSecuritySetup::setActive()
{
_active = true;
_showMenu(true);
}
void insertDummy(int len);
void
CSecuritySetup::_showMenu(bool init)
{
_mode = 0;
_password.Idx = 0;
_password.State = 0;
DebugPort.enable(true);
if(init)
_credsSetup = NVstore.getCredentials();
int len;
DebugPort.print("\014");
DebugPort.println("Security configuration");
DebugPort.println("");
DebugPort.println(" Access Point credentials");
DebugPort.printf(" <1> - set SSID, currently \"%s\"\r\n", _credsSetup.APSSID);
DebugPort.print(" <2> - set password");
len = strlen(_credsSetup.APpassword);
insertDummy(len);
DebugPort.println("");
DebugPort.println(" Web page credentials");
DebugPort.printf(" <3> - set username, currently \"%s\"\r\n", _credsSetup.webUsername);
DebugPort.print(" <4> - set password");
len = strlen(_credsSetup.webPassword);
insertDummy(len);
DebugPort.println("");
DebugPort.println(" /update web page credentials");
DebugPort.printf(" <5> - set username, currently \"%s\"\r\n", _credsSetup.webUpdateUsername);
DebugPort.printf(" <6> - set password");
len = strlen(_credsSetup.webUpdatePassword);
insertDummy(len);
DebugPort.println("");
DebugPort.printf(" <ENTER> - save and exit\r\n");
DebugPort.printf(" <ESC> - abort\r\n");
DebugPort.enable(false); // suppress sundry debug whilst Security menu is active
}
void insertDummy(int len) {
if(len == 0)
DebugPort.println(", NOT REQUIRED!");
else {
char dummy[32];
memset(dummy, 0, 32);
if(len > 31)
len = 31;
for(int i = 0; i < len; i++)
dummy[i] = '*';
DebugPort.printf(" (%s)\r\n", dummy);
}
}
bool
CSecuritySetup::Handle(char& rxVal)
{
if(_active) {
DebugPort.enable(true);
_active = _handle(rxVal);
if(_active)
DebugPort.enable(false);
else
rxVal = 0;
return true;
}
return false;
}
bool
CSecuritySetup::_handle(char rxVal)
{
bool bJumptoMenuRoot = false;
if(_getPassword()) {
if(_handlePassword(rxVal)) {
if(!_getPassword())
_showMenu();
}
return true;
}
switch(_mode) {
case 0: // initial menu entry selection
if(rxVal == 0x1b) {
_credsSetup = NVstore.getCredentials();
return false;
}
if(rxVal == '\n') {
NVstore.setCredentials(_credsSetup);
NVstore.save();
return false;
}
if(rxVal >= '1' && rxVal <= '6') {
_mode = rxVal - '0';
DebugPort.print("\014");
switch(_mode) {
case 1:
DebugPort.printf("Enter new AP SSID (%s)", _credsSetup.APSSID);
_lineInput.reset(_credsSetup.APSSID, 31);
break;
case 2:
DebugPort.print("Enter current AP password");
_initPassword(0, "inbuilt Access Point");
break;
case 3:
DebugPort.printf("Enter new Web page access username (currently '%s', CTRL-X to erase)", _credsSetup.webUsername);
_lineInput.reset(_credsSetup.webUsername, 31);
break;
case 4:
DebugPort.print("Enter current web page access password");
_initPassword(1, "web page access");
break;
case 5:
DebugPort.printf("Enter new /update web page access username (currently '%s', CTRL-X to erase)", _credsSetup.webUpdateUsername);
_lineInput.reset(_credsSetup.webUpdateUsername, 31);
break;
case 6:
DebugPort.print("Enter current /update web page access password");
_initPassword(2, "/update web page access");
break;
}
DebugPort.print("... ");
}
else {
_showMenu();
}
return true;
case 1: // enter AP SSID
case 2: // enter AP password
case 3: // enter web page username
case 4: // enter web page password
case 5: // enter /update username
case 6: // enter /update password
if(_lineInput.handle(rxVal)) {
bJumptoMenuRoot = true;
}
break;
}
if(bJumptoMenuRoot) {
_showMenu();
}
return true;
}
void
CSecuritySetup::_initPassword(int idx, const char* prompt)
{
_lineInput.reset();
_lineInput.maskEntry();
_password.Idx = idx;
_password.State = 1;
if(strlen(_getCurrentPassword()) == 0) {
DebugPort.printf("\rEnter password for %s (CTRL-X for no password) - ", prompt);
_password.State = 2;
}
}
bool
CSecuritySetup::_getPassword()
{
return _password.State != 0;
}
bool
CSecuritySetup::_handlePassword(char rxVal)
{
switch(_password.State) {
case 1: // collect, then test existing password
if(_lineInput.handle(rxVal)) {
_password.str1 = _lineInput.getString();
_password.str2 = _getCurrentPassword();
if(_password.str1 != _password.str2) {
DebugPort.println("\r\nPassword does not match existing - ABORTING");
_password.State = 0;
}
else {
_password.State = 2;
DebugPort.print("\r\nPlease enter new password (CTRL-X for no password) - ");
DebugPort.enable(false); // block other debug msgs whilst we get the password
}
_lineInput.reset();
_lineInput.maskEntry();
}
return true;
case 2:
if(rxVal == ('x' & 0x1f)) { // special handling for CTRL-X - erase password
_password.State = 4;
DebugPort.print("\r\nConfirm no password required? (y/n) - ");
_password.str2 = "";
return true;
}
if(_lineInput.handle(rxVal)) {
_password.str1 = _lineInput.getString();
if(_lineInput.getLen() < 8) {
// ABORT - too short
DebugPort.println("\r\nNew password must be at least 8 characters - ABORTING");
_password.State = 0;
}
else if(_lineInput.getLen() > 31) {
// ABORT - too long!
DebugPort.println("\r\nNew password is longer than 31 characters - ABORTING");
_password.State = 0;
}
else {
_password.State = 3;
DebugPort.print("\r\nPlease confirm new password - ");
DebugPort.enable(false); // block other debug msgs whilst we get the password
}
_lineInput.reset();
_lineInput.maskEntry();
}
return true;
case 3:
if(_lineInput.handle(rxVal)) {
_password.str2 = _lineInput.getString();
_lineInput.reset();
if(_password.str1 != _password.str2) {
DebugPort.println("\r\nNew passwords do not match - ABORTING");
_password.State = 0;
}
else {
_password.State = 4;
DebugPort.print("\r\nSet new password (y/n) - ");
}
}
return true;
case 4:
if(rxVal == 'y' || rxVal == 'Y') {
_setPassword(_password.str2.c_str());
}
_password.State = 0;
return true;
}
return false;
}
const char*
CSecuritySetup::_getCurrentPassword() {
switch(_password.Idx) {
case 0: return _credsSetup.APpassword;
case 1: return _credsSetup.webPassword;
case 2: return _credsSetup.webUpdatePassword;
}
return "";
}
void
CSecuritySetup::_setPassword(const char* newPW)
{
switch(_password.Idx) {
case 0: strcpy(_credsSetup.APpassword, newPW); break;
case 1: strcpy(_credsSetup.webPassword, newPW); break;
case 2: strcpy(_credsSetup.webUpdatePassword, newPW); break;
}
}

View File

@ -35,3 +35,26 @@ public:
bool Handle(char& rxVal);
void setActive();
};
class CSecuritySetup {
CGetLine _lineInput;
int _mode;
bool _active;
struct {
int Idx;
int State;
String str1, str2;
} _password;
sCredentials _credsSetup;
bool _handle(char rxVal);
void _showMenu(bool init = false);
void _initPassword(int idx, const char*prompt);
bool _getPassword();
bool _handlePassword(char rxVal);
const char* _getCurrentPassword();
void _setPassword(const char* newPW);
public:
CSecuritySetup();
bool Handle(char& rxVal);
void setActive();
};

View File

@ -429,6 +429,7 @@ CBME280Sensor::getTemperature(float& tempReading, bool filtered)
float temperature = _bme.readTemperature();
update(temperature);
_lastSampleTime = millis() + 1000;
DebugPort.println("Forced BME sensor reading");
}
CSensor::getTemperature(tempReading, filtered);
@ -438,19 +439,38 @@ 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;
}
int
CBME280Sensor::getAllReadings(bme280_readings& readings)
{
int retval = _bme.readAll(readings);
_fAltitude = readings.altitude;
_fHumidity = readings.humidity;
update(readings.temperature);
_lastSampleTime = millis() + 1000;
return retval;
}
const char*
CBME280Sensor::getID()
{
@ -489,6 +509,9 @@ CTempSense::startConvert()
bool
CTempSense::readSensors()
{
bme280_readings readings;
getBME280().getAllReadings(readings);
return DS18B20.readSensors();
}
@ -628,19 +651,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,16 @@ 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);
int getAllReadings(bme280_readings& readings);
const char* getID();
int getCount() const { return _count; };
};
@ -119,8 +122,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

@ -66,6 +66,8 @@ extern const char* updateIndex;
extern const char* formatDoneContent;
extern const char* rebootIndex;
QueueHandle_t webSocketQueue = NULL;
extern void checkSplashScreenUpdate();
size_t streamFileSSL(fs::File &file, const String& contentType, httpsserver::HTTPResponse* pSSL);
@ -899,9 +901,6 @@ function onformatClick() {
void onWMConfig(HTTPRequest * req, httpsserver::HTTPResponse * res)
{
DebugPort.println("WEB: GET /wmconfig");
// server.send(200, "text/plain", "Start Config Portal - Retaining credential");
// res->setStatusCode(200);
// res->setHeader("Content-Type", "text/plain");
res->print("Start Config Portal - Retaining credential");
DebugPort.println("Starting web portal for wifi config");
delay(500);
@ -912,9 +911,6 @@ void onWMConfig(HTTPRequest * req, httpsserver::HTTPResponse * res)
void onResetWifi(HTTPRequest * req, httpsserver::HTTPResponse * res)
{
DebugPort.println("WEB: GET /resetwifi");
// server.send(200, "text/plain", "Start Config Portal - Resetting Wifi credentials!");
// res->setStatusCode(200);
// res->setHeader("Content-Type", "text/plain");
res->print("Start Config Portal - Resetting Wifi credentials!");
DebugPort.println("diconnecting client and wifi, then rebooting");
delay(500);
@ -936,7 +932,11 @@ bool sendWebSocketString(const char* Str)
CProfile profile;
#endif
if(webSocket.connectedClients()) {
char* pMsg = new char[strlen(Str)+1];
strcpy(pMsg, Str);
if(webSocketQueue) xQueueSend(webSocketQueue, &pMsg, 0);
/* if(webSocket.connectedClients()) {
#ifdef WEBTIMES
unsigned long tCon = profile.elapsed(true);

View File

@ -36,6 +36,7 @@ void listSPIFFS(const char * dirname, uint8_t levels, String& HTMLreport, int wi
const char* getWebContent(bool start);
void getWebContent(const char* filename);
bool checkWebSocketSend();
#endif

View File

@ -157,7 +157,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

@ -103,7 +103,7 @@ sBrowserUpload::begin(String& filename, int filesize)
}
int
sBrowserUpload::fragment(HTTPUpload& upload, httpsserver::HTTPResponse * res)
sBrowserUpload::fragment(HTTPUpload& upload, HTTPResponse * res)
{
if(isSPIFFSupload()) {
// SPIFFS update (may be error state)

View File

@ -119,7 +119,7 @@
#define USE_SSL_LOOP_TASK 1
// FreeRTOS task priorities
#define TASKPRIORITY_ARDUINO 3
#define TASKPRIORITY_HEATERCOMMS 4
#define TASKPRIORITY_SSL_CERT 1
#define TASKPRIORITY_SSL_LOOP 1
#define TASK_PRIORITY_ARDUINO 3
#define TASK_PRIORITY_HEATERCOMMS 4
#define TASK_PRIORITY_SSL_CERT 1
#define TASK_PRIORITY_SSL_LOOP 1