Restructured Folders

This commit is contained in:
2022-05-07 23:24:42 +02:00
parent f514ee62fc
commit ad6332acd4
39 changed files with 0 additions and 0 deletions

46
Software/src/can.cpp Normal file
View File

@@ -0,0 +1,46 @@
#ifdef FEATURE_ENABLE_CAN
#include "can.h"
MCP_CAN CAN0(GPIO_CS_CAN);
void Init_CAN()
{
if (CAN0.begin(MCP_STDEXT, CAN_500KBPS, MCP_16MHZ) != CAN_OK)
MaintainDTC(DTC_CAN_TRANSCEIVER_FAILED, true);
CAN0.init_Mask(0, 0, 0x07FF0000); // Init first mask...
CAN0.init_Mask(1, 0, 0x07FF0000); // Init second mask...
CAN0.init_Filt(0, 0, 0x012D0000); // Init first filter...
CAN0.setMode(MCP_NORMAL);
}
uint32_t Process_CAN_WheelSpeed()
{
#define FACTOR_RWP_KMH_890ADV 18 // Divider to convert Raw Data to km/h
can_frame canMsg;
static uint32_t lastRecTimestamp = 0;
uint16_t RearWheelSpeed_raw;
if (CAN0.readMsgBuf(&canMsg.can_id, &canMsg.can_dlc, canMsg.data) == CAN_OK)
{
RearWheelSpeed_raw = (uint16_t)canMsg.data[5] << 8 | canMsg.data[6];
// raw / FACTOR_RWP_KMH_890ADV -> km/h * 100000 -> cm/h / 3600 -> cm/s
// raw * 500 -> cm/s
uint32_t RWP_millimeter_per_second = (((uint32_t)RearWheelSpeed_raw * 1000000) / FACTOR_RWP_KMH_890ADV) / 3600;
uint32_t timesincelast = millis() - lastRecTimestamp;
lastRecTimestamp = millis();
uint32_t milimeters_to_add = (RWP_millimeter_per_second * timesincelast) / 1000;
return milimeters_to_add;
}
MaintainDTC(DTC_NO_CAN_SIGNAL, (millis() > lastRecTimestamp + 10000 ? true : false));
return 0;
}
#endif

21
Software/src/can.h Normal file
View File

@@ -0,0 +1,21 @@
#ifndef _CAN_H_
#define _CAN_H_
#include <Arduino.h>
#include <mcp_can.h>
#include <SPI.h>
#include "common.h"
#include "globals.h"
#include "dtc.h"
struct can_frame
{
unsigned long can_id;
uint8_t can_dlc;
uint8_t data[8] __attribute__((aligned(8)));
};
void Init_CAN();
uint32_t Process_CAN_WheelSpeed();
#endif

37
Software/src/common.h Normal file
View File

@@ -0,0 +1,37 @@
#ifndef _COMMON_H_
#define _COMMON_H_
#define Q(x) #x
#define QUOTE(x) Q(x)
#define GPIO_BUTTON D4
#define GPIO_LED D3
#define GPIO_TRIGGER D6
#define GPIO_PUMP D0
#define GPIO_CS_CAN D8
#ifndef HOST_NAME
#define HOST_NAME "ChainLube_%06X" // Use printf-Formatting - Chip-ID (uin32_t) will be added
#endif
#define SW_VERSION_MAJOR 1
#define SW_VERSION_MINOR 0
#ifndef OTA_DELAY
#define OTA_DELAY 50 // ticks -> 10ms / tick
#endif
#ifndef ADMIN_PASSWORD
#error "You need to define ADMIN_PASSWORD for OTA-Update"
#endif
#ifndef WIFI_PASSWORD
#error "You must define an WIFI_PASSWORD for OTA-Update"
#endif
#ifndef WIFI_SSID
#error "You must define an WIFI_SSID for OTA-Update"
#endif
#ifndef WIFI_AP_PASSWORD
#error "You must define an WIFI_AP_PASSWORD for Standalone AP-Mode"
#endif
#endif

226
Software/src/config.cpp Normal file
View File

@@ -0,0 +1,226 @@
#include "config.h"
I2C_eeprom ee(0x50, EEPROM_SIZE_BYTES);
LubeConfig_t LubeConfig;
persistenceData_t PersistenceData;
uint16_t eePersistenceMarker = 0;
const uint16_t eeVersion = 1; // inc
boolean eeAvailable = false;
const uint16_t startofLubeConfig = 16;
const uint16_t startofPersistence = 16 + sizeof(LubeConfig) + (sizeof(LubeConfig) % 16);
boolean checkEEPROMavailable();
void InitEEPROM()
{
ee.begin();
if (!checkEEPROMavailable())
{
globals.systemStatus = sysStat_Error;
MaintainDTC(DTC_NO_EEPROM_FOUND, true);
return;
}
GetConfig_EEPROM();
if (LubeConfig.EEPROM_Version != eeVersion)
{
FormatConfig_EEPROM();
globals.systemStatus = sysStat_Error;
MaintainDTC(DTC_EEPROM_VERSION_BAD, true);
return;
}
}
void EEPROM_Process()
{
switch (globals.requestEEAction)
{
case EE_CFG_SAVE:
StoreConfig_EEPROM();
globals.requestEEAction = EE_IDLE;
break;
case EE_CFG_LOAD:
GetConfig_EEPROM();
globals.requestEEAction = EE_IDLE;
break;
case EE_PDS_SAVE:
StorePersistence_EEPROM();
globals.requestEEAction = EE_IDLE;
break;
case EE_PDS_LOAD:
GetPersistence_EEPROM();
globals.requestEEAction = EE_IDLE;
break;
case EE_IDLE:
default:
globals.requestEEAction = EE_IDLE;
}
}
void StoreConfig_EEPROM()
{
LubeConfig.checksum = 0;
LubeConfig.checksum = Checksum_EEPROM((uint8_t *)&LubeConfig, sizeof(LubeConfig));
if (!checkEEPROMavailable())
return;
ee.updateBlock(startofLubeConfig, (uint8_t *)&LubeConfig, sizeof(LubeConfig));
}
void GetConfig_EEPROM()
{
if (!checkEEPROMavailable())
return;
ee.readBlock(startofLubeConfig, (uint8_t *)&LubeConfig, sizeof(LubeConfig));
uint32_t checksum = LubeConfig.checksum;
LubeConfig.checksum = 0;
if (Checksum_EEPROM((uint8_t *)&LubeConfig, sizeof(LubeConfig)) != checksum)
{
MaintainDTC(DTC_EEPROM_CFG_BAD, true);
FormatConfig_EEPROM();
}
LubeConfig.checksum = checksum;
}
uint16_t getPersistanceAddress()
{
return startofPersistence + eePersistenceMarker;
}
void StorePersistence_EEPROM()
{
if (PersistenceData.writeCycleCounter >= 0xFFF0)
MovePersistencePage_EEPROM(false);
else
PersistenceData.writeCycleCounter++;
PersistenceData.checksum = 0;
PersistenceData.checksum = Checksum_EEPROM((uint8_t *)&PersistenceData, sizeof(PersistenceData));
if (!checkEEPROMavailable())
return;
ee.updateBlock(getPersistanceAddress(), (uint8_t *)&PersistenceData, sizeof(PersistenceData));
}
void GetPersistence_EEPROM()
{
if (!checkEEPROMavailable())
return;
eePersistenceMarker = (ee.readByte(0) << 8) | ee.readByte(1);
ee.readBlock(getPersistanceAddress(), (uint8_t *)&PersistenceData, sizeof(PersistenceData));
uint32_t checksum = PersistenceData.checksum;
PersistenceData.checksum = 0;
if (Checksum_EEPROM((uint8_t *)&PersistenceData, sizeof(PersistenceData)) != checksum)
{
MaintainDTC(DTC_EEPROM_PDS_BAD, true);
FormatPersistence_EEPROM();
}
PersistenceData.checksum = checksum;
}
void FormatConfig_EEPROM()
{
LubeConfig_t defaults;
LubeConfig = defaults;
LubeConfig.EEPROM_Version = eeVersion;
StoreConfig_EEPROM();
}
void FormatPersistence_EEPROM()
{
persistenceData_t defaults;
PersistenceData = defaults;
eePersistenceMarker = 0;
StorePersistence_EEPROM();
}
void MovePersistencePage_EEPROM(boolean reset)
{
if (!checkEEPROMavailable())
return;
eePersistenceMarker = eePersistenceMarker + sizeof(PersistenceData);
PersistenceData.writeCycleCounter = 0;
// check if we reached the End of the EEPROM and Startover at the beginning
// if ((startofPersistence + eePersistenceMarker + sizeof(PersistenceData)) > ee.getDeviceSize() || reset)
// {
// eePersistenceMarker = 0;
// }
ee.updateByte(0, (uint8_t)(eePersistenceMarker >> 8));
ee.updateByte(1, (uint8_t)(eePersistenceMarker & 0xFF));
}
uint32_t Checksum_EEPROM(uint8_t const *data, size_t len)
{
if (data == NULL)
return 0;
uint32_t crc, mask;
crc = 0xFFFFFFFF;
while (len--)
{
crc ^= *data++;
for (uint8_t k = 0; k < 8; k++)
{
mask = -(crc & 1);
crc = (crc >> 1) ^ (0xEDB88320 & mask);
}
}
return ~crc;
}
void dumpEEPROM(uint16_t memoryAddress, uint16_t length)
{
#define BLOCK_TO_LENGTH 16
if (!checkEEPROMavailable())
return;
char ascii_buf[BLOCK_TO_LENGTH + 1];
sprintf(ascii_buf, "%*s", BLOCK_TO_LENGTH, "ASCII");
Serial.print(PSTR("\nAddress "));
for (int x = 0; x < BLOCK_TO_LENGTH; x++)
Serial.printf("%3d", x);
memoryAddress = memoryAddress / BLOCK_TO_LENGTH * BLOCK_TO_LENGTH;
length = (length + BLOCK_TO_LENGTH - 1) / BLOCK_TO_LENGTH * BLOCK_TO_LENGTH;
for (unsigned int i = 0; i < length; i++)
{
int blockpoint = memoryAddress % BLOCK_TO_LENGTH;
if (blockpoint == 0)
{
ascii_buf[BLOCK_TO_LENGTH] = 0;
Serial.printf(" %s", ascii_buf);
Serial.printf("\n0x%05X:", memoryAddress);
}
ascii_buf[blockpoint] = ee.readByte(memoryAddress);
Serial.printf(" %02X", ascii_buf[blockpoint]);
if (ascii_buf[blockpoint] < 0x20 || ascii_buf[blockpoint] > 0x7E)
ascii_buf[blockpoint] = '.';
memoryAddress++;
}
Serial.println();
}
boolean checkEEPROMavailable()
{
if (!ee.isConnected())
{
MaintainDTC(DTC_NO_EEPROM_FOUND, true);
return false;
}
return true;
}

