801 lines
25 KiB
C++
Raw Normal View History

/**
* @file main.cpp
*
* @brief Main source file for the Souko's ChainLube Mk1 ESP8266 project.
*
* This file includes necessary libraries, defines configuration options, and declares global variables
* and function prototypes. It sets up essential components, initializes peripherals, and defines
* callbacks for interrupt service routines (ISRs) and timers. The main setup function configures the
* project, and the loop function handles the main execution loop, performing various tasks based on
* the configured options.
*
* @author Marcel Peterkau
* @date 09.01.2024
*/
2022-01-07 21:02:27 +01:00
#include <Arduino.h>
#include <Wire.h>
2022-08-19 00:10:42 +02:00
#ifdef FEATURE_ENABLE_OLED
2022-01-07 21:02:27 +01:00
#include <U8g2lib.h>
2022-08-19 00:10:42 +02:00
#endif
2022-01-07 21:02:27 +01:00
#include <ESP8266WiFi.h>
#include <ArduinoOTA.h>
2022-02-10 09:54:24 +01:00
2023-03-02 22:30:42 +01:00
#include <Adafruit_NeoPixel.h>
2022-01-07 23:36:02 +01:00
#include <Ticker.h>
2022-01-07 21:02:27 +01:00
#include "common.h"
2022-02-10 09:54:24 +01:00
2022-08-22 09:23:01 +02:00
#include "sanitycheck.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"
2023-02-23 23:14:58 +01:00
#include "debugger.h"
2022-02-04 21:28:49 +01:00
#include "can.h"
#include "gps.h"
#include "dtc.h"
2023-03-02 22:30:42 +01:00
#include "led_colors.h"
2022-01-07 21:02:27 +01:00
#ifdef FEATURE_ENABLE_WIFI_CLIENT
2022-01-14 21:28:50 +01:00
#include <ESP8266WiFiMulti.h>
2022-08-21 11:28:58 +02:00
const char *ssid = QUOTE(WIFI_SSID_CLIENT);
const char *password = QUOTE(WIFI_PASSWORD_CLIENT);
2022-01-07 23:36:02 +01:00
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
uint32_t (*wheelSpeedcapture)() = nullptr;
2022-01-07 21:02:27 +01:00
bool startSetupMode = false;
2022-01-07 23:36:02 +01:00
volatile uint32_t wheel_pulse = 0;
2023-03-02 22:30:42 +01:00
Adafruit_NeoPixel leds(1, GPIO_LED, NEO_RGB + NEO_KHZ800);
2022-01-07 21:02:27 +01:00
// Function-Prototypes
2022-01-07 23:36:02 +01:00
void IRAM_ATTR trigger_ISR();
2023-03-02 22:30:42 +01:00
void LED_Process(uint8_t override = false, uint32_t setColor = LED_DEFAULT_COLOR);
2022-08-19 00:10:42 +02:00
#ifdef FEATURE_ENABLE_OLED
U8X8_SSD1306_128X64_NONAME_HW_I2C u8x8(-1);
2022-01-14 15:36:17 +01:00
void Display_Process();
2022-08-19 00:10:42 +02:00
#endif
2022-01-14 15:36:17 +01:00
void Button_Process();
void toggleWiFiAP(bool shutdown = false);
void SystemShutdown(bool restart = false);
uint32_t Process_Impulse_WheelSpeed();
void EEPROMCyclicPDS_callback();
2022-02-10 09:54:24 +01:00
#ifdef FEATURE_ENABLE_WIFI_CLIENT
2022-01-14 21:28:50 +01:00
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
Ticker EEPROMCyclicPDSTicker(EEPROMCyclicPDS_callback, 60000, 0, MILLIS);
2022-01-07 21:02:27 +01:00
/**
* @brief Initializes the ESP8266 project, configuring various components and setting up required services.
*
* This setup function is responsible for initializing the ESP8266 project, including setting the CPU frequency,
* configuring WiFi settings, initializing DTC storage, handling WiFi client functionality (if enabled),
* initializing the Serial communication, setting up an OLED display (if enabled), initializing EEPROM,
* loading configuration and persistence data from EEPROM, initializing LEDs, setting up the chosen speed source
* (CAN, GPS, Impulse), configuring GPIO pins, setting up Over-The-Air (OTA) updates, initializing the web user interface,
* initializing global variables, starting cyclic EEPROM updates for Persistence Data Structure (PDS), and printing
* initialization status messages to Serial.
*/
2022-01-07 21:02:27 +01:00
void setup()
{
// Set CPU frequency to 80MHz
2022-01-07 21:02:27 +01:00
system_update_cpu_freq(SYS_CPU_80MHZ);
// Generate a unique device name based on ESP chip ID
2022-08-14 17:38:45 +02:00
snprintf(globals.DeviceName, 32, HOST_NAME, ESP.getChipId());
// Disable WiFi persistent storage
2022-01-07 21:02:27 +01:00
WiFi.persistent(false);
// Initialize and clear Diagnostic Trouble Code (DTC) storage
ClearAllDTC();
#ifdef FEATURE_ENABLE_WIFI_CLIENT
// Configure WiFi settings for client mode if enabled
2022-01-14 21:28:50 +01:00
WiFi.mode(WIFI_STA);
2022-08-14 17:38:45 +02:00
WiFi.setHostname(globals.DeviceName);
wifiMulti.addAP(QUOTE(WIFI_SSID_CLIENT), QUOTE(WIFI_PASSWORD_CLIENT));
2022-01-14 21:28:50 +01:00
WiFiMaintainConnectionTicker.start();
#else
// Disable WiFi if WiFi client feature is not enabled
2022-01-14 21:28:50 +01:00
WiFi.mode(WIFI_OFF);
#endif
// Initialize Serial communication
2022-01-07 21:02:27 +01:00
Serial.begin(115200);
2023-05-01 11:29:22 +02:00
Serial.print("\n\nSouko's ChainLube Mk1\n");
Serial.print(globals.DeviceName);
2022-01-07 21:02:27 +01:00
2022-08-19 00:10:42 +02:00
#ifdef FEATURE_ENABLE_OLED
// Initialize OLED display if enabled
2022-01-07 21:02:27 +01:00
u8x8.begin();
u8x8.setFont(u8x8_font_chroma48medium8_r);
2023-05-01 11:29:22 +02:00
u8x8.clearDisplay();
u8x8.drawString(0, 0, "KTM ChainLube V1");
u8x8.refreshDisplay();
Serial.print("\nDisplay-Init done");
2022-08-19 00:10:42 +02:00
#endif
// Initialize EEPROM, load configuration, and persistence data from EEPROM
InitEEPROM();
GetConfig_EEPROM();
GetPersistence_EEPROM();
Serial.print("\nEE-Init done");
// Initialize LEDs
2023-03-02 22:30:42 +01:00
leds.begin();
2023-05-01 11:29:22 +02:00
Serial.print("\nLED-Init done");
2022-02-10 09:54:24 +01:00
// Initialize based on the chosen speed source (CAN, GPS, Impulse)
switch (LubeConfig.SpeedSource)
{
case SOURCE_CAN:
Init_CAN();
wheelSpeedcapture = &Process_CAN_WheelSpeed;
Serial.print("\nCAN-Init done");
break;
case SOURCE_GPS:
Init_GPS();
wheelSpeedcapture = &Process_GPS_WheelSpeed;
Serial.print("\nGPS-Init done");
break;
case SOURCE_IMPULSE:
pinMode(GPIO_TRIGGER, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(GPIO_TRIGGER), trigger_ISR, FALLING);
wheelSpeedcapture = &Process_Impulse_WheelSpeed;
Serial.print("\nPulse-Input Init done");
break;
default:
break;
}
2023-05-01 11:29:22 +02:00
Serial.print("\nSource-Init done");
// Configure GPIO pins for button and pump control
2022-01-07 21:02:27 +01:00
pinMode(GPIO_BUTTON, INPUT_PULLUP);
pinMode(GPIO_PUMP, OUTPUT);
// Set up OTA updates
2022-01-07 21:02:27 +01:00
ArduinoOTA.setPort(8266);
2022-08-14 17:38:45 +02:00
ArduinoOTA.setHostname(globals.DeviceName);
2022-01-07 23:36:02 +01:00
ArduinoOTA.setPassword(QUOTE(ADMIN_PASSWORD));
2022-08-19 00:10:42 +02:00
#ifdef FEATURE_ENABLE_OLED
// Set up OTA callbacks for OLED display if enabled
2022-01-07 21:02:27 +01:00
ArduinoOTA.onStart([]()
{
u8x8.clearDisplay();
2024-01-09 22:52:28 +01:00
u8x8.drawString(0, 6, "OTA-Update");
2022-01-07 21:02:27 +01:00
u8x8.refreshDisplay(); });
ArduinoOTA.onProgress([](unsigned int progress, unsigned int total)
{
static bool refreshed = false;
if (!refreshed)
{
u8x8.clearDisplay();
refreshed = true;
2024-01-09 22:52:28 +01:00
u8x8.drawString(0, 6, "OTA Upload");
2022-01-07 21:02:27 +01:00
}
uint32_t percent = progress / (total / 100);
2024-01-09 22:52:28 +01:00
u8x8.setCursor(0, 7);
2022-01-07 21:02:27 +01:00
u8x8.printf("%d %%", percent);
u8x8.refreshDisplay(); });
ArduinoOTA.onEnd([]()
{
u8x8.clearDisplay();
2024-01-09 22:52:28 +01:00
u8x8.drawString(0, 6, "OTA-Restart");
2022-01-07 21:02:27 +01:00
u8x8.refreshDisplay(); });
2022-08-19 00:10:42 +02:00
#endif
// Begin OTA updates
2022-01-07 21:02:27 +01:00
ArduinoOTA.begin();
2023-05-01 11:29:22 +02:00
Serial.print("\nOTA-Init done");
// Initialize the web user interface
2022-01-07 23:36:02 +01:00
initWebUI();
2023-05-01 11:29:22 +02:00
Serial.print("\nWebUI-Init done");
// Initialize global variables
initGlobals();
2023-05-01 11:29:22 +02:00
Serial.print("\nglobals-Init done");
// Start cyclic EEPROM updates for Persistence Data Structure (PDS)
EEPROMCyclicPDSTicker.start();
2023-05-01 11:29:22 +02:00
Serial.print("\nSetup Done\n");
2022-01-07 21:02:27 +01:00
}
/**
* @brief Main execution loop for the ESP8266 project, performing various tasks based on configuration.
*
* This loop function handles different tasks based on the configured source of speed data (impulse, CAN, time, GPS).
* It calculates wheel distance, runs the lubrication application, updates the OLED display (if enabled),
* processes CAN messages, handles button input, manages LED behavior, performs EEPROM-related tasks, handles
* webserver operations, processes Diagnostic Trouble Codes (DTC), and manages debugging. Additionally, it
* integrates functionalities such as Over-The-Air (OTA) updates, cyclic EEPROM updates for Persistence Data
* Structure (PDS), WiFi connection maintenance, and system shutdown handling.
*/
2022-01-07 21:02:27 +01:00
void loop()
{
// Run lubrication application with the calculated wheel distance
RunLubeApp(wheelSpeedcapture());
2022-08-19 00:10:42 +02:00
#ifdef FEATURE_ENABLE_OLED
// Update OLED display if enabled
2022-01-14 15:36:17 +01:00
Display_Process();
2023-09-25 07:21:33 +02:00
#endif
// Process CAN messages if the speed source is not impulse
if (LubeConfig.SpeedSource != SOURCE_IMPULSE)
{
CAN_Process();
}
// Process button input, manage LED behavior, perform EEPROM tasks, handle webserver operations,
// process Diagnostic Trouble Codes (DTC), and manage debugging
2022-01-14 15:36:17 +01:00
Button_Process();
LED_Process();
2022-02-04 21:24:15 +01:00
EEPROM_Process();
2023-02-23 23:14:58 +01:00
Webserver_Process();
2023-02-24 19:24:26 +01:00
DTC_Process();
2023-03-14 23:30:26 +01:00
Debug_Process();
2022-01-07 23:36:02 +01:00
// Handle OTA updates and update cyclic EEPROM tasks for Persistence Data Structure (PDS)
2022-01-07 21:02:27 +01:00
ArduinoOTA.handle();
2023-02-24 19:24:26 +01:00
EEPROMCyclicPDSTicker.update();
#ifdef FEATURE_ENABLE_WIFI_CLIENT
// Update WiFi connection maintenance ticker if WiFi client feature is enabled
2022-01-14 21:28:50 +01:00
WiFiMaintainConnectionTicker.update();
#endif
// Perform system shutdown if the status is set to shutdown
if (globals.systemStatus == sysStat_Shutdown)
SystemShutdown(false);
// Yield to allow other tasks to run
2022-01-07 21:02:27 +01:00
yield();
}
#ifdef FEATURE_ENABLE_WIFI_CLIENT
/**
* @brief Callback function for maintaining WiFi connection and handling connection failures.
*
* This callback function is used by a ticker to periodically check the WiFi connection status.
* If the device is not connected to WiFi, it counts connection failures. If the number of failures
* exceeds a defined threshold, the function triggers the initiation of an Access Point (AP) mode
* using the `toggleWiFiAP` function.
*/
2022-01-07 23:36:02 +01:00
void wifiMaintainConnectionTicker_callback()
{
// Static variables to track WiFi connection failure count and maximum allowed failures
2022-01-07 23:36:02 +01:00
static uint32_t WiFiFailCount = 0;
const uint32_t WiFiFailMax = 20;
// Check if the device is connected to WiFi
2022-01-07 23:36:02 +01:00
if (wifiMulti.run(connectTimeoutMs) == WL_CONNECTED)
{
return; // Exit if connected
2022-01-07 23:36:02 +01:00
}
else
{
// Increment WiFi connection failure count
2022-01-07 23:36:02 +01:00
if (WiFiFailCount < WiFiFailMax)
{
WiFiFailCount++;
}
else
{
// Trigger AP mode if the maximum failures are reached
2024-01-12 19:52:25 +01:00
Debug_pushMessage("WiFi not connected! - Start AP\n");
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
/**
* @brief Callback function for cyclically storing Persistence Data Structure (PDS) to EEPROM.
*
* This callback function is invoked periodically to store the Persistence Data Structure (PDS)
* to the EEPROM. It ensures that essential data is saved persistently, allowing the system to
* recover its state after power cycles or resets.
*/
void EEPROMCyclicPDS_callback()
{
StorePersistence_EEPROM();
}
/**
* @brief Interrupt Service Routine (ISR) triggered by wheel speed sensor pulses.
*
* This ISR is called whenever a pulse is detected from the wheel speed sensor. It increments
* the `wheel_pulse` variable, which is used to track the number of pulses received.
*/
2022-01-07 23:36:02 +01:00
void trigger_ISR()
{
wheel_pulse++;
2022-01-09 20:51:16 +01:00
}
/**
* @brief Manages LED behavior based on the current system status and user overrides.
*
* This function handles LED behavior, including startup animations, confirmation animations for
* normal and rain modes, indication for purge, error, shutdown, and normal operation. It supports
* user overrides to set a specific LED color. The LED status is determined by the current system
* status, and specific LED patterns are displayed accordingly.
*
* @param override Flag indicating whether to override the LED behavior (0: No override, 1: Override, 2: Resume previous state).
* @param SetColor The color to set when overriding the LED behavior.
*/
2023-03-02 22:30:42 +01:00
void LED_Process(uint8_t override, uint32_t SetColor)
2022-01-09 20:51:16 +01:00
{
// Enumeration to represent LED status
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,
2023-03-03 11:39:43 +01:00
LED_Shutdown,
2022-01-14 15:36:17 +01:00
LED_Override
2022-01-09 20:51:16 +01:00
} tLED_Status;
// Static variables to track LED status, system status, override color, and previous LED status
static tSystem_Status oldSysStatus = sysStat_Startup;
static tLED_Status LED_Status = LED_Startup;
2023-03-02 22:30:42 +01:00
static uint32_t LED_override_color = 0;
2022-01-14 15:36:17 +01:00
static tLED_Status LED_ResumeOverrideStatus = LED_Startup;
2022-01-09 20:51:16 +01:00
// Variables for managing LED animation timing
uint8_t color = 0;
uint32_t timer = 0;
2023-03-02 22:30:42 +01:00
uint32_t animtimer = 0;
static uint32_t timestamp = 0;
timer = millis();
// Handle LED overrides
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;
2023-09-25 07:18:46 +02:00
Debug_pushMessage("Override LED_Status\n");
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;
2023-09-25 07:18:46 +02:00
Debug_pushMessage("Resume LED_Status\n");
2022-01-14 15:36:17 +01:00
}
}
// Update LED status when system status changes
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;
2023-09-25 07:18:46 +02:00
Debug_pushMessage("sysStat: Startup\n");
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;
2023-09-25 07:18:46 +02:00
Debug_pushMessage("sysStat: Normal\n");
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;
2023-09-25 07:18:46 +02:00
Debug_pushMessage("sysStat: Rain\n");
2022-01-10 00:55:04 +01:00
break;
case sysStat_Purge:
LED_Status = LED_Purge;
2023-09-25 07:18:46 +02:00
Debug_pushMessage("sysStat: Purge\n");
2022-01-10 00:55:04 +01:00
break;
case sysStat_Error:
LED_Status = LED_Error;
2023-09-25 07:18:46 +02:00
Debug_pushMessage("sysStat: Error\n");
2022-01-10 00:55:04 +01:00
break;
case sysStat_Shutdown:
2023-03-03 11:39:43 +01:00
LED_Status = LED_Shutdown;
2023-09-25 07:18:46 +02:00
Debug_pushMessage("sysStat: Shutdown\n");
2023-03-03 11:39:43 +01:00
break;
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
// Handle different LED statuses
2022-01-09 20:51:16 +01:00
switch (LED_Status)
{
case LED_Startup:
2023-03-02 22:30:42 +01:00
leds.setBrightness(LubeConfig.LED_Max_Brightness);
2022-01-14 15:36:17 +01:00
if (globals.TankPercentage < LubeConfig.TankRemindAtPercentage)
2023-03-02 22:30:42 +01:00
leds.setPixelColor(0, LED_STARTUP_TANKWARN);
2022-01-14 15:36:17 +01:00
else
2023-03-02 22:30:42 +01:00
leds.setPixelColor(0, LED_STARTUP_NORMAL);
2022-01-09 20:51:16 +01:00
break;
2022-01-09 20:51:16 +01:00
case LED_Confirm_Normal:
2023-03-02 22:30:42 +01:00
animtimer = timer % 500;
color = map(animtimer / 2, 0, 250, 0, LubeConfig.LED_Max_Brightness);
leds.setPixelColor(0, LED_NORMAL_COLOR);
if (animtimer < 250)
leds.setBrightness(color);
else
leds.setBrightness(LubeConfig.LED_Max_Brightness - color);
if (timestamp < timer)
{
LED_Status = LED_Normal;
2023-09-25 07:18:46 +02:00
Debug_pushMessage("LED_Status: Confirm -> Normal\n");
}
2022-01-09 20:51:16 +01:00
break;
2022-01-09 20:51:16 +01:00
case LED_Normal:
2023-03-02 22:30:42 +01:00
leds.setBrightness(LubeConfig.LED_Min_Brightness);
leds.setPixelColor(0, LED_NORMAL_COLOR);
if (timer % 2000 > 1950 && LubeConfig.LED_Mode_Flash == true)
leds.setBrightness(LubeConfig.LED_Max_Brightness);
else if (timer % 2000 > 1500 && WiFi.getMode() != WIFI_OFF)
leds.setPixelColor(0, LED_WIFI_BLINK);
2022-01-09 20:51:16 +01:00
break;
2022-01-09 20:51:16 +01:00
case LED_Confirm_Rain:
2023-03-02 22:30:42 +01:00
animtimer = timer % 500;
color = map(animtimer / 2, 0, 250, 0, LubeConfig.LED_Max_Brightness);
leds.setPixelColor(0, LED_RAIN_COLOR);
if (animtimer < 250)
leds.setBrightness(color);
else
leds.setBrightness(LubeConfig.LED_Max_Brightness - color);
if (timestamp < timer)
{
LED_Status = LED_Rain;
2023-09-25 07:18:46 +02:00
Debug_pushMessage("LED_Status: Confirm -> Rain\n");
}
2022-01-09 20:51:16 +01:00
break;
2022-01-09 20:51:16 +01:00
case LED_Rain:
2023-03-02 22:30:42 +01:00
leds.setBrightness(LubeConfig.LED_Min_Brightness);
leds.setPixelColor(0, LED_RAIN_COLOR);
if (timer % 2000 > 1950 && LubeConfig.LED_Mode_Flash == true)
leds.setBrightness(LubeConfig.LED_Max_Brightness);
else if (timer % 2000 > 1500 && WiFi.getMode() != WIFI_OFF)
leds.setPixelColor(0, LED_WIFI_BLINK);
2022-01-09 20:51:16 +01:00
break;
2022-01-09 20:51:16 +01:00
case LED_Purge:
timer = timer % 500;
2023-03-02 22:30:42 +01:00
color = map(timer / 2, 0, 250, LubeConfig.LED_Min_Brightness, LubeConfig.LED_Max_Brightness);
leds.setPixelColor(0, LED_PURGE_COLOR);
if (timer < 250)
2023-03-02 22:30:42 +01:00
leds.setBrightness(color);
else
2023-03-02 22:30:42 +01:00
leds.setBrightness(LubeConfig.LED_Max_Brightness - color);
2022-01-09 20:51:16 +01:00
break;
2022-01-09 20:51:16 +01:00
case LED_Error:
2023-03-02 22:30:42 +01:00
leds.setBrightness(LubeConfig.LED_Max_Brightness);
leds.setPixelColor(0, timer % 500 > 250 ? LED_ERROR_BLINK : 0);
2022-01-09 20:51:16 +01:00
break;
2023-03-03 11:39:43 +01:00
case LED_Shutdown:
timer = timer % 600;
leds.setPixelColor(0, LED_SHUTDOWN_BLINK);
if (timer < 500)
{
color = map(timer, 0, 500, LubeConfig.LED_Max_Brightness, LubeConfig.LED_Min_Brightness);
leds.setBrightness(color);
}
else
{
leds.setBrightness(LubeConfig.LED_Min_Brightness);
}
break;
2022-01-14 15:36:17 +01:00
case LED_Override:
2023-03-02 22:30:42 +01:00
leds.setBrightness(LubeConfig.LED_Max_Brightness);
leds.setPixelColor(0, LED_override_color);
2022-01-14 15:36:17 +01:00
break;
2022-01-09 20:51:16 +01:00
default:
break;
}
2023-03-02 22:30:42 +01:00
leds.show();
2022-01-09 20:51:16 +01:00
}
2022-08-19 00:10:42 +02:00
#ifdef FEATURE_ENABLE_OLED
/**
* @brief Manages the display content based on the current system status and updates the OLED display.
*
* This function handles the content to be displayed on the OLED screen, taking into account the
* current system status. It clears the display and prints relevant information such as system mode,
* remaining lubrication distance, tank level, WiFi status, speed source, and IP address. Additionally,
* it refreshes the OLED display with the updated content.
*/
2022-01-14 15:36:17 +01:00
void Display_Process()
2022-01-10 00:55:04 +01:00
{
// Static variable to track the previous system status
static tSystem_Status oldSysStatus = sysStat_Startup;
// Check if the system status has changed since the last update
if (oldSysStatus != globals.systemStatus)
{
// Clear the display and print the system title when the status changes
u8x8.clearDisplay();
u8x8.drawString(0, 0, "KTM ChainLube V1");
oldSysStatus = globals.systemStatus;
}
// Set the cursor position for displaying information on the OLED screen
u8x8.setCursor(0, 1);
// Calculate remaining lubrication distance based on system mode
uint32_t DistRemain = globals.systemStatus == sysStat_Normal ? LubeConfig.DistancePerLube_Default : LubeConfig.DistancePerLube_Rain;
2023-02-23 17:46:28 +01:00
DistRemain = DistRemain - (PersistenceData.TravelDistance_highRes_mm / 1000);
// Display relevant information on the OLED screen based on system status
u8x8.printf(PSTR("Mode: %10s\n"), globals.systemStatustxt);
if (globals.systemStatus == sysStat_Error)
{
// Display the last Diagnostic Trouble Code (DTC) in case of an error
u8x8.printf(PSTR("last DTC: %6d\n"), getlastDTC(false));
}
else
{
// Display information such as next lubrication distance, tank level, WiFi status, speed source, and IP address
u8x8.printf(PSTR("next Lube: %4dm\n"), DistRemain);
u8x8.printf(PSTR("Tank: %8dml\n"), PersistenceData.tankRemain_microL / 1000);
u8x8.printf(PSTR("WiFi: %10s\n"), (WiFi.getMode() == WIFI_AP ? "AP" : WiFi.getMode() == WIFI_OFF ? "OFF"
2022-03-08 23:03:10 +01:00
: WiFi.getMode() == WIFI_STA ? "CLIENT"
: "UNKNOWN"));
u8x8.printf(PSTR("Source: %8s\n"), SpeedSourceString[LubeConfig.SpeedSource]);
u8x8.printf("%s\n", WiFi.localIP().toString().c_str());
}
// Refresh the OLED display with the updated content
2022-01-10 00:55:04 +01:00
u8x8.refreshDisplay();
2022-01-14 15:36:17 +01:00
}
2022-08-19 00:10:42 +02:00
#endif
2022-01-14 15:36:17 +01:00
/**
* @brief Processes the button input and performs corresponding actions based on button state and timing.
*
* This function handles the button input, detecting button presses and executing actions based on
* predefined time delays. Actions include toggling WiFi, starting purge, toggling operating modes,
* and displaying feedback through LEDs. The function utilizes an enumeration to track button actions
* and manages the timing for different actions.
*/
2022-01-14 15:36:17 +01:00
void Button_Process()
{
// Time delays for different button actions
2022-01-14 15:36:17 +01:00
#define BUTTON_ACTION_DELAY_TOGGLEMODE 500
#define BUTTON_ACTION_DELAY_PURGE 3500
#define BUTTON_ACTION_DELAY_WIFI 6500
#define BUTTON_ACTION_DELAY_NOTHING 9500
// Enumeration to represent button actions
2022-01-14 15:36:17 +01:00
typedef enum buttonAction_e
{
BTN_INACTIVE,
BTN_NOTHING,
BTN_TOGGLEMODE,
BTN_TOGGLEWIFI,
BTN_STARTPURGE
} buttonAction_t;
// Static variables to track button state and timing
2022-01-14 15:36:17 +01:00
static uint32_t buttonTimestamp = 0;
static buttonAction_t buttonAction = BTN_INACTIVE;
// Check if button is pressed (LOW)
2022-01-14 15:36:17 +01:00
if (digitalRead(GPIO_BUTTON) == LOW)
{
// Update button timestamp on the first button press
2022-01-14 15:36:17 +01:00
if (buttonTimestamp == 0)
buttonTimestamp = millis();
// Check and execute actions based on predefined time delays
2022-01-14 15:36:17 +01:00
if (buttonTimestamp + BUTTON_ACTION_DELAY_NOTHING < millis())
{
2023-03-02 22:30:42 +01:00
LED_Process(1, COLOR_WARM_WHITE);
2022-01-14 15:36:17 +01:00
buttonAction = BTN_NOTHING;
}
else if (buttonTimestamp + BUTTON_ACTION_DELAY_WIFI < millis())
{
2023-03-02 22:30:42 +01:00
LED_Process(1, LED_WIFI_BLINK);
2022-01-14 15:36:17 +01:00
buttonAction = BTN_TOGGLEWIFI;
}
else if (buttonTimestamp + BUTTON_ACTION_DELAY_PURGE < millis())
{
2023-03-02 22:30:42 +01:00
LED_Process(1, LED_PURGE_COLOR);
2022-01-14 15:36:17 +01:00
buttonAction = BTN_STARTPURGE;
}
else if (buttonTimestamp + BUTTON_ACTION_DELAY_TOGGLEMODE < millis())
{
2023-03-02 22:30:42 +01:00
uint32_t color = globals.systemStatus == sysStat_Normal ? LED_RAIN_COLOR : LED_NORMAL_COLOR;
2022-01-14 15:36:17 +01:00
LED_Process(1, color);
buttonAction = BTN_TOGGLEMODE;
}
}
else // Button is released
2022-01-14 15:36:17 +01:00
{
// Execute corresponding actions based on the detected button action
2022-01-14 15:36:17 +01:00
if (buttonAction != BTN_INACTIVE)
{
switch (buttonAction)
{
case BTN_TOGGLEWIFI:
toggleWiFiAP();
2023-09-25 07:18:46 +02:00
Debug_pushMessage("Starting WiFi AP\n");
2022-01-14 15:36:17 +01:00
break;
case BTN_STARTPURGE:
globals.systemStatus = sysStat_Purge;
globals.purgePulses = LubeConfig.BleedingPulses;
2023-09-25 07:18:46 +02:00
Debug_pushMessage("Starting Purge\n");
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;
2022-01-14 15:36:17 +01:00
default:
break;
}
2023-09-25 07:18:46 +02:00
Debug_pushMessage("Toggling Mode\n");
2022-01-14 15:36:17 +01:00
break;
case BTN_NOTHING:
default:
2023-09-25 07:18:46 +02:00
Debug_pushMessage("Nothing or invalid\n");
2022-01-14 15:36:17 +01:00
break;
}
// Display feedback through LEDs
2022-01-14 15:36:17 +01:00
LED_Process(2);
}
// Reset button state and timestamp
2022-01-14 15:36:17 +01:00
buttonAction = BTN_INACTIVE;
buttonTimestamp = 0;
}
}
/**
* @brief Toggles the WiFi functionality based on the current status.
*
* This function manages the WiFi state, either turning it off or starting it as an Access Point (AP),
* depending on the current mode. If the WiFi is turned off, it can be started in AP mode with the
* device name and password configured. Additionally, it may stop certain operations related to WiFi
* maintenance or display debug messages based on the defined features.
*
* @param shutdown Flag indicating whether the system is in a shutdown state.
*/
void toggleWiFiAP(bool shutdown)
2022-01-14 15:36:17 +01:00
{
// Check if WiFi is currently active
2022-01-14 21:28:50 +01:00
if (WiFi.getMode() != WIFI_OFF)
{
// Turn off WiFi
2022-01-14 21:28:50 +01:00
WiFi.mode(WIFI_OFF);
2023-09-25 07:18:46 +02:00
Debug_pushMessage("WiFi turned off\n");
// Stop WiFi maintenance connection ticker if enabled
#ifdef FEATURE_ENABLE_WIFI_CLIENT
WiFiMaintainConnectionTicker.stop();
#endif
2022-01-14 21:28:50 +01:00
}
else
{
// Start WiFi in Access Point (AP) mode
2022-01-14 21:28:50 +01:00
WiFi.mode(WIFI_AP);
WiFi.softAPConfig(IPAddress(WIFI_AP_IP_GW), IPAddress(WIFI_AP_IP_GW), IPAddress(255, 255, 255, 0));
2022-08-14 17:38:45 +02:00
WiFi.softAP(globals.DeviceName, QUOTE(WIFI_AP_PASSWORD));
// Stop WiFi maintenance connection ticker if enabled and display debug messages
#ifdef FEATURE_ENABLE_WIFI_CLIENT
2022-01-14 21:28:50 +01:00
WiFiMaintainConnectionTicker.stop();
2023-09-25 07:18:46 +02:00
Debug_pushMessage("WiFi AP started, stopped Maintain-Timer\n");
2022-01-14 21:28:50 +01:00
#else
2023-09-25 07:18:46 +02:00
Debug_pushMessage("WiFi AP started\n");
2022-01-14 21:28:50 +01:00
#endif
}
}
/**
* @brief Performs necessary tasks before shutting down and optionally restarts the ESP.
*
* This function initiates a system shutdown, performing tasks such as storing configuration
* and persistence data to EEPROM before shutting down. If a restart is requested, the ESP
* will be restarted; otherwise, the system will enter an indefinite loop.
*
* @param restart Flag indicating whether to restart the ESP after shutdown (default: false).
*/
void SystemShutdown(bool restart)
{
static uint32_t shutdown_delay = 0;
// Initialize shutdown delay on the first call
if (shutdown_delay == 0)
{
shutdown_delay = millis() + SHUTDOWN_DELAY_MS;
2022-08-24 23:08:57 +02:00
Serial.printf("Shutdown requested - Restarting in %d seconds\n", SHUTDOWN_DELAY_MS / 1000);
}
// Check if the shutdown delay has elapsed
if (shutdown_delay < millis())
{
Webserver_Shutdown();
// Store persistence data to EEPROM
StorePersistence_EEPROM();
// Perform restart if requested, otherwise enter an indefinite loop
if (restart)
ESP.restart();
else
while (1)
;
}
2022-01-31 09:26:10 +01:00
}
/**
* @brief Processes the impulses from the wheel speed sensor and converts them into traveled distance.
*
* This function takes the pulse count from the wheel speed sensor and converts it into distance
* traveled in millimeters. The conversion is based on the configured parameters such as the number
* of pulses per revolution and the distance traveled per revolution.
*
* @return The calculated distance traveled in millimeters.
*/
uint32_t Process_Impulse_WheelSpeed()
2022-01-31 09:26:10 +01:00
{
uint32_t add_milimeters = 0;
// Calculate traveled Distance in mm
if (LubeConfig.PulsePerRevolution != 0)
add_milimeters = (wheel_pulse * (LubeConfig.DistancePerRevolution_mm / LubeConfig.PulsePerRevolution));
if (globals.measurementActive == true)
globals.measuredPulses = globals.measuredPulses + wheel_pulse;
wheel_pulse = 0;
2022-01-31 09:26:10 +01:00
return add_milimeters;
2022-05-01 15:15:32 +02:00
}