Compare commits
36 Commits
Firmware_1
...
aa3a2106aa
Author | SHA1 | Date | |
---|---|---|---|
aa3a2106aa | |||
f8a195bd4b | |||
b20481140c | |||
b37c0a05be | |||
2138f640ee | |||
d593e40f38 | |||
3bb9bf694e | |||
f320fb1ca6 | |||
b775738e20 | |||
c42de4b24c | |||
ce9f1a2306 | |||
e1770527ab | |||
aff1d40297 | |||
caff1c185f | |||
bea78c0020 | |||
744f8c431c | |||
e9567602d3 | |||
0469b183f2 | |||
e3392d92c4 | |||
6a6227ed85 | |||
c8f5cda4ba | |||
0bc7d0862b | |||
c593b8a546 | |||
6221262dbf | |||
83e288fdcf | |||
9c4c4a14b4 | |||
49b3598275 | |||
8fdd09f32f | |||
f87d2aaeca | |||
34c50df2e9 | |||
cb3d49ad13 | |||
f02a53e161 | |||
50208e4a1a | |||
a563182f3e | |||
335b883043 | |||
fb366b4976 |
BIN
Documentation/Anschluss Schemata PCB Rev_1.2.jpg
Normal file
BIN
Documentation/Anschluss Schemata PCB Rev_1.2.jpg
Normal file
Binary file not shown.
After Width: | Height: | Size: 79 KiB |
BIN
Documentation/Anschluss Schemata PCB Rev_1.3.jpg
Normal file
BIN
Documentation/Anschluss Schemata PCB Rev_1.3.jpg
Normal file
Binary file not shown.
After Width: | Height: | Size: 101 KiB |
BIN
Documentation/PCB_rev_1.2 Connections.png
Normal file
BIN
Documentation/PCB_rev_1.2 Connections.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 69 KiB |
BIN
Documentation/PCB_rev_1.3 Connections.png
Normal file
BIN
Documentation/PCB_rev_1.3 Connections.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 65 KiB |
127
Software/build_dtcs.py
Normal file
127
Software/build_dtcs.py
Normal file
@@ -0,0 +1,127 @@
|
|||||||
|
Import("env") # pylint: disable=undefined-variable
|
||||||
|
env.Execute("\"$PYTHONEXE\" -m pip install jinja2")
|
||||||
|
|
||||||
|
import os
|
||||||
|
import time
|
||||||
|
from jinja2 import Environment, FileSystemLoader
|
||||||
|
import json
|
||||||
|
|
||||||
|
# Pfad zur Eingabedatei und Ausgabedatei
|
||||||
|
input_file = "src/dtc_defs.txt"
|
||||||
|
output_file = "include/dtc_defs.h"
|
||||||
|
json_output_file = "data_src/static/dtc_table.json"
|
||||||
|
|
||||||
|
# Überprüfen, ob das Verzeichnis existiert, andernfalls erstellen
|
||||||
|
json_output_dir = os.path.dirname(json_output_file)
|
||||||
|
if not os.path.exists(json_output_dir):
|
||||||
|
os.makedirs(json_output_dir)
|
||||||
|
|
||||||
|
# Mehrdimensionales Array zum Speichern der Zeilen aus der Eingabedatei
|
||||||
|
dtc_lines = []
|
||||||
|
|
||||||
|
# Lesen und analysieren der Eingabedatei
|
||||||
|
with open(input_file, "r", encoding="utf-8") as f:
|
||||||
|
for line in f:
|
||||||
|
line = line.strip()
|
||||||
|
if not line or line.startswith("#"):
|
||||||
|
continue
|
||||||
|
|
||||||
|
parts = line.split(";")
|
||||||
|
if len(parts) == 5:
|
||||||
|
num, dtc_name, dtc_severity, title, description = [part.strip() for part in parts]
|
||||||
|
dtc_lines.append([int(num), dtc_name, dtc_severity, title, description])
|
||||||
|
|
||||||
|
# Überprüfen auf Duplikate in den DTC-Nummern und DTC-Namen
|
||||||
|
num_set = set()
|
||||||
|
dtc_name_set = set()
|
||||||
|
duplicates = []
|
||||||
|
|
||||||
|
for line in dtc_lines:
|
||||||
|
num, dtc_name, _, _, _ = line
|
||||||
|
if num in num_set:
|
||||||
|
duplicates.append(f"DTC-Nummer {num} ist ein Duplikat.")
|
||||||
|
else:
|
||||||
|
num_set.add(num)
|
||||||
|
|
||||||
|
if dtc_name in dtc_name_set:
|
||||||
|
duplicates.append(f"DTC-Name '{dtc_name}' ist ein Duplikat.")
|
||||||
|
else:
|
||||||
|
dtc_name_set.add(dtc_name)
|
||||||
|
|
||||||
|
if duplicates:
|
||||||
|
for duplicate in duplicates:
|
||||||
|
print(f"Fehler: {duplicate}")
|
||||||
|
raise ValueError("Duplicate DTC Data detected")
|
||||||
|
|
||||||
|
# Suchen nach DTC_NO_DTC und DTC_LAST_DTC
|
||||||
|
dtc_no_dtc_added = False
|
||||||
|
dtc_last_dtc_line = None
|
||||||
|
|
||||||
|
for line in dtc_lines:
|
||||||
|
_, dtc_name, _, _, _ = line
|
||||||
|
if dtc_name == "DTC_NO_DTC":
|
||||||
|
dtc_no_dtc_added = True
|
||||||
|
elif dtc_name == "DTC_LAST_DTC":
|
||||||
|
dtc_last_dtc_line = line
|
||||||
|
|
||||||
|
# Einen DTC für DTC_NO_DTC hinzufügen (wenn nicht vorhanden)
|
||||||
|
if not dtc_no_dtc_added:
|
||||||
|
dtc_lines.insert(0, [0, "DTC_NO_DTC", "DTC_NONE", "No Error", "No Error"])
|
||||||
|
|
||||||
|
# Falls DTC_LAST_DTC existiert, lösche es
|
||||||
|
if dtc_last_dtc_line:
|
||||||
|
dtc_lines.remove(dtc_last_dtc_line)
|
||||||
|
|
||||||
|
# Einen DTC für DTC_LAST_DTC hinzufügen (mit der höchsten Nummer)
|
||||||
|
if dtc_lines:
|
||||||
|
highest_num = max([line[0] for line in dtc_lines])
|
||||||
|
else:
|
||||||
|
highest_num = 0
|
||||||
|
|
||||||
|
dtc_lines.append([highest_num + 1, "DTC_LAST_DTC", "DTC_NONE", "Last Error", "Last Error"])
|
||||||
|
|
||||||
|
# Sortieren der Zeilen nach der Nummer aufsteigend
|
||||||
|
dtc_lines.sort(key=lambda x: x[0])
|
||||||
|
|
||||||
|
# DTC_NAME_CONSTANT-Makros initialisieren
|
||||||
|
dtc_macros = []
|
||||||
|
dtc_structs = []
|
||||||
|
dtc_table_data = []
|
||||||
|
|
||||||
|
# Verarbeiten der sortierten Zeilen
|
||||||
|
for i, line in enumerate(dtc_lines):
|
||||||
|
num, dtc_name, dtc_severity, title, description = line
|
||||||
|
dtc_macros.append(f"#define {dtc_name:<30} {num}")
|
||||||
|
comma = "," if i < len(dtc_lines) - 1 else " "
|
||||||
|
dtc_structs.append(f" {{ {dtc_name:<30}, {dtc_severity:<12} }}{comma} // {description}")
|
||||||
|
dtc_table_data.append({"num": num, "title": title, "description": description})
|
||||||
|
|
||||||
|
# Unix-Zeitstempel hinzufügen
|
||||||
|
timestamp = int(time.time())
|
||||||
|
|
||||||
|
env = Environment(loader=FileSystemLoader('include', encoding='utf-8'))
|
||||||
|
# Lade das Jinja2-Template aus der Datei
|
||||||
|
template = env.get_template('dtc_defs.h.j2')
|
||||||
|
|
||||||
|
# Erstelle ein Context-Dictionary mit den erforderlichen Daten
|
||||||
|
context = {
|
||||||
|
'timestamp_unix': timestamp,
|
||||||
|
'timestamp' : time.strftime('%Y-%m-%d %H:%M:%S', time.localtime(timestamp)),
|
||||||
|
'dtc_macros': dtc_macros, # Übergebe die dtc_macros-Liste direkt
|
||||||
|
'dtc_structs': dtc_structs, # Übergebe die dtc_structs-Liste direkt
|
||||||
|
}
|
||||||
|
|
||||||
|
# Rendere das Template mit den Werten und erhalte den Header-Text
|
||||||
|
header_text = template.render(context)
|
||||||
|
|
||||||
|
# Schreibe den generierten Header-Text in die Header-Datei
|
||||||
|
with open(output_file, "w", encoding='utf-8') as f:
|
||||||
|
f.write(header_text)
|
||||||
|
|
||||||
|
print(f"Header-Datei wurde erstellt: {output_file}")
|
||||||
|
|
||||||
|
# JSON-Datei mit UTF-8-Zeichencodierung erstellen
|
||||||
|
with open(json_output_file, 'w', encoding='utf-8') as json_f:
|
||||||
|
json.dump(dtc_table_data, json_f, ensure_ascii=False, indent=4, separators=(',', ': '))
|
||||||
|
|
||||||
|
print(f"JSON-Datei wurde erstellt: {json_output_file}")
|
@@ -11,6 +11,7 @@
|
|||||||
<script src="static/js/jquery.min.js"></script>
|
<script src="static/js/jquery.min.js"></script>
|
||||||
<script src="static/js/bootstrap.min.js"></script>
|
<script src="static/js/bootstrap.min.js"></script>
|
||||||
<script src="static/js/websocket.js"></script>
|
<script src="static/js/websocket.js"></script>
|
||||||
|
<script src="static/js/dtc_table.js"></script>
|
||||||
<link rel="apple-touch-icon" sizes="180x180" href="static/img/apple-touch-icon.png">
|
<link rel="apple-touch-icon" sizes="180x180" href="static/img/apple-touch-icon.png">
|
||||||
<link rel="icon" type="image/png" sizes="32x32" href="static/img/favicon-32x32.png">
|
<link rel="icon" type="image/png" sizes="32x32" href="static/img/favicon-32x32.png">
|
||||||
<link rel="icon" type="image/png" sizes="16x16" href="static/img/favicon-16x16.png">
|
<link rel="icon" type="image/png" sizes="16x16" href="static/img/favicon-16x16.png">
|
||||||
@@ -33,9 +34,8 @@
|
|||||||
<ul class="navbar-nav nav mr-auto mt-2 mt-lg-0">
|
<ul class="navbar-nav nav mr-auto mt-2 mt-lg-0">
|
||||||
|
|
||||||
<li class="nav-item"><a class="nav-link active" role="tab" data-toggle="tab" href="#tab_home">Home</a></li>
|
<li class="nav-item"><a class="nav-link active" role="tab" data-toggle="tab" href="#tab_home">Home</a></li>
|
||||||
<li class="nav-item"><a class="nav-link" role="tab" data-toggle="tab" href="#tab_source">Wegstrecke</a></li>
|
|
||||||
<li class="nav-item"><a class="nav-link" role="tab" data-toggle="tab" href="#tab_lube">Schmierung</a></li>
|
|
||||||
<li class="nav-item"><a class="nav-link" role="tab" data-toggle="tab" href="#tab_maintenance">Wartung</a></li>
|
<li class="nav-item"><a class="nav-link" role="tab" data-toggle="tab" href="#tab_maintenance">Wartung</a></li>
|
||||||
|
<li class="nav-item"><a class="nav-link" role="tab" data-toggle="tab" href="#tab_source">Einstellungen</a></li>
|
||||||
<li class="nav-item"><a class="nav-link" role="tab" data-toggle="tab" href="#tab_sysinfo">Systeminfo</a></li>
|
<li class="nav-item"><a class="nav-link" role="tab" data-toggle="tab" href="#tab_sysinfo">Systeminfo</a></li>
|
||||||
<li class="nav-item"><a class="nav-link" role="tab" data-toggle="tab" href="#tab_fwupdate">Update</a></li>
|
<li class="nav-item"><a class="nav-link" role="tab" data-toggle="tab" href="#tab_fwupdate">Update</a></li>
|
||||||
|
|
||||||
@@ -55,6 +55,7 @@
|
|||||||
<h3 class="pt-3">KTM CAN Chain Lube</h3>
|
<h3 class="pt-3">KTM CAN Chain Lube</h3>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
<!-- Div Group Tank remain -->
|
||||||
<hr />
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
<h4>Tankinhalt verbleibend</h4>
|
<h4>Tankinhalt verbleibend</h4>
|
||||||
@@ -65,13 +66,17 @@
|
|||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</p>
|
</p>
|
||||||
|
<!-- Div Group Tank remain -->
|
||||||
|
<!-- Div Group current Mode -->
|
||||||
<hr />
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
<h4>aktueller Modus</h4>
|
<h4>aktueller Modus</h4>
|
||||||
<input class="form-control" type="text" placeholder="%SYSTEM_STATUS%" readonly>
|
<input class="form-control" type="text" placeholder="%SYSTEM_STATUS%" readonly>
|
||||||
</p>
|
</p>
|
||||||
<hr />
|
<!-- Div Group current Mode -->
|
||||||
|
<!-- Div Group DTC Table -->
|
||||||
<div %SHOW_DTC_TABLE%>
|
<div %SHOW_DTC_TABLE%>
|
||||||
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
<h4>Fehlercodes</h4>
|
<h4>Fehlercodes</h4>
|
||||||
<table class="table">
|
<table class="table">
|
||||||
@@ -86,13 +91,152 @@
|
|||||||
</tbody>
|
</tbody>
|
||||||
</table>
|
</table>
|
||||||
</p>
|
</p>
|
||||||
<hr />
|
|
||||||
</div>
|
</div>
|
||||||
|
<!-- Div Group DTC Table -->
|
||||||
</div>
|
</div>
|
||||||
<!-- Div Tab Home-->
|
<!-- Div Tab Home-->
|
||||||
<!-- Div Tab Source Settings-->
|
|
||||||
|
<!-- Div Tab Maintenance -->
|
||||||
|
<div id="tab_maintenance" class="tab-pane fade" role="tabpanel">
|
||||||
|
<h3>Wartung</h3>
|
||||||
|
<!-- Div Group Tank remain -->
|
||||||
|
<hr />
|
||||||
|
<p>
|
||||||
|
<h4>Ölvorrat</h4>
|
||||||
|
<form action="post.htm" method="POST" class="form-horizontal">
|
||||||
|
<div class="form-group row">
|
||||||
|
<label for="tankremain_maint" class="control-label col-4">Tankinhalt verbleibend</label>
|
||||||
|
<div class="col-8">
|
||||||
|
<div class="progress">
|
||||||
|
<div id="tankremain_maint" class="progress-bar text-light" role="progressbar"
|
||||||
|
aria-valuenow="%TANK_REMAIN_CAPACITY%" aria-valuemin="0" aria-valuemax="100"
|
||||||
|
style="width: %TANK_REMAIN_CAPACITY%%">
|
||||||
|
%TANK_REMAIN_CAPACITY%%
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="form-group row">
|
||||||
|
<div class="col text-center">
|
||||||
|
<button name="resettank" type="submit" class="btn btn-outline-primary ml-2">Tank zurücksetzen</button>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</form>
|
||||||
|
</p>
|
||||||
|
<!-- Div Group Tank remain -->
|
||||||
|
<!-- Div Group Purging -->
|
||||||
|
<hr />
|
||||||
|
<p>
|
||||||
|
<h4>Entlüftung</h4>
|
||||||
|
<form action="post.htm" method="POST" class="form-horizontal">
|
||||||
|
<div class="form-group row">
|
||||||
|
<label for="purgepulse" class="control-label col-4">Entlüftung Dosierung</label>
|
||||||
|
<div class="col-8">
|
||||||
|
<div class="input-group">
|
||||||
|
<input id="purgepulse" name="purgepulse" value="%BLEEDING_PULSES%" type="text" class="form-control">
|
||||||
|
<div class="input-group-append">
|
||||||
|
<span class="input-group-text">Pulse</span>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="form-group row">
|
||||||
|
<div class="col text-center">
|
||||||
|
<button name="maintsave" type="submit" class="btn btn-outline-primary">Speichern</button>
|
||||||
|
<button name="purgenow" type="submit" class="btn btn-outline-primary ml-2">Entlüftung starten</button>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</form>
|
||||||
|
</p>
|
||||||
|
<!-- Div Group Purging -->
|
||||||
|
<!-- Div Group Measure -->
|
||||||
|
<div %SHOW_IMPULSE_SETTINGS%>
|
||||||
|
<hr />
|
||||||
|
<p>
|
||||||
|
<h4>Einmessen</h4>
|
||||||
|
<form action="post.htm" method="POST" class="form-horizontal">
|
||||||
|
<div class="form-group row">
|
||||||
|
<label for="measuredpulses" class="control-label col-4">erfasste Pulse</label>
|
||||||
|
<div class="col-8">
|
||||||
|
<div class="input-group">
|
||||||
|
<input id="measuredpulses" name="measuredpulses" value="%MEASURED_PULSES%" type="text" readonly
|
||||||
|
class="form-control">
|
||||||
|
<div class="input-group-append">
|
||||||
|
<span class="input-group-text">Pulse</span>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="form-group row">
|
||||||
|
<div class="col text-center">
|
||||||
|
<button name="measurestartstop" type="submit" class="btn btn-outline-primary">%MEASURE_BTN%</button>
|
||||||
|
<button name="measurereset" type="submit" class="btn btn-outline-primary ml-2">Reset</button>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</form>
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<!-- Div Group Purging -->
|
||||||
|
<!-- Div Group EEPROM formatting -->
|
||||||
|
<hr />
|
||||||
|
<p>
|
||||||
|
<h4>EEPROM formatieren</h4>
|
||||||
|
<div class="alert alert-primary alert-dismissable show fade" role="alert">
|
||||||
|
<button type="button" class="close" data-dismiss="alert" aria-label="Close">
|
||||||
|
<span aria-hidden="true">×</span>
|
||||||
|
</button>
|
||||||
|
<strong>Achtung!</strong><br>
|
||||||
|
Das Formatieren der EEPROM-Bereiche sollte nur ausgeführt werden wenn es unbedingt erforderlich ist!
|
||||||
|
Hierdurch werden alle Einstellungen zurück gesetzt bzw. alle Betriebsdaten gehen verloren.
|
||||||
|
Folgende Situationen erfordern unter anderem eine Formatierung:
|
||||||
|
- Erstinitialisierung (bei neu aufgebautem Gerät)
|
||||||
|
- Firmware-Update (nur wenn es die Release-Notes fordern)
|
||||||
|
</div>
|
||||||
|
<form action="post.htm" method="POST" class="form-horizontal">
|
||||||
|
<div class="form-group row">
|
||||||
|
<div class="offset-4 col-8">
|
||||||
|
<div class="form-check">
|
||||||
|
<input class="form-check-input" type="checkbox" name="reset_ee_cfg" id="reset_ee_cfg">
|
||||||
|
<label class="form-check-label" for="reset_ee_cfg">
|
||||||
|
Bereich "CFG"
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
<div class="form-check">
|
||||||
|
<input class="form-check-input" type="checkbox" name="reset_ee_pds" id="reset_ee_pds">
|
||||||
|
<label class="form-check-label" for="reset_ee_pds">
|
||||||
|
Bereich "PDS"
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="form-group row">
|
||||||
|
<div class="col text-center">
|
||||||
|
<button name="reset_ee_btn" type="submit" class="btn btn-outline-primary">EEPROM formatieren</button>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</form>
|
||||||
|
</p>
|
||||||
|
<!-- Div Group EEPROM formatting -->
|
||||||
|
<!-- Div Group Device Reboot -->
|
||||||
|
<hr />
|
||||||
|
<p>
|
||||||
|
<h4>Gerät neustarten</h4>
|
||||||
|
<form action="post.htm" method="POST" class="form-horizontal">
|
||||||
|
<div class="form-group row">
|
||||||
|
<div class="col text-center">
|
||||||
|
<button name="reboot" type="submit" class="btn btn-outline-primary">Reboot</button>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</form>
|
||||||
|
</p>
|
||||||
|
<!-- Div Group Device Reboot -->
|
||||||
|
</div>
|
||||||
|
<!-- Div Tab Maintenance -->
|
||||||
|
|
||||||
|
<!-- Div Tab Settings-->
|
||||||
<div id="tab_source" class="tab-pane fade" role="tabpanel">
|
<div id="tab_source" class="tab-pane fade" role="tabpanel">
|
||||||
<h3>Wegstreckenerfassung</h3>
|
<h3>Einstellungen</h3>
|
||||||
|
<!-- Div Group Signal Source -->
|
||||||
<hr />
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
<h4>Signalquelle</h4>
|
<h4>Signalquelle</h4>
|
||||||
@@ -120,7 +264,8 @@
|
|||||||
</div>
|
</div>
|
||||||
</form>
|
</form>
|
||||||
</p>
|
</p>
|
||||||
<!-- Div Source:Impulse Settings-->
|
<!-- Div Group Signal Source -->
|
||||||
|
<!-- Div Group Source:Impulse Settings-->
|
||||||
<div %SHOW_IMPULSE_SETTINGS%>
|
<div %SHOW_IMPULSE_SETTINGS%>
|
||||||
<hr />
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
@@ -181,10 +326,9 @@
|
|||||||
</div>
|
</div>
|
||||||
</form>
|
</form>
|
||||||
</p>
|
</p>
|
||||||
<hr />
|
|
||||||
</div>
|
</div>
|
||||||
<!-- Div Source:Impulse Settings-->
|
<!-- Div Group Source:Impulse Settings-->
|
||||||
<!-- Div Source:CAN Settings-->
|
<!-- Div Group Source:CAN Settings-->
|
||||||
<div %SHOW_CAN_SETTINGS%>
|
<div %SHOW_CAN_SETTINGS%>
|
||||||
<hr />
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
@@ -205,10 +349,9 @@
|
|||||||
</div>
|
</div>
|
||||||
</form>
|
</form>
|
||||||
</p>
|
</p>
|
||||||
<hr />
|
|
||||||
</div>
|
</div>
|
||||||
<!-- Div Source:CAN Settings-->
|
<!-- Div Group Source:CAN Settings-->
|
||||||
<!-- Div Source:GPS Settings-->
|
<!-- Div Group Source:GPS Settings-->
|
||||||
<div %SHOW_GPS_SETTINGS%>
|
<div %SHOW_GPS_SETTINGS%>
|
||||||
<hr />
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
@@ -229,14 +372,9 @@
|
|||||||
</div>
|
</div>
|
||||||
</form>
|
</form>
|
||||||
</p>
|
</p>
|
||||||
<hr />
|
|
||||||
</div>
|
</div>
|
||||||
<!-- Div Source:GPS Settings-->
|
<!-- Div Group Source:GPS Settings-->
|
||||||
</div>
|
<!-- Div Group Lube Settings-->
|
||||||
<!-- Div Tab Source Settings-->
|
|
||||||
<!-- Div Tab Lube -->
|
|
||||||
<div id="tab_lube" class="tab-pane fade" role="tabpanel">
|
|
||||||
<h3>Schmierung</h3>
|
|
||||||
<hr />
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
<h4>Dosierung</h4>
|
<h4>Dosierung</h4>
|
||||||
@@ -272,15 +410,11 @@
|
|||||||
</div>
|
</div>
|
||||||
</form>
|
</form>
|
||||||
</p>
|
</p>
|
||||||
<hr />
|
<!-- Div Group Lube Settings-->
|
||||||
</div>
|
<!-- Div Group Oiltank Settings -->
|
||||||
<!-- Div Tab Lube -->
|
|
||||||
<!-- Div Tab Maintenance -->
|
|
||||||
<div id="tab_maintenance" class="tab-pane fade" role="tabpanel">
|
|
||||||
<h3>Wartung</h3>
|
|
||||||
<hr />
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
<h4>Ölvorrat</h4>
|
<h4>Öltank</h4>
|
||||||
<form action="post.htm" method="POST" class="form-horizontal">
|
<form action="post.htm" method="POST" class="form-horizontal">
|
||||||
<div class="form-group row">
|
<div class="form-group row">
|
||||||
<label for="tankcap" class="control-label col-4">Tankkapazität</label>
|
<label for="tankcap" class="control-label col-4">Tankkapazität</label>
|
||||||
@@ -318,104 +452,80 @@
|
|||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="form-group row">
|
|
||||||
<label for="tankremain_maint" class="control-label col-4">Tankinhalt verbleibend</label>
|
|
||||||
<div class="col-8">
|
|
||||||
<div class="progress">
|
|
||||||
<div id="tankremain_maint" class="progress-bar text-light" role="progressbar"
|
|
||||||
aria-valuenow="%TANK_REMAIN_CAPACITY%" aria-valuemin="0" aria-valuemax="100"
|
|
||||||
style="width: %TANK_REMAIN_CAPACITY%%">
|
|
||||||
%TANK_REMAIN_CAPACITY%%
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div class="form-group row">
|
<div class="form-group row">
|
||||||
<div class="col text-center">
|
<div class="col text-center">
|
||||||
<button name="oilsave" type="submit" class="btn btn-outline-primary">Speichern</button>
|
<button name="oilsave" type="submit" class="btn btn-outline-primary">Speichern</button>
|
||||||
<button name="resettank" type="submit" class="btn btn-outline-primary ml-2">Tank zurücksetzen</button>
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</form>
|
</form>
|
||||||
</p>
|
</p>
|
||||||
|
<!-- Div Group Oiltank Settings -->
|
||||||
|
<!-- Div Group LED Settings-->
|
||||||
<hr />
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
<h4>Entlüftung</h4>
|
<h4>LED Einstellungen</h4>
|
||||||
<form action="post.htm" method="POST" class="form-horizontal">
|
<form action="post.htm" method="POST" class="form-horizontal">
|
||||||
<div class="form-group row">
|
<div class="form-group row">
|
||||||
<label for="purgepulse" class="control-label col-4">Entlüftung Dosierung</label>
|
<label for="ledmodeflash" class="control-label col-4">LED Modus blinken</label>
|
||||||
|
<div class="col-8">
|
||||||
|
<div class="form-check">
|
||||||
|
<input class="form-check-input" type="checkbox" name="ledmodeflash" id="ledmodeflash" %LEDFLASHCHECKED%>
|
||||||
|
<label class="form-check-label" for="ledmodeflash">
|
||||||
|
LED blinken
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="form-group row">
|
||||||
|
<label for="ledmaxbrightness" class="control-label col-4">Max Helligkeit</label>
|
||||||
<div class="col-8">
|
<div class="col-8">
|
||||||
<div class="input-group">
|
<div class="input-group">
|
||||||
<input id="purgepulse" name="purgepulse" value="%BLEEDING_PULSES%" type="text" class="form-control">
|
<input id="ledmaxbrightness" name="ledmaxbrightness" value="%LED_MAX_BRIGHTNESS%" type="text"
|
||||||
<div class="input-group-append">
|
class="form-control" required="required">
|
||||||
<span class="input-group-text">Pulse</span>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="form-group row">
|
||||||
|
<label for="ledminbrightness" class="control-label col-4">Min Helligkeit</label>
|
||||||
|
<div class="col-8">
|
||||||
|
<div class="input-group">
|
||||||
|
<input id="ledminbrightness" name="ledminbrightness" value="%LED_MIN_BRIGHTNESS%" type="text"
|
||||||
|
class="form-control" required="required">
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="form-group row">
|
<div class="form-group row">
|
||||||
<div class="col text-center">
|
<div class="col text-center">
|
||||||
<button name="maintsave" type="submit" class="btn btn-outline-primary">Speichern</button>
|
<button name="ledsave" type="submit" class="btn btn-outline-primary">Speichern</button>
|
||||||
<button name="purgenow" type="submit" class="btn btn-outline-primary ml-2">Entlüftung starten</button>
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</form>
|
</form>
|
||||||
</p>
|
</p>
|
||||||
<hr />
|
<!-- Div Group Lube Settings-->
|
||||||
<p>
|
|
||||||
<h4>EEPROM formatieren</h4>
|
|
||||||
<div class="alert alert-primary alert-dismissable show fade" role="alert">
|
|
||||||
<button type="button" class="close" data-dismiss="alert" aria-label="Close">
|
|
||||||
<span aria-hidden="true">×</span>
|
|
||||||
</button>
|
|
||||||
<strong>Achtung!</strong><br>
|
|
||||||
Das Formatieren der EEPROM-Bereiche sollte nur ausgeführt werden wenn es unbedingt erforderlich ist!
|
|
||||||
Hierdurch werden alle Einstellungen zurück gesetzt bzw. alle Betriebsdaten gehen verloren.
|
|
||||||
Folgende Situationen erfordern unter anderem eine Formatierung:
|
|
||||||
- Erstinitialisierung (bei neu aufgebautem Gerät)
|
|
||||||
- Firmware-Update (nur wenn es die Release-Notes fordern)
|
|
||||||
</div>
|
|
||||||
<form action="post.htm" method="POST" class="form-horizontal">
|
|
||||||
<div class="form-group row">
|
|
||||||
<div class="offset-4 col-8">
|
|
||||||
<div class="form-check">
|
|
||||||
<input class="form-check-input" type="checkbox" name="reset_ee_cfg" id="reset_ee_cfg">
|
|
||||||
<label class="form-check-label" for="reset_ee_cfg">
|
|
||||||
Bereich "CFG"
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
<div class="form-check">
|
|
||||||
<input class="form-check-input" type="checkbox" name="reset_ee_pds" id="reset_ee_pds">
|
|
||||||
<label class="form-check-label" for="reset_ee_pds">
|
|
||||||
Bereich "PDS"
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div class="form-group row">
|
|
||||||
<div class="col text-center">
|
|
||||||
<button name="reset_ee_btn" type="submit" class="btn btn-outline-primary">EEPROM formatieren</button>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</form>
|
|
||||||
</p>
|
|
||||||
<hr />
|
|
||||||
<p>
|
|
||||||
<h4>Gerät neustarten</h4>
|
|
||||||
<form action="post.htm" method="POST" class="form-horizontal">
|
|
||||||
<div class="form-group row">
|
|
||||||
<div class="col text-center">
|
|
||||||
<button name="reboot" type="submit" class="btn btn-outline-primary">Reboot</button>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</form>
|
|
||||||
</p>
|
|
||||||
<hr />
|
|
||||||
</div>
|
</div>
|
||||||
<!-- Div Tab Maintenance -->
|
<!-- Div Tab Settings -->
|
||||||
|
|
||||||
<!-- Div Tab SystemInfo -->
|
<!-- Div Tab SystemInfo -->
|
||||||
<div id="tab_sysinfo" class="tab-pane fade" role="tabpanel">
|
<div id="tab_sysinfo" class="tab-pane fade" role="tabpanel">
|
||||||
<h3>Systeminfo</h3>
|
<h3>Systeminfo</h3>
|
||||||
|
<!-- Div Group Sysinfo:Geraeteinfo -->
|
||||||
|
<hr />
|
||||||
|
<p>
|
||||||
|
<h4>Gerät</h4>
|
||||||
|
<table class="table">
|
||||||
|
<tbody>
|
||||||
|
<tr>
|
||||||
|
<th class="col-7" scope="col">Parameter</td>
|
||||||
|
<th class="col-5" scope="col">Value</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>Hostname</td>
|
||||||
|
<td>%HOSTNAME%</td>
|
||||||
|
</tr>
|
||||||
|
</table>
|
||||||
|
</p>
|
||||||
|
<!-- Div Group Sysinfo:Geraeteinfo -->
|
||||||
|
<!-- Div Group Sysinfo:Settings -->
|
||||||
<hr />
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
<h4>Einstellungen</h4>
|
<h4>Einstellungen</h4>
|
||||||
@@ -481,6 +591,22 @@
|
|||||||
<td>CANSource</td>
|
<td>CANSource</td>
|
||||||
<td>%CAN_SOURCE%</td>
|
<td>%CAN_SOURCE%</td>
|
||||||
</tr>
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>LED Mode Flash</td>
|
||||||
|
<td>%LED_MODE_FLASH%</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>LED Max Brightness</td>
|
||||||
|
<td>%LED_MAX_BRIGHTNESS%</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>LED Min Brightness</td>
|
||||||
|
<td>%LED_MIN_BRIGHTNESS%</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>EEPROM Version</td>
|
||||||
|
<td>%EEPROM_VERSION%</td>
|
||||||
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
<td>Checksum</td>
|
<td>Checksum</td>
|
||||||
<td>%CONFIG_CHECKSUM%</td>
|
<td>%CONFIG_CHECKSUM%</td>
|
||||||
@@ -488,6 +614,8 @@
|
|||||||
</tbody>
|
</tbody>
|
||||||
</table>
|
</table>
|
||||||
</p>
|
</p>
|
||||||
|
<!-- Div Group Sysinfo:Settings -->
|
||||||
|
<!-- Div Group Sysinfo:Persistance -->
|
||||||
<hr />
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
<h4>Betriebsdaten</h4>
|
<h4>Betriebsdaten</h4>
|
||||||
@@ -523,25 +651,29 @@
|
|||||||
</tr>
|
</tr>
|
||||||
</table>
|
</table>
|
||||||
</p>
|
</p>
|
||||||
|
<!-- Div Group Sysinfo:Persistance -->
|
||||||
|
<!-- Div Group LiveDebug -->
|
||||||
<hr />
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
<h4>Live Debug</h4>
|
<h4>Live Debug</h4>
|
||||||
<div class="form-group row">
|
<div class="form-group row">
|
||||||
<textarea class="form-control" spellcheck="false" id="livedebug-out" rows="3" readonly></textarea>
|
<textarea class="form-control" spellcheck="false" id="livedebug-out" rows="3" readonly></textarea>
|
||||||
</div>
|
</div>
|
||||||
<div class="form-group row">
|
<div class="form-group row">
|
||||||
<div class="col text-center">
|
<div class="col text-center">
|
||||||
<button id="btn-ws-start" class="btn btn-outline-primary">Start</button>
|
<button id="btn-ws-start" class="btn btn-outline-primary">Start</button>
|
||||||
<button id="btn-ws-stop" class="btn btn-outline-primary ml-2">Stop</button>
|
<button id="btn-ws-stop" class="btn btn-outline-primary ml-2">Stop</button>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</p>
|
</p>
|
||||||
<hr />
|
<!-- Div Group LiveDebug -->
|
||||||
</div>
|
</div>
|
||||||
<!-- Div Tab SystemInfo -->
|
<!-- Div Tab SystemInfo -->
|
||||||
|
|
||||||
<!-- Div Tab Firmware Update-->
|
<!-- Div Tab Firmware Update-->
|
||||||
<div id="tab_fwupdate" class="tab-pane fade" role="tabpanel">
|
<div id="tab_fwupdate" class="tab-pane fade" role="tabpanel">
|
||||||
<h3>Firmware</h3>
|
<h3>Firmware</h3>
|
||||||
|
<!-- Div Group VersionInfo -->
|
||||||
<hr />
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
<h4>Version-Info</h4>
|
<h4>Version-Info</h4>
|
||||||
@@ -559,8 +691,14 @@
|
|||||||
<td>Flash Version</td>
|
<td>Flash Version</td>
|
||||||
<td>%FS_VERSION%</td>
|
<td>%FS_VERSION%</td>
|
||||||
</tr>
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>Git Revision</td>
|
||||||
|
<td>%GIT_REV%</td>
|
||||||
|
</tr>
|
||||||
</table>
|
</table>
|
||||||
</p>
|
</p>
|
||||||
|
<!-- Div Group VersionInfo -->
|
||||||
|
<!-- Div Group EEPROM Backup -->
|
||||||
<hr />
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
<h4>EEPROM-Backup</h4>
|
<h4>EEPROM-Backup</h4>
|
||||||
@@ -570,6 +708,8 @@
|
|||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</p>
|
</p>
|
||||||
|
<!-- Div Group EEPROM Backup -->
|
||||||
|
<!-- Div Group EEPROM Restore -->
|
||||||
<hr />
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
<h4>EEPROM-Restore</h4>
|
<h4>EEPROM-Restore</h4>
|
||||||
@@ -588,6 +728,8 @@
|
|||||||
</div>
|
</div>
|
||||||
</form>
|
</form>
|
||||||
</p>
|
</p>
|
||||||
|
<!-- Div Group EEPROM Restore -->
|
||||||
|
<!-- Div Group Firmware Update -->
|
||||||
<hr />
|
<hr />
|
||||||
<p>
|
<p>
|
||||||
<h4>Firmware-Update</h4>
|
<h4>Firmware-Update</h4>
|
||||||
@@ -606,7 +748,7 @@
|
|||||||
</div>
|
</div>
|
||||||
</form>
|
</form>
|
||||||
</p>
|
</p>
|
||||||
<hr />
|
<!-- Div Group Firmware Update -->
|
||||||
</div>
|
</div>
|
||||||
<!-- Div Tab Firmware Update-->
|
<!-- Div Tab Firmware Update-->
|
||||||
</div>
|
</div>
|
||||||
@@ -618,7 +760,7 @@
|
|||||||
<footer class="page-footer navbar-dark bg-primary font-small fixed-bottom">
|
<footer class="page-footer navbar-dark bg-primary font-small fixed-bottom">
|
||||||
<div class="container-fluid text-center">
|
<div class="container-fluid text-center">
|
||||||
<div class="footer-copyright text-center py-3">
|
<div class="footer-copyright text-center py-3">
|
||||||
<span class="text-muted">© 2022 -
|
<span class="text-muted">© 2023 -
|
||||||
<a class="text-reset fw-bold" href="https://eventronics.de/">Marcel Peterkau</a></span>
|
<a class="text-reset fw-bold" href="https://eventronics.de/">Marcel Peterkau</a></span>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
@@ -673,19 +815,27 @@
|
|||||||
var dtc = dtctr.data('dtc')
|
var dtc = dtctr.data('dtc')
|
||||||
var debugval = dtctr.data('debugval')
|
var debugval = dtctr.data('debugval')
|
||||||
var modal = $(this)
|
var modal = $(this)
|
||||||
$.getJSON('static/tt_dtc/dtc_' + dtc + '.json', function (data) {
|
|
||||||
modal.find('.modal-title').text(data.title)
|
getDescriptionForDTCNumber(dtc, function (error, title, description) {
|
||||||
modal.find('.dtc-desc').text(data.description)
|
if (error)
|
||||||
if (debugval > 0) {
|
{
|
||||||
modal.find('.dtc-debugval').text("Debugvalue: " + debugval)
|
console.error("Fehler beim Abrufen der Beschreibung:", error);
|
||||||
|
modal.find('.modal-title').text("Fehler")
|
||||||
|
modal.find('.dtc-desc').text("DTC-Beschreibung konnte nicht geladen werden")
|
||||||
}
|
}
|
||||||
else {
|
else
|
||||||
modal.find('.dtc-debugval').remove()
|
{
|
||||||
|
modal.find('.modal-title').text(title)
|
||||||
|
modal.find('.dtc-desc').text(description)
|
||||||
|
if (debugval > 0)
|
||||||
|
{
|
||||||
|
modal.find('.dtc-debugval').text("Debugvalue: " + debugval)
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
modal.find('.dtc-debugval').remove()
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}).fail(function () {
|
|
||||||
console.log("An error has occurred.");
|
|
||||||
modal.find('.modal-title').text("Fehler")
|
|
||||||
modal.find('.dtc-desc').text("DTC-Beschreibung konnte nicht geladen werden")
|
|
||||||
});
|
});
|
||||||
});
|
});
|
||||||
|
|
||||||
|
77
Software/data_src/static/dtc_table.json
Normal file
77
Software/data_src/static/dtc_table.json
Normal file
@@ -0,0 +1,77 @@
|
|||||||
|
[
|
||||||
|
{
|
||||||
|
"num": 0,
|
||||||
|
"title": "No Error",
|
||||||
|
"description": "No Error"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"num": 1,
|
||||||
|
"title": "Ölvorrat leer",
|
||||||
|
"description": "Ölvorrat ist komplett leer. Den Ölvorrat auffüllen und im Menu 'Wartung' zurück setzen"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"num": 2,
|
||||||
|
"title": "Ölvorrat niedrig",
|
||||||
|
"description": "Ölvorrat ist unter der Warnschwelle. Den Ölvorrat demnächst auffüllen und im Menu 'Wartung' zurück setzen"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"num": 3,
|
||||||
|
"title": "kein EEPROM erkannt",
|
||||||
|
"description": "Es wurde kein EEPROM gefunden. Dies lässt einen Hardware-Defekt vermuten."
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"num": 4,
|
||||||
|
"title": "EEPROM CFG Checksumme",
|
||||||
|
"description": "Die Checksumme der Config-Partition des EEPROM ist ungültig. Setzen sie den EEPROM-Bereich 'CFG' im Menu 'Wartung' zurück"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"num": 5,
|
||||||
|
"title": "EEPROM PDS Checksumme",
|
||||||
|
"description": "Die Checksumme der Betriebsdaten-Partition des EEPROM ist ungültig. Setzen sie den EEPROM-Bereich 'PDS' im Menu 'Wartung' zurück"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"num": 6,
|
||||||
|
"title": "EEPROM PDS Adresse",
|
||||||
|
"description": "Die Adresse der Betriebsdaten-Partition im EEPROM ist ungültig. Setzen sie den EEPROM-Bereich 'PDS' im Menu 'Wartung' zurück"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"num": 7,
|
||||||
|
"title": "EEPROM Version falsch",
|
||||||
|
"description": "Die Layout-Version des EEPROM stimmt nicht mit der Firmware-Version überein. Setzen sie den EEPROM-Bereich 'CFG' im Menu 'Wartung' zurück"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"num": 8,
|
||||||
|
"title": "Flashspeicher Fehler",
|
||||||
|
"description": "Der Flashspeicher konnte nicht initialisiert werden. Aktualisieren sie Flash & Firmware"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"num": 9,
|
||||||
|
"title": "Flashversion falsch",
|
||||||
|
"description": "Die Version des Flashspeicher stimmt nicht mit der Firmware-Version überein. Aktualisieren sie den Flash mit der passenden Update-Datei"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"num": 10,
|
||||||
|
"title": "Keine GPS-Verbindung",
|
||||||
|
"description": "Es wurde kein GPS-Signal über die serielle Schnittstelle empfangen, Prüfen sie die Verbindung und das GPS-Modul"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"num": 11,
|
||||||
|
"title": "CAN-Transceiver Error",
|
||||||
|
"description": "Es konnte keine Verbindung zum CAN-Transceiver hergestellt werden. Prüfen Sie die Hardware auf Defekte"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"num": 12,
|
||||||
|
"title": "Keine CAN-Verbindung",
|
||||||
|
"description": "Es konnte kein CAN-Signal empfangen werden. Prüfen sie die Verbindung und die Einstellungen"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"num": 13,
|
||||||
|
"title": "Config-Validierung",
|
||||||
|
"description": "Ein oder mehrer Einstellungswerte sind ausserhalb plausibler Werte. Prüfen Sie Ihre Einstellungen"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"num": 14,
|
||||||
|
"title": "Last Error",
|
||||||
|
"description": "Last Error"
|
||||||
|
}
|
||||||
|
]
|
23
Software/data_src/static/js/dtc_table.js
Normal file
23
Software/data_src/static/js/dtc_table.js
Normal file
@@ -0,0 +1,23 @@
|
|||||||
|
const jsonFilePath = "static/dtc_table.json";
|
||||||
|
|
||||||
|
function getDescriptionForDTCNumber(number, callback) {
|
||||||
|
fetch(jsonFilePath)
|
||||||
|
.then((response) => response.json())
|
||||||
|
.then((data) => {
|
||||||
|
const foundEntry = data.find((entry) => entry.num === number);
|
||||||
|
|
||||||
|
if (foundEntry) {
|
||||||
|
const description = foundEntry.description;
|
||||||
|
const title = foundEntry.title;
|
||||||
|
callback(null, title, description);
|
||||||
|
} else {
|
||||||
|
// Wenn die Nummer nicht gefunden wurde, geben Sie einen Fehler zurück
|
||||||
|
callback(`Beschreibung für Nummer ${number} nicht gefunden.`,null, null);
|
||||||
|
}
|
||||||
|
})
|
||||||
|
.catch((error) => {
|
||||||
|
// Im Fehlerfall geben Sie den Fehler zurück
|
||||||
|
callback(error, null, null);
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
@@ -1,4 +0,0 @@
|
|||||||
{
|
|
||||||
"title": "Ölvorrat leer",
|
|
||||||
"description": "Ölvorrat ist komplett leer. Den Ölvorrat auffüllen und im Menu 'Wartung' zurück setzen"
|
|
||||||
}
|
|
@@ -1,4 +0,0 @@
|
|||||||
{
|
|
||||||
"title": "Keine GPS-Verbindung",
|
|
||||||
"description": "Es wurde kein GPS-Signal über die serielle Schnittstelle empfangen, Prüfen sie die Verbindung und das GPS-Modul"
|
|
||||||
}
|
|
@@ -1,4 +0,0 @@
|
|||||||
{
|
|
||||||
"title": "CAN-Transceiver Error",
|
|
||||||
"description": "Es konnte keine Verbindung zum CAN-Transceiver hergestellt werden. Prüfen Sie die Hardware auf Defekte"
|
|
||||||
}
|
|
@@ -1,4 +0,0 @@
|
|||||||
{
|
|
||||||
"title": "Keine CAN-Verbindung",
|
|
||||||
"description": "Es konnte kein CAN-Signal empfangen werden. Prüfen sie die Verbindung und die Einstellungen"
|
|
||||||
}
|
|
@@ -1,4 +0,0 @@
|
|||||||
{
|
|
||||||
"title": "Config-Validierung",
|
|
||||||
"description": "Ein oder mehrer Einstellungswerte sind ausserhalb plausibler Werte. Prüfen Sie Ihre Einstellungen"
|
|
||||||
}
|
|
@@ -1,4 +0,0 @@
|
|||||||
{
|
|
||||||
"title": "Ölvorrat niedrig",
|
|
||||||
"description": "Ölvorrat ist unter der Warnschwelle. Den Ölvorrat demnächst auffüllen und im Menu 'Wartung' zurück setzen"
|
|
||||||
}
|
|
@@ -1,4 +0,0 @@
|
|||||||
{
|
|
||||||
"title": "kein EEPROM gefunden",
|
|
||||||
"description": "Es wurde kein EEPROM gefunden. Dies lässt einen Hardware-Defekt vermuten."
|
|
||||||
}
|
|
@@ -1,4 +0,0 @@
|
|||||||
{
|
|
||||||
"title": "EEPROM CFG Checksumme",
|
|
||||||
"description": "Die Checksumme der Config-Partition des EEPROM ist ungültig. Setzen sie den EEPROM-Bereich 'CFG' im Menu 'Wartung' zurück"
|
|
||||||
}
|
|
@@ -1,4 +0,0 @@
|
|||||||
{
|
|
||||||
"title": "EEPROM PDS Checksumme",
|
|
||||||
"description": "Die Checksumme der Betriebsdaten-Partition des EEPROM ist ungültig. Setzen sie den EEPROM-Bereich 'PDS' im Menu 'Wartung' zurück"
|
|
||||||
}
|
|
@@ -1,4 +0,0 @@
|
|||||||
{
|
|
||||||
"title": "EEPROM PDS Adresse",
|
|
||||||
"description": "Die Adresse der Betriebsdaten-Partition im EEPROM ist ungültig. Setzen sie den EEPROM-Bereich 'PDS' im Menu 'Wartung' zurück"
|
|
||||||
}
|
|
@@ -1,4 +0,0 @@
|
|||||||
{
|
|
||||||
"title": "EEPROM Version falsch",
|
|
||||||
"description": "Die Layout-Version des EEPROM stimmt nicht mit der Firmware-Version überein. Setzen sie den EEPROM-Bereich 'CFG' im Menu 'Wartung' zurück"
|
|
||||||
}
|
|
@@ -1,4 +0,0 @@
|
|||||||
{
|
|
||||||
"title": "Flashstorage Fehler",
|
|
||||||
"description": "Der Flashstorage konnte nicht initialisiert werden. Aktualisieren sie Flash & Firmware"
|
|
||||||
}
|
|
@@ -1,4 +0,0 @@
|
|||||||
{
|
|
||||||
"title": "Flashstorage Version falsch",
|
|
||||||
"description": "Die Version des Flashstorage stimmt nicht mit der Firmware-Version überein. Aktualisieren sie den Flash mit der passenden Update-Datei"
|
|
||||||
}
|
|
@@ -1 +1 @@
|
|||||||
1.3
|
1.04
|
@@ -7,6 +7,7 @@
|
|||||||
#include "common.h"
|
#include "common.h"
|
||||||
#include "globals.h"
|
#include "globals.h"
|
||||||
#include "dtc.h"
|
#include "dtc.h"
|
||||||
|
#include "debugger.h"
|
||||||
|
|
||||||
struct can_frame
|
struct can_frame
|
||||||
{
|
{
|
||||||
@@ -16,6 +17,7 @@ struct can_frame
|
|||||||
};
|
};
|
||||||
|
|
||||||
void Init_CAN();
|
void Init_CAN();
|
||||||
|
void CAN_Process();
|
||||||
uint32_t Process_CAN_WheelSpeed();
|
uint32_t Process_CAN_WheelSpeed();
|
||||||
|
|
||||||
#endif
|
#endif
|
@@ -3,17 +3,24 @@
|
|||||||
|
|
||||||
#define Q(x) #x
|
#define Q(x) #x
|
||||||
#define QUOTE(x) Q(x)
|
#define QUOTE(x) Q(x)
|
||||||
|
#define SET_BIT(value, bitPosition) ((value) |= (1U << (bitPosition)))
|
||||||
|
|
||||||
#if PCB_REV == 2
|
#if PCB_REV == 1
|
||||||
#define GPIO_BUTTON D7
|
#define GPIO_BUTTON D7
|
||||||
#define GPIO_LED D8
|
#define GPIO_LED D8
|
||||||
#define GPIO_TRIGGER D6
|
#define GPIO_TRIGGER D6
|
||||||
#define GPIO_PUMP D5
|
#define GPIO_PUMP D5
|
||||||
#elif PCB_REV == 1 || PCB_REV == 3
|
#elif PCB_REV == 2
|
||||||
#define GPIO_BUTTON D5
|
#define GPIO_BUTTON D7
|
||||||
#define GPIO_LED D6
|
#define GPIO_LED D8
|
||||||
#define GPIO_TRIGGER D4
|
#define GPIO_TRIGGER D6
|
||||||
#define GPIO_PUMP D3
|
#define GPIO_PUMP D5
|
||||||
|
#elif PCB_REV == 3
|
||||||
|
#define GPIO_BUTTON D4
|
||||||
|
#define GPIO_LED D3
|
||||||
|
#define GPIO_TRIGGER D6
|
||||||
|
#define GPIO_PUMP D0
|
||||||
|
#define GPIO_CS_CAN D8
|
||||||
#elif PCB_REV == 4
|
#elif PCB_REV == 4
|
||||||
#define GPIO_BUTTON D4
|
#define GPIO_BUTTON D4
|
||||||
#define GPIO_LED D3
|
#define GPIO_LED D3
|
||||||
@@ -26,9 +33,6 @@
|
|||||||
#define HOST_NAME "ChainLube_%06X" // Use printf-Formatting - Chip-ID (uin32_t) will be added
|
#define HOST_NAME "ChainLube_%06X" // Use printf-Formatting - Chip-ID (uin32_t) will be added
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define SW_VERSION 1.4
|
|
||||||
#define FLASH_FS_VERSION 1.4
|
|
||||||
|
|
||||||
#ifndef OTA_DELAY
|
#ifndef OTA_DELAY
|
||||||
#define OTA_DELAY 50 // ticks -> 10ms / tick
|
#define OTA_DELAY 50 // ticks -> 10ms / tick
|
||||||
#endif
|
#endif
|
@@ -16,7 +16,9 @@
|
|||||||
|
|
||||||
typedef enum SpeedSource_e
|
typedef enum SpeedSource_e
|
||||||
{
|
{
|
||||||
|
#ifdef FEATURE_ENABLE_TIMER
|
||||||
SOURCE_TIME,
|
SOURCE_TIME,
|
||||||
|
#endif
|
||||||
SOURCE_IMPULSE,
|
SOURCE_IMPULSE,
|
||||||
#ifdef FEATURE_ENABLE_GPS
|
#ifdef FEATURE_ENABLE_GPS
|
||||||
SOURCE_GPS,
|
SOURCE_GPS,
|
||||||
@@ -27,7 +29,9 @@ typedef enum SpeedSource_e
|
|||||||
} SpeedSource_t;
|
} SpeedSource_t;
|
||||||
|
|
||||||
const char SpeedSourceString[][8] = {
|
const char SpeedSourceString[][8] = {
|
||||||
|
#ifdef FEATURE_ENABLE_TIMER
|
||||||
"Timer",
|
"Timer",
|
||||||
|
#endif
|
||||||
"Impuls",
|
"Impuls",
|
||||||
#ifdef FEATURE_ENABLE_GPS
|
#ifdef FEATURE_ENABLE_GPS
|
||||||
"GPS",
|
"GPS",
|
||||||
@@ -54,13 +58,15 @@ const size_t GPSBaudRateString_Elements = sizeof(GPSBaudRateString) / sizeof(GPS
|
|||||||
#ifdef FEATURE_ENABLE_CAN
|
#ifdef FEATURE_ENABLE_CAN
|
||||||
typedef enum CANSource_e
|
typedef enum CANSource_e
|
||||||
{
|
{
|
||||||
KTM_890_ADV_R_2021
|
KTM_890_ADV_R_2021,
|
||||||
|
KTM_1290_SD_R_2023
|
||||||
} CANSource_t;
|
} CANSource_t;
|
||||||
|
|
||||||
const char CANSourceString[][28] = {
|
const char CANSourceString[][30] = {
|
||||||
"KTM 890 Adventure R (2021)"};
|
"KTM 890 Adventure R (2021)",
|
||||||
|
"KTM 1290 Superduke R (2023)"};
|
||||||
|
|
||||||
const char CANSourceString_Elements = sizeof(CANSourceString) / sizeof(CANSourceString[0]);
|
const size_t CANSourceString_Elements = sizeof(CANSourceString) / sizeof(CANSourceString[0]);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const size_t SpeedSourceString_Elements = sizeof(SpeedSourceString) / sizeof(SpeedSourceString[0]);
|
const size_t SpeedSourceString_Elements = sizeof(SpeedSourceString) / sizeof(SpeedSourceString[0]);
|
||||||
@@ -96,6 +102,9 @@ typedef struct
|
|||||||
#ifdef FEATURE_ENABLE_CAN
|
#ifdef FEATURE_ENABLE_CAN
|
||||||
CANSource_t CANSource = KTM_890_ADV_R_2021;
|
CANSource_t CANSource = KTM_890_ADV_R_2021;
|
||||||
#endif
|
#endif
|
||||||
|
bool LED_Mode_Flash = false;
|
||||||
|
uint8_t LED_Max_Brightness = 255;
|
||||||
|
uint8_t LED_Min_Brightness = 5;
|
||||||
uint32_t checksum = 0;
|
uint32_t checksum = 0;
|
||||||
} LubeConfig_t;
|
} LubeConfig_t;
|
||||||
|
|
||||||
@@ -107,6 +116,9 @@ const LubeConfig_t LubeConfig_defaults = {
|
|||||||
#ifdef FEATURE_ENABLE_CAN
|
#ifdef FEATURE_ENABLE_CAN
|
||||||
KTM_890_ADV_R_2021,
|
KTM_890_ADV_R_2021,
|
||||||
#endif
|
#endif
|
||||||
|
false,
|
||||||
|
255,
|
||||||
|
5,
|
||||||
0};
|
0};
|
||||||
|
|
||||||
void InitEEPROM();
|
void InitEEPROM();
|
46
Software/include/debugger.h
Normal file
46
Software/include/debugger.h
Normal file
@@ -0,0 +1,46 @@
|
|||||||
|
#ifndef _DEBUGGER_H_
|
||||||
|
#define _DEBUGGER_H_
|
||||||
|
|
||||||
|
#include <Arduino.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
|
||||||
|
{
|
||||||
|
disabled,
|
||||||
|
enabled
|
||||||
|
} DebugStatus_t;
|
||||||
|
|
||||||
|
typedef enum DebugPorts_e
|
||||||
|
{
|
||||||
|
dbg_Serial,
|
||||||
|
dbg_Webui,
|
||||||
|
dbg_cntElements
|
||||||
|
} DebugPorts_t;
|
||||||
|
|
||||||
|
const char sDebugPorts[dbg_cntElements][7] = {
|
||||||
|
"Serial",
|
||||||
|
"WebUI"};
|
||||||
|
|
||||||
|
extern DebugStatus_t DebuggerStatus[dbg_cntElements];
|
||||||
|
|
||||||
|
void initDebugger();
|
||||||
|
void pushCANDebug(uint32_t id, uint8_t dlc, uint8_t *data);
|
||||||
|
void Debug_pushMessage(const char *format, ...);
|
||||||
|
void SetDebugportStatus(DebugPorts_t port, DebugStatus_t status);
|
||||||
|
void Debug_Process();
|
||||||
|
|
||||||
|
#endif
|
26
Software/include/dtc.h
Normal file
26
Software/include/dtc.h
Normal file
@@ -0,0 +1,26 @@
|
|||||||
|
#ifndef _DTC_H_
|
||||||
|
#define _DTC_H_
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "dtc_defs.h"
|
||||||
|
|
||||||
|
#define MAX_DTC_STORAGE 6
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
DTCNum_t Number;
|
||||||
|
uint32_t timestamp;
|
||||||
|
DTCActive_t active;
|
||||||
|
uint32_t debugVal;
|
||||||
|
} DTCEntry_t;
|
||||||
|
|
||||||
|
void MaintainDTC(DTCNum_t DTC_no, boolean active, uint32_t DebugValue = 0);
|
||||||
|
void ClearDTC(DTCNum_t DTC_no);
|
||||||
|
void ClearAllDTC();
|
||||||
|
DTCNum_t getlastDTC(boolean only_active);
|
||||||
|
DTCNum_t ActiveDTCseverity(DTCSeverity_t severity);
|
||||||
|
DTCSeverity_t getSeverityForDTC(DTCNum_t targetCode);
|
||||||
|
void DTC_Process();
|
||||||
|
|
||||||
|
extern DTCEntry_t DTCStorage[MAX_DTC_STORAGE];
|
||||||
|
#endif
|
65
Software/include/dtc_defs.h
Normal file
65
Software/include/dtc_defs.h
Normal file
@@ -0,0 +1,65 @@
|
|||||||
|
// Auto-generated by script on 2023-10-20 12:04:36
|
||||||
|
#ifndef DTC_DEFS_H
|
||||||
|
#define DTC_DEFS_H
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
typedef uint32_t DTCNum_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
DTC_INACTIVE,
|
||||||
|
DTC_ACTIVE,
|
||||||
|
DTC_PREVIOUS
|
||||||
|
} DTCActive_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
DTC_NONE,
|
||||||
|
DTC_INFO,
|
||||||
|
DTC_WARN,
|
||||||
|
DTC_CRITICAL
|
||||||
|
} DTCSeverity_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
DTCNum_t code;
|
||||||
|
DTCSeverity_t severity;
|
||||||
|
} DTC_t;
|
||||||
|
|
||||||
|
#define DTC_NO_DTC 0
|
||||||
|
#define DTC_TANK_EMPTY 1
|
||||||
|
#define DTC_TANK_LOW 2
|
||||||
|
#define DTC_NO_EEPROM_FOUND 3
|
||||||
|
#define DTC_EEPROM_CFG_BAD 4
|
||||||
|
#define DTC_EEPROM_PDS_BAD 5
|
||||||
|
#define DTC_EEPROM_PDSADRESS_BAD 6
|
||||||
|
#define DTC_EEPROM_VERSION_BAD 7
|
||||||
|
#define DTC_FLASHFS_ERROR 8
|
||||||
|
#define DTC_FLASHFS_VERSION_ERROR 9
|
||||||
|
#define DTC_NO_GPS_SERIAL 10
|
||||||
|
#define DTC_CAN_TRANSCEIVER_FAILED 11
|
||||||
|
#define DTC_NO_CAN_SIGNAL 12
|
||||||
|
#define DTC_EEPROM_CFG_SANITY 13
|
||||||
|
#define DTC_LAST_DTC 14
|
||||||
|
|
||||||
|
const DTC_t dtc_definitions[] = {
|
||||||
|
{ DTC_NO_DTC , DTC_NONE }, // No Error
|
||||||
|
{ DTC_TANK_EMPTY , DTC_CRITICAL }, // Ölvorrat ist komplett leer. Den Ölvorrat auffüllen und im Menu 'Wartung' zurück setzen
|
||||||
|
{ DTC_TANK_LOW , DTC_WARN }, // Ölvorrat ist unter der Warnschwelle. Den Ölvorrat demnächst auffüllen und im Menu 'Wartung' zurück setzen
|
||||||
|
{ DTC_NO_EEPROM_FOUND , DTC_CRITICAL }, // Es wurde kein EEPROM gefunden. Dies lässt einen Hardware-Defekt vermuten.
|
||||||
|
{ DTC_EEPROM_CFG_BAD , DTC_CRITICAL }, // Die Checksumme der Config-Partition des EEPROM ist ungültig. Setzen sie den EEPROM-Bereich 'CFG' im Menu 'Wartung' zurück
|
||||||
|
{ DTC_EEPROM_PDS_BAD , DTC_CRITICAL }, // Die Checksumme der Betriebsdaten-Partition des EEPROM ist ungültig. Setzen sie den EEPROM-Bereich 'PDS' im Menu 'Wartung' zurück
|
||||||
|
{ DTC_EEPROM_PDSADRESS_BAD , DTC_CRITICAL }, // Die Adresse der Betriebsdaten-Partition im EEPROM ist ungültig. Setzen sie den EEPROM-Bereich 'PDS' im Menu 'Wartung' zurück
|
||||||
|
{ DTC_EEPROM_VERSION_BAD , DTC_CRITICAL }, // Die Layout-Version des EEPROM stimmt nicht mit der Firmware-Version überein. Setzen sie den EEPROM-Bereich 'CFG' im Menu 'Wartung' zurück
|
||||||
|
{ DTC_FLASHFS_ERROR , DTC_CRITICAL }, // Der Flashspeicher konnte nicht initialisiert werden. Aktualisieren sie Flash & Firmware
|
||||||
|
{ DTC_FLASHFS_VERSION_ERROR , DTC_CRITICAL }, // Die Version des Flashspeicher stimmt nicht mit der Firmware-Version überein. Aktualisieren sie den Flash mit der passenden Update-Datei
|
||||||
|
{ DTC_NO_GPS_SERIAL , DTC_CRITICAL }, // Es wurde kein GPS-Signal über die serielle Schnittstelle empfangen, Prüfen sie die Verbindung und das GPS-Modul
|
||||||
|
{ DTC_CAN_TRANSCEIVER_FAILED , DTC_CRITICAL }, // Es konnte keine Verbindung zum CAN-Transceiver hergestellt werden. Prüfen Sie die Hardware auf Defekte
|
||||||
|
{ DTC_NO_CAN_SIGNAL , DTC_WARN }, // Es konnte kein CAN-Signal empfangen werden. Prüfen sie die Verbindung und die Einstellungen
|
||||||
|
{ DTC_EEPROM_CFG_SANITY , DTC_WARN }, // Ein oder mehrer Einstellungswerte sind ausserhalb plausibler Werte. Prüfen Sie Ihre Einstellungen
|
||||||
|
{ DTC_LAST_DTC , DTC_NONE } // Last Error
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint32_t dtc_generation_timestamp = 1697796276;
|
||||||
|
|
||||||
|
#endif // DTC_DEFS_H
|
40
Software/include/dtc_defs.h.j2
Normal file
40
Software/include/dtc_defs.h.j2
Normal file
@@ -0,0 +1,40 @@
|
|||||||
|
// Auto-generated by script on {{ timestamp }}
|
||||||
|
#ifndef DTC_DEFS_H
|
||||||
|
#define DTC_DEFS_H
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
typedef uint32_t DTCNum_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
DTC_INACTIVE,
|
||||||
|
DTC_ACTIVE,
|
||||||
|
DTC_PREVIOUS
|
||||||
|
} DTCActive_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
DTC_NONE,
|
||||||
|
DTC_INFO,
|
||||||
|
DTC_WARN,
|
||||||
|
DTC_CRITICAL
|
||||||
|
} DTCSeverity_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
DTCNum_t code;
|
||||||
|
DTCSeverity_t severity;
|
||||||
|
} DTC_t;
|
||||||
|
|
||||||
|
{% for dtc in dtc_macros -%}
|
||||||
|
{{ dtc }}
|
||||||
|
{% endfor %}
|
||||||
|
const DTC_t dtc_definitions[] = {
|
||||||
|
{% for struct in dtc_structs -%}
|
||||||
|
{{ struct }}
|
||||||
|
{% endfor -%}
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint32_t dtc_generation_timestamp = {{ timestamp_unix }};
|
||||||
|
|
||||||
|
#endif // DTC_DEFS_H
|
@@ -39,10 +39,27 @@ typedef struct Globals_s
|
|||||||
uint16_t eePersistanceAdress;
|
uint16_t eePersistanceAdress;
|
||||||
uint8_t TankPercentage;
|
uint8_t TankPercentage;
|
||||||
bool hasDTC;
|
bool hasDTC;
|
||||||
|
bool measurementActive;
|
||||||
|
uint32_t measuredPulses;
|
||||||
} Globals_t;
|
} Globals_t;
|
||||||
|
|
||||||
extern Globals_t globals;
|
extern Globals_t globals;
|
||||||
|
|
||||||
|
typedef struct Constants_s
|
||||||
|
{
|
||||||
|
uint8_t FW_Version_major;
|
||||||
|
uint8_t FW_Version_minor;
|
||||||
|
uint8_t Required_Flash_Version_major;
|
||||||
|
uint8_t Required_Flash_Version_minor;
|
||||||
|
char GitHash[11];
|
||||||
|
} Constants_t;
|
||||||
|
|
||||||
|
const Constants_t constants PROGMEM = {
|
||||||
|
1,4, // Firmware_Version
|
||||||
|
1,4, // Required Flash Version
|
||||||
|
GIT_REV // Git-Hash-String
|
||||||
|
};
|
||||||
|
|
||||||
void initGlobals();
|
void initGlobals();
|
||||||
|
|
||||||
#endif
|
#endif
|
35
Software/include/led_colors.h
Normal file
35
Software/include/led_colors.h
Normal file
@@ -0,0 +1,35 @@
|
|||||||
|
#ifndef _LED_COLORS_H_
|
||||||
|
#define _LED_COLORS_H_
|
||||||
|
|
||||||
|
#define COLOR_RED 0xFF0000
|
||||||
|
#define COLOR_GREEN 0x00FF00
|
||||||
|
#define COLOR_BLUE 0x0000FF
|
||||||
|
#define COLOR_YELLOW 0xFF9600
|
||||||
|
#define COLOR_ORANGE 0xFF2800
|
||||||
|
#define COLOR_TEAL 0x00FF78
|
||||||
|
#define COLOR_CYAN 0x00FFFF
|
||||||
|
#define COLOR_PURPLE 0xB400FF
|
||||||
|
#define COLOR_MAGENTA 0xFF0014
|
||||||
|
#define COLOR_WHITE 0xFFFFFF
|
||||||
|
#define COLOR_BLACK 0x000000
|
||||||
|
#define COLOR_GOLD 0xFFDE1E
|
||||||
|
#define COLOR_PINK 0xF25AFF
|
||||||
|
#define COLOR_AQUA 0x32FFFF
|
||||||
|
#define COLOR_JADE 0x00FF28
|
||||||
|
#define COLOR_AMBER 0xFF6400
|
||||||
|
#define COLOR_WARM_WHITE 0xFDF5E6
|
||||||
|
|
||||||
|
|
||||||
|
#define LED_DEFAULT_COLOR COLOR_WARM_WHITE
|
||||||
|
#define LED_STARTUP_NORMAL COLOR_WARM_WHITE
|
||||||
|
#define LED_STARTUP_TANKWARN COLOR_AMBER
|
||||||
|
#define LED_NORMAL_COLOR COLOR_GREEN
|
||||||
|
#define LED_RAIN_COLOR COLOR_BLUE
|
||||||
|
#define LED_WIFI_BLINK COLOR_YELLOW
|
||||||
|
#define LED_PURGE_COLOR COLOR_MAGENTA
|
||||||
|
#define LED_ERROR_BLINK COLOR_RED
|
||||||
|
#define LED_SHUTDOWN_BLINK COLOR_CYAN
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* _LED_COLORS_H_ */
|
@@ -7,6 +7,7 @@
|
|||||||
#include "common.h"
|
#include "common.h"
|
||||||
#include "globals.h"
|
#include "globals.h"
|
||||||
#include "dtc.h"
|
#include "dtc.h"
|
||||||
|
#include "debugger.h"
|
||||||
|
|
||||||
void RunLubeApp(uint32_t add_milimeters);
|
void RunLubeApp(uint32_t add_milimeters);
|
||||||
void LubePulse();
|
void LubePulse();
|
@@ -8,11 +8,17 @@
|
|||||||
#error "Unsupported PCB-Revision"
|
#error "Unsupported PCB-Revision"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if PCB_REV < 4 && defined(FEATURE_ENABLE_CAN)
|
#if PCB_REV < 3 && defined(FEATURE_ENABLE_CAN)
|
||||||
#error "CAN-Feature unsupported with this PCB-Rev"
|
#error "CAN-Feature unsupported with this PCB-Rev"
|
||||||
#endif
|
#endif
|
||||||
#if PCB_REV < 4 && defined(DFEATURE_ENABLE_GPS)
|
#if PCB_REV < 4 && defined(DFEATURE_ENABLE_GPS)
|
||||||
#error "CAN-Feature unsupported with this PCB-Rev"
|
#error "GPS-Feature unsupported with this PCB-Rev"
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef CAN_DEBUG_MESSAGE
|
||||||
|
#ifndef FEATURE_ENABLE_CAN
|
||||||
|
#error "You cannot enable CAN-Debug-Message without FEATURE_ENABLE_CAN"
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
@@ -11,19 +11,13 @@
|
|||||||
[platformio]
|
[platformio]
|
||||||
extra_configs =
|
extra_configs =
|
||||||
wifi_credentials.ini
|
wifi_credentials.ini
|
||||||
|
default_envs = pcb_rev_1-3, pcb_rev_1-2
|
||||||
|
|
||||||
[env:d1_mini]
|
[env]
|
||||||
platform = espressif8266
|
platform = espressif8266
|
||||||
board = d1_mini
|
board = d1_mini
|
||||||
framework = arduino
|
framework = arduino
|
||||||
|
|
||||||
upload_protocol = esptool
|
|
||||||
upload_speed = 921600
|
|
||||||
;upload_port = ChainLube_DDEFB2
|
|
||||||
;upload_protocol = espota
|
|
||||||
;upload_flags =
|
|
||||||
; --auth=${wifi_cred.admin_password}
|
|
||||||
|
|
||||||
build_flags =
|
build_flags =
|
||||||
!python git_rev_macro.py
|
!python git_rev_macro.py
|
||||||
-DWIFI_SSID_CLIENT=${wifi_cred.wifi_ssid_client}
|
-DWIFI_SSID_CLIENT=${wifi_cred.wifi_ssid_client}
|
||||||
@@ -32,30 +26,58 @@ build_flags =
|
|||||||
-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
|
||||||
-DATOMIC_FS_UPDATE
|
-DATOMIC_FS_UPDATE
|
||||||
-DFEATURE_ENABLE_WIFI_CLIENT
|
|
||||||
-DFEATURE_ENABLE_OLED
|
|
||||||
-DFEATURE_ENABLE_CAN
|
|
||||||
;-DFEATURE_ENABLE_GPS
|
|
||||||
-DFEATURE_ENABLE_WEBSOCKETS
|
|
||||||
-DPCB_REV=4
|
|
||||||
;-DNO_MODE_FLASH
|
|
||||||
|
|
||||||
;build_type = debug
|
|
||||||
|
|
||||||
board_build.filesystem = littlefs
|
board_build.filesystem = littlefs
|
||||||
extra_scripts = post:prepare_littlefs.py
|
extra_scripts =
|
||||||
|
post:prepare_littlefs.py
|
||||||
|
pre:build_dtcs.py
|
||||||
|
pre:prepare_fwfiles.py
|
||||||
|
|
||||||
monitor_filters = esp8266_exception_decoder
|
monitor_filters = esp8266_exception_decoder
|
||||||
monitor_speed = 115200
|
monitor_speed = 115200
|
||||||
|
|
||||||
board_build.ldscript = eagle.flash.4m1m.ld
|
|
||||||
lib_ldf_mode = deep
|
lib_ldf_mode = deep
|
||||||
lib_deps =
|
lib_deps =
|
||||||
olikraus/U8g2 @ ^2.28.8
|
olikraus/U8g2 @ ^2.28.8
|
||||||
https://github.com/FastLED/FastLED.git#3d2ab78 ;fastled/FastLED @ ^3.5.0
|
adafruit/Adafruit NeoPixel @ ^1.11.0
|
||||||
sstaub/Ticker @ ^4.2.0
|
sstaub/Ticker @ ^4.2.0
|
||||||
coryjfowler/mcp_can @ ^1.5.0
|
|
||||||
robtillaart/I2C_EEPROM @ ^1.5.2
|
robtillaart/I2C_EEPROM @ ^1.5.2
|
||||||
mikalhart/TinyGPSPlus @ ^1.0.3
|
|
||||||
me-no-dev/ESP Async WebServer @ ^1.2.3
|
me-no-dev/ESP Async WebServer @ ^1.2.3
|
||||||
bblanchon/ArduinoJson @ ^6.19.4
|
bblanchon/ArduinoJson @ ^6.19.4
|
||||||
|
|
||||||
|
[env:pcb_rev_1-3]
|
||||||
|
;build_type = debug
|
||||||
|
custom_pcb_revision = 3
|
||||||
|
build_flags =
|
||||||
|
${env.build_flags}
|
||||||
|
;-DFEATURE_ENABLE_WIFI_CLIENT
|
||||||
|
;-DFEATURE_ENABLE_TIMER
|
||||||
|
;-DFEATURE_ENABLE_GPS
|
||||||
|
-DFEATURE_ENABLE_OLED
|
||||||
|
-DFEATURE_ENABLE_WEBSOCKETS
|
||||||
|
-DFEATURE_ENABLE_CAN
|
||||||
|
-DCAN_DEBUG_MESSAGE
|
||||||
|
-DPCB_REV=${this.custom_pcb_revision}
|
||||||
|
|
||||||
|
board_build.ldscript = eagle.flash.4m1m.ld
|
||||||
|
|
||||||
|
lib_deps =
|
||||||
|
${env.lib_deps}
|
||||||
|
coryjfowler/mcp_can @ ^1.5.0
|
||||||
|
mikalhart/TinyGPSPlus @ ^1.0.3
|
||||||
|
|
||||||
|
[env:pcb_rev_1-2]
|
||||||
|
;build_type = debug
|
||||||
|
custom_pcb_revision = 2
|
||||||
|
build_flags =
|
||||||
|
${env.build_flags}
|
||||||
|
;-DFEATURE_ENABLE_WIFI_CLIENT
|
||||||
|
;-DFEATURE_ENABLE_TIMER
|
||||||
|
-DFEATURE_ENABLE_OLED
|
||||||
|
-DFEATURE_ENABLE_WEBSOCKETS
|
||||||
|
-DPCB_REV=${this.custom_pcb_revision}
|
||||||
|
|
||||||
|
board_build.ldscript = eagle.flash.4m1m.ld
|
||||||
|
|
||||||
|
lib_deps =
|
||||||
|
${env.lib_deps}
|
3
Software/prepare_fwfiles.py
Normal file
3
Software/prepare_fwfiles.py
Normal file
@@ -0,0 +1,3 @@
|
|||||||
|
Import("env")
|
||||||
|
|
||||||
|
env.Replace(PROGNAME="firmware_pcb_1.%s.fw" % env.GetProjectOption("custom_pcb_revision"))
|
@@ -2,36 +2,75 @@
|
|||||||
#include "can.h"
|
#include "can.h"
|
||||||
|
|
||||||
MCP_CAN CAN0(GPIO_CS_CAN);
|
MCP_CAN CAN0(GPIO_CS_CAN);
|
||||||
|
#ifdef CAN_DEBUG_MESSAGE
|
||||||
|
void sendCANDebugMessage();
|
||||||
|
#endif
|
||||||
|
|
||||||
void Init_CAN()
|
void Init_CAN()
|
||||||
{
|
{
|
||||||
|
|
||||||
if (CAN0.begin(MCP_STDEXT, CAN_500KBPS, MCP_16MHZ) != CAN_OK)
|
if (CAN0.begin(MCP_STDEXT, CAN_500KBPS, MCP_16MHZ) != CAN_OK)
|
||||||
MaintainDTC(DTC_CAN_TRANSCEIVER_FAILED, DTC_CRITICAL, true);
|
MaintainDTC(DTC_CAN_TRANSCEIVER_FAILED, true);
|
||||||
|
|
||||||
CAN0.init_Mask(0, 0, 0x07FF0000); // Init first mask...
|
CAN0.init_Mask(0, 0, 0x07FF0000); // Init first mask...
|
||||||
CAN0.init_Mask(1, 0, 0x07FF0000); // Init second mask...
|
CAN0.init_Mask(1, 0, 0x07FF0000); // Init second mask...
|
||||||
CAN0.init_Filt(0, 0, 0x012D0000); // Init first filter...
|
|
||||||
|
switch (LubeConfig.CANSource)
|
||||||
|
{
|
||||||
|
case KTM_890_ADV_R_2021:
|
||||||
|
CAN0.init_Filt(0, 0, 0x012D0000); // Init first filter...
|
||||||
|
break;
|
||||||
|
case KTM_1290_SD_R_2023:
|
||||||
|
CAN0.init_Filt(0, 0, 0x012D0000); // Init first filter...
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
CAN0.setMode(MCP_NORMAL);
|
CAN0.setMode(MCP_NORMAL);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void CAN_Process()
|
||||||
|
{
|
||||||
|
static uint32_t previousMillis = 0;
|
||||||
|
|
||||||
|
if (millis() - previousMillis >= 100)
|
||||||
|
{
|
||||||
|
sendCANDebugMessage();
|
||||||
|
previousMillis = millis();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
uint32_t Process_CAN_WheelSpeed()
|
uint32_t Process_CAN_WheelSpeed()
|
||||||
{
|
{
|
||||||
#define FACTOR_RWP_KMH_890ADV 18 // Divider to convert Raw Data to km/h
|
#define FACTOR_RWP_KMH_890ADV 18 // Divider to convert Raw Data to km/h
|
||||||
|
#define FACTOR_RWP_KMH_1290SD 18 // Divider to convert Raw Data to km/h
|
||||||
can_frame canMsg;
|
can_frame canMsg;
|
||||||
static uint32_t lastRecTimestamp = 0;
|
static uint32_t lastRecTimestamp = 0;
|
||||||
uint16_t RearWheelSpeed_raw;
|
uint16_t RearWheelSpeed_raw;
|
||||||
uint32_t milimeters_to_add = 0;
|
uint32_t milimeters_to_add = 0;
|
||||||
|
uint32_t RWP_millimeter_per_second = 0;
|
||||||
|
|
||||||
if (CAN0.readMsgBuf(&canMsg.can_id, &canMsg.can_dlc, canMsg.data) == CAN_OK)
|
if (CAN0.readMsgBuf(&canMsg.can_id, &canMsg.can_dlc, canMsg.data) == CAN_OK)
|
||||||
{
|
{
|
||||||
|
|
||||||
RearWheelSpeed_raw = (uint16_t)canMsg.data[5] << 8 | canMsg.data[6];
|
switch (LubeConfig.CANSource)
|
||||||
// raw / FACTOR_RWP_KMH_890ADV -> km/h * 100000 -> cm/h / 3600 -> cm/s
|
{
|
||||||
// raw * 500 -> cm/s
|
case KTM_890_ADV_R_2021:
|
||||||
uint32_t RWP_millimeter_per_second = (((uint32_t)RearWheelSpeed_raw * 1000000) / FACTOR_RWP_KMH_890ADV) / 3600;
|
// raw / FACTOR_RWP_KMH_890ADV -> km/h * 100000 -> cm/h / 3600 -> cm/s
|
||||||
|
// raw * 500 -> cm/s
|
||||||
|
RearWheelSpeed_raw = (uint16_t)canMsg.data[5] << 8 | canMsg.data[6];
|
||||||
|
RWP_millimeter_per_second = (((uint32_t)RearWheelSpeed_raw * 1000000) / FACTOR_RWP_KMH_890ADV) / 3600;
|
||||||
|
break;
|
||||||
|
case KTM_1290_SD_R_2023:
|
||||||
|
// raw / FACTOR_RWP_KMH_1290SD -> km/h * 100000 -> cm/h / 3600 -> cm/s
|
||||||
|
// raw * 500 -> cm/s
|
||||||
|
RearWheelSpeed_raw = (uint16_t)canMsg.data[5] << 8 | canMsg.data[6];
|
||||||
|
RWP_millimeter_per_second = (((uint32_t)RearWheelSpeed_raw * 1000000) / FACTOR_RWP_KMH_1290SD) / 3600;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
uint32_t timesincelast = millis() - lastRecTimestamp;
|
uint32_t timesincelast = millis() - lastRecTimestamp;
|
||||||
lastRecTimestamp = millis();
|
lastRecTimestamp = millis();
|
||||||
@@ -39,11 +78,62 @@ uint32_t Process_CAN_WheelSpeed()
|
|||||||
milimeters_to_add = (RWP_millimeter_per_second * timesincelast) / 1000;
|
milimeters_to_add = (RWP_millimeter_per_second * timesincelast) / 1000;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (lastRecTimestamp != 0)
|
if (lastRecTimestamp > 1000)
|
||||||
{
|
{
|
||||||
MaintainDTC(DTC_NO_CAN_SIGNAL, DTC_CRITICAL, (millis() > lastRecTimestamp + 10000 ? true : false));
|
MaintainDTC(DTC_NO_CAN_SIGNAL, (millis() > lastRecTimestamp + 10000 ? true : false));
|
||||||
}
|
}
|
||||||
|
|
||||||
return milimeters_to_add;
|
return milimeters_to_add;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef CAN_DEBUG_MESSAGE
|
||||||
|
void sendCANDebugMessage()
|
||||||
|
{
|
||||||
|
#define MAX_DEBUG_MULTIPLEXER 6
|
||||||
|
static uint8_t debugMultiplexer = 0;
|
||||||
|
byte data[8] = {debugMultiplexer, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF};
|
||||||
|
uint32_t millisValue = millis();
|
||||||
|
|
||||||
|
switch (debugMultiplexer)
|
||||||
|
{
|
||||||
|
case 0:
|
||||||
|
memcpy(&data[1], &millisValue, sizeof(millisValue));
|
||||||
|
memcpy(&data[5], &globals.purgePulses, sizeof(globals.purgePulses));
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
data[1] = (uint8_t)globals.systemStatus;
|
||||||
|
data[2] = (uint8_t)globals.resumeStatus;
|
||||||
|
data[3] = (uint8_t)globals.requestEEAction;
|
||||||
|
data[4] = globals.TankPercentage;
|
||||||
|
data[5] = (0x01 & globals.hasDTC) | ((0x01 & globals.measurementActive) << 1);
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
memcpy(&data[1], &globals.eePersistanceAdress, sizeof(globals.eePersistanceAdress));
|
||||||
|
memcpy(&data[3], &PersistenceData.tankRemain_microL, sizeof(PersistenceData.tankRemain_microL));
|
||||||
|
break;
|
||||||
|
case 3:
|
||||||
|
memcpy(&data[1], &PersistenceData.writeCycleCounter, sizeof(PersistenceData.writeCycleCounter));
|
||||||
|
memcpy(&data[3], &PersistenceData.TravelDistance_highRes_mm, sizeof(PersistenceData.TravelDistance_highRes_mm));
|
||||||
|
break;
|
||||||
|
case 4:
|
||||||
|
memcpy(&data[1], &PersistenceData.odometer_mm, sizeof(PersistenceData.odometer_mm));
|
||||||
|
break;
|
||||||
|
case 5:
|
||||||
|
memcpy(&data[1], &PersistenceData.odometer, sizeof(PersistenceData.odometer));
|
||||||
|
break;
|
||||||
|
case 6:
|
||||||
|
memcpy(&data[1], &PersistenceData.checksum, sizeof(PersistenceData.checksum));
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
debugMultiplexer++;
|
||||||
|
debugMultiplexer = debugMultiplexer > MAX_DEBUG_MULTIPLEXER ? 0 : debugMultiplexer;
|
||||||
|
|
||||||
|
byte sndStat = CAN0.sendMsgBuf(0x7FF, 0, 8, data);
|
||||||
|
if (sndStat != CAN_OK)
|
||||||
|
Debug_pushMessage("failed sending CAN-DbgMsg: %d\n", sndStat);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
@@ -36,7 +36,7 @@ void EEPROM_Process()
|
|||||||
case EE_CFG_FORMAT:
|
case EE_CFG_FORMAT:
|
||||||
FormatConfig_EEPROM();
|
FormatConfig_EEPROM();
|
||||||
globals.requestEEAction = EE_IDLE;
|
globals.requestEEAction = EE_IDLE;
|
||||||
globals.systemStatus = sysStat_Shutdown;
|
GetConfig_EEPROM();
|
||||||
Debug_pushMessage("Formated EEPROM CFG\n");
|
Debug_pushMessage("Formated EEPROM CFG\n");
|
||||||
break;
|
break;
|
||||||
case EE_PDS_SAVE:
|
case EE_PDS_SAVE:
|
||||||
@@ -52,11 +52,14 @@ void EEPROM_Process()
|
|||||||
case EE_PDS_FORMAT:
|
case EE_PDS_FORMAT:
|
||||||
FormatPersistence_EEPROM();
|
FormatPersistence_EEPROM();
|
||||||
globals.requestEEAction = EE_IDLE;
|
globals.requestEEAction = EE_IDLE;
|
||||||
|
GetPersistence_EEPROM();
|
||||||
Debug_pushMessage("Formated EEPROM PDS\n");
|
Debug_pushMessage("Formated EEPROM PDS\n");
|
||||||
break;
|
break;
|
||||||
case EE_FORMAT_ALL:
|
case EE_FORMAT_ALL:
|
||||||
FormatConfig_EEPROM();
|
FormatConfig_EEPROM();
|
||||||
FormatPersistence_EEPROM();
|
FormatPersistence_EEPROM();
|
||||||
|
GetConfig_EEPROM();
|
||||||
|
GetPersistence_EEPROM();
|
||||||
globals.requestEEAction = EE_IDLE;
|
globals.requestEEAction = EE_IDLE;
|
||||||
Debug_pushMessage("Formated EEPROM ALL\n");
|
Debug_pushMessage("Formated EEPROM ALL\n");
|
||||||
break;
|
break;
|
||||||
@@ -80,6 +83,12 @@ void StoreConfig_EEPROM()
|
|||||||
return;
|
return;
|
||||||
|
|
||||||
ee.updateBlock(startofLubeConfig, (uint8_t *)&LubeConfig, sizeof(LubeConfig));
|
ee.updateBlock(startofLubeConfig, (uint8_t *)&LubeConfig, sizeof(LubeConfig));
|
||||||
|
|
||||||
|
uint32_t ConfigSanityCheckResult = ConfigSanityCheck(false);
|
||||||
|
if (ConfigSanityCheckResult > 0)
|
||||||
|
{
|
||||||
|
MaintainDTC(DTC_EEPROM_CFG_SANITY, true, ConfigSanityCheckResult);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void GetConfig_EEPROM()
|
void GetConfig_EEPROM()
|
||||||
@@ -94,16 +103,14 @@ void GetConfig_EEPROM()
|
|||||||
|
|
||||||
if (Checksum_EEPROM((uint8_t *)&LubeConfig, sizeof(LubeConfig)) != checksum)
|
if (Checksum_EEPROM((uint8_t *)&LubeConfig, sizeof(LubeConfig)) != checksum)
|
||||||
{
|
{
|
||||||
MaintainDTC(DTC_EEPROM_CFG_BAD, DTC_CRITICAL, true);
|
MaintainDTC(DTC_EEPROM_CFG_BAD, true);
|
||||||
}
|
}
|
||||||
LubeConfig.checksum = checksum;
|
LubeConfig.checksum = checksum;
|
||||||
|
|
||||||
uint32_t ConfigSanityCheckResult = ConfigSanityCheck(false);
|
uint32_t ConfigSanityCheckResult = ConfigSanityCheck(false);
|
||||||
|
|
||||||
if (ConfigSanityCheckResult > 0)
|
if (ConfigSanityCheckResult > 0)
|
||||||
{
|
{
|
||||||
MaintainDTC(DTC_EEPROM_CFG_SANITY, DTC_WARN, true, ConfigSanityCheckResult);
|
MaintainDTC(DTC_EEPROM_CFG_SANITY, true, ConfigSanityCheckResult);
|
||||||
globals.requestEEAction = EE_CFG_SAVE;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -135,7 +142,7 @@ void GetPersistence_EEPROM()
|
|||||||
{
|
{
|
||||||
MovePersistencePage_EEPROM(true);
|
MovePersistencePage_EEPROM(true);
|
||||||
FormatPersistence_EEPROM();
|
FormatPersistence_EEPROM();
|
||||||
MaintainDTC(DTC_EEPROM_PDSADRESS_BAD, DTC_CRITICAL, true);
|
MaintainDTC(DTC_EEPROM_PDSADRESS_BAD, true);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
@@ -146,7 +153,7 @@ void GetPersistence_EEPROM()
|
|||||||
|
|
||||||
if (Checksum_EEPROM((uint8_t *)&PersistenceData, sizeof(PersistenceData)) != checksum)
|
if (Checksum_EEPROM((uint8_t *)&PersistenceData, sizeof(PersistenceData)) != checksum)
|
||||||
{
|
{
|
||||||
MaintainDTC(DTC_EEPROM_PDS_BAD, DTC_CRITICAL, true);
|
MaintainDTC(DTC_EEPROM_PDS_BAD, true);
|
||||||
}
|
}
|
||||||
PersistenceData.checksum = checksum;
|
PersistenceData.checksum = checksum;
|
||||||
}
|
}
|
||||||
@@ -242,10 +249,10 @@ boolean checkEEPROMavailable()
|
|||||||
{
|
{
|
||||||
if (!ee.isConnected())
|
if (!ee.isConnected())
|
||||||
{
|
{
|
||||||
MaintainDTC(DTC_NO_EEPROM_FOUND, DTC_CRITICAL, true);
|
MaintainDTC(DTC_NO_EEPROM_FOUND, true);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
MaintainDTC(DTC_NO_EEPROM_FOUND, DTC_CRITICAL, false);
|
MaintainDTC(DTC_NO_EEPROM_FOUND, false);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -255,84 +262,84 @@ uint32_t ConfigSanityCheck(bool autocorrect)
|
|||||||
|
|
||||||
if (!(LubeConfig.DistancePerLube_Default > 0) || !(LubeConfig.DistancePerLube_Default < 50000))
|
if (!(LubeConfig.DistancePerLube_Default > 0) || !(LubeConfig.DistancePerLube_Default < 50000))
|
||||||
{
|
{
|
||||||
setting_reset_bits = setting_reset_bits | (1 << 0);
|
SET_BIT(setting_reset_bits, 0);
|
||||||
if (autocorrect)
|
if (autocorrect)
|
||||||
LubeConfig.DistancePerLube_Default = LubeConfig_defaults.DistancePerLube_Default;
|
LubeConfig.DistancePerLube_Default = LubeConfig_defaults.DistancePerLube_Default;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!(LubeConfig.DistancePerLube_Rain > 0) || !(LubeConfig.DistancePerLube_Rain < 50000))
|
if (!(LubeConfig.DistancePerLube_Rain > 0) || !(LubeConfig.DistancePerLube_Rain < 50000))
|
||||||
{
|
{
|
||||||
setting_reset_bits = setting_reset_bits | (1 << 1);
|
SET_BIT(setting_reset_bits, 1);
|
||||||
if (autocorrect)
|
if (autocorrect)
|
||||||
LubeConfig.DistancePerLube_Rain = LubeConfig_defaults.DistancePerLube_Rain;
|
LubeConfig.DistancePerLube_Rain = LubeConfig_defaults.DistancePerLube_Rain;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!(LubeConfig.tankCapacity_ml > 0) || !(LubeConfig.tankCapacity_ml < 5000))
|
if (!(LubeConfig.tankCapacity_ml > 0) || !(LubeConfig.tankCapacity_ml < 5000))
|
||||||
{
|
{
|
||||||
setting_reset_bits = setting_reset_bits | (1 << 2);
|
SET_BIT(setting_reset_bits, 2);
|
||||||
if (autocorrect)
|
if (autocorrect)
|
||||||
LubeConfig.tankCapacity_ml = LubeConfig_defaults.tankCapacity_ml;
|
LubeConfig.tankCapacity_ml = LubeConfig_defaults.tankCapacity_ml;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!(LubeConfig.amountPerDose_microL > 0) || !(LubeConfig.amountPerDose_microL < 100))
|
if (!(LubeConfig.amountPerDose_microL > 0) || !(LubeConfig.amountPerDose_microL < 100))
|
||||||
{
|
{
|
||||||
setting_reset_bits = setting_reset_bits | (1 << 3);
|
SET_BIT(setting_reset_bits, 3);
|
||||||
if (autocorrect)
|
if (autocorrect)
|
||||||
LubeConfig.amountPerDose_microL = LubeConfig_defaults.amountPerDose_microL;
|
LubeConfig.amountPerDose_microL = LubeConfig_defaults.amountPerDose_microL;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!(LubeConfig.TankRemindAtPercentage >= 0) || !(LubeConfig.TankRemindAtPercentage <= 100))
|
if (!(LubeConfig.TankRemindAtPercentage >= 0) || !(LubeConfig.TankRemindAtPercentage <= 100))
|
||||||
{
|
{
|
||||||
setting_reset_bits = setting_reset_bits | (1 << 4);
|
SET_BIT(setting_reset_bits, 4);
|
||||||
if (autocorrect)
|
if (autocorrect)
|
||||||
LubeConfig.TankRemindAtPercentage = LubeConfig_defaults.TankRemindAtPercentage;
|
LubeConfig.TankRemindAtPercentage = LubeConfig_defaults.TankRemindAtPercentage;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!(LubeConfig.PulsePerRevolution > 0) || !(LubeConfig.PulsePerRevolution < 1000))
|
if (!(LubeConfig.PulsePerRevolution > 0) || !(LubeConfig.PulsePerRevolution < 1000))
|
||||||
{
|
{
|
||||||
setting_reset_bits = setting_reset_bits | (1 << 5);
|
SET_BIT(setting_reset_bits, 5);
|
||||||
if (autocorrect)
|
if (autocorrect)
|
||||||
LubeConfig.PulsePerRevolution = LubeConfig_defaults.PulsePerRevolution;
|
LubeConfig.PulsePerRevolution = LubeConfig_defaults.PulsePerRevolution;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!(LubeConfig.TireWidth_mm > 0) || !(LubeConfig.TireWidth_mm < 500))
|
if (!(LubeConfig.TireWidth_mm > 0) || !(LubeConfig.TireWidth_mm < 500))
|
||||||
{
|
{
|
||||||
setting_reset_bits = setting_reset_bits | (1 << 6);
|
SET_BIT(setting_reset_bits, 6);
|
||||||
if (autocorrect)
|
if (autocorrect)
|
||||||
LubeConfig.TireWidth_mm = LubeConfig_defaults.TireWidth_mm;
|
LubeConfig.TireWidth_mm = LubeConfig_defaults.TireWidth_mm;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!(LubeConfig.TireWidthHeight_Ratio > 0) || !(LubeConfig.TireWidthHeight_Ratio < 150))
|
if (!(LubeConfig.TireWidthHeight_Ratio > 0) || !(LubeConfig.TireWidthHeight_Ratio < 150))
|
||||||
{
|
{
|
||||||
setting_reset_bits = setting_reset_bits | (1 << 7);
|
SET_BIT(setting_reset_bits, 7);
|
||||||
if (autocorrect)
|
if (autocorrect)
|
||||||
LubeConfig.TireWidthHeight_Ratio = LubeConfig_defaults.TireWidthHeight_Ratio;
|
LubeConfig.TireWidthHeight_Ratio = LubeConfig_defaults.TireWidthHeight_Ratio;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!(LubeConfig.RimDiameter_Inch > 0) || !(LubeConfig.RimDiameter_Inch < 30))
|
if (!(LubeConfig.RimDiameter_Inch > 0) || !(LubeConfig.RimDiameter_Inch < 30))
|
||||||
{
|
{
|
||||||
setting_reset_bits = setting_reset_bits | (1 << 8);
|
SET_BIT(setting_reset_bits, 8);
|
||||||
if (autocorrect)
|
if (autocorrect)
|
||||||
LubeConfig.RimDiameter_Inch = LubeConfig_defaults.RimDiameter_Inch;
|
LubeConfig.RimDiameter_Inch = LubeConfig_defaults.RimDiameter_Inch;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!(LubeConfig.DistancePerRevolution_mm > 0) || !(LubeConfig.DistancePerRevolution_mm < 10000))
|
if (!(LubeConfig.DistancePerRevolution_mm > 0) || !(LubeConfig.DistancePerRevolution_mm < 10000))
|
||||||
{
|
{
|
||||||
setting_reset_bits = setting_reset_bits | (1 << 9);
|
SET_BIT(setting_reset_bits, 9);
|
||||||
if (autocorrect)
|
if (autocorrect)
|
||||||
LubeConfig.DistancePerRevolution_mm = LubeConfig_defaults.DistancePerRevolution_mm;
|
LubeConfig.DistancePerRevolution_mm = LubeConfig_defaults.DistancePerRevolution_mm;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!(LubeConfig.BleedingPulses > 0) || !(LubeConfig.BleedingPulses < 1001))
|
if (!(LubeConfig.BleedingPulses > 0) || !(LubeConfig.BleedingPulses < 1001))
|
||||||
{
|
{
|
||||||
setting_reset_bits = setting_reset_bits | (1 << 10);
|
SET_BIT(setting_reset_bits, 10);
|
||||||
if (autocorrect)
|
if (autocorrect)
|
||||||
LubeConfig.BleedingPulses = LubeConfig_defaults.BleedingPulses;
|
LubeConfig.BleedingPulses = LubeConfig_defaults.BleedingPulses;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!(LubeConfig.SpeedSource >= 0) || !(LubeConfig.SpeedSource < SpeedSourceString_Elements))
|
if (!(LubeConfig.SpeedSource >= 0) || !(LubeConfig.SpeedSource < SpeedSourceString_Elements))
|
||||||
{
|
{
|
||||||
setting_reset_bits = setting_reset_bits | (1 << 11);
|
SET_BIT(setting_reset_bits, 11);
|
||||||
if (autocorrect)
|
if (autocorrect)
|
||||||
LubeConfig.SpeedSource = LubeConfig_defaults.SpeedSource;
|
LubeConfig.SpeedSource = LubeConfig_defaults.SpeedSource;
|
||||||
}
|
}
|
||||||
@@ -340,7 +347,7 @@ uint32_t ConfigSanityCheck(bool autocorrect)
|
|||||||
#ifdef FEATURE_ENABLE_GPS
|
#ifdef FEATURE_ENABLE_GPS
|
||||||
if (!(LubeConfig.GPSBaudRate >= 0) || !(LubeConfig.GPSBaudRate < GPSBaudRateString_Elements))
|
if (!(LubeConfig.GPSBaudRate >= 0) || !(LubeConfig.GPSBaudRate < GPSBaudRateString_Elements))
|
||||||
{
|
{
|
||||||
setting_reset_bits = setting_reset_bits | (1 << 12);
|
SET_BIT(setting_reset_bits, 12);
|
||||||
if (autocorrect)
|
if (autocorrect)
|
||||||
LubeConfig.GPSBaudRate = LubeConfig_defaults.GPSBaudRate;
|
LubeConfig.GPSBaudRate = LubeConfig_defaults.GPSBaudRate;
|
||||||
}
|
}
|
||||||
@@ -349,7 +356,7 @@ uint32_t ConfigSanityCheck(bool autocorrect)
|
|||||||
#ifdef FEATURE_ENABLE_CAN
|
#ifdef FEATURE_ENABLE_CAN
|
||||||
if (!(LubeConfig.CANSource >= 0) || !(LubeConfig.CANSource < CANSourceString_Elements))
|
if (!(LubeConfig.CANSource >= 0) || !(LubeConfig.CANSource < CANSourceString_Elements))
|
||||||
{
|
{
|
||||||
setting_reset_bits = setting_reset_bits | (1 << 13);
|
SET_BIT(setting_reset_bits, 13);
|
||||||
if (autocorrect)
|
if (autocorrect)
|
||||||
LubeConfig.CANSource = LubeConfig_defaults.CANSource;
|
LubeConfig.CANSource = LubeConfig_defaults.CANSource;
|
||||||
}
|
}
|
||||||
|
@@ -3,7 +3,7 @@
|
|||||||
DebugStatus_t DebuggerStatus[dbg_cntElements];
|
DebugStatus_t DebuggerStatus[dbg_cntElements];
|
||||||
|
|
||||||
String IpAddress2String(const IPAddress &ipAddress);
|
String IpAddress2String(const IPAddress &ipAddress);
|
||||||
void processCmdDebug();
|
void processCmdDebug(String command);
|
||||||
void Debug_formatCFG();
|
void Debug_formatCFG();
|
||||||
void Debug_formatPersistence();
|
void Debug_formatPersistence();
|
||||||
void Debug_printSystemInfo();
|
void Debug_printSystemInfo();
|
||||||
@@ -13,6 +13,7 @@ void Debug_dumpConfig();
|
|||||||
void Debug_dumpPersistance();
|
void Debug_dumpPersistance();
|
||||||
void Debug_ShowDTCs();
|
void Debug_ShowDTCs();
|
||||||
void Debug_dumpGlobals();
|
void Debug_dumpGlobals();
|
||||||
|
void Debug_printHelp();
|
||||||
|
|
||||||
void initDebugger()
|
void initDebugger()
|
||||||
{
|
{
|
||||||
@@ -22,15 +23,84 @@ void initDebugger()
|
|||||||
Serial.setDebugOutput(false);
|
Serial.setDebugOutput(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void Debug_Process()
|
||||||
|
{
|
||||||
|
typedef enum InputProcessed_e
|
||||||
|
{
|
||||||
|
IDLE,
|
||||||
|
CMD_COMPLETE,
|
||||||
|
CMD_ABORT,
|
||||||
|
CMD_OVERFLOW
|
||||||
|
} InputProcessed_t;
|
||||||
|
|
||||||
|
static unsigned int inputCnt = 0;
|
||||||
|
static char inputBuffer[32];
|
||||||
|
InputProcessed_t InputProcessed = IDLE;
|
||||||
|
|
||||||
|
if (Serial.available())
|
||||||
|
{
|
||||||
|
char inputChar = Serial.read();
|
||||||
|
|
||||||
|
switch (inputChar)
|
||||||
|
{
|
||||||
|
case '\n':
|
||||||
|
inputBuffer[inputCnt] = 0; // terminate the String
|
||||||
|
inputCnt = 0;
|
||||||
|
InputProcessed = CMD_COMPLETE;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 0x1B: // Esc
|
||||||
|
inputBuffer[0] = 0;
|
||||||
|
inputCnt = 0;
|
||||||
|
InputProcessed = CMD_ABORT;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 0x21 ... 0x7E: // its a real letter or sign and not some control-chars
|
||||||
|
inputBuffer[inputCnt] = inputChar;
|
||||||
|
inputCnt++;
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (inputCnt > sizeof(inputBuffer))
|
||||||
|
{
|
||||||
|
inputCnt = 0;
|
||||||
|
inputBuffer[sizeof(inputBuffer) - 1] = 0; // terminate the String
|
||||||
|
InputProcessed = CMD_OVERFLOW;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (InputProcessed)
|
||||||
|
{
|
||||||
|
case CMD_ABORT:
|
||||||
|
Debug_pushMessage("Abort\n");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case CMD_COMPLETE:
|
||||||
|
processCmdDebug(String(inputBuffer));
|
||||||
|
break;
|
||||||
|
|
||||||
|
case CMD_OVERFLOW:
|
||||||
|
Debug_pushMessage("input Buffer overflow\n");
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
InputProcessed = IDLE;
|
||||||
|
}
|
||||||
|
|
||||||
void SetDebugportStatus(DebugPorts_t port, DebugStatus_t status)
|
void SetDebugportStatus(DebugPorts_t port, DebugStatus_t status)
|
||||||
{
|
{
|
||||||
if (status == disabled)
|
if (status == disabled)
|
||||||
Debug_pushMessage("disable DebugPort %s", sDebugPorts[port]);
|
Debug_pushMessage("disable DebugPort %s\n", sDebugPorts[port]);
|
||||||
|
|
||||||
DebuggerStatus[port] = status;
|
DebuggerStatus[port] = status;
|
||||||
|
|
||||||
if (status == enabled)
|
if (status == enabled)
|
||||||
Debug_pushMessage("enabled DebugPort %s", sDebugPorts[port]);
|
Debug_pushMessage("enabled DebugPort %s\n", sDebugPorts[port]);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Debug_pushMessage(const char *format, ...)
|
void Debug_pushMessage(const char *format, ...)
|
||||||
@@ -81,7 +151,9 @@ void pushCANDebug(uint32_t id, uint8_t dlc, uint8_t *data)
|
|||||||
|
|
||||||
void processCmdDebug(String command)
|
void processCmdDebug(String command)
|
||||||
{
|
{
|
||||||
if (command == "sysinfo")
|
if (command == "help")
|
||||||
|
Debug_printHelp();
|
||||||
|
else if (command == "sysinfo")
|
||||||
Debug_printSystemInfo();
|
Debug_printSystemInfo();
|
||||||
else if (command == "netinfo")
|
else if (command == "netinfo")
|
||||||
Debug_printWifiInfo();
|
Debug_printWifiInfo();
|
||||||
@@ -107,87 +179,91 @@ void processCmdDebug(String command)
|
|||||||
Debug_ShowDTCs();
|
Debug_ShowDTCs();
|
||||||
else if (command == "dumpGlobals")
|
else if (command == "dumpGlobals")
|
||||||
Debug_dumpGlobals();
|
Debug_dumpGlobals();
|
||||||
|
else if (command == "sdbg")
|
||||||
|
SetDebugportStatus(dbg_Serial, enabled);
|
||||||
|
else
|
||||||
|
Debug_pushMessage("unknown Command\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
void Debug_formatCFG()
|
void Debug_formatCFG()
|
||||||
{
|
{
|
||||||
Debug_pushMessage("Formatting Config-EEPROM and reseting to default");
|
Debug_pushMessage("Formatting Config-EEPROM and reseting to default\n");
|
||||||
FormatConfig_EEPROM();
|
FormatConfig_EEPROM();
|
||||||
}
|
}
|
||||||
|
|
||||||
void Debug_formatPersistence()
|
void Debug_formatPersistence()
|
||||||
{
|
{
|
||||||
Debug_pushMessage("Formatting Persistence-EEPROM and reseting to default");
|
Debug_pushMessage("Formatting Persistence-EEPROM and reseting to default\n");
|
||||||
FormatPersistence_EEPROM();
|
FormatPersistence_EEPROM();
|
||||||
}
|
}
|
||||||
|
|
||||||
void RemotDebug_printSystemInfo()
|
void Debug_printSystemInfo()
|
||||||
{
|
{
|
||||||
Debug_pushMessage("Souko's ChainOiler Mk1");
|
Debug_pushMessage("Souko's ChainOiler Mk1\n");
|
||||||
Debug_pushMessage("Hostname: %s", globals.DeviceName);
|
Debug_pushMessage("Hostname: %s\n", globals.DeviceName);
|
||||||
|
|
||||||
FlashMode_t ideMode = ESP.getFlashChipMode();
|
FlashMode_t ideMode = ESP.getFlashChipMode();
|
||||||
Debug_pushMessage("Sdk version: %s", ESP.getSdkVersion());
|
Debug_pushMessage("Sdk version: %s\n", ESP.getSdkVersion());
|
||||||
Debug_pushMessage("Core Version: %s", ESP.getCoreVersion().c_str());
|
Debug_pushMessage("Core Version: %s\n", ESP.getCoreVersion().c_str());
|
||||||
Debug_pushMessage("Boot Version: %u", ESP.getBootVersion());
|
Debug_pushMessage("Boot Version: %u\n", ESP.getBootVersion());
|
||||||
Debug_pushMessage("Boot Mode: %u", ESP.getBootMode());
|
Debug_pushMessage("Boot Mode: %u\n", ESP.getBootMode());
|
||||||
Debug_pushMessage("CPU Frequency: %u MHz", ESP.getCpuFreqMHz());
|
Debug_pushMessage("CPU Frequency: %u MHz\n", ESP.getCpuFreqMHz());
|
||||||
Debug_pushMessage("Reset reason: %s", ESP.getResetReason().c_str());
|
Debug_pushMessage("Reset reason: %s\n", ESP.getResetReason().c_str());
|
||||||
Debug_pushMessage("Flash Size: %d", ESP.getFlashChipRealSize());
|
Debug_pushMessage("Flash Size: %d\n", ESP.getFlashChipRealSize());
|
||||||
Debug_pushMessage("Flash Size IDE: %d", ESP.getFlashChipSize());
|
Debug_pushMessage("Flash Size IDE: %d\n", ESP.getFlashChipSize());
|
||||||
Debug_pushMessage("Flash ide mode: %s", (ideMode == FM_QIO ? "QIO" : ideMode == FM_QOUT ? "QOUT"
|
Debug_pushMessage("Flash ide mode: %s\n", (ideMode == FM_QIO ? "QIO" : ideMode == FM_QOUT ? "QOUT"
|
||||||
: ideMode == FM_DIO ? "DIO"
|
: ideMode == FM_DIO ? "DIO"
|
||||||
: ideMode == FM_DOUT ? "DOUT"
|
: ideMode == FM_DOUT ? "DOUT"
|
||||||
: "UNKNOWN"));
|
: "UNKNOWN"));
|
||||||
Debug_pushMessage("OTA-Pass: %s", QUOTE(ADMIN_PASSWORD));
|
Debug_pushMessage("OTA-Pass: %s\n", QUOTE(ADMIN_PASSWORD));
|
||||||
Debug_pushMessage("Git-Revison: %s", GIT_REV);
|
Debug_pushMessage("Git-Revison: %s\n", constants.GitHash);
|
||||||
Debug_pushMessage("Sw-Version: %s", QUOTE(SW_VERSION));
|
Debug_pushMessage("Sw-Version: %d.%02d\n", constants.FW_Version_major, constants.FW_Version_minor);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Debug_dumpConfig()
|
void Debug_dumpConfig()
|
||||||
{
|
{
|
||||||
Debug_pushMessage("DistancePerLube_Default: %d", LubeConfig.DistancePerLube_Default);
|
Debug_pushMessage("DistancePerLube_Default: %d\n", LubeConfig.DistancePerLube_Default);
|
||||||
Debug_pushMessage("DistancePerLube_Rain: %d", LubeConfig.DistancePerLube_Rain);
|
Debug_pushMessage("DistancePerLube_Rain: %d\n", LubeConfig.DistancePerLube_Rain);
|
||||||
Debug_pushMessage("tankCapacity_ml: %d", LubeConfig.tankCapacity_ml);
|
Debug_pushMessage("tankCapacity_ml: %d\n", LubeConfig.tankCapacity_ml);
|
||||||
Debug_pushMessage("amountPerDose_microL: %d", LubeConfig.amountPerDose_microL);
|
Debug_pushMessage("amountPerDose_microL: %d\n", LubeConfig.amountPerDose_microL);
|
||||||
Debug_pushMessage("TankRemindAtPercentage: %d", LubeConfig.TankRemindAtPercentage);
|
Debug_pushMessage("TankRemindAtPercentage: %d\n", LubeConfig.TankRemindAtPercentage);
|
||||||
Debug_pushMessage("PulsePerRevolution: %d", LubeConfig.PulsePerRevolution);
|
Debug_pushMessage("PulsePerRevolution: %d\n", LubeConfig.PulsePerRevolution);
|
||||||
Debug_pushMessage("TireWidth_mm: %d", LubeConfig.TireWidth_mm);
|
Debug_pushMessage("TireWidth_mm: %d\n", LubeConfig.TireWidth_mm);
|
||||||
Debug_pushMessage("TireWidthHeight_Ratio: %d", LubeConfig.TireWidth_mm);
|
Debug_pushMessage("TireWidthHeight_Ratio: %d\n", LubeConfig.TireWidth_mm);
|
||||||
Debug_pushMessage("RimDiameter_Inch: %d", LubeConfig.RimDiameter_Inch);
|
Debug_pushMessage("RimDiameter_Inch: %d\n", LubeConfig.RimDiameter_Inch);
|
||||||
Debug_pushMessage("DistancePerRevolution_mm: %d", LubeConfig.DistancePerRevolution_mm);
|
Debug_pushMessage("DistancePerRevolution_mm: %d\n", LubeConfig.DistancePerRevolution_mm);
|
||||||
Debug_pushMessage("BleedingPulses: %d", LubeConfig.BleedingPulses);
|
Debug_pushMessage("BleedingPulses: %d\n", LubeConfig.BleedingPulses);
|
||||||
Debug_pushMessage("SpeedSource: %d", LubeConfig.SpeedSource);
|
Debug_pushMessage("SpeedSource: %d\n", LubeConfig.SpeedSource);
|
||||||
#ifdef FEATURE_ENABLE_GPS
|
#ifdef FEATURE_ENABLE_GPS
|
||||||
Debug_pushMessage("GPSBaudRate: %d", LubeConfig.GPSBaudRate);
|
Debug_pushMessage("GPSBaudRate: %d\n", LubeConfig.GPSBaudRate);
|
||||||
#endif
|
#endif
|
||||||
#ifdef FEATURE_ENABLE_CAN
|
#ifdef FEATURE_ENABLE_CAN
|
||||||
Debug_pushMessage("CANSource: %d", LubeConfig.CANSource);
|
Debug_pushMessage("CANSource: %d\n", LubeConfig.CANSource);
|
||||||
#endif
|
#endif
|
||||||
Debug_pushMessage("checksum: 0x%08X", LubeConfig.checksum);
|
Debug_pushMessage("checksum: 0x%08X\n", LubeConfig.checksum);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Debug_dumpGlobals()
|
void Debug_dumpGlobals()
|
||||||
{
|
{
|
||||||
Debug_pushMessage("systemStatus: %d", globals.systemStatus);
|
Debug_pushMessage("systemStatus: %d\n", globals.systemStatus);
|
||||||
Debug_pushMessage("resumeStatus: %d", globals.resumeStatus);
|
Debug_pushMessage("resumeStatus: %d\n", globals.resumeStatus);
|
||||||
Debug_pushMessage("systemStatustxt: %s", globals.systemStatustxt);
|
Debug_pushMessage("systemStatustxt: %s\n", globals.systemStatustxt);
|
||||||
Debug_pushMessage("purgePulses: %d", globals.purgePulses);
|
Debug_pushMessage("purgePulses: %d\n", globals.purgePulses);
|
||||||
Debug_pushMessage("requestEEAction: %d", globals.requestEEAction);
|
Debug_pushMessage("requestEEAction: %d\n", globals.requestEEAction);
|
||||||
Debug_pushMessage("DeviceName: %s", globals.DeviceName);
|
Debug_pushMessage("DeviceName: %s\n", globals.DeviceName);
|
||||||
Debug_pushMessage("FlashVersion: %s", globals.FlashVersion);
|
Debug_pushMessage("FlashVersion: %s\n", globals.FlashVersion);
|
||||||
Debug_pushMessage("eePersistanceAdress: %d", globals.eePersistanceAdress);
|
Debug_pushMessage("eePersistanceAdress: %d\n", globals.eePersistanceAdress);
|
||||||
Debug_pushMessage("TankPercentage: %d", globals.TankPercentage);
|
Debug_pushMessage("TankPercentage: %d\n", globals.TankPercentage);
|
||||||
Debug_pushMessage("hasDTC: %d", globals.hasDTC);
|
Debug_pushMessage("hasDTC: %d\n", globals.hasDTC);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Debug_dumpPersistance()
|
void Debug_dumpPersistance()
|
||||||
{
|
{
|
||||||
Debug_pushMessage("writeCycleCounter: %d", PersistenceData.writeCycleCounter);
|
Debug_pushMessage("writeCycleCounter: %d\n", PersistenceData.writeCycleCounter);
|
||||||
Debug_pushMessage("tankRemain_microL: %d", PersistenceData.tankRemain_microL);
|
Debug_pushMessage("tankRemain_microL: %d\n", PersistenceData.tankRemain_microL);
|
||||||
Debug_pushMessage("TravelDistance_highRes_mm: %d", PersistenceData.TravelDistance_highRes_mm);
|
Debug_pushMessage("TravelDistance_highRes_mm: %d\n", PersistenceData.TravelDistance_highRes_mm);
|
||||||
Debug_pushMessage("checksum: %d", PersistenceData.checksum);
|
Debug_pushMessage("checksum: %d\n", PersistenceData.checksum);
|
||||||
Debug_pushMessage("PSD Adress: 0x%04X", globals.eePersistanceAdress);
|
Debug_pushMessage("PSD Adress: 0x%04X\n", globals.eePersistanceAdress);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Debug_printWifiInfo()
|
void Debug_printWifiInfo()
|
||||||
@@ -229,6 +305,8 @@ void Debug_ShowDTCs()
|
|||||||
char buff_timestamp[16]; // Format: DD-hh:mm:ss:xxx
|
char buff_timestamp[16]; // Format: DD-hh:mm:ss:xxx
|
||||||
char buff_active[9];
|
char buff_active[9];
|
||||||
|
|
||||||
|
Debug_pushMessage("\n timestamp | DTC-Nr. | status | severity\n");
|
||||||
|
|
||||||
for (uint32_t i = 0; i < MAX_DTC_STORAGE; i++)
|
for (uint32_t i = 0; i < MAX_DTC_STORAGE; i++)
|
||||||
{
|
{
|
||||||
if (DTCStorage[i].Number < DTC_LAST_DTC)
|
if (DTCStorage[i].Number < DTC_LAST_DTC)
|
||||||
@@ -247,7 +325,19 @@ void Debug_ShowDTCs()
|
|||||||
else
|
else
|
||||||
strcpy(buff_active, "none");
|
strcpy(buff_active, "none");
|
||||||
|
|
||||||
Debug_pushMessage("%s \t %6d \t %s \t %d", buff_timestamp, DTCStorage[i].Number, buff_active, DTCStorage[i].severity);
|
Debug_pushMessage("%s %7d %8s %8d\n", buff_timestamp, DTCStorage[i].Number, buff_active);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void Debug_printHelp()
|
||||||
|
{
|
||||||
|
char buff[64];
|
||||||
|
|
||||||
|
for (unsigned int i = sizeof(helpCmd) / 63; i < sizeof(helpCmd) / 63; i++)
|
||||||
|
{
|
||||||
|
memcpy_P(buff, (helpCmd + (i * 63)), 63);
|
||||||
|
buff[63] = 0;
|
||||||
|
Debug_pushMessage(buff);
|
||||||
|
}
|
||||||
}
|
}
|
@@ -1,45 +0,0 @@
|
|||||||
#ifndef _DEBUGGER_H_
|
|
||||||
#define _DEBUGGER_H_
|
|
||||||
|
|
||||||
#include <Arduino.h>
|
|
||||||
#include "webui.h"
|
|
||||||
|
|
||||||
const char helpCmd[] = "sysinfo - System Info\r\n"
|
|
||||||
"netinfo - WiFi Info\r\n"
|
|
||||||
"formatPDS - Format Persistence EEPROM Data\r\n"
|
|
||||||
"formatCFG - Format Configuration EEPROM Data\r\n"
|
|
||||||
"checkEE - Check EEPROM with checksum\r\n"
|
|
||||||
"dumpEE1k - dump the first 1kb of EEPROM to Serial\r\n"
|
|
||||||
"dumpEE - dump the whole EPPROM to Serial\r\n"
|
|
||||||
"resetPageEE - Reset the PersistenceData Page\r\n"
|
|
||||||
"dumpCFG - print Config struct\r\n"
|
|
||||||
"dumpPDS - print PersistanceStruct\r\n"
|
|
||||||
"saveEE - save EE-Data\r\n"
|
|
||||||
"showdtc - Show all DTCs\r\n"
|
|
||||||
"dumpGlobals - print globals\r\n";
|
|
||||||
|
|
||||||
typedef enum DebugStatus_e
|
|
||||||
{
|
|
||||||
disabled,
|
|
||||||
enabled
|
|
||||||
} DebugStatus_t;
|
|
||||||
|
|
||||||
typedef enum DebugPorts_e
|
|
||||||
{
|
|
||||||
dbg_Serial,
|
|
||||||
dbg_Webui,
|
|
||||||
dbg_cntElements
|
|
||||||
} DebugPorts_t;
|
|
||||||
|
|
||||||
const char sDebugPorts[dbg_cntElements][7] = {
|
|
||||||
"Serial",
|
|
||||||
"WebUI"};
|
|
||||||
|
|
||||||
extern DebugStatus_t DebuggerStatus[dbg_cntElements];
|
|
||||||
|
|
||||||
void initDebugger();
|
|
||||||
void pushCANDebug(uint32_t id, uint8_t dlc, uint8_t *data);
|
|
||||||
void Debug_pushMessage(const char *format, ...);
|
|
||||||
void SetDebugportStatus(DebugPorts_t port, DebugStatus_t status);
|
|
||||||
|
|
||||||
#endif
|
|
@@ -1,9 +1,9 @@
|
|||||||
#include "dtc.h"
|
#include "dtc.h"
|
||||||
#include "debugger.h"
|
#include "debugger.h"
|
||||||
|
|
||||||
DTCEntry_s DTCStorage[MAX_DTC_STORAGE];
|
DTCEntry_t DTCStorage[MAX_DTC_STORAGE];
|
||||||
|
|
||||||
void MaintainDTC(DTCNums_t DTC_no, DTCSeverity_t DTC_severity, boolean active, uint32_t DebugValue)
|
void MaintainDTC(DTCNum_t DTC_no, boolean active, uint32_t DebugValue)
|
||||||
{
|
{
|
||||||
for (int i = 0; i < MAX_DTC_STORAGE; i++)
|
for (int i = 0; i < MAX_DTC_STORAGE; i++)
|
||||||
{
|
{
|
||||||
@@ -14,7 +14,6 @@ void MaintainDTC(DTCNums_t DTC_no, DTCSeverity_t DTC_severity, boolean active, u
|
|||||||
Debug_pushMessage("DTC gone active: %d, DebugVal: %d\n", DTC_no, DebugValue);
|
Debug_pushMessage("DTC gone active: %d, DebugVal: %d\n", DTC_no, DebugValue);
|
||||||
DTCStorage[i].timestamp = millis();
|
DTCStorage[i].timestamp = millis();
|
||||||
DTCStorage[i].active = DTC_ACTIVE;
|
DTCStorage[i].active = DTC_ACTIVE;
|
||||||
DTCStorage[i].severity = DTC_severity;
|
|
||||||
DTCStorage[i].debugVal = DebugValue;
|
DTCStorage[i].debugVal = DebugValue;
|
||||||
}
|
}
|
||||||
if (!active && DTCStorage[i].active == DTC_ACTIVE)
|
if (!active && DTCStorage[i].active == DTC_ACTIVE)
|
||||||
@@ -39,21 +38,20 @@ void MaintainDTC(DTCNums_t DTC_no, DTCSeverity_t DTC_severity, boolean active, u
|
|||||||
DTCStorage[i].timestamp = millis();
|
DTCStorage[i].timestamp = millis();
|
||||||
DTCStorage[i].active = DTC_ACTIVE;
|
DTCStorage[i].active = DTC_ACTIVE;
|
||||||
DTCStorage[i].debugVal = DebugValue;
|
DTCStorage[i].debugVal = DebugValue;
|
||||||
DTCStorage[i].severity = DTC_severity;
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ClearDTC(DTCNums_t DTC_no)
|
void ClearDTC(DTCNum_t DTC_no)
|
||||||
{
|
{
|
||||||
for (int i = 0; i < MAX_DTC_STORAGE; i++)
|
for (int i = 0; i < MAX_DTC_STORAGE; i++)
|
||||||
{
|
{
|
||||||
if (DTCStorage[i].Number == DTC_no)
|
if (DTCStorage[i].Number == DTC_no)
|
||||||
{
|
{
|
||||||
DTCStorage[i].Number = DTC_LAST_DTC;
|
DTCStorage[i].Number = DTC_LAST_DTC;
|
||||||
DTCStorage[i].active = DTC_NONE;
|
DTCStorage[i].active = DTC_INACTIVE;
|
||||||
DTCStorage[i].timestamp = 0;
|
DTCStorage[i].timestamp = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -64,12 +62,12 @@ void ClearAllDTC()
|
|||||||
for (int i = 0; i < MAX_DTC_STORAGE; i++)
|
for (int i = 0; i < MAX_DTC_STORAGE; i++)
|
||||||
{
|
{
|
||||||
DTCStorage[i].Number = DTC_LAST_DTC;
|
DTCStorage[i].Number = DTC_LAST_DTC;
|
||||||
DTCStorage[i].active = DTC_NONE;
|
DTCStorage[i].active = DTC_INACTIVE;
|
||||||
DTCStorage[i].timestamp = 0;
|
DTCStorage[i].timestamp = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
DTCNums_t getlastDTC(boolean only_active)
|
DTCNum_t getlastDTC(boolean only_active)
|
||||||
{
|
{
|
||||||
int8_t pointer = -1;
|
int8_t pointer = -1;
|
||||||
uint32_t lasttimestamp = 0;
|
uint32_t lasttimestamp = 0;
|
||||||
@@ -89,34 +87,28 @@ DTCNums_t getlastDTC(boolean only_active)
|
|||||||
return pointer >= 0 ? DTCStorage[pointer].Number : DTC_LAST_DTC;
|
return pointer >= 0 ? DTCStorage[pointer].Number : DTC_LAST_DTC;
|
||||||
}
|
}
|
||||||
|
|
||||||
DTCNums_t getlastDTC_Severity(boolean only_active, DTCSeverity_t severity)
|
DTCSeverity_t getSeverityForDTC(DTCNum_t targetCode)
|
||||||
{
|
{
|
||||||
int8_t pointer = -1;
|
for (int i = 0; i < DTC_LAST_DTC; i++)
|
||||||
uint32_t lasttimestamp = 0;
|
|
||||||
|
|
||||||
for (int i = 0; i < MAX_DTC_STORAGE; i++)
|
|
||||||
{
|
{
|
||||||
if (DTCStorage[i].Number > 0 && DTCStorage[i].timestamp > lasttimestamp)
|
if (dtc_definitions[i].code == targetCode)
|
||||||
{
|
{
|
||||||
if ((only_active == false || DTCStorage[i].active == DTC_ACTIVE) && DTCStorage[i].severity == severity)
|
return dtc_definitions[i].severity;
|
||||||
{
|
|
||||||
pointer = i;
|
|
||||||
lasttimestamp = DTCStorage[i].timestamp;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
return DTC_NONE;
|
||||||
return pointer >= 0 ? DTCStorage[pointer].Number : DTC_LAST_DTC;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void DTC_Process()
|
void DTC_Process()
|
||||||
{
|
{
|
||||||
static tSystem_Status preserverSysStatusError;
|
static tSystem_Status preserverSysStatusError;
|
||||||
|
DTCNum_t lastDTC = getlastDTC(true);
|
||||||
|
|
||||||
if (getlastDTC(false) < DTC_LAST_DTC)
|
if (lastDTC < DTC_LAST_DTC)
|
||||||
{
|
{
|
||||||
globals.hasDTC = true;
|
globals.hasDTC = true;
|
||||||
if (getlastDTC_Severity(true, DTC_CRITICAL) < DTC_LAST_DTC)
|
|
||||||
|
if (getSeverityForDTC(lastDTC) == DTC_CRITICAL && globals.systemStatus != sysStat_Shutdown)
|
||||||
{
|
{
|
||||||
if (globals.systemStatus != sysStat_Error)
|
if (globals.systemStatus != sysStat_Error)
|
||||||
{
|
{
|
||||||
@@ -124,16 +116,14 @@ void DTC_Process()
|
|||||||
}
|
}
|
||||||
globals.systemStatus = sysStat_Error;
|
globals.systemStatus = sysStat_Error;
|
||||||
}
|
}
|
||||||
else
|
|
||||||
{
|
|
||||||
if (globals.systemStatus == sysStat_Error)
|
|
||||||
{
|
|
||||||
globals.systemStatus = preserverSysStatusError;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
globals.hasDTC = false;
|
globals.hasDTC = false;
|
||||||
|
|
||||||
|
if (globals.systemStatus == sysStat_Error)
|
||||||
|
{
|
||||||
|
globals.systemStatus = preserverSysStatusError;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
@@ -1,61 +0,0 @@
|
|||||||
#ifndef _DTC_H_
|
|
||||||
#define _DTC_H_
|
|
||||||
|
|
||||||
#include <Arduino.h>
|
|
||||||
|
|
||||||
#define MAX_DTC_STORAGE 6
|
|
||||||
|
|
||||||
typedef enum DTCNums_e
|
|
||||||
{
|
|
||||||
DTC_TANK_EMPTY = 1,
|
|
||||||
DTC_TANK_LOW,
|
|
||||||
DTC_NO_EEPROM_FOUND,
|
|
||||||
DTC_EEPROM_CFG_BAD,
|
|
||||||
DTC_EEPROM_PDS_BAD,
|
|
||||||
DTC_EEPROM_PDSADRESS_BAD,
|
|
||||||
DTC_EEPROM_VERSION_BAD,
|
|
||||||
DTC_FLASHFS_ERROR,
|
|
||||||
DTC_FLASHFS_VERSION_ERROR,
|
|
||||||
#ifdef FEATURE_ENABLE_GPS
|
|
||||||
DTC_NO_GPS_SERIAL,
|
|
||||||
#endif
|
|
||||||
#ifdef FEATURE_ENABLE_CAN
|
|
||||||
DTC_CAN_TRANSCEIVER_FAILED,
|
|
||||||
DTC_NO_CAN_SIGNAL,
|
|
||||||
#endif
|
|
||||||
DTC_EEPROM_CFG_SANITY,
|
|
||||||
DTC_LAST_DTC
|
|
||||||
} DTCNums_t;
|
|
||||||
|
|
||||||
typedef enum DTCActive_e
|
|
||||||
{
|
|
||||||
DTC_NONE,
|
|
||||||
DTC_ACTIVE,
|
|
||||||
DTC_PREVIOUS
|
|
||||||
} DTCActive_t;
|
|
||||||
|
|
||||||
typedef enum DTCSeverity_e
|
|
||||||
{
|
|
||||||
DTC_INFO,
|
|
||||||
DTC_WARN,
|
|
||||||
DTC_CRITICAL
|
|
||||||
} DTCSeverity_t;
|
|
||||||
|
|
||||||
typedef struct DTCEntry_s
|
|
||||||
{
|
|
||||||
DTCNums_t Number;
|
|
||||||
uint32_t timestamp;
|
|
||||||
DTCActive_t active;
|
|
||||||
DTCSeverity_t severity;
|
|
||||||
uint32_t debugVal;
|
|
||||||
} DTCEntry_t;
|
|
||||||
|
|
||||||
void MaintainDTC(DTCNums_t DTC_no, DTCSeverity_t DTC_severity, boolean active, uint32_t DebugValue = 0);
|
|
||||||
void ClearDTC(DTCNums_t DTC_no);
|
|
||||||
void ClearAllDTC();
|
|
||||||
DTCNums_t getlastDTC(boolean only_active);
|
|
||||||
DTCNums_t getlastDTC_Severity(boolean only_active, DTCSeverity_t severity);
|
|
||||||
void DTC_Process();
|
|
||||||
|
|
||||||
extern DTCEntry_s DTCStorage[MAX_DTC_STORAGE];
|
|
||||||
#endif
|
|
16
Software/src/dtc_defs.txt
Normal file
16
Software/src/dtc_defs.txt
Normal file
@@ -0,0 +1,16 @@
|
|||||||
|
# No. | DTC-Constant | Severity | Title | Description
|
||||||
|
#-----|------------------------------|---------------|-----------------------|----------------------------------------------------------------------------------------------------------------------------------------------------
|
||||||
|
1; DTC_TANK_EMPTY; DTC_CRITICAL; Ölvorrat leer; Ölvorrat ist komplett leer. Den Ölvorrat auffüllen und im Menu 'Wartung' zurück setzen
|
||||||
|
2; DTC_TANK_LOW; DTC_WARN; Ölvorrat niedrig; Ölvorrat ist unter der Warnschwelle. Den Ölvorrat demnächst auffüllen und im Menu 'Wartung' zurück setzen
|
||||||
|
3; DTC_NO_EEPROM_FOUND; DTC_CRITICAL; kein EEPROM erkannt; Es wurde kein EEPROM gefunden. Dies lässt einen Hardware-Defekt vermuten.
|
||||||
|
4; DTC_EEPROM_CFG_BAD; DTC_CRITICAL; EEPROM CFG Checksumme; Die Checksumme der Config-Partition des EEPROM ist ungültig. Setzen sie den EEPROM-Bereich 'CFG' im Menu 'Wartung' zurück
|
||||||
|
5; DTC_EEPROM_PDS_BAD; DTC_CRITICAL; EEPROM PDS Checksumme; Die Checksumme der Betriebsdaten-Partition des EEPROM ist ungültig. Setzen sie den EEPROM-Bereich 'PDS' im Menu 'Wartung' zurück
|
||||||
|
6; DTC_EEPROM_PDSADRESS_BAD; DTC_CRITICAL; EEPROM PDS Adresse; Die Adresse der Betriebsdaten-Partition im EEPROM ist ungültig. Setzen sie den EEPROM-Bereich 'PDS' im Menu 'Wartung' zurück
|
||||||
|
7; DTC_EEPROM_VERSION_BAD; DTC_CRITICAL; EEPROM Version falsch; Die Layout-Version des EEPROM stimmt nicht mit der Firmware-Version überein. Setzen sie den EEPROM-Bereich 'CFG' im Menu 'Wartung' zurück
|
||||||
|
8; DTC_FLASHFS_ERROR; DTC_CRITICAL; Flashspeicher Fehler; Der Flashspeicher konnte nicht initialisiert werden. Aktualisieren sie Flash & Firmware
|
||||||
|
9; DTC_FLASHFS_VERSION_ERROR; DTC_CRITICAL; Flashversion falsch; Die Version des Flashspeicher stimmt nicht mit der Firmware-Version überein. Aktualisieren sie den Flash mit der passenden Update-Datei
|
||||||
|
10; DTC_NO_GPS_SERIAL; DTC_CRITICAL; Keine GPS-Verbindung; Es wurde kein GPS-Signal über die serielle Schnittstelle empfangen, Prüfen sie die Verbindung und das GPS-Modul
|
||||||
|
11; DTC_CAN_TRANSCEIVER_FAILED; DTC_CRITICAL; CAN-Transceiver Error; Es konnte keine Verbindung zum CAN-Transceiver hergestellt werden. Prüfen Sie die Hardware auf Defekte
|
||||||
|
12; DTC_NO_CAN_SIGNAL; DTC_WARN; Keine CAN-Verbindung; Es konnte kein CAN-Signal empfangen werden. Prüfen sie die Verbindung und die Einstellungen
|
||||||
|
13; DTC_EEPROM_CFG_SANITY; DTC_WARN; Config-Validierung; Ein oder mehrer Einstellungswerte sind ausserhalb plausibler Werte. Prüfen Sie Ihre Einstellungen
|
||||||
|
|
@@ -8,4 +8,6 @@ void initGlobals()
|
|||||||
globals.requestEEAction = EE_IDLE;
|
globals.requestEEAction = EE_IDLE;
|
||||||
globals.resumeStatus = sysStat_Normal;
|
globals.resumeStatus = sysStat_Normal;
|
||||||
globals.systemStatus = sysStat_Startup;
|
globals.systemStatus = sysStat_Startup;
|
||||||
|
globals.measurementActive = false;
|
||||||
|
globals.measuredPulses = 0;
|
||||||
}
|
}
|
||||||
|
@@ -7,8 +7,8 @@ void RunLubeApp(uint32_t add_milimeters)
|
|||||||
|
|
||||||
globals.TankPercentage = PersistenceData.tankRemain_microL / (LubeConfig.tankCapacity_ml * 10);
|
globals.TankPercentage = PersistenceData.tankRemain_microL / (LubeConfig.tankCapacity_ml * 10);
|
||||||
|
|
||||||
MaintainDTC(DTC_TANK_EMPTY, DTC_CRITICAL, (PersistenceData.tankRemain_microL < LubeConfig.amountPerDose_microL));
|
MaintainDTC(DTC_TANK_EMPTY, (PersistenceData.tankRemain_microL < LubeConfig.amountPerDose_microL));
|
||||||
MaintainDTC(DTC_TANK_LOW, DTC_WARN, (globals.TankPercentage < LubeConfig.TankRemindAtPercentage));
|
MaintainDTC(DTC_TANK_LOW, (globals.TankPercentage < LubeConfig.TankRemindAtPercentage));
|
||||||
|
|
||||||
// Add traveled Distance in mm
|
// Add traveled Distance in mm
|
||||||
PersistenceData.TravelDistance_highRes_mm += add_milimeters;
|
PersistenceData.TravelDistance_highRes_mm += add_milimeters;
|
||||||
@@ -22,6 +22,7 @@ void RunLubeApp(uint32_t add_milimeters)
|
|||||||
switch (globals.systemStatus)
|
switch (globals.systemStatus)
|
||||||
{
|
{
|
||||||
case sysStat_Startup:
|
case sysStat_Startup:
|
||||||
|
strcpy_P(globals.systemStatustxt, PSTR("Startup"));
|
||||||
if (millis() > STARTUP_DELAY)
|
if (millis() > STARTUP_DELAY)
|
||||||
{
|
{
|
||||||
globals.systemStatus = sysStat_Normal;
|
globals.systemStatus = sysStat_Normal;
|
||||||
@@ -30,6 +31,7 @@ void RunLubeApp(uint32_t add_milimeters)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case sysStat_Normal:
|
case sysStat_Normal:
|
||||||
|
strcpy_P(globals.systemStatustxt, PSTR("Normal"));
|
||||||
if (PersistenceData.TravelDistance_highRes_mm / 1000 > LubeConfig.DistancePerLube_Default)
|
if (PersistenceData.TravelDistance_highRes_mm / 1000 > LubeConfig.DistancePerLube_Default)
|
||||||
{
|
{
|
||||||
LubePulse();
|
LubePulse();
|
||||||
@@ -38,6 +40,7 @@ void RunLubeApp(uint32_t add_milimeters)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case sysStat_Rain:
|
case sysStat_Rain:
|
||||||
|
strcpy_P(globals.systemStatustxt, PSTR("Rain"));
|
||||||
if (PersistenceData.TravelDistance_highRes_mm / 1000 > LubeConfig.DistancePerLube_Rain)
|
if (PersistenceData.TravelDistance_highRes_mm / 1000 > LubeConfig.DistancePerLube_Rain)
|
||||||
{
|
{
|
||||||
LubePulse();
|
LubePulse();
|
||||||
@@ -45,12 +48,14 @@ void RunLubeApp(uint32_t add_milimeters)
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case sysStat_Purge:
|
case sysStat_Purge:
|
||||||
|
strcpy_P(globals.systemStatustxt, PSTR("Purge"));
|
||||||
if (globals.purgePulses > 0)
|
if (globals.purgePulses > 0)
|
||||||
{
|
{
|
||||||
if (lubePulseTimestamp + LUBE_PULSE_PAUSE_MS < millis())
|
if (lubePulseTimestamp + LUBE_PULSE_PAUSE_MS < millis())
|
||||||
{
|
{
|
||||||
LubePulse();
|
LubePulse();
|
||||||
globals.purgePulses--;
|
globals.purgePulses--;
|
||||||
|
Debug_pushMessage("Purge remain: %d\n", globals.purgePulses);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
@@ -58,32 +63,14 @@ void RunLubeApp(uint32_t add_milimeters)
|
|||||||
globals.systemStatus = globals.resumeStatus;
|
globals.systemStatus = globals.resumeStatus;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case sysStat_Error:
|
|
||||||
case sysStat_Shutdown:
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
switch (globals.systemStatus)
|
|
||||||
{
|
|
||||||
case sysStat_Normal:
|
|
||||||
strcpy_P(globals.systemStatustxt, PSTR("Normal"));
|
|
||||||
break;
|
|
||||||
case sysStat_Purge:
|
|
||||||
strcpy_P(globals.systemStatustxt, PSTR("Purge"));
|
|
||||||
break;
|
|
||||||
case sysStat_Rain:
|
|
||||||
strcpy_P(globals.systemStatustxt, PSTR("Rain"));
|
|
||||||
break;
|
|
||||||
case sysStat_Startup:
|
|
||||||
strcpy_P(globals.systemStatustxt, PSTR("Startup"));
|
|
||||||
break;
|
|
||||||
case sysStat_Error:
|
case sysStat_Error:
|
||||||
strcpy_P(globals.systemStatustxt, PSTR("Error"));
|
strcpy_P(globals.systemStatustxt, PSTR("Error"));
|
||||||
break;
|
break;
|
||||||
case sysStat_Shutdown:
|
case sysStat_Shutdown:
|
||||||
strcpy_P(globals.systemStatustxt, PSTR("Shutdown"));
|
strcpy_P(globals.systemStatustxt, PSTR("Shutdown"));
|
||||||
break;
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
// maintain Pin-State of Lube-Pump
|
// maintain Pin-State of Lube-Pump
|
||||||
|
@@ -6,7 +6,7 @@
|
|||||||
#include <ESP8266WiFi.h>
|
#include <ESP8266WiFi.h>
|
||||||
#include <ArduinoOTA.h>
|
#include <ArduinoOTA.h>
|
||||||
|
|
||||||
#include <FastLED.h>
|
#include <Adafruit_NeoPixel.h>
|
||||||
#include <Ticker.h>
|
#include <Ticker.h>
|
||||||
|
|
||||||
#include "common.h"
|
#include "common.h"
|
||||||
@@ -25,6 +25,7 @@
|
|||||||
#include "gps.h"
|
#include "gps.h"
|
||||||
#endif
|
#endif
|
||||||
#include "dtc.h"
|
#include "dtc.h"
|
||||||
|
#include "led_colors.h"
|
||||||
|
|
||||||
#ifdef FEATURE_ENABLE_WIFI_CLIENT
|
#ifdef FEATURE_ENABLE_WIFI_CLIENT
|
||||||
#include <ESP8266WiFiMulti.h>
|
#include <ESP8266WiFiMulti.h>
|
||||||
@@ -39,11 +40,11 @@ ESP8266WiFiMulti wifiMulti;
|
|||||||
bool startSetupMode = false;
|
bool startSetupMode = false;
|
||||||
volatile uint32_t wheel_pulse = 0;
|
volatile uint32_t wheel_pulse = 0;
|
||||||
|
|
||||||
CRGB leds[1];
|
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, CRGB setColor = CRGB::White);
|
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();
|
||||||
@@ -78,42 +79,42 @@ void setup()
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
Serial.println("\n\nSouko's ChainLube Mk1");
|
Serial.print("\n\nSouko's ChainLube Mk1\n");
|
||||||
Serial.println(globals.DeviceName);
|
Serial.print(globals.DeviceName);
|
||||||
|
|
||||||
|
#ifdef FEATURE_ENABLE_OLED
|
||||||
|
u8x8.begin();
|
||||||
|
u8x8.setFont(u8x8_font_chroma48medium8_r);
|
||||||
|
u8x8.clearDisplay();
|
||||||
|
u8x8.drawString(0, 0, "KTM ChainLube V1");
|
||||||
|
u8x8.refreshDisplay();
|
||||||
|
Serial.print("\nDisplay-Init done");
|
||||||
|
#endif
|
||||||
|
|
||||||
InitEEPROM();
|
InitEEPROM();
|
||||||
GetConfig_EEPROM();
|
GetConfig_EEPROM();
|
||||||
GetPersistence_EEPROM();
|
GetPersistence_EEPROM();
|
||||||
#ifdef FEATURE_ENABLE_OLED
|
Serial.print("\nEE-Init done");
|
||||||
u8x8.begin();
|
|
||||||
u8x8.setFont(u8x8_font_chroma48medium8_r);
|
|
||||||
#endif
|
|
||||||
FastLED.addLeds<WS2811, GPIO_LED, RGB>(leds, 1); // GRB ordering is assumed
|
|
||||||
|
|
||||||
switch (LubeConfig.SpeedSource)
|
leds.begin();
|
||||||
{
|
Serial.print("\nLED-Init done");
|
||||||
case SOURCE_IMPULSE:
|
|
||||||
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;
|
Serial.print("\nPulse-Input Init done");
|
||||||
#ifdef FEATURE_ENABLE_GPS
|
#ifdef FEATURE_ENABLE_GPS
|
||||||
case SOURCE_GPS:
|
Init_GPS();
|
||||||
Init_GPS();
|
Serial.print("\nGPS-Init done");
|
||||||
break;
|
|
||||||
#endif
|
#endif
|
||||||
case SOURCE_TIME:
|
|
||||||
|
|
||||||
break;
|
|
||||||
#ifdef FEATURE_ENABLE_CAN
|
#ifdef FEATURE_ENABLE_CAN
|
||||||
case SOURCE_CAN:
|
if (LubeConfig.SpeedSource != SOURCE_IMPULSE)
|
||||||
|
{
|
||||||
Init_CAN();
|
Init_CAN();
|
||||||
break;
|
Serial.print("\nCAN-Init done");
|
||||||
#endif
|
|
||||||
default:
|
|
||||||
Debug_pushMessage("Source Setting N/A");
|
|
||||||
break;
|
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
Serial.print("\nSource-Init done");
|
||||||
pinMode(GPIO_BUTTON, INPUT_PULLUP);
|
pinMode(GPIO_BUTTON, INPUT_PULLUP);
|
||||||
pinMode(GPIO_PUMP, OUTPUT);
|
pinMode(GPIO_PUMP, OUTPUT);
|
||||||
|
|
||||||
@@ -148,17 +149,13 @@ void setup()
|
|||||||
u8x8.refreshDisplay(); });
|
u8x8.refreshDisplay(); });
|
||||||
#endif
|
#endif
|
||||||
ArduinoOTA.begin();
|
ArduinoOTA.begin();
|
||||||
|
Serial.print("\nOTA-Init done");
|
||||||
#ifdef FEATURE_ENABLE_OLED
|
|
||||||
u8x8.clearDisplay();
|
|
||||||
u8x8.drawString(0, 0, "KTM ChainLube V1");
|
|
||||||
u8x8.refreshDisplay();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
initWebUI();
|
initWebUI();
|
||||||
|
Serial.print("\nWebUI-Init done");
|
||||||
initGlobals();
|
initGlobals();
|
||||||
|
Serial.print("\nglobals-Init done");
|
||||||
EEPROMCyclicPDSTicker.start();
|
EEPROMCyclicPDSTicker.start();
|
||||||
Serial.println("Setup Done");
|
Serial.print("\nSetup Done\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop()
|
void loop()
|
||||||
@@ -175,8 +172,10 @@ void loop()
|
|||||||
wheelDistance = Process_CAN_WheelSpeed();
|
wheelDistance = Process_CAN_WheelSpeed();
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef FEATURE_ENABLE_TIMER
|
||||||
case SOURCE_TIME:
|
case SOURCE_TIME:
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
#ifdef FEATURE_ENABLE_GPS
|
#ifdef FEATURE_ENABLE_GPS
|
||||||
case SOURCE_GPS:
|
case SOURCE_GPS:
|
||||||
wheelDistance = Process_GPS_WheelSpeed();
|
wheelDistance = Process_GPS_WheelSpeed();
|
||||||
@@ -187,12 +186,19 @@ void loop()
|
|||||||
RunLubeApp(wheelDistance);
|
RunLubeApp(wheelDistance);
|
||||||
#ifdef FEATURE_ENABLE_OLED
|
#ifdef FEATURE_ENABLE_OLED
|
||||||
Display_Process();
|
Display_Process();
|
||||||
|
#endif
|
||||||
|
#ifdef FEATURE_ENABLE_CAN
|
||||||
|
if (LubeConfig.SpeedSource != SOURCE_IMPULSE)
|
||||||
|
{
|
||||||
|
CAN_Process();
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
Button_Process();
|
Button_Process();
|
||||||
LED_Process();
|
LED_Process();
|
||||||
EEPROM_Process();
|
EEPROM_Process();
|
||||||
Webserver_Process();
|
Webserver_Process();
|
||||||
DTC_Process();
|
DTC_Process();
|
||||||
|
Debug_Process();
|
||||||
|
|
||||||
ArduinoOTA.handle();
|
ArduinoOTA.handle();
|
||||||
EEPROMCyclicPDSTicker.update();
|
EEPROMCyclicPDSTicker.update();
|
||||||
@@ -247,7 +253,7 @@ void trigger_ISR()
|
|||||||
wheel_pulse++;
|
wheel_pulse++;
|
||||||
}
|
}
|
||||||
|
|
||||||
void LED_Process(uint8_t override, CRGB SetColor)
|
void LED_Process(uint8_t override, uint32_t SetColor)
|
||||||
{
|
{
|
||||||
typedef enum
|
typedef enum
|
||||||
{
|
{
|
||||||
@@ -258,16 +264,18 @@ void LED_Process(uint8_t override, CRGB SetColor)
|
|||||||
LED_Confirm_Rain,
|
LED_Confirm_Rain,
|
||||||
LED_Purge,
|
LED_Purge,
|
||||||
LED_Error,
|
LED_Error,
|
||||||
|
LED_Shutdown,
|
||||||
LED_Override
|
LED_Override
|
||||||
} tLED_Status;
|
} tLED_Status;
|
||||||
|
|
||||||
static tSystem_Status oldSysStatus = sysStat_Startup;
|
static tSystem_Status oldSysStatus = sysStat_Startup;
|
||||||
static tLED_Status LED_Status = LED_Startup;
|
static tLED_Status LED_Status = LED_Startup;
|
||||||
static CRGB LED_override_color = 0;
|
static uint32_t LED_override_color = 0;
|
||||||
static tLED_Status LED_ResumeOverrideStatus = LED_Startup;
|
static tLED_Status LED_ResumeOverrideStatus = LED_Startup;
|
||||||
|
|
||||||
uint8_t color = 0;
|
uint8_t color = 0;
|
||||||
uint32_t timer = 0;
|
uint32_t timer = 0;
|
||||||
|
uint32_t animtimer = 0;
|
||||||
static uint32_t timestamp = 0;
|
static uint32_t timestamp = 0;
|
||||||
timer = millis();
|
timer = millis();
|
||||||
|
|
||||||
@@ -276,7 +284,7 @@ void LED_Process(uint8_t override, CRGB SetColor)
|
|||||||
if (LED_Status != LED_Override)
|
if (LED_Status != LED_Override)
|
||||||
{
|
{
|
||||||
LED_ResumeOverrideStatus = LED_Status;
|
LED_ResumeOverrideStatus = LED_Status;
|
||||||
Debug_pushMessage("Override LED_Status");
|
Debug_pushMessage("Override LED_Status\n");
|
||||||
}
|
}
|
||||||
LED_Status = LED_Override;
|
LED_Status = LED_Override;
|
||||||
LED_override_color = SetColor;
|
LED_override_color = SetColor;
|
||||||
@@ -287,7 +295,7 @@ void LED_Process(uint8_t override, CRGB SetColor)
|
|||||||
if (LED_Status == LED_Override)
|
if (LED_Status == LED_Override)
|
||||||
{
|
{
|
||||||
LED_Status = LED_ResumeOverrideStatus;
|
LED_Status = LED_ResumeOverrideStatus;
|
||||||
Debug_pushMessage("Resume LED_Status");
|
Debug_pushMessage("Resume LED_Status\n");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -297,27 +305,30 @@ void LED_Process(uint8_t override, CRGB SetColor)
|
|||||||
{
|
{
|
||||||
case sysStat_Startup:
|
case sysStat_Startup:
|
||||||
LED_Status = LED_Startup;
|
LED_Status = LED_Startup;
|
||||||
Debug_pushMessage("sysStat: Startup");
|
Debug_pushMessage("sysStat: Startup\n");
|
||||||
break;
|
break;
|
||||||
case sysStat_Normal:
|
case sysStat_Normal:
|
||||||
timestamp = timer + 3500;
|
timestamp = timer + 3500;
|
||||||
LED_Status = LED_Confirm_Normal;
|
LED_Status = LED_Confirm_Normal;
|
||||||
Debug_pushMessage("sysStat: Normal");
|
Debug_pushMessage("sysStat: Normal\n");
|
||||||
break;
|
break;
|
||||||
case sysStat_Rain:
|
case sysStat_Rain:
|
||||||
timestamp = timer + 3500;
|
timestamp = timer + 3500;
|
||||||
LED_Status = LED_Confirm_Rain;
|
LED_Status = LED_Confirm_Rain;
|
||||||
Debug_pushMessage("sysStat: Rain");
|
Debug_pushMessage("sysStat: Rain\n");
|
||||||
break;
|
break;
|
||||||
case sysStat_Purge:
|
case sysStat_Purge:
|
||||||
LED_Status = LED_Purge;
|
LED_Status = LED_Purge;
|
||||||
Debug_pushMessage("sysStat: Purge");
|
Debug_pushMessage("sysStat: Purge\n");
|
||||||
break;
|
break;
|
||||||
case sysStat_Error:
|
case sysStat_Error:
|
||||||
LED_Status = LED_Error;
|
LED_Status = LED_Error;
|
||||||
Debug_pushMessage("sysStat: Error");
|
Debug_pushMessage("sysStat: Error\n");
|
||||||
break;
|
break;
|
||||||
case sysStat_Shutdown:
|
case sysStat_Shutdown:
|
||||||
|
LED_Status = LED_Shutdown;
|
||||||
|
Debug_pushMessage("sysStat: Shutdown\n");
|
||||||
|
break;
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@@ -327,84 +338,105 @@ void LED_Process(uint8_t override, CRGB SetColor)
|
|||||||
switch (LED_Status)
|
switch (LED_Status)
|
||||||
{
|
{
|
||||||
case LED_Startup:
|
case LED_Startup:
|
||||||
FastLED.setBrightness(255);
|
leds.setBrightness(LubeConfig.LED_Max_Brightness);
|
||||||
|
|
||||||
if (globals.TankPercentage < LubeConfig.TankRemindAtPercentage)
|
if (globals.TankPercentage < LubeConfig.TankRemindAtPercentage)
|
||||||
leds[0] = CRGB::OrangeRed;
|
leds.setPixelColor(0, LED_STARTUP_TANKWARN);
|
||||||
else
|
else
|
||||||
leds[0] = CRGB::White;
|
leds.setPixelColor(0, LED_STARTUP_NORMAL);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case LED_Confirm_Normal:
|
case LED_Confirm_Normal:
|
||||||
FastLED.setBrightness(255);
|
animtimer = timer % 500;
|
||||||
leds[0] = timer % 250 > 125 ? CRGB(0, 255, 0) : CRGB(0, 4, 0);
|
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)
|
if (timestamp < timer)
|
||||||
{
|
{
|
||||||
LED_Status = LED_Normal;
|
LED_Status = LED_Normal;
|
||||||
FastLED.setBrightness(64);
|
Debug_pushMessage("LED_Status: Confirm -> Normal\n");
|
||||||
Debug_pushMessage("LED_Status: Confirm -> Normal");
|
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case LED_Normal:
|
case LED_Normal:
|
||||||
#ifndef NO_MODE_FLASH
|
leds.setBrightness(LubeConfig.LED_Min_Brightness);
|
||||||
if (timer % 2000 > 1950)
|
leds.setPixelColor(0, LED_NORMAL_COLOR);
|
||||||
leds[0] = CRGB(0, 255, 0);
|
|
||||||
else if (WiFi.getMode() != WIFI_OFF && timer % 2000 > 1800 && timer % 2000 < 1850)
|
if (timer % 2000 > 1950 && LubeConfig.LED_Mode_Flash == true)
|
||||||
#else
|
leds.setBrightness(LubeConfig.LED_Max_Brightness);
|
||||||
if (WiFi.getMode() != WIFI_OFF && timer % 2000 > 1950)
|
else if (timer % 2000 > 1500 && WiFi.getMode() != WIFI_OFF)
|
||||||
#endif
|
leds.setPixelColor(0, LED_WIFI_BLINK);
|
||||||
leds[0] = CRGB(255, 128, 0);
|
|
||||||
else
|
|
||||||
leds[0] = CRGB(0, 4, 0);
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case LED_Confirm_Rain:
|
case LED_Confirm_Rain:
|
||||||
FastLED.setBrightness(255);
|
animtimer = timer % 500;
|
||||||
leds[0] = timer % 250 > 125 ? CRGB(0, 0, 255) : CRGB(0, 0, 4);
|
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)
|
if (timestamp < timer)
|
||||||
{
|
{
|
||||||
LED_Status = LED_Rain;
|
LED_Status = LED_Rain;
|
||||||
FastLED.setBrightness(64);
|
Debug_pushMessage("LED_Status: Confirm -> Rain\n");
|
||||||
Debug_pushMessage("LED_Status: Confirm -> Rain");
|
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case LED_Rain:
|
case LED_Rain:
|
||||||
#ifndef NO_MODE_FLASH
|
leds.setBrightness(LubeConfig.LED_Min_Brightness);
|
||||||
if (timer % 2000 > 1950)
|
leds.setPixelColor(0, LED_RAIN_COLOR);
|
||||||
leds[0] = CRGB(0, 0, 255);
|
|
||||||
else if (WiFi.getMode() != WIFI_OFF && timer % 2000 > 1800 && timer % 2000 < 1850)
|
if (timer % 2000 > 1950 && LubeConfig.LED_Mode_Flash == true)
|
||||||
#else
|
leds.setBrightness(LubeConfig.LED_Max_Brightness);
|
||||||
if (WiFi.getMode() != WIFI_OFF && timer % 2000 > 1950)
|
else if (timer % 2000 > 1500 && WiFi.getMode() != WIFI_OFF)
|
||||||
#endif
|
leds.setPixelColor(0, LED_WIFI_BLINK);
|
||||||
leds[0] = CRGB(255, 128, 0);
|
|
||||||
else
|
|
||||||
leds[0] = CRGB(0, 0, 4);
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case LED_Purge:
|
case LED_Purge:
|
||||||
timer = timer % 500;
|
timer = timer % 500;
|
||||||
color = timer / 2;
|
color = map(timer / 2, 0, 250, LubeConfig.LED_Min_Brightness, LubeConfig.LED_Max_Brightness);
|
||||||
leds[0] = CRGB::DeepPink;
|
leds.setPixelColor(0, LED_PURGE_COLOR);
|
||||||
if (timer < 250)
|
if (timer < 250)
|
||||||
FastLED.setBrightness(color);
|
leds.setBrightness(color);
|
||||||
else
|
else
|
||||||
FastLED.setBrightness(250 - color);
|
leds.setBrightness(LubeConfig.LED_Max_Brightness - color);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case LED_Error:
|
case LED_Error:
|
||||||
leds[0] = timer % 500 > 250 ? CRGB::Red : CRGB::Black;
|
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;
|
break;
|
||||||
|
|
||||||
case LED_Override:
|
case LED_Override:
|
||||||
leds[0] = LED_override_color;
|
leds.setBrightness(LubeConfig.LED_Max_Brightness);
|
||||||
|
leds.setPixelColor(0, LED_override_color);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
FastLED.show();
|
leds.show();
|
||||||
}
|
}
|
||||||
#ifdef FEATURE_ENABLE_OLED
|
#ifdef FEATURE_ENABLE_OLED
|
||||||
void Display_Process()
|
void Display_Process()
|
||||||
@@ -468,22 +500,22 @@ void Button_Process()
|
|||||||
|
|
||||||
if (buttonTimestamp + BUTTON_ACTION_DELAY_NOTHING < millis())
|
if (buttonTimestamp + BUTTON_ACTION_DELAY_NOTHING < millis())
|
||||||
{
|
{
|
||||||
LED_Process(1, CRGB::White);
|
LED_Process(1, COLOR_WARM_WHITE);
|
||||||
buttonAction = BTN_NOTHING;
|
buttonAction = BTN_NOTHING;
|
||||||
}
|
}
|
||||||
else if (buttonTimestamp + BUTTON_ACTION_DELAY_WIFI < millis())
|
else if (buttonTimestamp + BUTTON_ACTION_DELAY_WIFI < millis())
|
||||||
{
|
{
|
||||||
LED_Process(1, CRGB::Yellow);
|
LED_Process(1, LED_WIFI_BLINK);
|
||||||
buttonAction = BTN_TOGGLEWIFI;
|
buttonAction = BTN_TOGGLEWIFI;
|
||||||
}
|
}
|
||||||
else if (buttonTimestamp + BUTTON_ACTION_DELAY_PURGE < millis())
|
else if (buttonTimestamp + BUTTON_ACTION_DELAY_PURGE < millis())
|
||||||
{
|
{
|
||||||
LED_Process(1, CRGB::DeepPink);
|
LED_Process(1, LED_PURGE_COLOR);
|
||||||
buttonAction = BTN_STARTPURGE;
|
buttonAction = BTN_STARTPURGE;
|
||||||
}
|
}
|
||||||
else if (buttonTimestamp + BUTTON_ACTION_DELAY_TOGGLEMODE < millis())
|
else if (buttonTimestamp + BUTTON_ACTION_DELAY_TOGGLEMODE < millis())
|
||||||
{
|
{
|
||||||
CRGB color = globals.systemStatus == sysStat_Normal ? CRGB::Blue : CRGB::Green;
|
uint32_t color = globals.systemStatus == sysStat_Normal ? LED_RAIN_COLOR : LED_NORMAL_COLOR;
|
||||||
LED_Process(1, color);
|
LED_Process(1, color);
|
||||||
buttonAction = BTN_TOGGLEMODE;
|
buttonAction = BTN_TOGGLEMODE;
|
||||||
}
|
}
|
||||||
@@ -496,13 +528,13 @@ void Button_Process()
|
|||||||
{
|
{
|
||||||
case BTN_TOGGLEWIFI:
|
case BTN_TOGGLEWIFI:
|
||||||
toggleWiFiAP();
|
toggleWiFiAP();
|
||||||
Debug_pushMessage("Starting WiFi AP");
|
Debug_pushMessage("Starting WiFi AP\n");
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case BTN_STARTPURGE:
|
case BTN_STARTPURGE:
|
||||||
globals.systemStatus = sysStat_Purge;
|
globals.systemStatus = sysStat_Purge;
|
||||||
globals.purgePulses = LubeConfig.BleedingPulses;
|
globals.purgePulses = LubeConfig.BleedingPulses;
|
||||||
Debug_pushMessage("Starting Purge");
|
Debug_pushMessage("Starting Purge\n");
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case BTN_TOGGLEMODE:
|
case BTN_TOGGLEMODE:
|
||||||
@@ -520,12 +552,12 @@ void Button_Process()
|
|||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
Debug_pushMessage("Toggling Mode");
|
Debug_pushMessage("Toggling Mode\n");
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case BTN_NOTHING:
|
case BTN_NOTHING:
|
||||||
default:
|
default:
|
||||||
Debug_pushMessage("Nothing or invalid");
|
Debug_pushMessage("Nothing or invalid\n");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
LED_Process(2);
|
LED_Process(2);
|
||||||
@@ -540,7 +572,7 @@ void toggleWiFiAP(boolean shutdown)
|
|||||||
if (WiFi.getMode() != WIFI_OFF)
|
if (WiFi.getMode() != WIFI_OFF)
|
||||||
{
|
{
|
||||||
WiFi.mode(WIFI_OFF);
|
WiFi.mode(WIFI_OFF);
|
||||||
Debug_pushMessage("WiFi turned off");
|
Debug_pushMessage("WiFi turned off\n");
|
||||||
#ifdef FEATURE_ENABLE_WIFI_CLIENT
|
#ifdef FEATURE_ENABLE_WIFI_CLIENT
|
||||||
WiFiMaintainConnectionTicker.stop();
|
WiFiMaintainConnectionTicker.stop();
|
||||||
#endif
|
#endif
|
||||||
@@ -552,9 +584,9 @@ void toggleWiFiAP(boolean shutdown)
|
|||||||
WiFi.softAP(globals.DeviceName, QUOTE(WIFI_AP_PASSWORD));
|
WiFi.softAP(globals.DeviceName, QUOTE(WIFI_AP_PASSWORD));
|
||||||
#ifdef FEATURE_ENABLE_WIFI_CLIENT
|
#ifdef FEATURE_ENABLE_WIFI_CLIENT
|
||||||
WiFiMaintainConnectionTicker.stop();
|
WiFiMaintainConnectionTicker.stop();
|
||||||
Debug_pushMessage("WiFi AP started, stopped Maintain-Timer");
|
Debug_pushMessage("WiFi AP started, stopped Maintain-Timer\n");
|
||||||
#else
|
#else
|
||||||
Debug_pushMessage("WiFi AP started");
|
Debug_pushMessage("WiFi AP started\n");
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -578,11 +610,15 @@ void SystemShutdown()
|
|||||||
|
|
||||||
uint32_t Process_Impulse_WheelSpeed()
|
uint32_t Process_Impulse_WheelSpeed()
|
||||||
{
|
{
|
||||||
uint32_t add_milimeters;
|
uint32_t add_milimeters = 0;
|
||||||
// Calculate traveled Distance in mm
|
// Calculate traveled Distance in mm
|
||||||
add_milimeters = (wheel_pulse * (LubeConfig.DistancePerRevolution_mm / LubeConfig.PulsePerRevolution));
|
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;
|
wheel_pulse = 0;
|
||||||
|
|
||||||
return add_milimeters;
|
return add_milimeters;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@@ -19,6 +19,7 @@ AsyncWebSocket webSocket("/ws");
|
|||||||
|
|
||||||
void WebsocketEvent_Callback(AsyncWebSocket *server, AsyncWebSocketClient *client, AwsEventType type, void *arg, uint8_t *data, size_t len);
|
void WebsocketEvent_Callback(AsyncWebSocket *server, AsyncWebSocketClient *client, AwsEventType type, void *arg, uint8_t *data, size_t len);
|
||||||
void Websocket_HandleMessage(void *arg, uint8_t *data, size_t len);
|
void Websocket_HandleMessage(void *arg, uint8_t *data, size_t len);
|
||||||
|
void Websocket_RefreshClientData_DTCs();
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -27,15 +28,17 @@ void initWebUI()
|
|||||||
if (!LittleFS.begin())
|
if (!LittleFS.begin())
|
||||||
{
|
{
|
||||||
Debug_pushMessage("An Error has occurred while mounting LittleFS\n");
|
Debug_pushMessage("An Error has occurred while mounting LittleFS\n");
|
||||||
MaintainDTC(DTC_FLASHFS_ERROR, DTC_CRITICAL, true);
|
MaintainDTC(DTC_FLASHFS_ERROR, true);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
GetFlashVersion(globals.FlashVersion, sizeof(globals.FlashVersion));
|
GetFlashVersion(globals.FlashVersion, sizeof(globals.FlashVersion));
|
||||||
|
|
||||||
if (strcmp(globals.FlashVersion, QUOTE(FLASH_FS_VERSION)))
|
char buffer[6];
|
||||||
|
snprintf(buffer, sizeof(buffer), "%d.%02d", constants.Required_Flash_Version_major, constants.Required_Flash_Version_minor);
|
||||||
|
if (strcmp(globals.FlashVersion, buffer))
|
||||||
{
|
{
|
||||||
MaintainDTC(DTC_FLASHFS_VERSION_ERROR, DTC_WARN, true);
|
MaintainDTC(DTC_FLASHFS_VERSION_ERROR, true);
|
||||||
}
|
}
|
||||||
|
|
||||||
MDNS.begin(globals.DeviceName);
|
MDNS.begin(globals.DeviceName);
|
||||||
@@ -70,6 +73,8 @@ void Webserver_Process()
|
|||||||
|
|
||||||
String processor(const String &var)
|
String processor(const String &var)
|
||||||
{
|
{
|
||||||
|
if (var == "HOSTNAME")
|
||||||
|
return String(globals.DeviceName);
|
||||||
if (var == "TANK_REMAIN_CAPACITY")
|
if (var == "TANK_REMAIN_CAPACITY")
|
||||||
return String((PersistenceData.tankRemain_microL / 10) / LubeConfig.tankCapacity_ml);
|
return String((PersistenceData.tankRemain_microL / 10) / LubeConfig.tankCapacity_ml);
|
||||||
if (var == "LUBE_DISTANCE_NORMAL")
|
if (var == "LUBE_DISTANCE_NORMAL")
|
||||||
@@ -108,6 +113,16 @@ String processor(const String &var)
|
|||||||
#else
|
#else
|
||||||
return "Feature N/A";
|
return "Feature N/A";
|
||||||
#endif
|
#endif
|
||||||
|
if (var == "LED_MODE_FLASH")
|
||||||
|
return String(LubeConfig.LED_Mode_Flash);
|
||||||
|
if (var == "LEDFLASHCHECKED")
|
||||||
|
return String(LubeConfig.LED_Mode_Flash == true ? "checked" : "");
|
||||||
|
if (var == "LED_MAX_BRIGHTNESS")
|
||||||
|
return String(LubeConfig.LED_Max_Brightness);
|
||||||
|
if (var == "LED_MIN_BRIGHTNESS")
|
||||||
|
return String(LubeConfig.LED_Min_Brightness);
|
||||||
|
if (var == "EEPROM_VERSION")
|
||||||
|
return String(LubeConfig.EEPROM_Version);
|
||||||
if (var == "CONFIG_CHECKSUM")
|
if (var == "CONFIG_CHECKSUM")
|
||||||
{
|
{
|
||||||
char buffer[7];
|
char buffer[7];
|
||||||
@@ -169,7 +184,7 @@ String processor(const String &var)
|
|||||||
temp = temp + " data-debugval=" + String(DTCStorage[i].debugVal) + "><td>" + String(buff_timestamp);
|
temp = temp + " data-debugval=" + String(DTCStorage[i].debugVal) + "><td>" + String(buff_timestamp);
|
||||||
temp = temp + "</td><td>" + String(DTCStorage[i].Number) + "</td><td>";
|
temp = temp + "</td><td>" + String(DTCStorage[i].Number) + "</td><td>";
|
||||||
temp = temp + "<img src=static/img/";
|
temp = temp + "<img src=static/img/";
|
||||||
switch (DTCStorage[i].severity)
|
switch (getSeverityForDTC(DTCStorage[i].Number))
|
||||||
{
|
{
|
||||||
case DTC_CRITICAL:
|
case DTC_CRITICAL:
|
||||||
temp = temp + "critical";
|
temp = temp + "critical";
|
||||||
@@ -180,6 +195,9 @@ String processor(const String &var)
|
|||||||
case DTC_INFO:
|
case DTC_INFO:
|
||||||
temp = temp + "info";
|
temp = temp + "info";
|
||||||
break;
|
break;
|
||||||
|
case DTC_NONE:
|
||||||
|
temp = temp + "none";
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
temp = temp + ".png></td><td>";
|
temp = temp + ".png></td><td>";
|
||||||
|
|
||||||
@@ -219,7 +237,7 @@ String processor(const String &var)
|
|||||||
return temp;
|
return temp;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#ifdef FEATURE_EABLE_GPS
|
#ifdef FEATURE_ENABLE_GPS
|
||||||
if (var == "GPSBAUD_SELECT_OPTIONS")
|
if (var == "GPSBAUD_SELECT_OPTIONS")
|
||||||
{
|
{
|
||||||
String temp;
|
String temp;
|
||||||
@@ -234,13 +252,26 @@ String processor(const String &var)
|
|||||||
|
|
||||||
if (var == "SYSTEM_STATUS")
|
if (var == "SYSTEM_STATUS")
|
||||||
return String(globals.systemStatustxt);
|
return String(globals.systemStatustxt);
|
||||||
|
|
||||||
if (var == "SW_VERSION")
|
if (var == "SW_VERSION")
|
||||||
{
|
{
|
||||||
return String(QUOTE(SW_VERSION));
|
char buffer[6];
|
||||||
|
snprintf(buffer, sizeof(buffer), "%d.%02d", constants.FW_Version_major, constants.FW_Version_minor);
|
||||||
|
return String(buffer);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (var == "FS_VERSION")
|
if (var == "FS_VERSION")
|
||||||
return String(globals.FlashVersion);
|
return String(globals.FlashVersion);
|
||||||
|
|
||||||
|
if (var == "GIT_REV")
|
||||||
|
return String(constants.GitHash);
|
||||||
|
|
||||||
|
if (var == "MEASURED_PULSES")
|
||||||
|
return String(globals.measuredPulses);
|
||||||
|
|
||||||
|
if (var == "MEASURE_BTN")
|
||||||
|
return String(globals.measurementActive == true ? "Stop" : "Start");
|
||||||
|
|
||||||
if (var == "PLACEHOLDER")
|
if (var == "PLACEHOLDER")
|
||||||
return "placeholder";
|
return "placeholder";
|
||||||
|
|
||||||
@@ -288,7 +319,7 @@ 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
|
#ifdef FEATURE_ENABLE_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();
|
||||||
@@ -296,7 +327,7 @@ void WebserverPOST_Callback(AsyncWebServerRequest *request)
|
|||||||
globals.requestEEAction = EE_CFG_SAVE;
|
globals.requestEEAction = EE_CFG_SAVE;
|
||||||
// end: POST Form Source GPS Settings
|
// end: POST Form Source GPS Settings
|
||||||
#endif
|
#endif
|
||||||
#ifdef FEATURE_EABLE_CAN
|
#ifdef FEATURE_ENABLE_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();
|
||||||
@@ -357,6 +388,32 @@ void WebserverPOST_Callback(AsyncWebServerRequest *request)
|
|||||||
globals.systemStatus = sysStat_Shutdown;
|
globals.systemStatus = sysStat_Shutdown;
|
||||||
}
|
}
|
||||||
// end: POST Form Maintenance
|
// end: POST Form Maintenance
|
||||||
|
// begin: POST Form LED Settings
|
||||||
|
if (p->name() == "ledmaxbrightness")
|
||||||
|
LubeConfig.LED_Max_Brightness = p->value().toInt();
|
||||||
|
if (p->name() == "ledminbrightness")
|
||||||
|
LubeConfig.LED_Min_Brightness = p->value().toInt();
|
||||||
|
if (p->name() == "ledsave")
|
||||||
|
{
|
||||||
|
if (request->hasParam("ledmodeflash", true))
|
||||||
|
{
|
||||||
|
AsyncWebParameter *param = request->getParam("ledmodeflash", true);
|
||||||
|
if (param->value() == "on")
|
||||||
|
LubeConfig.LED_Mode_Flash = true;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
LubeConfig.LED_Mode_Flash = false;
|
||||||
|
}
|
||||||
|
globals.requestEEAction = EE_CFG_SAVE;
|
||||||
|
}
|
||||||
|
// end: POST Form LED SEttings
|
||||||
|
// begin: POST Form Measure Pulses
|
||||||
|
if (p->name() == "measurereset")
|
||||||
|
globals.measuredPulses = 0;
|
||||||
|
if (p->name() == "measurestartstop")
|
||||||
|
globals.measurementActive = !globals.measurementActive;
|
||||||
|
// end: POST Form Measure Pulses
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -426,28 +483,84 @@ void WebserverFirmwareUpdate_Callback(AsyncWebServerRequest *request, const Stri
|
|||||||
|
|
||||||
void WebserverEERestore_Callback(AsyncWebServerRequest *request, const String &filename, size_t index, uint8_t *data, size_t len, bool final)
|
void WebserverEERestore_Callback(AsyncWebServerRequest *request, const String &filename, size_t index, uint8_t *data, size_t len, bool final)
|
||||||
{
|
{
|
||||||
|
|
||||||
bool ee_done = false;
|
bool ee_done = false;
|
||||||
bool validext = false;
|
static bool validext = false;
|
||||||
|
static char *buffer = NULL;
|
||||||
|
static uint32_t read_ptr = 0;
|
||||||
|
DeserializationError error;
|
||||||
|
|
||||||
if (!index)
|
if (!index)
|
||||||
{
|
{
|
||||||
Debug_pushMessage("EEPROM restore\n");
|
|
||||||
// size_t content_len = request->contentLength();
|
|
||||||
validext = (filename.indexOf(".ee.json") > -1);
|
validext = (filename.indexOf(".ee.json") > -1);
|
||||||
|
if (validext)
|
||||||
|
{
|
||||||
|
buffer = (char *)malloc(1536);
|
||||||
|
read_ptr = 0;
|
||||||
|
if (buffer == NULL)
|
||||||
|
Debug_pushMessage("malloc() failed for EEPROM-Restore");
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (validext)
|
if (buffer != NULL)
|
||||||
{
|
{
|
||||||
Debug_pushMessage("Restoring EEPROM-Stuff\n");
|
memcpy(buffer + read_ptr, data, len);
|
||||||
|
read_ptr = read_ptr + len;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (final)
|
if (final)
|
||||||
{
|
{
|
||||||
|
if (buffer != NULL)
|
||||||
|
{
|
||||||
|
Serial.print(buffer);
|
||||||
|
StaticJsonDocument<1536> doc;
|
||||||
|
error = deserializeJson(doc, buffer);
|
||||||
|
if (error)
|
||||||
|
{
|
||||||
|
Debug_pushMessage("deserializeJson() failed: %s\n", error.f_str());
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
|
||||||
|
LubeConfig.DistancePerLube_Default = doc["config"]["DistancePerLube_Default"].as<uint32_t>();
|
||||||
|
LubeConfig.DistancePerLube_Rain = doc["config"]["DistancePerLube_Rain"].as<uint32_t>();
|
||||||
|
LubeConfig.tankCapacity_ml = doc["config"]["tankCapacity_ml"].as<uint32_t>();
|
||||||
|
LubeConfig.amountPerDose_microL = doc["config"]["amountPerDose_microL"].as<uint32_t>();
|
||||||
|
LubeConfig.TankRemindAtPercentage = doc["config"]["TankRemindAtPercentage"].as<uint8_t>();
|
||||||
|
LubeConfig.PulsePerRevolution = doc["config"]["PulsePerRevolution"].as<uint8_t>();
|
||||||
|
LubeConfig.TireWidth_mm = doc["config"]["TireWidth_mm"].as<uint32_t>();
|
||||||
|
LubeConfig.TireWidthHeight_Ratio = doc["config"]["TireWidthHeight_Ratio"].as<uint32_t>();
|
||||||
|
LubeConfig.RimDiameter_Inch = doc["config"]["RimDiameter_Inch"].as<uint32_t>();
|
||||||
|
LubeConfig.DistancePerRevolution_mm = doc["config"]["DistancePerRevolution_mm"].as<uint32_t>();
|
||||||
|
LubeConfig.BleedingPulses = doc["config"]["BleedingPulses"].as<uint16_t>();
|
||||||
|
LubeConfig.SpeedSource = (SpeedSource_t)doc["config"]["SpeedSource"].as<int>();
|
||||||
|
#ifdef FEATURE_ENABLE_GPS
|
||||||
|
LubeConfig.GPSBaudRate = (GPSBaudRate_t)doc["config"]["GPSBaudRate"].as<int>();
|
||||||
|
#endif
|
||||||
|
#ifdef FEATURE_ENABLE_CAN
|
||||||
|
LubeConfig.CANSource = (CANSource_t)doc["config"]["CANSource"].as<int>();
|
||||||
|
#endif
|
||||||
|
LubeConfig.LED_Mode_Flash = doc["config"]["LED_Mode_Flash"].as<bool>();
|
||||||
|
LubeConfig.LED_Max_Brightness = doc["config"]["LED_Max_Brightness"].as<uint8_t>();
|
||||||
|
LubeConfig.LED_Min_Brightness = doc["config"]["LED_Min_Brightness"].as<uint8_t>();
|
||||||
|
|
||||||
|
PersistenceData.writeCycleCounter = doc["persis"]["writeCycleCounter"].as<uint16_t>();
|
||||||
|
PersistenceData.tankRemain_microL = doc["persis"]["tankRemain_microL"].as<uint32_t>();
|
||||||
|
PersistenceData.TravelDistance_highRes_mm = doc["persis"]["TravelDistance_highRes_mm"].as<uint32_t>();
|
||||||
|
PersistenceData.odometer_mm = doc["persis"]["odometer_mm"].as<uint32_t>();
|
||||||
|
PersistenceData.odometer = doc["persis"]["odometer"].as<uint32_t>();
|
||||||
|
PersistenceData.checksum = doc["persis"]["checksum"].as<uint32_t>();
|
||||||
|
|
||||||
|
ee_done = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
free(buffer);
|
||||||
|
|
||||||
AsyncWebServerResponse *response = request->beginResponse(302, "text/plain", "Please wait while the device reboots");
|
AsyncWebServerResponse *response = request->beginResponse(302, "text/plain", "Please wait while the device reboots");
|
||||||
response->addHeader("Refresh", "20");
|
response->addHeader("Refresh", "20");
|
||||||
response->addHeader("Location", "/");
|
response->addHeader("Location", "/");
|
||||||
request->send(response);
|
request->send(response);
|
||||||
|
|
||||||
if (ee_done)
|
if (ee_done)
|
||||||
{
|
{
|
||||||
Debug_pushMessage("Update complete");
|
Debug_pushMessage("Update complete");
|
||||||
@@ -468,8 +581,11 @@ void WebServerEEJSON_Callback(AsyncWebServerRequest *request)
|
|||||||
char buffer[16];
|
char buffer[16];
|
||||||
|
|
||||||
fwinfo["DeviceName"] = globals.DeviceName;
|
fwinfo["DeviceName"] = globals.DeviceName;
|
||||||
fwinfo["FW-Version"] = QUOTE(SW_VERSION);
|
sprintf(buffer, "%d.%02d", constants.Required_Flash_Version_major, constants.Required_Flash_Version_minor);
|
||||||
|
fwinfo["FW-Version"] = buffer;
|
||||||
fwinfo["FS-Version"] = globals.FlashVersion;
|
fwinfo["FS-Version"] = globals.FlashVersion;
|
||||||
|
snprintf_P(buffer, sizeof(buffer), "%s", constants.GitHash);
|
||||||
|
fwinfo["Git-Hash"] = buffer;
|
||||||
|
|
||||||
JsonObject config = json.createNestedObject("config");
|
JsonObject config = json.createNestedObject("config");
|
||||||
|
|
||||||
@@ -495,6 +611,9 @@ void WebServerEEJSON_Callback(AsyncWebServerRequest *request)
|
|||||||
config["CANSource"] = LubeConfig.CANSource;
|
config["CANSource"] = LubeConfig.CANSource;
|
||||||
config["CANSource_Str"] = CANSourceString[LubeConfig.CANSource];
|
config["CANSource_Str"] = CANSourceString[LubeConfig.CANSource];
|
||||||
#endif
|
#endif
|
||||||
|
config["LED_Mode_Flash"] = LubeConfig.LED_Mode_Flash;
|
||||||
|
config["LED_Max_Brightness"] = LubeConfig.LED_Max_Brightness;
|
||||||
|
config["LED_Min_Brightness"] = LubeConfig.LED_Min_Brightness;
|
||||||
sprintf(buffer, "0x%08X", LubeConfig.checksum);
|
sprintf(buffer, "0x%08X", LubeConfig.checksum);
|
||||||
config["checksum"] = buffer;
|
config["checksum"] = buffer;
|
||||||
|
|
||||||
|
Reference in New Issue
Block a user