113
Software/src/config.h Normal file
View File

@@ -0,0 +1,113 @@
#ifndef _CONFIG_H_
#define _CONFIG_H_
#include <Arduino.h>
#include <Wire.h>
#include <I2C_eeprom.h>
#include "globals.h"
#include "dtc.h"
#define EEPROM_SIZE_BYTES I2C_DEVICESIZE_24LC256
typedef enum SpeedSource_e
{
SOURCE_TIME,
SOURCE_IMPULSE,
#ifdef FEATURE_ENABLE_GPS
SOURCE_GPS,
#endif
#if FEATURE_ENABLE_CAN
SOURCE_CAN
#endif
} SpeedSource_t;
const char SpeedSourceString[][8] = {
"Timer",
"Impuls",
#ifdef FEATURE_ENABLE_GPS
"GPS",
#endif
#if FEATURE_ENABLE_CAN
"CAN-Bus"
#endif
};
#ifdef FEATURE_ENABLE_GPS
typedef enum GPSBaudRate_e
{
BAUD_9600,
BAUD_115200
} GPSBaudRate_t;
const char GPSBaudRateString[][7] = {
"9600",
"115200"};
const size_t GPSBaudRateString_Elements = sizeof(GPSBaudRateString) / sizeof(GPSBaudRateString[0]);
#endif
#ifdef FEATURE_ENABLE_CAN
typedef enum CANSource_e
{
KTM_890_ADV_R_2021
} CANSource_t;
const char CANSourceString[][28] = {
"KTM 890 Adventure R (2021)"};
const char CANSourceString_Elements = sizeof(CANSourceString) / sizeof(CANSourceString[0]);
#endif
const size_t SpeedSourceString_Elements = sizeof(SpeedSourceString) / sizeof(SpeedSourceString[0]);
typedef struct
{
uint16_t writeCycleCounter = 0;
uint32_t tankRemain_µl = 0;
uint32_t TravelDistance_highRes_mm = 0;
uint32_t odometer_mm = 0;
uint32_t odometer = 0;
uint32_t checksum = 0;
} persistenceData_t;
typedef struct
{
uint8_t EEPROM_Version = 0;
uint32_t DistancePerLube_Default = 8000;
uint32_t DistancePerLube_Rain = 4000;
uint32_t tankCapacity_ml = 320;
uint32_t amountPerDose_µl = 72;
uint8_t TankRemindAtPercentage = 30;
uint8_t PulsePerRevolution = 1;
uint32_t TireWidth_mm = 150;
uint32_t TireWidthHeight_Ratio = 70;
uint32_t RimDiameter_Inch = 18;
uint32_t DistancePerRevolution_mm = 2000;
uint8_t BleedingPulses = 25;
SpeedSource_t SpeedSource = SOURCE_IMPULSE;
#ifdef FEATURE_ENABLE_GPS
GPSBaudRate_t GPSBaudRate = BAUD_115200;
#endif
#ifdef FEATURE_ENABLE_CAN
CANSource_t CANSource = KTM_890_ADV_R_2021;
#endif
uint32_t checksum = 0;
} LubeConfig_t;
void InitEEPROM();
void EEPROM_Process();
void StoreConfig_EEPROM();
void GetConfig_EEPROM();
void StorePersistence_EEPROM();
void GetPersistence_EEPROM();
void FormatConfig_EEPROM();
void FormatPersistence_EEPROM();
uint32_t Checksum_EEPROM(uint8_t const *data, size_t len);
void dumpEEPROM(uint16_t memoryAddress, uint16_t length);
void MovePersistencePage_EEPROM(boolean reset);
uint16_t getPersistanceAddress();
extern LubeConfig_t LubeConfig;
extern persistenceData_t PersistenceData;
extern uint16_t eePersistenceMarker;
#endif // _CONFIG_H_

85
Software/src/dtc.cpp Normal file
View File

