Compare commits
2 Commits
125fc17c39
...
c399672755
Author | SHA1 | Date | |
---|---|---|---|
c399672755 | |||
dd34bfe645 |
84
Software/Jenkinsfile
vendored
Normal file
84
Software/Jenkinsfile
vendored
Normal file
@ -0,0 +1,84 @@
|
|||||||
|
pipeline {
|
||||||
|
agent any
|
||||||
|
|
||||||
|
options {
|
||||||
|
timestamps()
|
||||||
|
ansiColor('xterm')
|
||||||
|
}
|
||||||
|
|
||||||
|
environment {
|
||||||
|
// Default-Env, kann später via Parameter überschrieben werden
|
||||||
|
BUILD_ENV = "pcb_rev_1-4_serial"
|
||||||
|
PIO_HOME_DIR = "${WORKSPACE}/.pio"
|
||||||
|
}
|
||||||
|
|
||||||
|
parameters {
|
||||||
|
choice(
|
||||||
|
name: 'BUILD_ENV',
|
||||||
|
choices: ['pcb_rev_1-2_serial', 'pcb_rev_1-3_serial', 'pcb_rev_1-4_serial'],
|
||||||
|
description: 'Welches Environment soll gebaut werden?'
|
||||||
|
)
|
||||||
|
}
|
||||||
|
|
||||||
|
stages {
|
||||||
|
stage('🧼 Cleanup') {
|
||||||
|
steps {
|
||||||
|
deleteDir()
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
stage('Checkout') {
|
||||||
|
steps {
|
||||||
|
sshagent(['gitea-ssh']) {
|
||||||
|
sh 'git clone git@git.hiabuto.net:souko/Kettenoeler.git .'
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
stage('🧪 Python & PlatformIO Setup') {
|
||||||
|
steps {
|
||||||
|
sh '''
|
||||||
|
python3 -m venv .venv
|
||||||
|
. .venv/bin/activate
|
||||||
|
pip install --upgrade pip platformio
|
||||||
|
'''
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
stage('📄 Dummy-Credential-Datei erstellen') {
|
||||||
|
steps {
|
||||||
|
writeFile file: 'wifi_credentials.ini', text: '''
|
||||||
|
[wifi_cred]
|
||||||
|
wifi_ssid_client = DummySSID
|
||||||
|
wifi_password_client = DummyPass
|
||||||
|
admin_password = Admin1234
|
||||||
|
wifi_ap_password = ApPass1234
|
||||||
|
'''.stripIndent()
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
stage('⚙️ Build Environment: ${params.BUILD_ENV}') {
|
||||||
|
steps {
|
||||||
|
sh '''
|
||||||
|
. .venv/bin/activate
|
||||||
|
platformio run -e ${BUILD_ENV}
|
||||||
|
'''
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
stage('📦 Firmware sichern') {
|
||||||
|
steps {
|
||||||
|
archiveArtifacts artifacts: ".pio/build/${params.BUILD_ENV}/firmware.bin", fingerprint: true
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
post {
|
||||||
|
success {
|
||||||
|
echo "✅ Build erfolgreich abgeschlossen – Firmware liegt bereit als Artefakt."
|
||||||
|
}
|
||||||
|
failure {
|
||||||
|
echo "💣 Build fehlgeschlagen – bitte Logs prüfen!"
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
18
Software/include/button_actions.h
Normal file
18
Software/include/button_actions.h
Normal file
@ -0,0 +1,18 @@
|
|||||||
|
// === button_actions.h ===
|
||||||
|
#ifndef _BUTTON_ACTIONS_H_
|
||||||
|
#define _BUTTON_ACTIONS_H_
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "buttoncontrol.h"
|
||||||
|
|
||||||
|
// Deklarationen der Button-Callbacks
|
||||||
|
void ButtonAction_ToggleMode();
|
||||||
|
void ButtonAction_StartPurge();
|
||||||
|
void ButtonAction_ToggleWiFi();
|
||||||
|
void ButtonAction_WashMode();
|
||||||
|
|
||||||
|
// Bereitstellung der Aktionsliste
|
||||||
|
extern const ButtonActionEntry buttonActions[];
|
||||||
|
extern const uint8_t buttonActionCount;
|
||||||
|
|
||||||
|
#endif
|
30
Software/include/buttoncontrol.h
Normal file
30
Software/include/buttoncontrol.h
Normal file
@ -0,0 +1,30 @@
|
|||||||
|
// === buttoncontrol.h ===
|
||||||
|
#ifndef _BUTTONCONTROL_H_
|
||||||
|
#define _BUTTONCONTROL_H_
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
|
||||||
|
// Aktionen, die vom Button ausgelöst werden können
|
||||||
|
enum ButtonAction
|
||||||
|
{
|
||||||
|
BTN_NONE,
|
||||||
|
BTN_CUSTOM
|
||||||
|
};
|
||||||
|
|
||||||
|
// Callback-Funktionstyp
|
||||||
|
typedef void (*ButtonCallback)();
|
||||||
|
|
||||||
|
struct ButtonActionEntry
|
||||||
|
{
|
||||||
|
uint32_t holdTimeMs;
|
||||||
|
uint32_t ledColor;
|
||||||
|
ButtonCallback callback;
|
||||||
|
};
|
||||||
|
|
||||||
|
// Initialisierung des Buttonmoduls
|
||||||
|
void ButtonControl_Init(uint8_t pin, const ButtonActionEntry *actions, uint8_t actionCount);
|
||||||
|
|
||||||
|
// Muss regelmäßig in loop() aufgerufen werden
|
||||||
|
void ButtonControl_Update();
|
||||||
|
|
||||||
|
#endif
|
@ -41,9 +41,10 @@
|
|||||||
#elif PCB_REV == 4
|
#elif PCB_REV == 4
|
||||||
#define GPIO_BUTTON D4
|
#define GPIO_BUTTON D4
|
||||||
#define GPIO_LED D3
|
#define GPIO_LED D3
|
||||||
#define GPIO_TRIGGER D6
|
#define GPIO_TRIGGER D8
|
||||||
#define GPIO_PUMP D0
|
#define GPIO_PUMP D0
|
||||||
#define GPIO_CS_CAN D8
|
#define GPIO_CS_CAN D8
|
||||||
|
#define GPIO_CE_KLINE D8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef HOST_NAME
|
#ifndef HOST_NAME
|
||||||
|
@ -16,19 +16,6 @@
|
|||||||
|
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include "webui.h"
|
#include "webui.h"
|
||||||
const char PROGMEM helpCmd[] = "sysinfo - System Info\n"
|
|
||||||
"netinfo - WiFi Info\n"
|
|
||||||
"formatPDS - Format Persistence EEPROM Data\n"
|
|
||||||
"formatCFG - Format Configuration EEPROM Data\n"
|
|
||||||
"checkEE - Check EEPROM with checksum\n"
|
|
||||||
"dumpEE1k - dump the first 1kb of EEPROM to Serial\n"
|
|
||||||
"dumpEE - dump the whole EPPROM to Serial\n"
|
|
||||||
"resetPageEE - Reset the PersistenceData Page\n"
|
|
||||||
"dumpCFG - print Config struct\n"
|
|
||||||
"dumpPDS - print PersistanceStruct\n"
|
|
||||||
"saveEE - save EE-Data\n"
|
|
||||||
"showdtc - Show all DTCs\n"
|
|
||||||
"dumpGlobals - print globals\n";
|
|
||||||
|
|
||||||
typedef enum DebugStatus_e
|
typedef enum DebugStatus_e
|
||||||
{
|
{
|
||||||
@ -49,6 +36,13 @@ const char sDebugPorts[dbg_cntElements][7] = {
|
|||||||
|
|
||||||
extern DebugStatus_t DebuggerStatus[dbg_cntElements];
|
extern DebugStatus_t DebuggerStatus[dbg_cntElements];
|
||||||
|
|
||||||
|
enum LogLevel
|
||||||
|
{
|
||||||
|
LOG_INFO,
|
||||||
|
LOG_WARN,
|
||||||
|
LOG_ERROR
|
||||||
|
};
|
||||||
|
|
||||||
void initDebugger();
|
void initDebugger();
|
||||||
void pushCANDebug(uint32_t id, uint8_t dlc, uint8_t *data);
|
void pushCANDebug(uint32_t id, uint8_t dlc, uint8_t *data);
|
||||||
void Debug_pushMessage(const char *format, ...);
|
void Debug_pushMessage(const char *format, ...);
|
||||||
|
33
Software/include/ledcontrol.h
Normal file
33
Software/include/ledcontrol.h
Normal file
@ -0,0 +1,33 @@
|
|||||||
|
// === ledcontrol.h ===
|
||||||
|
#ifndef _LEDCONTROL_H_
|
||||||
|
#define _LEDCONTROL_H_
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
|
||||||
|
// LED-Muster
|
||||||
|
enum LedPattern
|
||||||
|
{
|
||||||
|
LED_PATTERN_ON,
|
||||||
|
LED_PATTERN_FLASH,
|
||||||
|
LED_PATTERN_FLASH_FAST,
|
||||||
|
LED_PATTERN_BLINK,
|
||||||
|
LED_PATTERN_BLINK_FAST,
|
||||||
|
LED_PATTERN_BREATH
|
||||||
|
};
|
||||||
|
|
||||||
|
// Initialisiert die LED-Steuerung
|
||||||
|
void LEDControl_Init(uint8_t pin);
|
||||||
|
|
||||||
|
// Setzt den Basiszustand (Farbe + Pattern), wird verwendet wenn kein Override aktiv ist
|
||||||
|
void LEDControl_SetBasic(uint32_t color, LedPattern pattern);
|
||||||
|
|
||||||
|
// Setzt ein Override mit Timeout (0 = bis explizit gecleart)
|
||||||
|
void LEDControl_SetOverride(uint32_t color, LedPattern pattern, uint32_t durationMs);
|
||||||
|
|
||||||
|
// Hebt das Override wieder auf
|
||||||
|
void LEDControl_ClearOverride();
|
||||||
|
|
||||||
|
// Muss regelmäßig aus loop() aufgerufen werden
|
||||||
|
void LEDControl_Update();
|
||||||
|
|
||||||
|
#endif
|
@ -11,7 +11,7 @@
|
|||||||
[platformio]
|
[platformio]
|
||||||
extra_configs =
|
extra_configs =
|
||||||
wifi_credentials.ini
|
wifi_credentials.ini
|
||||||
default_envs = pcb_rev_1-3_serial, pcb_rev_1-3_ota, pcb_rev_1-2_serial, pcb_rev_1-2_ota
|
default_envs = pcb_rev_1-4_serial
|
||||||
|
|
||||||
[env]
|
[env]
|
||||||
platform = espressif8266
|
platform = espressif8266
|
||||||
@ -51,6 +51,27 @@ lib_deps =
|
|||||||
coryjfowler/mcp_can @ ^1.5.0
|
coryjfowler/mcp_can @ ^1.5.0
|
||||||
mikalhart/TinyGPSPlus @ ^1.0.3
|
mikalhart/TinyGPSPlus @ ^1.0.3
|
||||||
|
|
||||||
|
[env:pcb_rev_1-4_serial]
|
||||||
|
extends = env
|
||||||
|
custom_pcb_revision = 4
|
||||||
|
upload_protocol = esptool
|
||||||
|
build_flags =
|
||||||
|
${env.build_flags}
|
||||||
|
-DPCB_REV=${this.custom_pcb_revision}
|
||||||
|
board_build.ldscript = eagle.flash.4m1m.ld
|
||||||
|
|
||||||
|
[env:pcb_rev_1-4_ota]
|
||||||
|
extends = env
|
||||||
|
custom_pcb_revision = 4
|
||||||
|
upload_protocol = espota
|
||||||
|
upload_port = 10.0.1.14
|
||||||
|
upload_flags =
|
||||||
|
--port=8266
|
||||||
|
--auth=${wifi_cred.admin_password}
|
||||||
|
build_flags =
|
||||||
|
${env.build_flags}
|
||||||
|
-DPCB_REV=${this.custom_pcb_revision}
|
||||||
|
board_build.ldscript = eagle.flash.4m1m.ld
|
||||||
|
|
||||||
[env:pcb_rev_1-3_serial]
|
[env:pcb_rev_1-3_serial]
|
||||||
extends = env
|
extends = env
|
||||||
|
49
Software/src/button_actions.cpp
Normal file
49
Software/src/button_actions.cpp
Normal file
@ -0,0 +1,49 @@
|
|||||||
|
// === button_actions.cpp ===
|
||||||
|
#include "button_actions.h"
|
||||||
|
#include "globals.h"
|
||||||
|
#include "debugger.h"
|
||||||
|
#include "led_colors.h"
|
||||||
|
|
||||||
|
void ButtonAction_ToggleMode()
|
||||||
|
{
|
||||||
|
if (globals.systemStatus == sysStat_Normal)
|
||||||
|
{
|
||||||
|
globals.systemStatus = sysStat_Rain;
|
||||||
|
globals.resumeStatus = sysStat_Rain;
|
||||||
|
}
|
||||||
|
else if (globals.systemStatus == sysStat_Rain)
|
||||||
|
{
|
||||||
|
globals.systemStatus = sysStat_Normal;
|
||||||
|
globals.resumeStatus = sysStat_Normal;
|
||||||
|
}
|
||||||
|
Debug_pushMessage("Toggling Mode\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
void ButtonAction_StartPurge()
|
||||||
|
{
|
||||||
|
globals.systemStatus = sysStat_Purge;
|
||||||
|
globals.purgePulses = LubeConfig.BleedingPulses;
|
||||||
|
Debug_pushMessage("Starting Purge\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
void ButtonAction_ToggleWiFi()
|
||||||
|
{
|
||||||
|
extern void toggleWiFiAP(bool shutdown = false);
|
||||||
|
toggleWiFiAP();
|
||||||
|
Debug_pushMessage("Toggling WiFi\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
void ButtonAction_WashMode()
|
||||||
|
{
|
||||||
|
Debug_pushMessage("Wash mode not yet implemented\n");
|
||||||
|
// TODO: Implementieren, sobald Verhalten klar ist
|
||||||
|
}
|
||||||
|
|
||||||
|
// Liste der Aktionen, sortiert nach Mindest-Haltezeit (ms)
|
||||||
|
const ButtonActionEntry buttonActions[] = {
|
||||||
|
{500, LED_RAIN_COLOR, ButtonAction_ToggleMode},
|
||||||
|
{3500, LED_PURGE_COLOR, ButtonAction_StartPurge},
|
||||||
|
{6500, LED_WIFI_BLINK, ButtonAction_ToggleWiFi},
|
||||||
|
{9500, COLOR_WARM_WHITE, ButtonAction_WashMode}};
|
||||||
|
|
||||||
|
const uint8_t buttonActionCount = sizeof(buttonActions) / sizeof(ButtonActionEntry);
|
64
Software/src/buttoncontrol.cpp
Normal file
64
Software/src/buttoncontrol.cpp
Normal file
@ -0,0 +1,64 @@
|
|||||||
|
|
||||||
|
// === buttoncontrol.cpp ===
|
||||||
|
#include "buttoncontrol.h"
|
||||||
|
#include "ledcontrol.h" // Neue LED-Logik wird hier verwendet
|
||||||
|
|
||||||
|
static uint8_t btnPin;
|
||||||
|
static uint32_t pressStart = 0;
|
||||||
|
static bool pressed = false;
|
||||||
|
static const ButtonActionEntry *btnActions = nullptr;
|
||||||
|
static uint8_t btnActionCount = 0;
|
||||||
|
static uint8_t currentActionIndex = 0xFF;
|
||||||
|
static uint32_t lastColor = 0;
|
||||||
|
|
||||||
|
void ButtonControl_Init(uint8_t pin, const ButtonActionEntry *actions, uint8_t actionCount)
|
||||||
|
{
|
||||||
|
btnPin = pin;
|
||||||
|
pinMode(btnPin, INPUT_PULLUP);
|
||||||
|
btnActions = actions;
|
||||||
|
btnActionCount = actionCount;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ButtonControl_Update()
|
||||||
|
{
|
||||||
|
bool currentState = digitalRead(btnPin) == LOW;
|
||||||
|
uint32_t now = millis();
|
||||||
|
|
||||||
|
if (currentState && !pressed)
|
||||||
|
{
|
||||||
|
pressStart = now;
|
||||||
|
pressed = true;
|
||||||
|
currentActionIndex = 0xFF;
|
||||||
|
lastColor = 0;
|
||||||
|
}
|
||||||
|
else if (currentState && pressed)
|
||||||
|
{
|
||||||
|
uint32_t duration = now - pressStart;
|
||||||
|
// Finde passende Aktion basierend auf Zeit
|
||||||
|
for (uint8_t i = 0; i < btnActionCount; i++)
|
||||||
|
{
|
||||||
|
if (duration >= btnActions[i].holdTimeMs)
|
||||||
|
{
|
||||||
|
if (currentActionIndex != i)
|
||||||
|
{
|
||||||
|
currentActionIndex = i;
|
||||||
|
lastColor = btnActions[i].ledColor;
|
||||||
|
// Farbe + Pattern setzen
|
||||||
|
LEDControl_SetOverride(lastColor, LED_PATTERN_BREATH, 0); // Kein Timeout, wird bei Release beendet
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if (!currentState && pressed)
|
||||||
|
{
|
||||||
|
pressed = false;
|
||||||
|
if (currentActionIndex != 0xFF && currentActionIndex < btnActionCount)
|
||||||
|
{
|
||||||
|
if (btnActions[currentActionIndex].callback)
|
||||||
|
{
|
||||||
|
btnActions[currentActionIndex].callback();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
LEDControl_ClearOverride(); // Override-Modus zurücksetzen
|
||||||
|
}
|
||||||
|
}
|
@ -12,6 +12,9 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include "debugger.h"
|
#include "debugger.h"
|
||||||
|
#include <map>
|
||||||
|
#include <functional>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
DebugStatus_t DebuggerStatus[dbg_cntElements];
|
DebugStatus_t DebuggerStatus[dbg_cntElements];
|
||||||
|
|
||||||
@ -94,10 +97,9 @@ void Debug_Process()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Check for input buffer overflow
|
// Check for input buffer overflow
|
||||||
if (inputCnt > sizeof(inputBuffer))
|
if (inputCnt >= sizeof(inputBuffer) - 1) {
|
||||||
{
|
inputBuffer[sizeof(inputBuffer) - 1] = '\0';
|
||||||
inputCnt = 0;
|
inputCnt = 0;
|
||||||
inputBuffer[sizeof(inputBuffer) - 1] = 0; // terminate the String
|
|
||||||
InputProcessed = CMD_OVERFLOW;
|
InputProcessed = CMD_OVERFLOW;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -147,6 +149,29 @@ void SetDebugportStatus(DebugPorts_t port, DebugStatus_t status)
|
|||||||
Debug_pushMessage("Enabled DebugPort %s\n", sDebugPorts[port]);
|
Debug_pushMessage("Enabled DebugPort %s\n", sDebugPorts[port]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void Debug_log(LogLevel level, const char *format, ...)
|
||||||
|
{
|
||||||
|
if ((DebuggerStatus[dbg_Serial] == enabled) || (DebuggerStatus[dbg_Webui] == enabled))
|
||||||
|
{
|
||||||
|
char buff[128];
|
||||||
|
va_list arg;
|
||||||
|
va_start(arg, format);
|
||||||
|
vsnprintf(buff, sizeof(buff), format, arg);
|
||||||
|
va_end(arg);
|
||||||
|
|
||||||
|
if (DebuggerStatus[dbg_Serial] == enabled)
|
||||||
|
{
|
||||||
|
Serial.print(buff);
|
||||||
|
}
|
||||||
|
if (DebuggerStatus[dbg_Webui] == enabled)
|
||||||
|
{
|
||||||
|
Websocket_PushLiveDebug(String(buff));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Pushes a formatted debug message to the enabled debug ports (Serial or WebUI).
|
* @brief Pushes a formatted debug message to the enabled debug ports (Serial or WebUI).
|
||||||
*
|
*
|
||||||
@ -218,68 +243,99 @@ void pushCANDebug(uint32_t id, uint8_t dlc, uint8_t *data)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
// === splitArgs Helper ===
|
||||||
* @brief Processes a debug command and performs corresponding actions.
|
std::vector<String> splitArgs(const String &input)
|
||||||
*
|
|
||||||
* @param command The debug command to be processed.
|
|
||||||
*/
|
|
||||||
void processCmdDebug(String command)
|
|
||||||
{
|
{
|
||||||
// Check the received command and execute corresponding actions
|
std::vector<String> tokens;
|
||||||
if (command == "help")
|
int start = 0, end = 0;
|
||||||
Debug_printHelp();
|
while ((end = input.indexOf(' ', start)) != -1)
|
||||||
else if (command == "sysinfo")
|
{
|
||||||
Debug_printSystemInfo();
|
tokens.push_back(input.substring(start, end));
|
||||||
else if (command == "netinfo")
|
start = end + 1;
|
||||||
Debug_printWifiInfo();
|
}
|
||||||
else if (command == "formatCFG")
|
if (start < input.length())
|
||||||
Debug_formatCFG();
|
tokens.push_back(input.substring(start));
|
||||||
else if (command == "formatPDS")
|
return tokens;
|
||||||
Debug_formatPersistence();
|
}
|
||||||
else if (command == "checkEE")
|
|
||||||
Debug_CheckEEPOM(false);
|
// === getArg helper ===
|
||||||
else if (command == "checkEEfix")
|
String getArg(const std::vector<String> &args, size_t index, const String &defaultVal = "")
|
||||||
Debug_CheckEEPOM(true);
|
{
|
||||||
else if (command == "dumpEE1k")
|
if (index < args.size())
|
||||||
dumpEEPROM(0, 1024);
|
return args[index];
|
||||||
else if (command == "dumpEE")
|
return defaultVal;
|
||||||
dumpEEPROM(0, EEPROM_SIZE_BYTES);
|
}
|
||||||
else if (command == "resetPageEE")
|
|
||||||
MovePersistencePage_EEPROM(true);
|
// === Command Handler Map ===
|
||||||
else if (command == "dumpCFG")
|
typedef std::function<void(const String &args)> DebugCmdHandler;
|
||||||
Debug_dumpConfig();
|
|
||||||
else if (command == "dumpPDS")
|
static const std::map<String, DebugCmdHandler> &getCmdMap()
|
||||||
Debug_dumpPersistance();
|
{
|
||||||
else if (command == "saveEE")
|
static const std::map<String, DebugCmdHandler> cmdMap = {
|
||||||
globals.requestEEAction = EE_ALL_SAVE;
|
{"help", [](const String &) {
|
||||||
else if (command == "dumpGlobals")
|
Debug_log(LOG_INFO, "Available commands:\n");
|
||||||
Debug_dumpGlobals();
|
for (const auto &entry : getCmdMap())
|
||||||
else if (command == "sdbg")
|
Debug_log(LOG_INFO, " - %s\n", entry.first.c_str());
|
||||||
SetDebugportStatus(dbg_Serial, enabled);
|
}},
|
||||||
else if (command == "dtc_show")
|
{"sysinfo", [](const String &) { Debug_printSystemInfo(); }},
|
||||||
Debug_ShowDTCs();
|
{"netinfo", [](const String &) { Debug_printWifiInfo(); }},
|
||||||
else if (command == "dtc_clear")
|
{"formatCFG", [](const String &) { Debug_formatCFG(); }},
|
||||||
ClearAllDTC();
|
{"formatPDS", [](const String &) { Debug_formatPersistence(); }},
|
||||||
else if (command == "dtc_crit")
|
{"checkEE", [](const String &) { Debug_CheckEEPOM(false); }},
|
||||||
MaintainDTC(DTC_FAKE_DTC_CRIT, true, millis());
|
{"checkEEfix", [](const String &) { Debug_CheckEEPOM(true); }},
|
||||||
else if (command == "dtc_warn")
|
{"dumpEE1k", [](const String &) { dumpEEPROM(0, 1024); }},
|
||||||
MaintainDTC(DTC_FAKE_DTC_WARN, true, millis());
|
{"dumpEE", [](const String &args) {
|
||||||
else if (command == "dtc_info")
|
int start = 0, len = EEPROM_SIZE_BYTES;
|
||||||
MaintainDTC(DTC_FAKE_DTC_INFO, true, millis());
|
auto tokens = splitArgs(args);
|
||||||
else if (command == "notify_error")
|
if (tokens.size() >= 2)
|
||||||
Websocket_PushNotification("Debug Error Notification", error);
|
{
|
||||||
else if (command == "notify_warning")
|
start = tokens[0].toInt();
|
||||||
Websocket_PushNotification("Debug Warning Notification", warning);
|
len = tokens[1].toInt();
|
||||||
else if (command == "notify_success")
|
}
|
||||||
Websocket_PushNotification("Debug Success Notification", success);
|
dumpEEPROM(start, len);
|
||||||
else if (command == "notify_info")
|
}},
|
||||||
Websocket_PushNotification("Debug Info Notification", info);
|
{"resetPageEE", [](const String &) { MovePersistencePage_EEPROM(true); }},
|
||||||
else if (command == "purge")
|
{"dumpCFG", [](const String &) { Debug_dumpConfig(); }},
|
||||||
Debug_Purge();
|
{"dumpPDS", [](const String &) { Debug_dumpPersistance(); }},
|
||||||
else if (command == "toggle_wifi")
|
{"saveEE", [](const String &) { globals.requestEEAction = EE_ALL_SAVE; }},
|
||||||
globals.toggle_wifi = true;
|
{"dumpGlobals", [](const String &) { Debug_dumpGlobals(); }},
|
||||||
|
{"sdbg", [](const String &) { SetDebugportStatus(dbg_Serial, enabled); }},
|
||||||
|
{"dtc_show", [](const String &) { Debug_ShowDTCs(); }},
|
||||||
|
{"dtc_clear", [](const String &) { ClearAllDTC(); }},
|
||||||
|
{"dtc_crit", [](const String &) { MaintainDTC(DTC_FAKE_DTC_CRIT, true, millis()); }},
|
||||||
|
{"dtc_warn", [](const String &) { MaintainDTC(DTC_FAKE_DTC_WARN, true, millis()); }},
|
||||||
|
{"dtc_info", [](const String &) { MaintainDTC(DTC_FAKE_DTC_INFO, true, millis()); }},
|
||||||
|
{"notify_error", [](const String &) { Websocket_PushNotification("Debug Error Notification", error); }},
|
||||||
|
{"notify_warning", [](const String &) { Websocket_PushNotification("Debug Warning Notification", warning); }},
|
||||||
|
{"notify_success", [](const String &) { Websocket_PushNotification("Debug Success Notification", success); }},
|
||||||
|
{"notify_info", [](const String &) { Websocket_PushNotification("Debug Info Notification", info); }},
|
||||||
|
{"purge", [](const String &) { Debug_Purge(); }},
|
||||||
|
{"toggle_wifi", [](const String &) { globals.toggle_wifi = true; }},
|
||||||
|
{"dtc_add", [](const String &args) {
|
||||||
|
auto tokens = splitArgs(args);
|
||||||
|
if (!tokens.empty())
|
||||||
|
{
|
||||||
|
int code = tokens[0].toInt();
|
||||||
|
MaintainDTC((DTCNum_t)code, true, millis());
|
||||||
|
}
|
||||||
|
}}
|
||||||
|
};
|
||||||
|
return cmdMap;
|
||||||
|
}
|
||||||
|
|
||||||
|
void processCmdDebug(String input)
|
||||||
|
{
|
||||||
|
input.trim();
|
||||||
|
int splitIndex = input.indexOf(' ');
|
||||||
|
String command = splitIndex == -1 ? input : input.substring(0, splitIndex);
|
||||||
|
String args = splitIndex == -1 ? "" : input.substring(splitIndex + 1);
|
||||||
|
|
||||||
|
auto &cmdMap = getCmdMap();
|
||||||
|
auto it = cmdMap.find(command);
|
||||||
|
if (it != cmdMap.end())
|
||||||
|
it->second(args);
|
||||||
else
|
else
|
||||||
Debug_pushMessage("unknown Command\n");
|
Debug_log(LOG_WARN, "Unknown command: '%s'\n", command.c_str());
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -473,25 +529,6 @@ void Debug_ShowDTCs()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Displays the help commands for debugging through Serial or WebUI.
|
|
||||||
* Each command is printed individually in a formatted manner.
|
|
||||||
*/
|
|
||||||
void Debug_printHelp()
|
|
||||||
{
|
|
||||||
char buff[64];
|
|
||||||
|
|
||||||
// Iterate through helpCmd and display each command
|
|
||||||
for (unsigned int i = 0; i < sizeof(helpCmd) / 63; i++)
|
|
||||||
{
|
|
||||||
// Copy a portion of helpCmd to buff for display
|
|
||||||
memcpy_P(buff, (helpCmd + (i * 63)), 63);
|
|
||||||
buff[63] = 0;
|
|
||||||
|
|
||||||
// Display the help command
|
|
||||||
Debug_pushMessage(buff);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Start purging for 10 pulses.
|
* @brief Start purging for 10 pulses.
|
||||||
|
106
Software/src/ledcontrol.cpp
Normal file
106
Software/src/ledcontrol.cpp
Normal file
@ -0,0 +1,106 @@
|
|||||||
|
|
||||||
|
// === ledcontrol.cpp ===
|
||||||
|
#include "ledcontrol.h"
|
||||||
|
#include <Adafruit_NeoPixel.h>
|
||||||
|
#include "globals.h"
|
||||||
|
|
||||||
|
static Adafruit_NeoPixel leds(1, GPIO_LED, NEO_RGB + NEO_KHZ800);
|
||||||
|
|
||||||
|
static uint32_t basicColor = 0x000000;
|
||||||
|
static LedPattern basicPattern = LED_PATTERN_ON;
|
||||||
|
|
||||||
|
static uint32_t overrideColor = 0;
|
||||||
|
static LedPattern overridePattern = LED_PATTERN_ON;
|
||||||
|
static uint32_t overrideEndTime = 0;
|
||||||
|
static bool overrideActive = false;
|
||||||
|
|
||||||
|
void LEDControl_Init(uint8_t pin)
|
||||||
|
{
|
||||||
|
leds.begin();
|
||||||
|
leds.setBrightness(LubeConfig.LED_Max_Brightness);
|
||||||
|
leds.setPixelColor(0, 0);
|
||||||
|
leds.show();
|
||||||
|
}
|
||||||
|
|
||||||
|
void LEDControl_SetBasic(uint32_t color, LedPattern pattern)
|
||||||
|
{
|
||||||
|
basicColor = color;
|
||||||
|
basicPattern = pattern;
|
||||||
|
}
|
||||||
|
|
||||||
|
void LEDControl_SetOverride(uint32_t color, LedPattern pattern, uint32_t durationMs)
|
||||||
|
{
|
||||||
|
overrideColor = color;
|
||||||
|
overridePattern = pattern;
|
||||||
|
overrideEndTime = millis() + durationMs;
|
||||||
|
overrideActive = true;
|
||||||
|
if (durationMs == 0)
|
||||||
|
overrideEndTime = 0xFFFFFFFF; // Kein Timeout
|
||||||
|
}
|
||||||
|
|
||||||
|
void LEDControl_ClearOverride()
|
||||||
|
{
|
||||||
|
overrideActive = false;
|
||||||
|
overrideEndTime = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void LEDControl_Update()
|
||||||
|
{
|
||||||
|
uint32_t now = millis();
|
||||||
|
uint32_t color = basicColor;
|
||||||
|
LedPattern pattern = basicPattern;
|
||||||
|
|
||||||
|
// Check override
|
||||||
|
if (overrideActive)
|
||||||
|
{
|
||||||
|
if (overrideEndTime != 0xFFFFFFFF && now >= overrideEndTime)
|
||||||
|
{
|
||||||
|
LEDControl_ClearOverride();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
color = overrideColor;
|
||||||
|
pattern = overridePattern;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t brightness = LubeConfig.LED_Min_Brightness;
|
||||||
|
bool on = true;
|
||||||
|
|
||||||
|
switch (pattern)
|
||||||
|
{
|
||||||
|
case LED_PATTERN_ON:
|
||||||
|
brightness = LubeConfig.LED_Max_Brightness;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case LED_PATTERN_FLASH:
|
||||||
|
on = (now % 1000) < 100;
|
||||||
|
brightness = LubeConfig.LED_Max_Brightness;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case LED_PATTERN_FLASH_FAST:
|
||||||
|
on = (now % 500) < 50;
|
||||||
|
brightness = LubeConfig.LED_Max_Brightness;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case LED_PATTERN_BLINK:
|
||||||
|
on = (now % 1000) < 500;
|
||||||
|
brightness = on ? LubeConfig.LED_Max_Brightness : 0;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case LED_PATTERN_BLINK_FAST:
|
||||||
|
on = (now % 400) < 200;
|
||||||
|
brightness = on ? LubeConfig.LED_Max_Brightness : 0;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case LED_PATTERN_BREATH:
|
||||||
|
brightness = map(now % 2000, 0, 1000, LubeConfig.LED_Min_Brightness, LubeConfig.LED_Max_Brightness);
|
||||||
|
if ((now % 2000) >= 1000)
|
||||||
|
brightness = LubeConfig.LED_Max_Brightness - (brightness - LubeConfig.LED_Min_Brightness);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
leds.setBrightness(brightness);
|
||||||
|
leds.setPixelColor(0, on ? color : 0);
|
||||||
|
leds.show();
|
||||||
|
}
|
@ -39,6 +39,10 @@
|
|||||||
#include "led_colors.h"
|
#include "led_colors.h"
|
||||||
#include "obd2_kline.h"
|
#include "obd2_kline.h"
|
||||||
#include "obd2_can.h"
|
#include "obd2_can.h"
|
||||||
|
#include "buttoncontrol.h"
|
||||||
|
#include "button_actions.h"
|
||||||
|
#include "ledcontrol.h"
|
||||||
|
|
||||||
|
|
||||||
#ifdef FEATURE_ENABLE_WIFI_CLIENT
|
#ifdef FEATURE_ENABLE_WIFI_CLIENT
|
||||||
#include <ESP8266WiFiMulti.h>
|
#include <ESP8266WiFiMulti.h>
|
||||||
@ -59,12 +63,10 @@ Adafruit_NeoPixel leds(1, GPIO_LED, NEO_RGB + NEO_KHZ800);
|
|||||||
|
|
||||||
// Function-Prototypes
|
// Function-Prototypes
|
||||||
void IRAM_ATTR trigger_ISR();
|
void IRAM_ATTR trigger_ISR();
|
||||||
void LED_Process(uint8_t override = false, uint32_t setColor = LED_DEFAULT_COLOR);
|
|
||||||
#ifdef FEATURE_ENABLE_OLED
|
#ifdef FEATURE_ENABLE_OLED
|
||||||
U8X8_SSD1306_128X64_NONAME_HW_I2C u8x8(-1);
|
U8X8_SSD1306_128X64_NONAME_HW_I2C u8x8(-1);
|
||||||
void Display_Process();
|
void Display_Process();
|
||||||
#endif
|
#endif
|
||||||
void Button_Process();
|
|
||||||
void toggleWiFiAP(bool shutdown = false);
|
void toggleWiFiAP(bool shutdown = false);
|
||||||
void SystemShutdown(bool restart = false);
|
void SystemShutdown(bool restart = false);
|
||||||
uint32_t Process_Impulse_WheelSpeed();
|
uint32_t Process_Impulse_WheelSpeed();
|
||||||
@ -134,7 +136,7 @@ void setup()
|
|||||||
Serial.print("\nEE-Init done");
|
Serial.print("\nEE-Init done");
|
||||||
|
|
||||||
// Initialize LEDs
|
// Initialize LEDs
|
||||||
leds.begin();
|
LEDControl_Init(GPIO_LED);
|
||||||
Serial.print("\nLED-Init done");
|
Serial.print("\nLED-Init done");
|
||||||
|
|
||||||
// Initialize based on the chosen speed source (CAN, GPS, Impulse)
|
// Initialize based on the chosen speed source (CAN, GPS, Impulse)
|
||||||
@ -175,6 +177,8 @@ void setup()
|
|||||||
pinMode(GPIO_BUTTON, INPUT_PULLUP);
|
pinMode(GPIO_BUTTON, INPUT_PULLUP);
|
||||||
pinMode(GPIO_PUMP, OUTPUT);
|
pinMode(GPIO_PUMP, OUTPUT);
|
||||||
|
|
||||||
|
ButtonControl_Init(GPIO_BUTTON, buttonActions, buttonActionCount);
|
||||||
|
|
||||||
// Set up OTA updates
|
// Set up OTA updates
|
||||||
ArduinoOTA.setPort(8266);
|
ArduinoOTA.setPort(8266);
|
||||||
ArduinoOTA.setHostname(globals.DeviceName);
|
ArduinoOTA.setHostname(globals.DeviceName);
|
||||||
@ -249,8 +253,8 @@ void loop()
|
|||||||
|
|
||||||
// Process button input, manage LED behavior, perform EEPROM tasks, handle webserver operations,
|
// Process button input, manage LED behavior, perform EEPROM tasks, handle webserver operations,
|
||||||
// process Diagnostic Trouble Codes (DTC), and manage debugging
|
// process Diagnostic Trouble Codes (DTC), and manage debugging
|
||||||
Button_Process();
|
ButtonControl_Update();
|
||||||
LED_Process();
|
LEDControl_Update();
|
||||||
EEPROM_Process();
|
EEPROM_Process();
|
||||||
Webserver_Process();
|
Webserver_Process();
|
||||||
DTC_Process();
|
DTC_Process();
|
||||||
@ -340,208 +344,6 @@ void trigger_ISR()
|
|||||||
wheel_pulse++;
|
wheel_pulse++;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
|
||||||
* @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.
|
|
||||||
*/
|
|
||||||
void LED_Process(uint8_t override, uint32_t SetColor)
|
|
||||||
{
|
|
||||||
// Enumeration to represent LED status
|
|
||||||
typedef enum
|
|
||||||
{
|
|
||||||
LED_Startup,
|
|
||||||
LED_Normal,
|
|
||||||
LED_Confirm_Normal,
|
|
||||||
LED_Rain,
|
|
||||||
LED_Confirm_Rain,
|
|
||||||
LED_Purge,
|
|
||||||
LED_Error,
|
|
||||||
LED_Shutdown,
|
|
||||||
LED_Override
|
|
||||||
} 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;
|
|
||||||
static uint32_t LED_override_color = 0;
|
|
||||||
static tLED_Status LED_ResumeOverrideStatus = LED_Startup;
|
|
||||||
|
|
||||||
// Variables for managing LED animation timing
|
|
||||||
uint8_t color = 0;
|
|
||||||
uint32_t timer = 0;
|
|
||||||
uint32_t animtimer = 0;
|
|
||||||
static uint32_t timestamp = 0;
|
|
||||||
timer = millis();
|
|
||||||
|
|
||||||
// Handle LED overrides
|
|
||||||
if (override == 1)
|
|
||||||
{
|
|
||||||
if (LED_Status != LED_Override)
|
|
||||||
{
|
|
||||||
LED_ResumeOverrideStatus = LED_Status;
|
|
||||||
Debug_pushMessage("Override LED_Status\n");
|
|
||||||
}
|
|
||||||
LED_Status = LED_Override;
|
|
||||||
LED_override_color = SetColor;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (override == 2)
|
|
||||||
{
|
|
||||||
if (LED_Status == LED_Override)
|
|
||||||
{
|
|
||||||
LED_Status = LED_ResumeOverrideStatus;
|
|
||||||
Debug_pushMessage("Resume LED_Status\n");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Update LED status when system status changes
|
|
||||||
if (oldSysStatus != globals.systemStatus)
|
|
||||||
{
|
|
||||||
switch (globals.systemStatus)
|
|
||||||
{
|
|
||||||
case sysStat_Startup:
|
|
||||||
LED_Status = LED_Startup;
|
|
||||||
Debug_pushMessage("sysStat: Startup\n");
|
|
||||||
break;
|
|
||||||
case sysStat_Normal:
|
|
||||||
timestamp = timer + 3500;
|
|
||||||
LED_Status = LED_Confirm_Normal;
|
|
||||||
Debug_pushMessage("sysStat: Normal\n");
|
|
||||||
break;
|
|
||||||
case sysStat_Rain:
|
|
||||||
timestamp = timer + 3500;
|
|
||||||
LED_Status = LED_Confirm_Rain;
|
|
||||||
Debug_pushMessage("sysStat: Rain\n");
|
|
||||||
break;
|
|
||||||
case sysStat_Purge:
|
|
||||||
LED_Status = LED_Purge;
|
|
||||||
Debug_pushMessage("sysStat: Purge\n");
|
|
||||||
break;
|
|
||||||
case sysStat_Error:
|
|
||||||
LED_Status = LED_Error;
|
|
||||||
Debug_pushMessage("sysStat: Error\n");
|
|
||||||
break;
|
|
||||||
case sysStat_Shutdown:
|
|
||||||
LED_Status = LED_Shutdown;
|
|
||||||
Debug_pushMessage("sysStat: Shutdown\n");
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
oldSysStatus = globals.systemStatus;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Handle different LED statuses
|
|
||||||
switch (LED_Status)
|
|
||||||
{
|
|
||||||
case LED_Startup:
|
|
||||||
leds.setBrightness(LubeConfig.LED_Max_Brightness);
|
|
||||||
|
|
||||||
if (globals.TankPercentage < LubeConfig.TankRemindAtPercentage)
|
|
||||||
leds.setPixelColor(0, LED_STARTUP_TANKWARN);
|
|
||||||
else
|
|
||||||
leds.setPixelColor(0, LED_STARTUP_NORMAL);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case LED_Confirm_Normal:
|
|
||||||
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;
|
|
||||||
Debug_pushMessage("LED_Status: Confirm -> Normal\n");
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case LED_Normal:
|
|
||||||
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);
|
|
||||||
|
|
||||||
break;
|
|
||||||
|
|
||||||
case LED_Confirm_Rain:
|
|
||||||
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;
|
|
||||||
Debug_pushMessage("LED_Status: Confirm -> Rain\n");
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case LED_Rain:
|
|
||||||
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);
|
|
||||||
|
|
||||||
break;
|
|
||||||
|
|
||||||
case LED_Purge:
|
|
||||||
timer = timer % 500;
|
|
||||||
color = map(timer / 2, 0, 250, LubeConfig.LED_Min_Brightness, LubeConfig.LED_Max_Brightness);
|
|
||||||
leds.setPixelColor(0, LED_PURGE_COLOR);
|
|
||||||
if (timer < 250)
|
|
||||||
leds.setBrightness(color);
|
|
||||||
else
|
|
||||||
leds.setBrightness(LubeConfig.LED_Max_Brightness - color);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case LED_Error:
|
|
||||||
leds.setBrightness(LubeConfig.LED_Max_Brightness);
|
|
||||||
leds.setPixelColor(0, timer % 500 > 250 ? LED_ERROR_BLINK : 0);
|
|
||||||
break;
|
|
||||||
|
|
||||||
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;
|
|
||||||
|
|
||||||
case LED_Override:
|
|
||||||
leds.setBrightness(LubeConfig.LED_Max_Brightness);
|
|
||||||
leds.setPixelColor(0, LED_override_color);
|
|
||||||
break;
|
|
||||||
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
leds.show();
|
|
||||||
}
|
|
||||||
|
|
||||||
#ifdef FEATURE_ENABLE_OLED
|
#ifdef FEATURE_ENABLE_OLED
|
||||||
/**
|
/**
|
||||||
@ -597,119 +399,6 @@ void Display_Process()
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
|
||||||
* @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.
|
|
||||||
*/
|
|
||||||
void Button_Process()
|
|
||||||
{
|
|
||||||
// Time delays for different button actions
|
|
||||||
#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
|
|
||||||
typedef enum buttonAction_e
|
|
||||||
{
|
|
||||||
BTN_INACTIVE,
|
|
||||||
BTN_NOTHING,
|
|
||||||
BTN_TOGGLEMODE,
|
|
||||||
BTN_TOGGLEWIFI,
|
|
||||||
BTN_STARTPURGE
|
|
||||||
} buttonAction_t;
|
|
||||||
|
|
||||||
// Static variables to track button state and timing
|
|
||||||
static uint32_t buttonTimestamp = 0;
|
|
||||||
static buttonAction_t buttonAction = BTN_INACTIVE;
|
|
||||||
|
|
||||||
// Check if button is pressed (LOW)
|
|
||||||
if (digitalRead(GPIO_BUTTON) == LOW)
|
|
||||||
{
|
|
||||||
// Update button timestamp on the first button press
|
|
||||||
if (buttonTimestamp == 0)
|
|
||||||
buttonTimestamp = millis();
|
|
||||||
|
|
||||||
// Check and execute actions based on predefined time delays
|
|
||||||
if (buttonTimestamp + BUTTON_ACTION_DELAY_NOTHING < millis())
|
|
||||||
{
|
|
||||||
LED_Process(1, COLOR_WARM_WHITE);
|
|
||||||
buttonAction = BTN_NOTHING;
|
|
||||||
}
|
|
||||||
else if (buttonTimestamp + BUTTON_ACTION_DELAY_WIFI < millis())
|
|
||||||
{
|
|
||||||
LED_Process(1, LED_WIFI_BLINK);
|
|
||||||
buttonAction = BTN_TOGGLEWIFI;
|
|
||||||
}
|
|
||||||
else if (buttonTimestamp + BUTTON_ACTION_DELAY_PURGE < millis())
|
|
||||||
{
|
|
||||||
LED_Process(1, LED_PURGE_COLOR);
|
|
||||||
buttonAction = BTN_STARTPURGE;
|
|
||||||
}
|
|
||||||
else if (buttonTimestamp + BUTTON_ACTION_DELAY_TOGGLEMODE < millis())
|
|
||||||
{
|
|
||||||
uint32_t color = globals.systemStatus == sysStat_Normal ? LED_RAIN_COLOR : LED_NORMAL_COLOR;
|
|
||||||
LED_Process(1, color);
|
|
||||||
buttonAction = BTN_TOGGLEMODE;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
else // Button is released
|
|
||||||
{
|
|
||||||
// Execute corresponding actions based on the detected button action
|
|
||||||
if (buttonAction != BTN_INACTIVE)
|
|
||||||
{
|
|
||||||
switch (buttonAction)
|
|
||||||
{
|
|
||||||
case BTN_TOGGLEWIFI:
|
|
||||||
toggleWiFiAP();
|
|
||||||
Debug_pushMessage("Starting WiFi AP\n");
|
|
||||||
break;
|
|
||||||
|
|
||||||
case BTN_STARTPURGE:
|
|
||||||
globals.systemStatus = sysStat_Purge;
|
|
||||||
globals.purgePulses = LubeConfig.BleedingPulses;
|
|
||||||
Debug_pushMessage("Starting Purge\n");
|
|
||||||
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;
|
|
||||||
}
|
|
||||||
Debug_pushMessage("Toggling Mode\n");
|
|
||||||
break;
|
|
||||||
|
|
||||||
case BTN_NOTHING:
|
|
||||||
default:
|
|
||||||
Debug_pushMessage("Nothing or invalid\n");
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Display feedback through LEDs
|
|
||||||
LED_Process(2);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Reset button state and timestamp
|
|
||||||
buttonAction = BTN_INACTIVE;
|
|
||||||
buttonTimestamp = 0;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Toggles the WiFi functionality based on the current status.
|
* @brief Toggles the WiFi functionality based on the current status.
|
||||||
*
|
*
|
||||||
@ -788,6 +477,36 @@ void SystemShutdown(bool restart)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void onToggleMode()
|
||||||
|
{
|
||||||
|
if (globals.systemStatus == sysStat_Normal)
|
||||||
|
{
|
||||||
|
globals.systemStatus = sysStat_Rain;
|
||||||
|
globals.resumeStatus = sysStat_Rain;
|
||||||
|
}
|
||||||
|
else if (globals.systemStatus == sysStat_Rain)
|
||||||
|
{
|
||||||
|
globals.systemStatus = sysStat_Normal;
|
||||||
|
globals.resumeStatus = sysStat_Normal;
|
||||||
|
}
|
||||||
|
Debug_pushMessage("Toggling Mode\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
void onStartPurge()
|
||||||
|
{
|
||||||
|
globals.systemStatus = sysStat_Purge;
|
||||||
|
globals.purgePulses = LubeConfig.BleedingPulses;
|
||||||
|
Debug_pushMessage("Starting Purge\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void onWashMode()
|
||||||
|
{
|
||||||
|
Debug_pushMessage("Wash mode start\n");
|
||||||
|
// Hier könntest du später gezieltes Nachölen implementieren
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Processes the impulses from the wheel speed sensor and converts them into traveled distance.
|
* @brief Processes the impulses from the wheel speed sensor and converts them into traveled distance.
|
||||||
*
|
*
|
||||||
|
Loading…
x
Reference in New Issue
Block a user