changed PreProcessor-Stuff for Feature-Handling

This commit is contained in:
Marcel Peterkau 2022-05-04 23:06:15 +02:00
parent 2b5039b8ab
commit 1c0ab060ff
9 changed files with 76 additions and 52 deletions

View File

@ -26,14 +26,15 @@ upload_speed = 921600
build_flags = build_flags =
!python git_rev_macro.py !python git_rev_macro.py
;-DWIFI_CLIENT
-DREMOTE_DEBUG
-DWIFI_SSID=${wifi_cred.wifi_ssid} -DWIFI_SSID=${wifi_cred.wifi_ssid}
-DWIFI_PASSWORD=${wifi_cred.wifi_password} -DWIFI_PASSWORD=${wifi_cred.wifi_password}
-DADMIN_PASSWORD=${wifi_cred.admin_password} -DADMIN_PASSWORD=${wifi_cred.admin_password}
-DWIFI_AP_PASSWORD=${wifi_cred.wifi_ap_password} -DWIFI_AP_PASSWORD=${wifi_cred.wifi_ap_password}
-DWIFI_AP_IP_GW=10,0,0,1 -DWIFI_AP_IP_GW=10,0,0,1
-DPCB_REVISION=13 ;-DFEATURE_ENABLE_WIFI_CLIENT
-DFEATURE_ENABLE_REMOTE_DEBUG
-DFEATURE_ENABLE_CAN
-DFEATURE_ENABLE_GPS
board_build.filesystem = littlefs board_build.filesystem = littlefs

View File

@ -1,3 +1,4 @@
#ifdef FEATURE_ENABLE_CAN
#include "can.h" #include "can.h"
MCP_CAN CAN0(GPIO_CS_CAN); MCP_CAN CAN0(GPIO_CS_CAN);
@ -42,3 +43,4 @@ uint32_t Process_CAN_WheelSpeed()
return 0; return 0;
} }
#endif

View File

@ -31,16 +31,4 @@
#error "You must define an WIFI_AP_PASSWORD for Standalone AP-Mode" #error "You must define an WIFI_AP_PASSWORD for Standalone AP-Mode"
#endif #endif
#ifndef PCB_REVISION
#error "You must define PCB_REVISION"
#else
#if PCB_REVISION == 13
#elif PCB_REVISION == 12
#elif PCB_REVISION == 10
#else
#error "Unknown PCB_REVISION defined"
#endif
#endif
#endif #endif

View File