@@ -0,0 +1,85 @@
#include "dtc.h"
DTCEntry_s DTCStorage[MAX_DTC_STORAGE];
void MaintainDTC(DTCNums_t DTC_no, boolean active)
{
for (int i = 0; i < MAX_DTC_STORAGE; i++)
{
if (DTCStorage[i].Number == DTC_no)
{
if (active && DTCStorage[i].active != DTC_ACTIVE)
{
Serial.printf("DTC gone active: %d\n", DTC_no);
DTCStorage[i].timestamp = millis();
DTCStorage[i].active = DTC_ACTIVE;
}
if (!active && DTCStorage[i].active == DTC_ACTIVE)
{
Serial.printf("DTC gone previous: %d\n", DTC_no);
DTCStorage[i].active = DTC_PREVIOUS;
}
return;
}
}
// DTC was not found with upper iteration, but is active
// so we need to look for free space to store DTC
if (active == true)
{
for (int i = 0; i < MAX_DTC_STORAGE; i++)
{
if (DTCStorage[i].Number == DTC_LAST_DTC)
{
Serial.printf("new DTC registered: %d\n", DTC_no);
DTCStorage[i].Number = DTC_no;
DTCStorage[i].timestamp = millis();
DTCStorage[i].active = DTC_ACTIVE;
return;
}
}
}
}
void ClearDTC(DTCNums_t DTC_no)
{
for (int i = 0; i < MAX_DTC_STORAGE; i++)
{
if (DTCStorage[i].Number == DTC_no)
{
DTCStorage[i].Number = DTC_LAST_DTC;
DTCStorage[i].active = DTC_NONE;
DTCStorage[i].timestamp = 0;
}
}
}
void ClearAllDTC()
{
for (int i = 0; i < MAX_DTC_STORAGE; i++)
{
DTCStorage[i].Number = DTC_LAST_DTC;
DTCStorage[i].active = DTC_NONE;
DTCStorage[i].timestamp = 0;
}
}
DTCNums_t getlastDTC(boolean only_active)
{
int8_t pointer = -1;
uint32_t lasttimestamp = 0;
for (int i = 0; i < MAX_DTC_STORAGE; i++)
{
if (DTCStorage[i].Number > 0 && DTCStorage[i].timestamp > lasttimestamp)
{
if (only_active == false || DTCStorage[i].active == DTC_ACTIVE)
{
pointer = i;
lasttimestamp = DTCStorage[i].timestamp;
}
}
}
return pointer >= 0 ? DTCStorage[pointer].Number : DTC_LAST_DTC;
}

45
Software/src/dtc.h Normal file
View File

@@ -0,0 +1,45 @@
#ifndef _DTC_H_
#define _DTC_H_
#include <Arduino.h>
#define MAX_DTC_STORAGE 6
typedef enum DTCNums_e
{
DTC_TANK_EMPTY = 1,
DTC_NO_EEPROM_FOUND,
DTC_EEPROM_CFG_BAD,
DTC_EEPROM_PDS_BAD,
DTC_EEPROM_VERSION_BAD,
#ifdef FEATURE_ENABLE_GPS
DTC_NO_GPS_SERIAL,
#endif
#ifdef FEATURE_ENABLE_CAN
DTC_CAN_TRANSCEIVER_FAILED,
DTC_NO_CAN_SIGNAL,
#endif
DTC_LAST_DTC
} DTCNums_t;
typedef enum DTCActive_e
{
DTC_NONE,
DTC_ACTIVE,
DTC_PREVIOUS
} DTCActive_t;
typedef struct DTCEntry_s
{
DTCNums_t Number;
uint32_t timestamp;
DTCActive_t active;
} DTCEntry_t;
void MaintainDTC(DTCNums_t DTC_no, boolean active);
void ClearDTC(DTCNums_t DTC_no);
void ClearAllDTC();
DTCNums_t getlastDTC(boolean only_active);
extern DTCEntry_s DTCStorage[MAX_DTC_STORAGE];
#endif

36
Software/src/globals.h Normal file
View File

@@ -0,0 +1,36 @@
#ifndef _GLOBALS_H_
#define _GLOBALS_H_
#include <Arduino.h>
typedef enum eSystem_Status
{
sysStat_Startup,
sysStat_Normal,
sysStat_Rain,
sysStat_Purge,
sysStat_Error,
sysStat_Shutdown
} tSystem_Status;
typedef enum eEERequest
{
EE_IDLE,
EE_CFG_SAVE,
EE_CFG_LOAD,
EE_PDS_SAVE,
EE_PDS_LOAD
} tEERequest;
typedef struct Globals_s
{
tSystem_Status systemStatus = sysStat_Startup;
tSystem_Status resumeStatus = sysStat_Startup;
char systemStatustxt[16] = "";
uint8_t purgePulses = 0;
eEERequest requestEEAction = EE_IDLE;
} Globals_t;
extern Globals_t globals;
#endif

59
Software/src/gps.cpp Normal file
View File

@@ -0,0 +1,59 @@
#ifdef FEATURE_ENABLE_GPS
#include "gps.h"
TinyGPSPlus gps;
void Init_GPS()
{
uint32_t baudrate;
switch (LubeConfig.GPSBaudRate)
{
case BAUD_9600:
baudrate = 9600;
break;
case BAUD_115200:
baudrate = 115200;
break;
default:
baudrate = 4800;
break;
}
Serial.printf(PSTR("Init GPS with Baud %d\n"), baudrate);
Serial.begin(baudrate);
}
uint32_t Process_GPS_WheelSpeed()
{
static uint32_t lastRecTimestamp;
static uint32_t lastValidSpeedTimestamp;
uint16_t RearWheelSpeed_kmh;
while (Serial.available() > 0)
{
uint8_t incoming = Serial.read();
if (gps.encode(incoming))
{
RearWheelSpeed_kmh = gps.speed.isValid() ? gps.speed.kmph() : 0;
if (RearWheelSpeed_kmh > 0)
{
uint32_t RWP_millimeter_per_second = ((uint32_t)RearWheelSpeed_kmh * 1000000) / 3600;
uint32_t timesincelast = millis() - lastValidSpeedTimestamp;
lastValidSpeedTimestamp = millis();
uint32_t milimeters_to_add = (RWP_millimeter_per_second * timesincelast) / 1000;
return milimeters_to_add;
}
lastRecTimestamp = millis();
}
}
MaintainDTC(DTC_NO_GPS_SERIAL, (millis() > lastRecTimestamp + 10000));
return 0;
}
#endif

12
Software/src/gps.h Normal file
View File

@@ -0,0 +1,12 @@
#ifndef _GPS_H_
#define _GPS_H_
#include <TinyGPSPlus.h>
#include "config.h"
#include "common.h"
#include "dtc.h"
void Init_GPS();
uint32_t Process_GPS_WheelSpeed();
#endif

113
Software/src/lubeapp.cpp Normal file
View File

@@ -0,0 +1,113 @@
#include "lubeapp.h"
uint32_t lubePulseTimestamp = 0;
void RunLubeApp(uint32_t add_milimeters)
{
MaintainDTC(DTC_TANK_EMPTY, (PersistenceData.tankRemain_µl < LubeConfig.amountPerDose_µl));
static tSystem_Status preserverSysStatusError;
if (getlastDTC(true) < DTC_LAST_DTC)
{
if (globals.systemStatus != sysStat_Error)
preserverSysStatusError = globals.systemStatus;
globals.systemStatus = sysStat_Error;
}
else
{
globals.systemStatus = preserverSysStatusError;
}
// Add traveled Distance in mm
PersistenceData.TravelDistance_highRes_mm += add_milimeters;
PersistenceData.odometer_mm += add_milimeters;
if (PersistenceData.odometer_mm >= 1000000)
{
PersistenceData.odometer++;
PersistenceData.odometer_mm = 0;
}
switch (globals.systemStatus)
{
case sysStat_Startup:
if (millis() > STARTUP_DELAY)
{
globals.systemStatus = sysStat_Normal;
globals.resumeStatus = sysStat_Normal;
}
break;
case sysStat_Normal:
if (PersistenceData.TravelDistance_highRes_mm / 1000 > LubeConfig.DistancePerLube_Default)
{
LubePulse();
PersistenceData.TravelDistance_highRes_mm = 0;
}
break;
case sysStat_Rain:
if (PersistenceData.TravelDistance_highRes_mm / 1000 > LubeConfig.DistancePerLube_Rain)
{
LubePulse();
PersistenceData.TravelDistance_highRes_mm = 0;
}
break;
case sysStat_Purge:
if (globals.purgePulses > 0)
{
if (lubePulseTimestamp + LUBE_PULSE_PAUSE_MS < millis())
{
LubePulse();
globals.purgePulses--;
}
}
else
{
globals.systemStatus = globals.resumeStatus;
}
break;
case sysStat_Error:
case sysStat_Shutdown:
default:
break;
}
switch (globals.systemStatus)
{
case sysStat_Normal:
strcpy(globals.systemStatustxt, PSTR("Normal"));
break;
case sysStat_Purge:
strcpy(globals.systemStatustxt, PSTR("Purge"));
break;
case sysStat_Rain:
strcpy(globals.systemStatustxt, PSTR("Rain"));
break;
case sysStat_Startup:
strcpy(globals.systemStatustxt, PSTR("Startup"));
break;
case sysStat_Error:
strcpy(globals.systemStatustxt, PSTR("Error"));
break;
case sysStat_Shutdown:
strcpy(globals.systemStatustxt, PSTR("Shutdown"));
break;
}
// maintain Pin-State of Lube-Pump
if (lubePulseTimestamp > millis())
digitalWrite(GPIO_PUMP, HIGH);
else
digitalWrite(GPIO_PUMP, LOW);
}
void LubePulse()
{
lubePulseTimestamp = millis() + LUBE_PULSE_LENGHT_MS;
if (PersistenceData.tankRemain_µl < LubeConfig.amountPerDose_µl)
PersistenceData.tankRemain_µl = 0;
else
PersistenceData.tankRemain_µl = PersistenceData.tankRemain_µl - LubeConfig.amountPerDose_µl;
}

