675 lines
17 KiB
C++
Raw Normal View History

2022-01-07 21:02:27 +01:00
#include <Arduino.h>
#include <Wire.h>
#include <U8g2lib.h>
#include <ESP8266WiFi.h>
#include <ESP8266mDNS.h>
#include <ArduinoOTA.h>
#include <RemoteDebug.h>
#include <FastLED.h>
2022-01-07 23:36:02 +01:00
#include <Ticker.h>
2022-01-31 09:26:10 +01:00
#if PCB_REVISION >= 13
#include <mcp_can.h>
#include <SPI.h>
#endif
2022-01-07 21:02:27 +01:00
#include "common.h"
#include "rmtdbghelp.h"
2022-01-08 03:14:26 +01:00
#include "lubeapp.h"
#include "webui.h"
2022-01-09 20:51:16 +01:00
#include "config.h"
#include "globals.h"
2022-01-07 21:02:27 +01:00
2022-01-14 21:28:50 +01:00
#ifdef WIFI_CLIENT
#include <ESP8266WiFiMulti.h>
2022-01-07 23:36:02 +01:00
const char *ssid = QUOTE(WIFI_SSID);
const char *password = QUOTE(WIFI_PASSWORD);
const uint32_t connectTimeoutMs = 5000;
2022-01-07 21:02:27 +01:00
2022-01-14 21:28:50 +01:00
ESP8266WiFiMulti wifiMulti;
2022-01-31 09:26:10 +01:00
#endif
2022-01-14 21:28:50 +01:00
2022-01-31 09:26:10 +01:00
#if PCB_REVISION >= 13
MCP_CAN CAN0(GPIO_CS_CAN);
2022-01-14 21:28:50 +01:00
#endif
2022-01-07 21:02:27 +01:00
#ifdef DEBUG
const bool debug_flag = true;
#else
const bool debug_flag = false;
#endif
bool startSetupMode = false;
char DeviceName[33];
Globals_t globals;
uint32_t TravelDistance_highRes;
2022-01-07 23:36:02 +01:00
volatile uint32_t wheel_pulse = 0;
2022-01-07 21:02:27 +01:00
U8X8_SSD1306_128X64_NONAME_HW_I2C u8x8(-1);
RemoteDebug Debug;
2022-01-07 23:36:02 +01:00
CRGB leds[1];
2022-01-07 21:02:27 +01:00
// Function-Prototypes
String IpAddress2String(const IPAddress &ipAddress);
void processCmdRemoteDebug();
void RemoteDebug_formatCFG();
void RemoteDebug_formatPersistence();
2022-01-07 21:02:27 +01:00
void RemotDebug_printSystemInfo();
void RemoteDebug_printWifiInfo();
void RemoteDebug_CheckEEPOM();
2022-02-04 21:24:15 +01:00
void RemoteDebug_dumpConfig();
void RemoteDebug_dumpPersistance();
2022-01-12 01:10:21 +01:00
void updateWebUITicker_callback();
2022-01-07 23:36:02 +01:00
void IRAM_ATTR trigger_ISR();
2022-01-14 15:36:17 +01:00
void LED_Process(uint8_t override = false, CRGB setColor = CRGB::White);
void Display_Process();
void Button_Process();
void toggleWiFiAP(boolean shutdown = false);
void SystemShutdown();
2022-01-31 09:26:10 +01:00
#if PCB_REVISION >= 13
void Init_CAN();
#endif
2022-01-07 21:02:27 +01:00
2022-01-14 21:28:50 +01:00
#ifdef WIFI_CLIENT
void wifiMaintainConnectionTicker_callback();
2022-01-07 23:36:02 +01:00
Ticker WiFiMaintainConnectionTicker(wifiMaintainConnectionTicker_callback, 1000, 0, MILLIS);
2022-01-14 21:28:50 +01:00
#endif
2022-01-12 01:10:21 +01:00
Ticker UpdateWebUITicker(updateWebUITicker_callback, 5000, 0, MILLIS);
2022-01-07 21:02:27 +01:00
void setup()
{
system_update_cpu_freq(SYS_CPU_80MHZ);
snprintf(DeviceName, 32, HOST_NAME, ESP.getChipId());
WiFi.persistent(false);
2022-01-14 21:28:50 +01:00
#ifdef 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
2022-01-07 21:02:27 +01:00
Serial.begin(115200);
Serial.setDebugOutput(true);
2022-01-07 23:36:02 +01:00
Serial.println("Souko's ChainLube Mk1");
2022-01-07 21:02:27 +01:00
Serial.println(DeviceName);
2022-01-31 09:26:10 +01:00
#if PCB_REVISION >= 12
InitEEPROM();
#endif
2022-01-09 20:51:16 +01:00
GetConfig_EEPROM();
GetPersistence_EEPROM();
2022-01-09 20:51:16 +01:00
2022-01-31 09:26:10 +01:00
#if PCB_REVISION >= 13
Init_CAN();
#endif
2022-01-07 21:02:27 +01:00
u8x8.begin();
u8x8.setFont(u8x8_font_chroma48medium8_r);
2022-01-07 23:36:02 +01:00
FastLED.addLeds<WS2811, GPIO_LED, GRB>(leds, 1); // GRB ordering is assumed
2022-01-31 09:26:10 +01:00
#if PCB_REVISION <= 13
2022-01-07 21:02:27 +01:00
pinMode(GPIO_TRIGGER, INPUT_PULLUP);
2022-01-31 09:26:10 +01:00
#endif
2022-01-07 21:02:27 +01:00
pinMode(GPIO_BUTTON, INPUT_PULLUP);
pinMode(GPIO_PUMP, OUTPUT);
2022-01-07 23:36:02 +01:00
attachInterrupt(digitalPinToInterrupt(GPIO_TRIGGER), trigger_ISR, FALLING);
2022-01-07 21:02:27 +01:00
if (MDNS.begin(DeviceName))
MDNS.addService("telnet", "tcp", 23);
Debug.begin(DeviceName); // Initialize the WiFi server
Debug.setResetCmdEnabled(true); // Enable the reset command
Debug.showProfiler(true); // Profiler (Good to measure times, to optimize codes)
Debug.showColors(true); // Colors
2022-01-07 23:36:02 +01:00
Debug.setPassword(QUOTE(ADMIN_PASSWORD));
Debug.setSerialEnabled(true);
Debug.showDebugLevel(true);
2022-01-07 21:02:27 +01:00
Debug.setHelpProjectsCmds(helpCmd);
Debug.setCallBackProjectCmds(&processCmdRemoteDebug);
ArduinoOTA.setPort(8266);
ArduinoOTA.setHostname(DeviceName);
2022-01-07 23:36:02 +01:00
ArduinoOTA.setPassword(QUOTE(ADMIN_PASSWORD));
2022-01-07 21:02:27 +01:00
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();
2022-01-07 23:36:02 +01:00
u8x8.drawString(4, 0, "Souko's");
u8x8.drawString(1, 1, "ChainLube Mk1");
2022-01-07 21:02:27 +01:00
u8x8.refreshDisplay();
2022-01-07 23:36:02 +01:00
initWebUI();
2022-01-12 01:10:21 +01:00
UpdateWebUITicker.start();
Serial.println("Setup Done");
2022-01-07 21:02:27 +01:00
}
void loop()
{
RunLubeApp(&wheel_pulse);
2022-01-12 01:10:21 +01:00
UpdateWebUITicker.update();
2022-01-09 20:51:16 +01:00
2022-01-14 15:36:17 +01:00
Display_Process();
Button_Process();
LED_Process();
2022-02-04 21:24:15 +01:00
EEPROM_Process();
2022-01-07 23:36:02 +01:00
2022-01-07 21:02:27 +01:00
ArduinoOTA.handle();
Debug.handle();
2022-01-14 21:28:50 +01:00
#ifdef WIFI_CLIENT
WiFiMaintainConnectionTicker.update();
#endif
if (globals.systemStatus == sysStat_Shutdown)
SystemShutdown();
2022-01-07 21:02:27 +01:00
yield();
}
String IpAddress2String(const IPAddress &ipAddress)
{
return String(ipAddress[0]) + String(".") +
String(ipAddress[1]) + String(".") +
String(ipAddress[2]) + String(".") +
String(ipAddress[3]);
}
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();
2022-01-31 09:26:10 +01:00
else if (lastCmd == "dumpEE1k")
dumpEEPROM(0, 1024);
else if (lastCmd == "dumpEE")
dumpEEPROM(0, EEPROM_SIZE_BYTES);
else if (lastCmd == "resetPageEE")
MovePersistencePage_EEPROM(true);
2022-02-04 21:24:15 +01:00
else if (lastCmd == "dumpCFG")
RemoteDebug_dumpConfig();
else if (lastCmd == "dumpPDS")
RemoteDebug_dumpPersistance();
else if (lastCmd == "saveEE")
StoreConfig_EEPROM();
}
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();
2022-01-07 21:02:27 +01:00
}
void RemotDebug_printSystemInfo()
{
debugA("Souko's ChainOiler Mk1");
debugA("Hostname: %s", DeviceName);
2022-01-08 03:14:26 +01:00
FlashMode_t ideMode = ESP.getFlashChipMode();
2022-01-07 21:02:27 +01:00
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());
2022-01-08 03:14:26 +01:00
debugA("Flash Size: %d", ESP.getFlashChipRealSize());
debugA("Flash Size IDE: %d", ESP.getFlashChipSize());
2022-01-09 20:51:16 +01:00
debugA("Flash ide mode: %s", (ideMode == FM_QIO ? "QIO" : ideMode == FM_QOUT ? "QOUT"
: ideMode == FM_DIO ? "DIO"
: ideMode == FM_DOUT ? "DOUT"
: "UNKNOWN"));
2022-01-07 23:36:02 +01:00
debugA("OTA-Pass: %s", QUOTE(ADMIN_PASSWORD));
debugA("Git-Revison: %s", GIT_REV);
2022-01-07 21:02:27 +01:00
}
2022-02-04 21:24:15 +01:00
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);
debugA("GPSBaudRate: %d", LubeConfig.GPSBaudRate);
#if PCB_REVISION == 13
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("distanceTraveled_m: %d", PersistenceData.distanceTraveled_m);
debugA("checksum: %d", PersistenceData.checksum);
}
2022-01-07 21:02:27 +01:00
void RemoteDebug_printWifiInfo()
{
}
2022-01-07 23:36:02 +01:00
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;
}
2022-01-14 21:28:50 +01:00
#ifdef WIFI_CLIENT
2022-01-07 23:36:02 +01:00
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
{
2022-01-14 21:28:50 +01:00
debugV("WiFi not connected! - Start AP");
toggleWiFiAP();
2022-01-07 23:36:02 +01:00
}
}
}
2022-01-14 21:28:50 +01:00
#endif
2022-01-07 23:36:02 +01:00
2022-01-12 01:10:21 +01:00
void updateWebUITicker_callback()
{
UpdateWebUI();
}
2022-01-07 23:36:02 +01:00
void trigger_ISR()
{
wheel_pulse++;
2022-01-09 20:51:16 +01:00
}
2022-01-14 15:36:17 +01:00
void LED_Process(uint8_t override, CRGB SetColor)
2022-01-09 20:51:16 +01:00
{
typedef enum
{
LED_Startup,
LED_Normal,
LED_Confirm_Normal,
LED_Rain,
LED_Confirm_Rain,
LED_Purge,
2022-01-14 15:36:17 +01:00
LED_Error,
LED_Override
2022-01-09 20:51:16 +01:00
} tLED_Status;
static tSystem_Status oldSysStatus = sysStat_Startup;
static tLED_Status LED_Status = LED_Startup;
2022-01-14 15:36:17 +01:00
static CRGB LED_override_color = 0;
static tLED_Status LED_ResumeOverrideStatus = LED_Startup;
2022-01-09 20:51:16 +01:00
uint8_t color = 0;
uint32_t timer = 0;
static uint32_t timestamp = 0;
timer = millis();
2022-01-14 15:36:17 +01:00
if (override == 1)
2022-01-09 20:51:16 +01:00
{
2022-01-14 15:36:17 +01:00
if (LED_Status != LED_Override)
{
LED_ResumeOverrideStatus = LED_Status;
2022-01-14 21:28:50 +01:00
debugV("Override LED_Status");
2022-01-14 15:36:17 +01:00
}
LED_Status = LED_Override;
LED_override_color = SetColor;
}
if (override == 2)
{
if (LED_Status == LED_Override)
{
LED_Status = LED_ResumeOverrideStatus;
2022-01-14 21:28:50 +01:00
debugV("Resume LED_Status");
2022-01-14 15:36:17 +01:00
}
}
if (oldSysStatus != globals.systemStatus)
{
switch (globals.systemStatus)
2022-01-09 20:51:16 +01:00
{
2022-01-10 00:55:04 +01:00
case sysStat_Startup:
LED_Status = LED_Startup;
2022-01-14 21:28:50 +01:00
debugV("sysStat: Startup");
2022-01-10 00:55:04 +01:00
break;
case sysStat_Normal:
timestamp = timer + 3500;
2022-01-10 00:55:04 +01:00
LED_Status = LED_Confirm_Normal;
2022-01-14 21:28:50 +01:00
debugV("sysStat: Normal");
2022-01-10 00:55:04 +01:00
break;
case sysStat_Rain:
timestamp = timer + 3500;
2022-01-10 00:55:04 +01:00
LED_Status = LED_Confirm_Rain;
2022-01-14 21:28:50 +01:00
debugV("sysStat: Rain");
2022-01-10 00:55:04 +01:00
break;
case sysStat_Purge:
LED_Status = LED_Purge;
2022-01-14 21:28:50 +01:00
debugV("sysStat: Purge");
2022-01-10 00:55:04 +01:00
break;
case sysStat_Error:
LED_Status = LED_Error;
2022-01-14 21:28:50 +01:00
debugV("sysStat: Error");
2022-01-10 00:55:04 +01:00
break;
case sysStat_Shutdown:
2022-01-12 00:52:27 +01:00
default:
break;
2022-01-09 20:51:16 +01:00
}
2022-01-14 15:36:17 +01:00
oldSysStatus = globals.systemStatus;
2022-01-09 20:51:16 +01:00
}
2022-01-10 00:55:04 +01:00
uint32_t percentage = PersistenceData.tankRemain_µl / (LubeConfig.tankCapacity_ml * 10);
2022-01-14 15:36:17 +01:00
2022-01-09 20:51:16 +01:00
switch (LED_Status)
{
case LED_Startup:
FastLED.setBrightness(255);
2022-01-14 15:36:17 +01:00
if (percentage < LubeConfig.TankRemindAtPercentage)
leds[0] = CRGB::OrangeRed;
else
leds[0] = CRGB::White;
2022-01-09 20:51:16 +01:00
break;
2022-01-09 20:51:16 +01:00
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);
2022-01-14 21:28:50 +01:00
debugV("LED_Status: Confirm -> Normal");
}
2022-01-09 20:51:16 +01:00
break;
2022-01-09 20:51:16 +01:00
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);
2022-01-09 20:51:16 +01:00
break;
2022-01-09 20:51:16 +01:00
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);
2022-01-14 21:28:50 +01:00
debugV("LED_Status: Confirm -> Rain");
}
2022-01-09 20:51:16 +01:00
break;
2022-01-09 20:51:16 +01:00
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);
2022-01-09 20:51:16 +01:00
break;
2022-01-09 20:51:16 +01:00
case LED_Purge:
timer = timer % 500;
color = timer / 2;
leds[0] = CRGB::DeepPink;
if (timer < 250)
FastLED.setBrightness(color);
else
FastLED.setBrightness(250 - color);
2022-01-09 20:51:16 +01:00
break;
2022-01-09 20:51:16 +01:00
case LED_Error:
leds[0] = timer % 500 > 250 ? CRGB::Red : CRGB::Black;
2022-01-09 20:51:16 +01:00
break;
2022-01-14 15:36:17 +01:00
case LED_Override:
leds[0] = LED_override_color;
break;
2022-01-09 20:51:16 +01:00
default:
break;
}
FastLED.show();
2022-01-09 20:51:16 +01:00
}
2022-01-10 00:55:04 +01:00
2022-01-14 15:36:17 +01:00
void Display_Process()
2022-01-10 00:55:04 +01:00
{
u8x8.setCursor(0, 3);
uint32_t DistRemain = globals.systemStatus == sysStat_Normal ? LubeConfig.DistancePerLube_Default : LubeConfig.DistancePerLube_Rain;
DistRemain -= TravelDistance_highRes / 1000;
u8x8.printf("Mode: %10s\n", globals.systemStatustxt);
u8x8.printf("next Lube: %4dm\n", DistRemain);
u8x8.printf("Tank: %8dml\n", PersistenceData.tankRemain_µl / 1000);
u8x8.printf("WiFi: %10s\n", (WiFi.getMode() == WIFI_AP ? "AP" : WiFi.getMode() == WIFI_OFF ? "OFF"
: WiFi.getMode() == WIFI_STA ? "CLIENT"
: "UNKNOWN"));
2022-01-10 00:55:04 +01:00
u8x8.refreshDisplay();
2022-01-14 15:36:17 +01:00
}
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();
2022-01-14 21:28:50 +01:00
debugV("Starting WiFi AP");
2022-01-14 15:36:17 +01:00
break;
case BTN_STARTPURGE:
globals.systemStatus = sysStat_Purge;
globals.purgePulses = LubeConfig.BleedingPulses;
2022-01-14 21:28:50 +01:00
debugV("Starting Purge");
2022-01-14 15:36:17 +01:00
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;
}
2022-01-14 21:28:50 +01:00
debugV("Toggling Mode");
2022-01-14 15:36:17 +01:00
break;
case BTN_NOTHING:
default:
2022-01-14 21:28:50 +01:00
debugV("Nothing or invalid");
2022-01-14 15:36:17 +01:00
break;
}
LED_Process(2);
}
buttonAction = BTN_INACTIVE;
buttonTimestamp = 0;
}
}
void toggleWiFiAP(boolean shutdown)
2022-01-14 15:36:17 +01:00
{
2022-01-14 21:28:50 +01:00
if (WiFi.getMode() != WIFI_OFF)
{
WiFi.mode(WIFI_OFF);
debugV("WiFi turned off");
#ifdef WIFI_CLIENT
WiFiMaintainConnectionTicker.stop();
#endif
2022-01-14 21:28:50 +01:00
}
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 WIFI_CLIENT
WiFiMaintainConnectionTicker.stop();
debugV("WiFi AP started, stopped Maintain-Timer");
#else
debugV("WiFi AP started");
#endif
}
}
void SystemShutdown()
{
StoreConfig_EEPROM();
ESP.restart();
2022-01-31 09:26:10 +01:00
}
#if PCB_REVISION >= 13
void Init_CAN()
{
// Initialize MCP2515 running at 16MHz with a baudrate of 500kb/s and the masks and filters disabled.
if (CAN0.begin(MCP_ANY, CAN_500KBPS, MCP_16MHZ) == CAN_OK)
Serial.println("MCP2515 Initialized Successfully!");
else
Serial.println("Error Initializing MCP2515...");
CAN0.setMode(MCP_NORMAL); // Change to normal mode to allow messages to be transmitted
}
void Recieve_CAN()
{
long unsigned int rxId;
unsigned char len = 0;
unsigned char rxBuf[8];
CAN0.readMsgBuf(&rxId, &len, rxBuf); // Read data: len = data length, buf = data byte(s)
}
#endif