@ -2,12 +2,8 @@
#define _CONFIG_H_ #define _CONFIG_H_
#include <Arduino.h> #include <Arduino.h>
#if PCB_REVISION >= 12
#include <Wire.h> #include <Wire.h>
#include <I2C_eeprom.h> #include <I2C_eeprom.h>
#else
#include <EEPROM.h>
#endif
#include "globals.h" #include "globals.h"
#include "dtc.h" #include "dtc.h"
@ -17,8 +13,10 @@ typedef enum SpeedSource_e
{ {
SOURCE_TIME, SOURCE_TIME,
SOURCE_IMPULSE, SOURCE_IMPULSE,
#ifdef FEATURE_ENABLE_GPS
SOURCE_GPS, SOURCE_GPS,
#if PCB_REVISION == 13 #endif
#if FEATURE_ENABLE_CAN
SOURCE_CAN SOURCE_CAN
#endif #endif
} SpeedSource_t; } SpeedSource_t;
@ -26,12 +24,15 @@ typedef enum SpeedSource_e
const char SpeedSourceString[][8] = { const char SpeedSourceString[][8] = {
"Timer", "Timer",
"Impuls", "Impuls",
#ifdef FEATURE_ENABLE_GPS
"GPS", "GPS",
#if PCB_REVISION >= 13 #endif
#if FEATURE_ENABLE_CAN
"CAN-Bus" "CAN-Bus"
#endif #endif
}; };
#ifdef FEATURE_ENABLE_GPS
typedef enum GPSBaudRate_e typedef enum GPSBaudRate_e
{ {
BAUD_9600, BAUD_9600,
@ -43,9 +44,9 @@ const char GPSBaudRateString[][7] = {
"115200"}; "115200"};
const size_t GPSBaudRateString_Elements = sizeof(GPSBaudRateString) / sizeof(GPSBaudRateString[0]); const size_t GPSBaudRateString_Elements = sizeof(GPSBaudRateString) / sizeof(GPSBaudRateString[0]);
#endif
#if PCB_REVISION >= 13 #ifdef FEATURE_ENABLE_CAN
typedef enum CANSource_e typedef enum CANSource_e
{ {
KTM_890_ADV_R_2021 KTM_890_ADV_R_2021
@ -82,8 +83,10 @@ typedef struct
uint32_t DistancePerRevolution_mm = 2000; uint32_t DistancePerRevolution_mm = 2000;
uint8_t BleedingPulses = 25; uint8_t BleedingPulses = 25;
SpeedSource_t SpeedSource = SOURCE_IMPULSE; SpeedSource_t SpeedSource = SOURCE_IMPULSE;
#ifdef FEATURE_ENABLE_GPS
GPSBaudRate_t GPSBaudRate = BAUD_115200; GPSBaudRate_t GPSBaudRate = BAUD_115200;
#if PCB_REVISION == 13 #endif
#ifdef FEATURE_ENABLE_CAN
CANSource_t CANSource = KTM_890_ADV_R_2021; CANSource_t CANSource = KTM_890_ADV_R_2021;
#endif #endif
uint32_t checksum = 0; uint32_t checksum = 0;

View File

@ -10,13 +10,13 @@ void MaintainDTC(DTCNums_t DTC_no, boolean active)
{ {
if (active && DTCStorage[i].active != DTC_ACTIVE) if (active && DTCStorage[i].active != DTC_ACTIVE)
{ {
Serial.printf("DTC gone active: %d", DTC_no); Serial.printf("DTC gone active: %d\n", DTC_no);
DTCStorage[i].timestamp = millis(); DTCStorage[i].timestamp = millis();
DTCStorage[i].active = DTC_ACTIVE; DTCStorage[i].active = DTC_ACTIVE;
} }
if (!active && DTCStorage[i].active == DTC_ACTIVE) if (!active && DTCStorage[i].active == DTC_ACTIVE)
{ {
Serial.printf("DTC gone previous: %d", DTC_no); Serial.printf("DTC gone previous: %d\n", DTC_no);
DTCStorage[i].active = DTC_PREVIOUS; DTCStorage[i].active = DTC_PREVIOUS;
} }
return; return;
@ -31,7 +31,7 @@ void MaintainDTC(DTCNums_t DTC_no, boolean active)
{ {
if (DTCStorage[i].Number == DTC_LAST_DTC) if (DTCStorage[i].Number == DTC_LAST_DTC)
{ {
Serial.printf("new DTC registered: %d", DTC_no); Serial.printf("new DTC registered: %d\n", DTC_no);
DTCStorage[i].Number = DTC_no; DTCStorage[i].Number = DTC_no;
DTCStorage[i].timestamp = millis(); DTCStorage[i].timestamp = millis();
DTCStorage[i].active = DTC_ACTIVE; DTCStorage[i].active = DTC_ACTIVE;

View File

@ -7,14 +7,18 @@
typedef enum DTCNums_e typedef enum DTCNums_e
{ {
DTC_NO_GPS_SERIAL = 1, DTC_TANK_EMPTY = 1,
DTC_TANK_EMPTY,
DTC_NO_EEPROM_FOUND, DTC_NO_EEPROM_FOUND,
DTC_EEPROM_CFG_BAD, DTC_EEPROM_CFG_BAD,
DTC_EEPROM_PDS_BAD, DTC_EEPROM_PDS_BAD,
DTC_EEPROM_VERSION_BAD, DTC_EEPROM_VERSION_BAD,
#ifdef FEATURE_ENABLE_GPS
DTC_NO_GPS_SERIAL,
#endif
#ifdef FEATURE_ENABLE_CAN
DTC_CAN_TRANSCEIVER_FAILED, DTC_CAN_TRANSCEIVER_FAILED,
DTC_NO_CAN_SIGNAL, DTC_NO_CAN_SIGNAL,
#endif
DTC_LAST_DTC DTC_LAST_DTC
} DTCNums_t; } DTCNums_t;

View File

@ -1,3 +1,4 @@
#ifdef FEATURE_ENABLE_GPS
#include "gps.h" #include "gps.h"
TinyGPSPlus gps; TinyGPSPlus gps;
@ -54,3 +55,5 @@ uint32_t Process_GPS_WheelSpeed()
return 0; return 0;
} }
#endif

View File

@ -14,11 +14,15 @@
#include "webui.h" #include "webui.h"
#include "config.h" #include "config.h"
#include "globals.h" #include "globals.h"
#ifdef FEATURE_ENABLE_CAN
#include "can.h" #include "can.h"
#endif
#ifdef FEATURE_ENABLE_GPS
#include "gps.h" #include "gps.h"
#endif
#include "dtc.h" #include "dtc.h"
#ifdef REMOTE_DEBUG #ifdef FEATURE_ENABLE_REMOTE_DEBUG
#include <RemoteDebug.h> #include <RemoteDebug.h>
#include "rmtdbghelp.h" #include "rmtdbghelp.h"
#else #else
@ -26,7 +30,7 @@
#define debugE Serial.println #define debugE Serial.println
#endif #endif
#ifdef WIFI_CLIENT #ifdef FEATURE_ENABLE_WIFI_CLIENT
#include <ESP8266WiFiMulti.h> #include <ESP8266WiFiMulti.h>
const char *ssid = QUOTE(WIFI_SSID); const char *ssid = QUOTE(WIFI_SSID);
@ -56,7 +60,7 @@ void SystemShutdown();
uint32_t Process_Impulse_WheelSpeed(); uint32_t Process_Impulse_WheelSpeed();
void EEPROMCyclicPDS_callback(); void EEPROMCyclicPDS_callback();
#ifdef REMOTE_DEBUG #ifdef FEATURE_ENABLE_REMOTE_DEBUG
RemoteDebug Debug; RemoteDebug Debug;
String IpAddress2String(const IPAddress &ipAddress); String IpAddress2String(const IPAddress &ipAddress);
void processCmdRemoteDebug(); void processCmdRemoteDebug();
@ -70,7 +74,7 @@ void RemoteDebug_dumpPersistance();
void RemoteDebug_ShowDTCs(); void RemoteDebug_ShowDTCs();
#endif #endif
#ifdef WIFI_CLIENT #ifdef FEATURE_ENABLE_WIFI_CLIENT
void wifiMaintainConnectionTicker_callback(); void wifiMaintainConnectionTicker_callback();
Ticker WiFiMaintainConnectionTicker(wifiMaintainConnectionTicker_callback, 1000, 0, MILLIS); Ticker WiFiMaintainConnectionTicker(wifiMaintainConnectionTicker_callback, 1000, 0, MILLIS);
#endif #endif
@ -84,7 +88,7 @@ void setup()
ClearAllDTC(); // Init DTC-Storage ClearAllDTC(); // Init DTC-Storage
#ifdef WIFI_CLIENT #ifdef FEATURE_ENABLE_WIFI_CLIENT
WiFi.mode(WIFI_STA); WiFi.mode(WIFI_STA);
WiFi.setHostname(DeviceName); WiFi.setHostname(DeviceName);
wifiMulti.addAP(QUOTE(WIFI_SSID), QUOTE(WIFI_PASSWORD)); wifiMulti.addAP(QUOTE(WIFI_SSID), QUOTE(WIFI_PASSWORD));
@ -99,9 +103,7 @@ void setup()
Serial.println("Souko's ChainLube Mk1"); Serial.println("Souko's ChainLube Mk1");
Serial.println(DeviceName); Serial.println(DeviceName);
#if PCB_REVISION >= 12
InitEEPROM(); InitEEPROM();
#endif
GetConfig_EEPROM(); GetConfig_EEPROM();
GetPersistence_EEPROM(); GetPersistence_EEPROM();
@ -116,14 +118,15 @@ void setup()
pinMode(GPIO_TRIGGER, INPUT_PULLUP); pinMode(GPIO_TRIGGER, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(GPIO_TRIGGER), trigger_ISR, FALLING); attachInterrupt(digitalPinToInterrupt(GPIO_TRIGGER), trigger_ISR, FALLING);
break; break;
#ifdef FEATURE_ENABLE_GPS
case SOURCE_GPS: case SOURCE_GPS:
Init_GPS(); Init_GPS();
break; break;
#endif
case SOURCE_TIME: case SOURCE_TIME:
break; break;
#if PCB_REVISION >= 13 #ifdef FEATURE_ENABLE_CAN
case SOURCE_CAN: case SOURCE_CAN:
Init_CAN(); Init_CAN();
break; break;
@ -136,7 +139,7 @@ void setup()
pinMode(GPIO_BUTTON, INPUT_PULLUP); pinMode(GPIO_BUTTON, INPUT_PULLUP);
pinMode(GPIO_PUMP, OUTPUT); pinMode(GPIO_PUMP, OUTPUT);
#ifdef REMOTE_DEBUG #ifdef FEATURE_ENABLE_REMOTE_DEBUG
if (MDNS.begin(DeviceName)) if (MDNS.begin(DeviceName))
MDNS.addService("telnet", "tcp", 23); MDNS.addService("telnet", "tcp", 23);
@ -202,14 +205,18 @@ void loop()
case SOURCE_IMPULSE: case SOURCE_IMPULSE:
wheelDistance = Process_Impulse_WheelSpeed(); wheelDistance = Process_Impulse_WheelSpeed();
break; break;
#ifdef FEATURE_ENABLE_CAN
case SOURCE_CAN: case SOURCE_CAN:
wheelDistance = Process_CAN_WheelSpeed(); wheelDistance = Process_CAN_WheelSpeed();
break; break;
#endif
case SOURCE_TIME: case SOURCE_TIME:
break; break;
#ifdef FEATURE_ENABLE_GPS
case SOURCE_GPS: case SOURCE_GPS:
wheelDistance = Process_GPS_WheelSpeed(); wheelDistance = Process_GPS_WheelSpeed();
break; break;
#endif
} }
RunLubeApp(wheelDistance); RunLubeApp(wheelDistance);
@ -220,10 +227,10 @@ void loop()
EEPROM_Process(); EEPROM_Process();
ArduinoOTA.handle(); ArduinoOTA.handle();
#ifdef REMOTE_DEBUG #ifdef FEATURE_ENABLE_REMOTE_DEBUG
Debug.handle(); Debug.handle();
#endif #endif
#ifdef WIFI_CLIENT #ifdef FEATURE_ENABLE_WIFI_CLIENT
WiFiMaintainConnectionTicker.update(); WiFiMaintainConnectionTicker.update();
#endif #endif
if (globals.systemStatus == sysStat_Shutdown) if (globals.systemStatus == sysStat_Shutdown)
@ -239,7 +246,7 @@ String IpAddress2String(const IPAddress &ipAddress)
String(ipAddress[3]); String(ipAddress[3]);
} }
#ifdef REMOTE_DEBUG #ifdef FEATURE_ENABLE_REMOTE_DEBUG
void processCmdRemoteDebug() void processCmdRemoteDebug()
{ {
String lastCmd = Debug.getLastCommand(); String lastCmd = Debug.getLastCommand();
@ -318,8 +325,10 @@ void RemoteDebug_dumpConfig()
debugA("DistancePerRevolution_mm: %d", LubeConfig.DistancePerRevolution_mm); debugA("DistancePerRevolution_mm: %d", LubeConfig.DistancePerRevolution_mm);
debugA("BleedingPulses: %d", LubeConfig.BleedingPulses); debugA("BleedingPulses: %d", LubeConfig.BleedingPulses);
debugA("SpeedSource: %d", LubeConfig.SpeedSource); debugA("SpeedSource: %d", LubeConfig.SpeedSource);
#ifdef FEATURE_ENABLE_GPS
debugA("GPSBaudRate: %d", LubeConfig.GPSBaudRate); debugA("GPSBaudRate: %d", LubeConfig.GPSBaudRate);
#if PCB_REVISION == 13 #endif
#ifdef FEATURE_ENABLE_CAN
debugA("CANSource: %d", LubeConfig.CANSource); debugA("CANSource: %d", LubeConfig.CANSource);
#endif #endif
debugA("checksum: 0x%08X", LubeConfig.checksum); debugA("checksum: 0x%08X", LubeConfig.checksum);
@ -369,7 +378,7 @@ void RemoteDebug_CheckEEPOM()
} }
#endif #endif
#ifdef WIFI_CLIENT #ifdef FEATURE_ENABLE_WIFI_CLIENT
void wifiMaintainConnectionTicker_callback() void wifiMaintainConnectionTicker_callback()
{ {
static uint32_t WiFiFailCount = 0; static uint32_t WiFiFailCount = 0;
@ -692,7 +701,7 @@ void toggleWiFiAP(boolean shutdown)
{ {
WiFi.mode(WIFI_OFF); WiFi.mode(WIFI_OFF);
debugV("WiFi turned off"); debugV("WiFi turned off");
#ifdef WIFI_CLIENT #ifdef FEATURE_ENABLE_WIFI_CLIENT
WiFiMaintainConnectionTicker.stop(); WiFiMaintainConnectionTicker.stop();
#endif #endif
} }
@ -701,7 +710,7 @@ void toggleWiFiAP(boolean shutdown)
WiFi.mode(WIFI_AP); WiFi.mode(WIFI_AP);
WiFi.softAPConfig(IPAddress(WIFI_AP_IP_GW), IPAddress(WIFI_AP_IP_GW), IPAddress(255, 255, 255, 0)); WiFi.softAPConfig(IPAddress(WIFI_AP_IP_GW), IPAddress(WIFI_AP_IP_GW), IPAddress(255, 255, 255, 0));
WiFi.softAP(DeviceName, QUOTE(WIFI_AP_PASSWORD)); WiFi.softAP(DeviceName, QUOTE(WIFI_AP_PASSWORD));
#ifdef WIFI_CLIENT #ifdef FEATURE_ENABLE_WIFI_CLIENT
WiFiMaintainConnectionTicker.stop(); WiFiMaintainConnectionTicker.stop();
debugV("WiFi AP started, stopped Maintain-Timer"); debugV("WiFi AP started, stopped Maintain-Timer");
#else #else

View File

@ -55,9 +55,11 @@ String processor(const String &var)
return String(LubeConfig.BleedingPulses); return String(LubeConfig.BleedingPulses);
if (var == "SPEED_SOURCE") if (var == "SPEED_SOURCE")
return String(SpeedSourceString[LubeConfig.SpeedSource]); return String(SpeedSourceString[LubeConfig.SpeedSource]);
#ifdef FEATURE_ENABLE_GPS
if (var == "GPS_BAUD") if (var == "GPS_BAUD")
return String(GPSBaudRateString[LubeConfig.GPSBaudRate]); return String(GPSBaudRateString[LubeConfig.GPSBaudRate]);
#if PCB_REVISION == 13 #endif
#ifdef FEATURE_ENABLE_CAN
if (var == "CAN_SOURCE") if (var == "CAN_SOURCE")
return String(CANSourceString[LubeConfig.CANSource]); return String(CANSourceString[LubeConfig.CANSource]);
#endif #endif
@ -81,10 +83,14 @@ String processor(const String &var)
} }
if (var == "SHOW_IMPULSE_SETTINGS") if (var == "SHOW_IMPULSE_SETTINGS")
return LubeConfig.SpeedSource == SOURCE_IMPULSE ? "" : "hidden"; return LubeConfig.SpeedSource == SOURCE_IMPULSE ? "" : "hidden";
#ifdef FEATURE_ENABLE_CAN
if (var == "SHOW_CAN_SETTINGS") if (var == "SHOW_CAN_SETTINGS")
return LubeConfig.SpeedSource == SOURCE_CAN ? "" : "hidden"; return LubeConfig.SpeedSource == SOURCE_CAN ? "" : "hidden";
#endif
#ifdef FEATURE_ENABLE_GPS
if (var == "SHOW_GPS_SETTINGS") if (var == "SHOW_GPS_SETTINGS")
return LubeConfig.SpeedSource == SOURCE_GPS ? "" : "hidden"; return LubeConfig.SpeedSource == SOURCE_GPS ? "" : "hidden";
#endif
if (var == "SHOW_DTC_TABLE") if (var == "SHOW_DTC_TABLE")
return globals.systemStatus == sysStat_Error ? "" : "hidden"; return globals.systemStatus == sysStat_Error ? "" : "hidden";
@ -131,6 +137,7 @@ String processor(const String &var)
return temp; return temp;
} }
#ifdef FEATURE_ENABLE_CAN
if (var == "CANSOURCE_SELECT_OPTIONS") if (var == "CANSOURCE_SELECT_OPTIONS")
{ {
String temp; String temp;
@ -141,6 +148,8 @@ String processor(const String &var)
} }
return temp; return temp;
} }
#endif
#ifdef FEATURE_EABLE_GPS
if (var == "GPSBAUD_SELECT_OPTIONS") if (var == "GPSBAUD_SELECT_OPTIONS")
{ {
String temp; String temp;
@ -151,6 +160,7 @@ String processor(const String &var)
} }
return temp; return temp;
} }
#endif
if (var == "SYSTEM_STATUS") if (var == "SYSTEM_STATUS")
return String(globals.systemStatustxt); return String(globals.systemStatustxt);
@ -202,18 +212,22 @@ void WebserverPOST_Callback(AsyncWebServerRequest *request)
if (p->name() == "pulsesave") if (p->name() == "pulsesave")
globals.requestEEAction = EE_CFG_SAVE; globals.requestEEAction = EE_CFG_SAVE;
// end: POST Form Source Pulse Settings // end: POST Form Source Pulse Settings
#ifdef FEATURE_EABLE_GPS
// begin: POST Form Source GPS Settings // begin: POST Form Source GPS Settings
if (p->name() == "gpsbaud") if (p->name() == "gpsbaud")
LubeConfig.GPSBaudRate = (GPSBaudRate_t)p->value().toInt(); LubeConfig.GPSBaudRate = (GPSBaudRate_t)p->value().toInt();
if (p->name() == "gpssave") if (p->name() == "gpssave")
globals.requestEEAction = EE_CFG_SAVE; globals.requestEEAction = EE_CFG_SAVE;
// end: POST Form Source GPS Settings // end: POST Form Source GPS Settings
#endif
#ifdef FEATURE_EABLE_CAN
// begin: POST Form Source CAN Settings // begin: POST Form Source CAN Settings
if (p->name() == "cansource") if (p->name() == "cansource")
LubeConfig.CANSource = (CANSource_t)p->value().toInt(); LubeConfig.CANSource = (CANSource_t)p->value().toInt();
if (p->name() == "cansave") if (p->name() == "cansave")
globals.requestEEAction = EE_CFG_SAVE; globals.requestEEAction = EE_CFG_SAVE;
// end: POST Form Source CAN Settings // end: POST Form Source CAN Settings
#endif
// begin: POST Form Lubrication // begin: POST Form Lubrication
if (p->name() == "lubedistancenormal") if (p->name() == "lubedistancenormal")
LubeConfig.DistancePerLube_Default = p->value().toInt(); LubeConfig.DistancePerLube_Default = p->value().toInt();