18
Software/src/lubeapp.h Normal file
View File

@@ -0,0 +1,18 @@
#ifndef _LUBEAPP_H_
#define _LUBEAPP_H_
#include <Arduino.h>
#include <stdlib.h>
#include "config.h"
#include "common.h"
#include "globals.h"
#include "dtc.h"
#define LUBE_PULSE_LENGHT_MS 160
#define LUBE_PULSE_PAUSE_MS 100
#define STARTUP_DELAY 5000
void RunLubeApp(uint32_t add_milimeters);
void LubePulse();
#endif

774
Software/src/main.cpp Normal file
View File

@@ -0,0 +1,774 @@
#include <Arduino.h>
#include <Wire.h>
#include <U8g2lib.h>
#include <ESP8266WiFi.h>
#include <ESP8266mDNS.h>
#include <ArduinoOTA.h>
#include <FastLED.h>
#include <Ticker.h>
#include "common.h"
#include "lubeapp.h"
#include "webui.h"
#include "config.h"
#include "globals.h"
#ifdef FEATURE_ENABLE_CAN
#include "can.h"
#endif
#ifdef FEATURE_ENABLE_GPS
#include "gps.h"
#endif
#include "dtc.h"
#ifdef FEATURE_ENABLE_REMOTE_DEBUG
#include <RemoteDebug.h>
#include "rmtdbghelp.h"
#else
#define debugV Serial.println
#define debugE Serial.println
#endif
#ifdef FEATURE_ENABLE_WIFI_CLIENT
#include <ESP8266WiFiMulti.h>
const char *ssid = QUOTE(WIFI_SSID);
const char *password = QUOTE(WIFI_PASSWORD);
const uint32_t connectTimeoutMs = 5000;
ESP8266WiFiMulti wifiMulti;
#endif
bool startSetupMode = false;
char DeviceName[33];
Globals_t globals;
uint32_t TravelDistance_highRes;
volatile uint32_t wheel_pulse = 0;
U8X8_SSD1306_128X64_NONAME_HW_I2C u8x8(-1);
CRGB leds[1];
// Function-Prototypes
void IRAM_ATTR trigger_ISR();
void LED_Process(uint8_t override = false, CRGB setColor = CRGB::White);
void Display_Process();
void Button_Process();
void toggleWiFiAP(boolean shutdown = false);
void SystemShutdown();
uint32_t Process_Impulse_WheelSpeed();
void EEPROMCyclicPDS_callback();
void initGlobals();
#ifdef FEATURE_ENABLE_REMOTE_DEBUG
RemoteDebug Debug;
String IpAddress2String(const IPAddress &ipAddress);
void processCmdRemoteDebug();
void RemoteDebug_formatCFG();
void RemoteDebug_formatPersistence();
void RemotDebug_printSystemInfo();
void RemoteDebug_printWifiInfo();
void RemoteDebug_CheckEEPOM();
void RemoteDebug_dumpConfig();
void RemoteDebug_dumpPersistance();
void RemoteDebug_ShowDTCs();
#endif
#ifdef FEATURE_ENABLE_WIFI_CLIENT
void wifiMaintainConnectionTicker_callback();
Ticker WiFiMaintainConnectionTicker(wifiMaintainConnectionTicker_callback, 1000, 0, MILLIS);
#endif
Ticker EEPROMCyclicPDSTicker(EEPROMCyclicPDS_callback, 60000, 0, MILLIS);
void setup()
{
system_update_cpu_freq(SYS_CPU_80MHZ);
snprintf(DeviceName, 32, HOST_NAME, ESP.getChipId());
WiFi.persistent(false);
ClearAllDTC(); // Init DTC-Storage
#ifdef FEATURE_ENABLE_WIFI_CLIENT
WiFi.mode(WIFI_STA);
WiFi.setHostname(DeviceName);
wifiMulti.addAP(QUOTE(WIFI_SSID), QUOTE(WIFI_PASSWORD));
WiFiMaintainConnectionTicker.start();
#else
WiFi.mode(WIFI_OFF);
#endif
Serial.begin(115200);
Serial.setDebugOutput(true);
Serial.println("Souko's ChainLube Mk1");
Serial.println(DeviceName);
InitEEPROM();
GetConfig_EEPROM();
GetPersistence_EEPROM();
u8x8.begin();
u8x8.setFont(u8x8_font_chroma48medium8_r);
FastLED.addLeds<WS2811, GPIO_LED, GRB>(leds, 1); // GRB ordering is assumed
switch (LubeConfig.SpeedSource)
{
case SOURCE_IMPULSE:
pinMode(GPIO_TRIGGER, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(GPIO_TRIGGER), trigger_ISR, FALLING);
break;
#ifdef FEATURE_ENABLE_GPS
case SOURCE_GPS:
Init_GPS();
break;
#endif
case SOURCE_TIME:
break;
#ifdef FEATURE_ENABLE_CAN
case SOURCE_CAN:
Init_CAN();
break;
#endif
default:
debugE("Source Setting N/A");
break;
}
pinMode(GPIO_BUTTON, INPUT_PULLUP);
pinMode(GPIO_PUMP, OUTPUT);
#ifdef FEATURE_ENABLE_REMOTE_DEBUG
if (MDNS.begin(DeviceName))
MDNS.addService("telnet", "tcp", 23);
Debug.begin(DeviceName);
Debug.setResetCmdEnabled(true);
Debug.showProfiler(false);
Debug.showColors(true);
Debug.setPassword(QUOTE(ADMIN_PASSWORD));
Debug.setSerialEnabled(true);
Debug.showDebugLevel(true);
Debug.setHelpProjectsCmds(helpCmd);
Debug.setCallBackProjectCmds(&processCmdRemoteDebug);
#endif
ArduinoOTA.setPort(8266);
ArduinoOTA.setHostname(DeviceName);
ArduinoOTA.setPassword(QUOTE(ADMIN_PASSWORD));
ArduinoOTA.onStart([]()
{
u8x8.clearDisplay();
u8x8.drawString(0, 0, "OTA-Update");
u8x8.refreshDisplay(); });
ArduinoOTA.onProgress([](unsigned int progress, unsigned int total)
{
static bool refreshed = false;
if (!refreshed)
{
u8x8.clearDisplay();
refreshed = true;
u8x8.drawString(0, 0, "OTA Upload");
}
uint32_t percent = progress / (total / 100);
u8x8.setCursor(0, 1);
u8x8.printf("%d %%", percent);
u8x8.refreshDisplay(); });
ArduinoOTA.onEnd([]()
{
u8x8.clearDisplay();
u8x8.drawString(0, 0, "OTA-Restart");
u8x8.refreshDisplay(); });
ArduinoOTA.begin();
u8x8.clearDisplay();
u8x8.drawString(0, 0, "KTM ChainLube V1");
u8x8.refreshDisplay();
initWebUI();
initGlobals();
EEPROMCyclicPDSTicker.start();
Serial.println("Setup Done");
}
void loop()
{
uint32_t wheelDistance = 0;
switch (LubeConfig.SpeedSource)
{
case SOURCE_IMPULSE:
wheelDistance = Process_Impulse_WheelSpeed();
break;
#ifdef FEATURE_ENABLE_CAN
case SOURCE_CAN:
wheelDistance = Process_CAN_WheelSpeed();
break;
#endif
case SOURCE_TIME:
break;
#ifdef FEATURE_ENABLE_GPS
case SOURCE_GPS:
wheelDistance = Process_GPS_WheelSpeed();
break;
#endif
}
RunLubeApp(wheelDistance);
EEPROMCyclicPDSTicker.update();
Display_Process();
Button_Process();
LED_Process();
EEPROM_Process();
ArduinoOTA.handle();
#ifdef FEATURE_ENABLE_REMOTE_DEBUG
Debug.handle();
#endif
#ifdef FEATURE_ENABLE_WIFI_CLIENT
WiFiMaintainConnectionTicker.update();
#endif
if (globals.systemStatus == sysStat_Shutdown)
SystemShutdown();
yield();
}
String IpAddress2String(const IPAddress &ipAddress)
{
return String(ipAddress[0]) + String(".") +
String(ipAddress[1]) + String(".") +
String(ipAddress[2]) + String(".") +
String(ipAddress[3]);
}
void initGlobals()
{
globals.purgePulses = 0;
globals.requestEEAction = EE_IDLE;
globals.resumeStatus = sysStat_Normal;
globals.systemStatus = sysStat_Startup;
}
#ifdef FEATURE_ENABLE_REMOTE_DEBUG
void processCmdRemoteDebug()
{
String lastCmd = Debug.getLastCommand();
if (lastCmd == "sysinfo")
RemotDebug_printSystemInfo();
else if (lastCmd == "netinfo")
RemoteDebug_printWifiInfo();
else if (lastCmd == "formatCFG")
RemoteDebug_formatCFG();
else if (lastCmd == "formatPDS")
RemoteDebug_formatPersistence();
else if (lastCmd == "checkEE")
RemoteDebug_CheckEEPOM();
else if (lastCmd == "dumpEE1k")
dumpEEPROM(0, 1024);
else if (lastCmd == "dumpEE")
dumpEEPROM(0, EEPROM_SIZE_BYTES);
else if (lastCmd == "resetPageEE")
MovePersistencePage_EEPROM(true);
else if (lastCmd == "dumpCFG")
RemoteDebug_dumpConfig();
else if (lastCmd == "dumpPDS")
RemoteDebug_dumpPersistance();
else if (lastCmd == "saveEE")
StoreConfig_EEPROM();
else if (lastCmd == "showdtc")
RemoteDebug_ShowDTCs();
}
void RemoteDebug_formatCFG()
{
debugA("Formatting Config-EEPROM and reseting to default");
FormatConfig_EEPROM();
}
void RemoteDebug_formatPersistence()
{
debugA("Formatting Persistence-EEPROM and reseting to default");
FormatPersistence_EEPROM();
}
void RemotDebug_printSystemInfo()
{
debugA("Souko's ChainOiler Mk1");
debugA("Hostname: %s", DeviceName);
FlashMode_t ideMode = ESP.getFlashChipMode();
debugA("Sdk version: %s", ESP.getSdkVersion());
debugA("Core Version: %s", ESP.getCoreVersion().c_str());
debugA("Boot Version: %u", ESP.getBootVersion());
debugA("Boot Mode: %u", ESP.getBootMode());
debugA("CPU Frequency: %u MHz", ESP.getCpuFreqMHz());
debugA("Reset reason: %s", ESP.getResetReason().c_str());
debugA("Flash Size: %d", ESP.getFlashChipRealSize());
debugA("Flash Size IDE: %d", ESP.getFlashChipSize());
debugA("Flash ide mode: %s", (ideMode == FM_QIO ? "QIO" : ideMode == FM_QOUT ? "QOUT"
: ideMode == FM_DIO ? "DIO"
: ideMode == FM_DOUT ? "DOUT"
: "UNKNOWN"));
debugA("OTA-Pass: %s", QUOTE(ADMIN_PASSWORD));
debugA("Git-Revison: %s", GIT_REV);
debugA("Sw-Version: %d.%02d", SW_VERSION_MAJOR, SW_VERSION_MINOR);
}
void RemoteDebug_dumpConfig()
{
debugA("DistancePerLube_Default: %d", LubeConfig.DistancePerLube_Default);
debugA("DistancePerLube_Rain: %d", LubeConfig.DistancePerLube_Rain);
debugA("tankCapacity_ml: %d", LubeConfig.tankCapacity_ml);
debugA("amountPerDose_µl: %d", LubeConfig.amountPerDose_µl);
debugA("TankRemindAtPercentage: %d", LubeConfig.TankRemindAtPercentage);
debugA("PulsePerRevolution: %d", LubeConfig.PulsePerRevolution);
debugA("TireWidth_mm: %d", LubeConfig.TireWidth_mm);
debugA("TireWidthHeight_Ratio: %d", LubeConfig.TireWidth_mm);
debugA("RimDiameter_Inch: %d", LubeConfig.RimDiameter_Inch);
debugA("DistancePerRevolution_mm: %d", LubeConfig.DistancePerRevolution_mm);
debugA("BleedingPulses: %d", LubeConfig.BleedingPulses);
debugA("SpeedSource: %d", LubeConfig.SpeedSource);
#ifdef FEATURE_ENABLE_GPS
debugA("GPSBaudRate: %d", LubeConfig.GPSBaudRate);
#endif
#ifdef FEATURE_ENABLE_CAN
debugA("CANSource: %d", LubeConfig.CANSource);
#endif
debugA("checksum: 0x%08X", LubeConfig.checksum);
}
void RemoteDebug_dumpPersistance()
{
debugA("writeCycleCounter: %d", PersistenceData.writeCycleCounter);
debugA("tankRemain_µl: %d", PersistenceData.tankRemain_µl);
debugA("TravelDistance_highRes_mm: %d", PersistenceData.TravelDistance_highRes_mm);
debugA("checksum: %d", PersistenceData.checksum);
debugA("PSD Adress: 0x%04X", getPersistanceAddress());
}
void RemoteDebug_printWifiInfo()
{
}
void RemoteDebug_CheckEEPOM()
{
uint32_t checksum = PersistenceData.checksum;
PersistenceData.checksum = 0;
if (Checksum_EEPROM((uint8_t *)&PersistenceData, sizeof(PersistenceData)) == checksum)
{
debugA("PersistenceData EEPROM Checksum OK\n");
}
else
{
debugA("PersistenceData EEPROM Checksum BAD\n");
}
PersistenceData.checksum = checksum;
checksum = LubeConfig.checksum;
LubeConfig.checksum = 0;
if (Checksum_EEPROM((uint8_t *)&LubeConfig, sizeof(LubeConfig)) == checksum)
{
debugA("LubeConfig EEPROM Checksum OK\n");
}
else
{
debugA("LubeConfig EEPROM Checksum BAD\n");
}
LubeConfig.checksum = checksum;
}
#endif
#ifdef FEATURE_ENABLE_WIFI_CLIENT
void wifiMaintainConnectionTicker_callback()
{
static uint32_t WiFiFailCount = 0;
const uint32_t WiFiFailMax = 20;
if (wifiMulti.run(connectTimeoutMs) == WL_CONNECTED)
{
return;
}
else
{
if (WiFiFailCount < WiFiFailMax)
{
WiFiFailCount++;
}
else
{
debugV("WiFi not connected! - Start AP");
toggleWiFiAP();
}
}
}
#endif
void EEPROMCyclicPDS_callback()
{
StorePersistence_EEPROM();
}
void trigger_ISR()
{
wheel_pulse++;
}
void LED_Process(uint8_t override, CRGB SetColor)
{
typedef enum
{
LED_Startup,
LED_Normal,
LED_Confirm_Normal,
LED_Rain,
LED_Confirm_Rain,
LED_Purge,
LED_Error,
LED_Override
} tLED_Status;
static tSystem_Status oldSysStatus = sysStat_Startup;
static tLED_Status LED_Status = LED_Startup;
static CRGB LED_override_color = 0;
static tLED_Status LED_ResumeOverrideStatus = LED_Startup;
uint8_t color = 0;
uint32_t timer = 0;
static uint32_t timestamp = 0;
timer = millis();
if (override == 1)
{
if (LED_Status != LED_Override)
{
LED_ResumeOverrideStatus = LED_Status;
debugV("Override LED_Status");
}
LED_Status = LED_Override;
LED_override_color = SetColor;
}
if (override == 2)
{
if (LED_Status == LED_Override)
{
LED_Status = LED_ResumeOverrideStatus;
debugV("Resume LED_Status");
}
}
if (oldSysStatus != globals.systemStatus)
{
switch (globals.systemStatus)
{
case sysStat_Startup:
LED_Status = LED_Startup;
debugV("sysStat: Startup");
break;
case sysStat_Normal:
timestamp = timer + 3500;
LED_Status = LED_Confirm_Normal;
debugV("sysStat: Normal");
break;
case sysStat_Rain:
timestamp = timer + 3500;
LED_Status = LED_Confirm_Rain;
debugV("sysStat: Rain");
break;
case sysStat_Purge:
LED_Status = LED_Purge;
debugV("sysStat: Purge");
break;
case sysStat_Error:
LED_Status = LED_Error;
debugV("sysStat: Error");
break;
case sysStat_Shutdown:
default:
break;
}
oldSysStatus = globals.systemStatus;
}
uint32_t percentage = PersistenceData.tankRemain_µl / (LubeConfig.tankCapacity_ml * 10);
switch (LED_Status)
{
case LED_Startup:
FastLED.setBrightness(255);
if (percentage < LubeConfig.TankRemindAtPercentage)
leds[0] = CRGB::OrangeRed;
else
leds[0] = CRGB::White;
break;
case LED_Confirm_Normal:
FastLED.setBrightness(255);
leds[0] = timer % 250 > 125 ? CRGB(0, 255, 0) : CRGB(0, 4, 0);
if (timestamp < timer)
{
LED_Status = LED_Normal;
FastLED.setBrightness(64);
debugV("LED_Status: Confirm -> Normal");
}
break;
case LED_Normal:
if (timer % 2000 > 1950)
leds[0] = CRGB(0, 255, 0);
else if (WiFi.getMode() != WIFI_OFF && timer % 2000 > 1800 && timer % 2000 < 1850)
leds[0] = CRGB(255, 128, 0);
else
leds[0] = CRGB(0, 4, 0);
break;
case LED_Confirm_Rain:
FastLED.setBrightness(255);
leds[0] = timer % 250 > 125 ? CRGB(0, 0, 255) : CRGB(0, 0, 4);
if (timestamp < timer)
{
LED_Status = LED_Rain;
FastLED.setBrightness(64);
debugV("LED_Status: Confirm -> Rain");
}
break;
case LED_Rain:
if (timer % 2000 > 1950)
leds[0] = CRGB(0, 0, 255);
else if (WiFi.getMode() != WIFI_OFF && timer % 2000 > 1800 && timer % 2000 < 1850)
leds[0] = CRGB(255, 128, 0);
else
leds[0] = CRGB(0, 0, 4);
break;
case LED_Purge:
timer = timer % 500;
color = timer / 2;
leds[0] = CRGB::DeepPink;
if (timer < 250)
FastLED.setBrightness(color);
else
FastLED.setBrightness(250 - color);
break;
case LED_Error:
leds[0] = timer % 500 > 250 ? CRGB::Red : CRGB::Black;
break;
case LED_Override:
leds[0] = LED_override_color;
break;
default:
break;
}
FastLED.show();
}
void Display_Process()
{
static tSystem_Status oldSysStatus = sysStat_Startup;
if (oldSysStatus != globals.systemStatus)
{
u8x8.clearDisplay();
u8x8.drawString(0, 0, "KTM ChainLube V1");
oldSysStatus = globals.systemStatus;
}
u8x8.setCursor(0, 1);
uint32_t DistRemain = globals.systemStatus == sysStat_Normal ? LubeConfig.DistancePerLube_Default : LubeConfig.DistancePerLube_Rain;
DistRemain -= TravelDistance_highRes / 1000;
u8x8.printf(PSTR("Mode: %10s\n"), globals.systemStatustxt);
if (globals.systemStatus == sysStat_Error)
{
u8x8.printf(PSTR("last DTC: %6d\n"), getlastDTC(false));
}
else
{
u8x8.printf(PSTR("next Lube: %4dm\n"), DistRemain);
u8x8.printf(PSTR("Tank: %8dml\n"), PersistenceData.tankRemain_µl / 1000);
u8x8.printf(PSTR("WiFi: %10s\n"), (WiFi.getMode() == WIFI_AP ? "AP" : WiFi.getMode() == WIFI_OFF ? "OFF"
: WiFi.getMode() == WIFI_STA ? "CLIENT"
: "UNKNOWN"));
u8x8.printf(PSTR("Source: %8s\n"), SpeedSourceString[LubeConfig.SpeedSource]);
u8x8.printf("%s\n", WiFi.localIP().toString().c_str());
}
u8x8.refreshDisplay();
}
void Button_Process()
{
#define BUTTON_ACTION_DELAY_TOGGLEMODE 500
#define BUTTON_ACTION_DELAY_PURGE 3500
#define BUTTON_ACTION_DELAY_WIFI 6500
#define BUTTON_ACTION_DELAY_NOTHING 9500
typedef enum buttonAction_e
{
BTN_INACTIVE,
BTN_NOTHING,
BTN_TOGGLEMODE,
BTN_TOGGLEWIFI,
BTN_STARTPURGE
} buttonAction_t;
static uint32_t buttonTimestamp = 0;
static buttonAction_t buttonAction = BTN_INACTIVE;
if (digitalRead(GPIO_BUTTON) == LOW)
{
if (buttonTimestamp == 0)
buttonTimestamp = millis();
if (buttonTimestamp + BUTTON_ACTION_DELAY_NOTHING < millis())
{
LED_Process(1, CRGB::White);
buttonAction = BTN_NOTHING;
}
else if (buttonTimestamp + BUTTON_ACTION_DELAY_WIFI < millis())
{
LED_Process(1, CRGB::Yellow);
buttonAction = BTN_TOGGLEWIFI;
}
else if (buttonTimestamp + BUTTON_ACTION_DELAY_PURGE < millis())
{
LED_Process(1, CRGB::DeepPink);
buttonAction = BTN_STARTPURGE;
}
else if (buttonTimestamp + BUTTON_ACTION_DELAY_TOGGLEMODE < millis())
{
CRGB color = globals.systemStatus == sysStat_Normal ? CRGB::Blue : CRGB::Green;
LED_Process(1, color);
buttonAction = BTN_TOGGLEMODE;
}
}
else
{
if (buttonAction != BTN_INACTIVE)
{
switch (buttonAction)
{
case BTN_TOGGLEWIFI:
toggleWiFiAP();
debugV("Starting WiFi AP");
break;
case BTN_STARTPURGE:
globals.systemStatus = sysStat_Purge;
globals.purgePulses = LubeConfig.BleedingPulses;
debugV("Starting Purge");
break;
case BTN_TOGGLEMODE:
switch (globals.systemStatus)
{
case sysStat_Normal:
globals.systemStatus = sysStat_Rain;
globals.resumeStatus = sysStat_Rain;
break;
case sysStat_Rain:
globals.systemStatus = sysStat_Normal;
globals.resumeStatus = sysStat_Normal;
break;
default:
break;
}
debugV("Toggling Mode");
break;
case BTN_NOTHING:
default:
debugV("Nothing or invalid");
break;
}
LED_Process(2);
}
buttonAction = BTN_INACTIVE;
buttonTimestamp = 0;
}
}
void toggleWiFiAP(boolean shutdown)
{
if (WiFi.getMode() != WIFI_OFF)
{
WiFi.mode(WIFI_OFF);
debugV("WiFi turned off");
#ifdef FEATURE_ENABLE_WIFI_CLIENT
WiFiMaintainConnectionTicker.stop();
#endif
}
else
{
WiFi.mode(WIFI_AP);
WiFi.softAPConfig(IPAddress(WIFI_AP_IP_GW), IPAddress(WIFI_AP_IP_GW), IPAddress(255, 255, 255, 0));
WiFi.softAP(DeviceName, QUOTE(WIFI_AP_PASSWORD));
#ifdef FEATURE_ENABLE_WIFI_CLIENT
WiFiMaintainConnectionTicker.stop();
debugV("WiFi AP started, stopped Maintain-Timer");
#else
debugV("WiFi AP started");
#endif
}
}
void SystemShutdown()
{
StoreConfig_EEPROM();
ESP.restart();
}
uint32_t Process_Impulse_WheelSpeed()
{
uint32_t add_milimeters;
// Calculate traveled Distance in mm
add_milimeters = (wheel_pulse * (LubeConfig.DistancePerRevolution_mm / LubeConfig.PulsePerRevolution));
wheel_pulse = 0;
return add_milimeters;
}
void RemoteDebug_ShowDTCs()
{
char buff_timestamp[16]; // Format: DD-hh:mm:ss:xxx
char buff_active[9];
for (uint32_t i = 0; i < MAX_DTC_STORAGE; i++)
{
if (DTCStorage[i].Number < DTC_LAST_DTC)
{
sprintf(buff_timestamp, "%02d-%02d:%02d:%02d:%03d",
DTCStorage[i].timestamp / 86400000, // Days
DTCStorage[i].timestamp / 360000 % 24, // Hours
DTCStorage[i].timestamp / 60000 % 60, // Minutes
DTCStorage[i].timestamp / 1000 % 60, // Seconds
DTCStorage[i].timestamp % 1000); // milliseconds
if (DTCStorage[i].active == DTC_ACTIVE)
strcpy(buff_active, "active");
else if (DTCStorage[i].active == DTC_PREVIOUS)
strcpy(buff_active, "previous");
else
strcpy(buff_active, "none");
debugA("%s \t %6d \t %s", buff_timestamp, DTCStorage[i].Number, buff_active);
}
}
}

12
Software/src/rmtdbghelp.h Normal file
View File

@@ -0,0 +1,12 @@
const char helpCmd[] = "sysinfo - System Info\r\n"
"netinfo - WiFi Info\r\n"
"formatPDS - Format Persistence EEPROM Data\r\n"
"formatCFG - Format Configuration EEPROM Data\r\n"
"checkEE - Check EEPROM with checksum\r\n"
"dumpEE1k - dump the first 1kb of EEPROM to Serial\r\n"
"dumpEE - dump the whole EPPROM to Serial\r\n"
"resetPageEE - Reset the PersistenceData Page\r\n"
"dumpCFG - print Config struct\r\n"
"dumpPDS - print PersistanceStruct\r\n"
"saveEE - save EE-Data\r\n"
"showdtc - Show all DTCs\r\n";

278
Software/src/webui.cpp Normal file
View File

@@ -0,0 +1,278 @@
#include "webui.h"
AsyncWebServer webServer(80);
const char *PARAM_MESSAGE = "message";
String processor(const String &var);
void WebserverPOST_Callback(AsyncWebServerRequest *request);
void WebserverNotFound_Callback(AsyncWebServerRequest *request);
void Webserver_Callback(AsyncWebServerRequest *request);
void initWebUI()
{
if (!LittleFS.begin())
{
Serial.println("An Error has occurred while mounting LittleFS");
return;
}
webServer.serveStatic("/static/", LittleFS, "/static/").setCacheControl("max-age=360000");
webServer.on("/", HTTP_GET, [](AsyncWebServerRequest *request)
{ request->redirect("/index.htm"); });
webServer.onNotFound(WebserverNotFound_Callback);
webServer.on("/index.htm", HTTP_GET, Webserver_Callback);
webServer.on("/post.htm", HTTP_POST, WebserverPOST_Callback);
webServer.begin();
}
String processor(const String &var)
{
if (var == "TANK_REMAIN_CAPACITY")
return String((PersistenceData.tankRemain_µl / 10) / LubeConfig.tankCapacity_ml);
if (var == "LUBE_DISTANCE_NORMAL")
return String(LubeConfig.DistancePerLube_Default);
if (var == "LUBE_DISTANCE_RAIN")
return String(LubeConfig.DistancePerLube_Rain);
if (var == "TANK_CAPACITY")
return String(LubeConfig.tankCapacity_ml);
if (var == "AMOUNT_PER_DOSE")
return String(LubeConfig.amountPerDose_µl);
if (var == "TANK_REMIND")
return String(LubeConfig.TankRemindAtPercentage);
if (var == "PULSE_PER_REV")
return String(LubeConfig.PulsePerRevolution);
if (var == "TIRE_WIDTH_MM")
return String(LubeConfig.TireWidth_mm);
if (var == "TIRE_RATIO")
return String(LubeConfig.TireWidthHeight_Ratio);
if (var == "RIM_DIAMETER")
return String(LubeConfig.RimDiameter_Inch);
if (var == "DISTANCE_PER_REV")
return String(LubeConfig.DistancePerRevolution_mm);
if (var == "BLEEDING_PULSES")
return String(LubeConfig.BleedingPulses);
if (var == "SPEED_SOURCE")
return String(SpeedSourceString[LubeConfig.SpeedSource]);
#ifdef FEATURE_ENABLE_GPS
if (var == "GPS_BAUD")
return String(GPSBaudRateString[LubeConfig.GPSBaudRate]);
#endif
#ifdef FEATURE_ENABLE_CAN
if (var == "CAN_SOURCE")
return String(CANSourceString[LubeConfig.CANSource]);
#endif
if (var == "CONFIG_CHECKSUM")
{
char buffer[7];
sprintf(buffer, "0x%04X", LubeConfig.checksum);
return String(buffer);
}
if (var == "WRITE_CYCLE_COUNT")
return String(PersistenceData.writeCycleCounter);
if (var == "PERSISTENCE_MARKER")
return String(getPersistanceAddress());
if (var == "TANK_REMAIN_UL")
return String(PersistenceData.tankRemain_µl);
if (var == "TRAVEL_DISTANCE_HIGHRES")
return String(PersistenceData.TravelDistance_highRes_mm);
if (var == "ODOMETER")
return String(PersistenceData.odometer);
if (var == "ODOMETER_M")
return String(PersistenceData.odometer_mm / 1000);
if (var == "PERSISTANCE_CHECKSUM")
{
char buffer[7];
sprintf(buffer, "0x%04X", PersistenceData.checksum);
return String(buffer);
}
if (var == "SHOW_IMPULSE_SETTINGS")
return LubeConfig.SpeedSource == SOURCE_IMPULSE ? "" : "hidden";
#ifdef FEATURE_ENABLE_CAN
if (var == "SHOW_CAN_SETTINGS")
return LubeConfig.SpeedSource == SOURCE_CAN ? "" : "hidden";
#endif
#ifdef FEATURE_ENABLE_GPS
if (var == "SHOW_GPS_SETTINGS")
return LubeConfig.SpeedSource == SOURCE_GPS ? "" : "hidden";
#endif
if (var == "SHOW_DTC_TABLE")
return globals.systemStatus == sysStat_Error ? "" : "hidden";
if (var == "DTC_TABLE")
{
String temp;
char buff_timestamp[16]; // Format: DD-hh:mm:ss:xxx
for (uint32_t i = 0; i < MAX_DTC_STORAGE; i++)
{
if (DTCStorage[i].Number < DTC_LAST_DTC)
{
sprintf(buff_timestamp, "%02d-%02d:%02d:%02d:%03d",
DTCStorage[i].timestamp / 86400000, // Days
DTCStorage[i].timestamp / 360000 % 24, // Hours
DTCStorage[i].timestamp / 60000 % 60, // Minutes
DTCStorage[i].timestamp / 1000 % 60, // Seconds
DTCStorage[i].timestamp % 1000); // milliseconds
temp = "<tr><td>" + String(buff_timestamp);
temp = temp + "</td><td>" + String(DTCStorage[i].Number) + "</td><td>";
if (DTCStorage[i].active == DTC_ACTIVE)
temp = temp + "active";
else if (DTCStorage[i].active == DTC_PREVIOUS)
temp = temp + "previous";
else
temp = temp + "none";
temp = temp + "</td></tr>";
}
}
return temp;
}
if (var == "SOURCE_SELECT_OPTIONS")
{
String temp;
for (uint32_t i = 0; i < SpeedSourceString_Elements; i++)
{
String selected = LubeConfig.SpeedSource == i ? " selected " : "";
temp = temp + "<option value=\"" + i + "\"" + selected + ">" + SpeedSourceString[i] + "</option>";
}
return temp;
}
#ifdef FEATURE_ENABLE_CAN
if (var == "CANSOURCE_SELECT_OPTIONS")
{
String temp;
for (uint32_t i = 0; i < CANSourceString_Elements; i++)
{
String selected = LubeConfig.CANSource == i ? " selected " : "";
temp = temp + "<option value=\"" + i + "\"" + selected + ">" + CANSourceString[i] + "</option>";
}
return temp;
}
#endif
#ifdef FEATURE_EABLE_GPS
if (var == "GPSBAUD_SELECT_OPTIONS")
{
String temp;
for (uint32_t i = 0; i < GPSBaudRateString_Elements; i++)
{
String selected = LubeConfig.GPSBaudRate == i ? " selected " : "";
temp = temp + "<option value=\"" + i + "\"" + selected + ">" + GPSBaudRateString[i] + "</option>";
}
return temp;
}
#endif
if (var == "SYSTEM_STATUS")
return String(globals.systemStatustxt);
if (var == "SW_VERSION")
{
char buffer[7];
sprintf(buffer, "%d.%02d", SW_VERSION_MAJOR, SW_VERSION_MINOR);
return String(buffer);
}
if (var == "PLACEHOLDER")
return "placeholder";
return String();
}
void Webserver_Callback(AsyncWebServerRequest *request)
{
request->send(LittleFS, "/index.htm", "text/html", false, processor);
}
void WebserverPOST_Callback(AsyncWebServerRequest *request)
{
request->send(LittleFS, "/post.htm", "text/html", false, processor);
Serial.print("POST:\n");
int paramsNr = request->params();
for (int i = 0; i < paramsNr; i++)
{
AsyncWebParameter *p = request->getParam(i);
Serial.printf("%s : %s\n", p->name().c_str(), p->value().c_str());
// begin: POST Form Source Changed
if (p->name() == "sourceselect")
{
SpeedSource_t temp = (SpeedSource_t)p->value().toInt();
Serial.printf("temp: %d", temp);
Serial.printf("SpeedSource: %d", LubeConfig.SpeedSource);
if (LubeConfig.SpeedSource != temp)
{
LubeConfig.SpeedSource = temp;
globals.systemStatus = sysStat_Shutdown;
}
}
// end: POST Form Source Changed
// begin: POST Form Source Pulse Settings
if (p->name() == "tirewidth")
LubeConfig.TireWidth_mm = p->value().toInt();
if (p->name() == "tireratio")
LubeConfig.TireWidthHeight_Ratio = p->value().toInt();
if (p->name() == "tiredia")
LubeConfig.RimDiameter_Inch = p->value().toInt();
if (p->name() == "pulserev")
LubeConfig.PulsePerRevolution = p->value().toInt();
if (p->name() == "pulsesave")
globals.requestEEAction = EE_CFG_SAVE;
// end: POST Form Source Pulse Settings
#ifdef FEATURE_EABLE_GPS
// begin: POST Form Source GPS Settings
if (p->name() == "gpsbaud")
LubeConfig.GPSBaudRate = (GPSBaudRate_t)p->value().toInt();
if (p->name() == "gpssave")
globals.requestEEAction = EE_CFG_SAVE;
// end: POST Form Source GPS Settings
#endif
#ifdef FEATURE_EABLE_CAN
// begin: POST Form Source CAN Settings
if (p->name() == "cansource")
LubeConfig.CANSource = (CANSource_t)p->value().toInt();
if (p->name() == "cansave")
globals.requestEEAction = EE_CFG_SAVE;
// end: POST Form Source CAN Settings
#endif
// begin: POST Form Lubrication
if (p->name() == "lubedistancenormal")
LubeConfig.DistancePerLube_Default = p->value().toInt();
if (p->name() == "lubedistancerain")
LubeConfig.DistancePerLube_Rain = p->value().toInt();
if (p->name() == "lubesave")
globals.requestEEAction = EE_CFG_SAVE;
// end: POST Form Lubrication
// begin: POST Form Oiltank
if (p->name() == "tankcap")
LubeConfig.tankCapacity_ml = p->value().toInt();
if (p->name() == "tankwarn")
LubeConfig.TankRemindAtPercentage = p->value().toInt();
if (p->name() == "pumppulse")
LubeConfig.amountPerDose_µl = p->value().toInt();
if (p->name() == "oilsave")
globals.requestEEAction = EE_CFG_SAVE;
// end: POST Form Oiltank
// begin: POST Form Maintenance
if (p->name() == "purgepulse")
LubeConfig.BleedingPulses = p->value().toInt();
if (p->name() == "maintsave")
globals.requestEEAction = EE_CFG_SAVE;
if (p->name() == "resettank")
{
PersistenceData.tankRemain_µl = LubeConfig.tankCapacity_ml * 1000;
globals.requestEEAction = EE_PDS_SAVE;
}
// end: POST Form Maintenance
}
}
void WebserverNotFound_Callback(AsyncWebServerRequest *request)
{
request->send(404, "text/html", "Not found");
}

16
Software/src/webui.h Normal file
View File

@@ -0,0 +1,16 @@
#ifndef _WEBUI_H_
#define _WEBUI_H_
#include <Arduino.h>
#include <FS.h>
#include <LittleFS.h>
#include <ESPAsyncTCP.h>
#include <ESPAsyncWebServer.h>
#include "config.h"
#include "globals.h"
#include "dtc.h"
#include "common.h"
void initWebUI();
#endif