Compare commits
12 Commits
PCB_Rev_1.
...
PCB_Rev_1.
Author | SHA1 | Date | |
---|---|---|---|
f3ce691b7d | |||
aefbdc43bc | |||
08c00efbdf | |||
cdbeb2b8c3 | |||
cfc6b144f3 | |||
e1ca503bd2 | |||
d68b562126 | |||
2217d68026 | |||
acb3c97c02 | |||
70ea944dc3 | |||
cff7c7b29c | |||
ea4895c262 |
1
Hardware/.gitignore
vendored
1
Hardware/.gitignore
vendored
@@ -28,3 +28,4 @@ fp-info-cache
|
|||||||
*.csv
|
*.csv
|
||||||
|
|
||||||
gerber/
|
gerber/
|
||||||
|
*-backups/
|
BIN
Hardware/BOM_Reichelt.xls.xlsx
Normal file
BIN
Hardware/BOM_Reichelt.xls.xlsx
Normal file
Binary file not shown.
74603
Hardware/Device.kicad_sym
Normal file
74603
Hardware/Device.kicad_sym
Normal file
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
443
Hardware/oiler SMD.kicad_pro
Normal file
443
Hardware/oiler SMD.kicad_pro
Normal file
@@ -0,0 +1,443 @@
|
|||||||
|
{
|
||||||
|
"board": {
|
||||||
|
"design_settings": {
|
||||||
|
"defaults": {
|
||||||
|
"board_outline_line_width": 0.049999999999999996,
|
||||||
|
"copper_line_width": 0.19999999999999998,
|
||||||
|
"copper_text_italic": false,
|
||||||
|
"copper_text_size_h": 1.5,
|
||||||
|
"copper_text_size_v": 1.5,
|
||||||
|
"copper_text_thickness": 0.3,
|
||||||
|
"copper_text_upright": false,
|
||||||
|
"courtyard_line_width": 0.049999999999999996,
|
||||||
|
"dimension_precision": 4,
|
||||||
|
"dimension_units": 3,
|
||||||
|
"dimensions": {
|
||||||
|
"arrow_length": 1270000,
|
||||||
|
"extension_offset": 500000,
|
||||||
|
"keep_text_aligned": true,
|
||||||
|
"suppress_zeroes": false,
|
||||||
|
"text_position": 0,
|
||||||
|
"units_format": 1
|
||||||
|
},
|
||||||
|
"fab_line_width": 0.09999999999999999,
|
||||||
|
"fab_text_italic": false,
|
||||||
|
"fab_text_size_h": 1.0,
|
||||||
|
"fab_text_size_v": 1.0,
|
||||||
|
"fab_text_thickness": 0.15,
|
||||||
|
"fab_text_upright": false,
|
||||||
|
"other_line_width": 0.09999999999999999,
|
||||||
|
"other_text_italic": false,
|
||||||
|
"other_text_size_h": 1.0,
|
||||||
|
"other_text_size_v": 1.0,
|
||||||
|
"other_text_thickness": 0.15,
|
||||||
|
"other_text_upright": false,
|
||||||
|
"pads": {
|
||||||
|
"drill": 0.762,
|
||||||
|
"height": 1.524,
|
||||||
|
"width": 1.524
|
||||||
|
},
|
||||||
|
"silk_line_width": 0.12,
|
||||||
|
"silk_text_italic": false,
|
||||||
|
"silk_text_size_h": 1.0,
|
||||||
|
"silk_text_size_v": 1.0,
|
||||||
|
"silk_text_thickness": 0.15,
|
||||||
|
"silk_text_upright": false,
|
||||||
|
"zones": {
|
||||||
|
"45_degree_only": false,
|
||||||
|
"min_clearance": 0.19999999999999998
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"diff_pair_dimensions": [],
|
||||||
|
"drc_exclusions": [],
|
||||||
|
"meta": {
|
||||||
|
"filename": "board_design_settings.json",
|
||||||
|
"version": 2
|
||||||
|
},
|
||||||
|
"rule_severities": {
|
||||||
|
"annular_width": "error",
|
||||||
|
"clearance": "error",
|
||||||
|
"copper_edge_clearance": "error",
|
||||||
|
"courtyards_overlap": "error",
|
||||||
|
"diff_pair_gap_out_of_range": "error",
|
||||||
|
"diff_pair_uncoupled_length_too_long": "error",
|
||||||
|
"drill_out_of_range": "error",
|
||||||
|
"duplicate_footprints": "warning",
|
||||||
|
"extra_footprint": "warning",
|
||||||
|
"footprint_type_mismatch": "error",
|
||||||
|
"hole_clearance": "error",
|
||||||
|
"hole_near_hole": "error",
|
||||||
|
"invalid_outline": "error",
|
||||||
|
"item_on_disabled_layer": "error",
|
||||||
|
"items_not_allowed": "error",
|
||||||
|
"length_out_of_range": "error",
|
||||||
|
"malformed_courtyard": "error",
|
||||||
|
"microvia_drill_out_of_range": "error",
|
||||||
|
"missing_courtyard": "ignore",
|
||||||
|
"missing_footprint": "warning",
|
||||||
|
"net_conflict": "warning",
|
||||||
|
"npth_inside_courtyard": "ignore",
|
||||||
|
"padstack": "error",
|
||||||
|
"pth_inside_courtyard": "ignore",
|
||||||
|
"shorting_items": "error",
|
||||||
|
"silk_over_copper": "warning",
|
||||||
|
"silk_overlap": "warning",
|
||||||
|
"skew_out_of_range": "error",
|
||||||
|
"through_hole_pad_without_hole": "error",
|
||||||
|
"too_many_vias": "error",
|
||||||
|
"track_dangling": "warning",
|
||||||
|
"track_width": "error",
|
||||||
|
"tracks_crossing": "error",
|
||||||
|
"unconnected_items": "error",
|
||||||
|
"unresolved_variable": "error",
|
||||||
|
"via_dangling": "warning",
|
||||||
|
"zone_has_empty_net": "error",
|
||||||
|
"zones_intersect": "error"
|
||||||
|
},
|
||||||
|
"rule_severitieslegacy_courtyards_overlap": true,
|
||||||
|
"rule_severitieslegacy_no_courtyard_defined": false,
|
||||||
|
"rules": {
|
||||||
|
"allow_blind_buried_vias": false,
|
||||||
|
"allow_microvias": false,
|
||||||
|
"max_error": 0.005,
|
||||||
|
"min_clearance": 0.0,
|
||||||
|
"min_copper_edge_clearance": 0.049999999999999996,
|
||||||
|
"min_hole_clearance": 0.25,
|
||||||
|
"min_hole_to_hole": 0.25,
|
||||||
|
"min_microvia_diameter": 0.19999999999999998,
|
||||||
|
"min_microvia_drill": 0.09999999999999999,
|
||||||
|
"min_silk_clearance": 0.0,
|
||||||
|
"min_through_hole_diameter": 0.3,
|
||||||
|
"min_track_width": 0.19999999999999998,
|
||||||
|
"min_via_annular_width": 0.049999999999999996,
|
||||||
|
"min_via_diameter": 0.39999999999999997,
|
||||||
|
"use_height_for_length_calcs": true
|
||||||
|
},
|
||||||
|
"track_widths": [
|
||||||
|
0.0,
|
||||||
|
0.5,
|
||||||
|
1.0,
|
||||||
|
2.0
|
||||||
|
],
|
||||||
|
"via_dimensions": [
|
||||||
|
{
|
||||||
|
"diameter": 0.0,
|
||||||
|
"drill": 0.0
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"diameter": 0.7,
|
||||||
|
"drill": 0.35
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"diameter": 1.0,
|
||||||
|
"drill": 0.6
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"diameter": 2.0,
|
||||||
|
"drill": 1.0
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"zones_allow_external_fillets": false,
|
||||||
|
"zones_use_no_outline": true
|
||||||
|
},
|
||||||
|
"layer_presets": []
|
||||||
|
},
|
||||||
|
"boards": [],
|
||||||
|
"cvpcb": {
|
||||||
|
"equivalence_files": []
|
||||||
|
},
|
||||||
|
"erc": {
|
||||||
|
"erc_exclusions": [],
|
||||||
|
"meta": {
|
||||||
|
"version": 0
|
||||||
|
},
|
||||||
|
"pin_map": [
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
2,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
1,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2
|
||||||
|
]
|
||||||
|
],
|
||||||
|
"rule_severities": {
|
||||||
|
"bus_definition_conflict": "error",
|
||||||
|
"bus_entry_needed": "error",
|
||||||
|
"bus_label_syntax": "error",
|
||||||
|
"bus_to_bus_conflict": "error",
|
||||||
|
"bus_to_net_conflict": "error",
|
||||||
|
"different_unit_footprint": "error",
|
||||||
|
"different_unit_net": "error",
|
||||||
|
"duplicate_reference": "error",
|
||||||
|
"duplicate_sheet_names": "error",
|
||||||
|
"extra_units": "error",
|
||||||
|
"global_label_dangling": "warning",
|
||||||
|
"hier_label_mismatch": "error",
|
||||||
|
"label_dangling": "error",
|
||||||
|
"lib_symbol_issues": "warning",
|
||||||
|
"multiple_net_names": "warning",
|
||||||
|
"net_not_bus_member": "warning",
|
||||||
|
"no_connect_connected": "warning",
|
||||||
|
"no_connect_dangling": "warning",
|
||||||
|
"pin_not_connected": "error",
|
||||||
|
"pin_not_driven": "error",
|
||||||
|
"pin_to_pin": "warning",
|
||||||
|
"power_pin_not_driven": "error",
|
||||||
|
"similar_labels": "warning",
|
||||||
|
"unannotated": "error",
|
||||||
|
"unit_value_mismatch": "error",
|
||||||
|
"unresolved_variable": "error",
|
||||||
|
"wire_dangling": "error"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"libraries": {
|
||||||
|
"pinned_footprint_libs": [],
|
||||||
|
"pinned_symbol_libs": []
|
||||||
|
},
|
||||||
|
"meta": {
|
||||||
|
"filename": "oiler SMD.kicad_pro",
|
||||||
|
"version": 1
|
||||||
|
},
|
||||||
|
"net_settings": {
|
||||||
|
"classes": [
|
||||||
|
{
|
||||||
|
"bus_width": 12.0,
|
||||||
|
"clearance": 0.2,
|
||||||
|
"diff_pair_gap": 0.25,
|
||||||
|
"diff_pair_via_gap": 0.25,
|
||||||
|
"diff_pair_width": 0.2,
|
||||||
|
"line_style": 0,
|
||||||
|
"microvia_diameter": 0.3,
|
||||||
|
"microvia_drill": 0.1,
|
||||||
|
"name": "Default",
|
||||||
|
"pcb_color": "rgba(0, 0, 0, 0.000)",
|
||||||
|
"schematic_color": "rgba(0, 0, 0, 0.000)",
|
||||||
|
"track_width": 0.25,
|
||||||
|
"via_diameter": 0.8,
|
||||||
|
"via_drill": 0.4,
|
||||||
|
"wire_width": 6.0
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"meta": {
|
||||||
|
"version": 2
|
||||||
|
},
|
||||||
|
"net_colors": null
|
||||||
|
},
|
||||||
|
"pcbnew": {
|
||||||
|
"last_paths": {
|
||||||
|
"gencad": "",
|
||||||
|
"idf": "",
|
||||||
|
"netlist": "Rehoiler SMD.net",
|
||||||
|
"specctra_dsn": "",
|
||||||
|
"step": "",
|
||||||
|
"vrml": ""
|
||||||
|
},
|
||||||
|
"page_layout_descr_file": ""
|
||||||
|
},
|
||||||
|
"schematic": {
|
||||||
|
"annotate_start_num": 0,
|
||||||
|
"drawing": {
|
||||||
|
"default_line_thickness": 6.0,
|
||||||
|
"default_text_size": 50.0,
|
||||||
|
"field_names": [],
|
||||||
|
"intersheets_ref_own_page": false,
|
||||||
|
"intersheets_ref_prefix": "",
|
||||||
|
"intersheets_ref_short": false,
|
||||||
|
"intersheets_ref_show": false,
|
||||||
|
"intersheets_ref_suffix": "",
|
||||||
|
"junction_size_choice": 3,
|
||||||
|
"label_size_ratio": 0.25,
|
||||||
|
"pin_symbol_size": 25.0,
|
||||||
|
"text_offset_ratio": 0.08
|
||||||
|
},
|
||||||
|
"legacy_lib_dir": "",
|
||||||
|
"legacy_lib_list": [],
|
||||||
|
"meta": {
|
||||||
|
"version": 1
|
||||||
|
},
|
||||||
|
"net_format_name": "Pcbnew",
|
||||||
|
"ngspice": {
|
||||||
|
"fix_include_paths": true,
|
||||||
|
"fix_passive_vals": false,
|
||||||
|
"meta": {
|
||||||
|
"version": 0
|
||||||
|
},
|
||||||
|
"model_mode": 0,
|
||||||
|
"workbook_filename": ""
|
||||||
|
},
|
||||||
|
"page_layout_descr_file": "",
|
||||||
|
"plot_directory": "",
|
||||||
|
"spice_adjust_passive_values": false,
|
||||||
|
"spice_external_command": "spice \"%I\"",
|
||||||
|
"subpart_first_id": 65,
|
||||||
|
"subpart_id_separator": 0
|
||||||
|
},
|
||||||
|
"sheets": [
|
||||||
|
[
|
||||||
|
"b1ddb058-f7b2-429c-9489-f4e2242ad7e5",
|
||||||
|
""
|
||||||
|
]
|
||||||
|
],
|
||||||
|
"text_variables": {}
|
||||||
|
}
|
3381
Hardware/oiler SMD.kicad_sch
Normal file
3381
Hardware/oiler SMD.kicad_sch
Normal file
File diff suppressed because it is too large
Load Diff
@@ -26,10 +26,12 @@ upload_speed = 921600
|
|||||||
|
|
||||||
build_flags =
|
build_flags =
|
||||||
!python git_rev_macro.py
|
!python git_rev_macro.py
|
||||||
|
-DWIFI_NOCLIENT
|
||||||
-DWIFI_SSID=${wifi_cred.wifi_ssid}
|
-DWIFI_SSID=${wifi_cred.wifi_ssid}
|
||||||
-DWIFI_PASSWORD=${wifi_cred.wifi_password}
|
-DWIFI_PASSWORD=${wifi_cred.wifi_password}
|
||||||
-DADMIN_PASSWORD=${wifi_cred.admin_password}
|
-DADMIN_PASSWORD=${wifi_cred.admin_password}
|
||||||
-DWIFI_AP_PASSWORD=${wifi_cred.wifi_ap_password}
|
-DWIFI_AP_PASSWORD=${wifi_cred.wifi_ap_password}
|
||||||
|
-DWIFI_AP_IP_GW=10,0,0,1
|
||||||
|
|
||||||
board_build.filesystem = littlefs
|
board_build.filesystem = littlefs
|
||||||
|
|
||||||
|
@@ -17,6 +17,7 @@ typedef struct
|
|||||||
uint32_t TireWidthHeight_Ratio = 70;
|
uint32_t TireWidthHeight_Ratio = 70;
|
||||||
uint32_t RimDiameter_Inch = 18;
|
uint32_t RimDiameter_Inch = 18;
|
||||||
uint32_t DistancePerRevolution_mm = 2000;
|
uint32_t DistancePerRevolution_mm = 2000;
|
||||||
|
uint8_t BleedingPulses = 25;
|
||||||
uint32_t checksum = 0;
|
uint32_t checksum = 0;
|
||||||
} LubeConfig_t;
|
} LubeConfig_t;
|
||||||
|
|
||||||
|
@@ -13,11 +13,13 @@ typedef enum eSystem_Status
|
|||||||
sysStat_Error
|
sysStat_Error
|
||||||
} tSystem_Status;
|
} tSystem_Status;
|
||||||
|
|
||||||
typedef struct Globals_t {
|
|
||||||
|
typedef struct Globals_s {
|
||||||
tSystem_Status systemStatus = sysStat_Startup;
|
tSystem_Status systemStatus = sysStat_Startup;
|
||||||
uint8_t purgePulses= 0;
|
uint8_t purgePulses= 0;
|
||||||
tSystem_Status resumeStatus = sysStat_Startup;
|
tSystem_Status resumeStatus = sysStat_Startup;
|
||||||
};
|
char systemStatustxt[16] = "";
|
||||||
|
}Globals_t;
|
||||||
|
|
||||||
extern Globals_t globals;
|
extern Globals_t globals;
|
||||||
extern uint32_t TravelDistance_highRes;
|
extern uint32_t TravelDistance_highRes;
|
||||||
|
@@ -1,13 +1,9 @@
|
|||||||
#include "lubeapp.h"
|
#include "lubeapp.h"
|
||||||
|
|
||||||
extern void LED_Process(tSystem_Status newStatus = sysStat_NOP);
|
|
||||||
|
|
||||||
uint32_t lubePulseTimestamp = 0;
|
uint32_t lubePulseTimestamp = 0;
|
||||||
|
|
||||||
void RunLubeApp(volatile uint32_t *wheelPulseCounter)
|
void RunLubeApp(volatile uint32_t *wheelPulseCounter)
|
||||||
{
|
{
|
||||||
uint32_t LubeDistance = 0;
|
|
||||||
|
|
||||||
// Calculate traveled Distance in mm
|
// Calculate traveled Distance in mm
|
||||||
TravelDistance_highRes += (*wheelPulseCounter * (LubeConfig.DistancePerRevolution_mm / LubeConfig.PulsePerRevolution));
|
TravelDistance_highRes += (*wheelPulseCounter * (LubeConfig.DistancePerRevolution_mm / LubeConfig.PulsePerRevolution));
|
||||||
*wheelPulseCounter = 0;
|
*wheelPulseCounter = 0;
|
||||||
@@ -16,8 +12,11 @@ void RunLubeApp(volatile uint32_t *wheelPulseCounter)
|
|||||||
switch (globals.systemStatus)
|
switch (globals.systemStatus)
|
||||||
{
|
{
|
||||||
case sysStat_Startup:
|
case sysStat_Startup:
|
||||||
globals.systemStatus = sysStat_Normal;
|
if (millis() > STARTUP_DELAY)
|
||||||
globals.resumeStatus = sysStat_Normal;
|
{
|
||||||
|
globals.systemStatus = sysStat_Normal;
|
||||||
|
globals.resumeStatus = sysStat_Normal;
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case sysStat_Normal:
|
case sysStat_Normal:
|
||||||
@@ -38,7 +37,7 @@ void RunLubeApp(volatile uint32_t *wheelPulseCounter)
|
|||||||
case sysStat_Purge:
|
case sysStat_Purge:
|
||||||
if (globals.purgePulses > 0)
|
if (globals.purgePulses > 0)
|
||||||
{
|
{
|
||||||
if (lubePulseTimestamp + LUBE_PULSE_LENGHT_MS + LUBE_PULSE_PAUSE_MS < millis())
|
if (lubePulseTimestamp + LUBE_PULSE_PAUSE_MS < millis())
|
||||||
{
|
{
|
||||||
LubePulse();
|
LubePulse();
|
||||||
globals.purgePulses--;
|
globals.purgePulses--;
|
||||||
@@ -49,6 +48,25 @@ void RunLubeApp(volatile uint32_t *wheelPulseCounter)
|
|||||||
globals.systemStatus = globals.resumeStatus;
|
globals.systemStatus = globals.resumeStatus;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
case sysStat_Error:
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (globals.systemStatus)
|
||||||
|
{
|
||||||
|
case sysStat_Normal:
|
||||||
|
strcpy(globals.systemStatustxt, "Normal");
|
||||||
|
break;
|
||||||
|
case sysStat_Purge:
|
||||||
|
strcpy(globals.systemStatustxt, "Purge");
|
||||||
|
break;
|
||||||
|
case sysStat_Rain:
|
||||||
|
strcpy(globals.systemStatustxt, "Rain");
|
||||||
|
break;
|
||||||
|
case sysStat_Startup:
|
||||||
|
strcpy(globals.systemStatustxt, "Startup");
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
// maintain Pin-State of Lube-Pump
|
// maintain Pin-State of Lube-Pump
|
||||||
|
@@ -2,12 +2,14 @@
|
|||||||
#define _LUBEAPP_H_
|
#define _LUBEAPP_H_
|
||||||
|
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
|
#include <stdlib.h>
|
||||||
#include "config.h"
|
#include "config.h"
|
||||||
#include "common.h"
|
#include "common.h"
|
||||||
#include "globals.h"
|
#include "globals.h"
|
||||||
|
|
||||||
#define LUBE_PULSE_LENGHT_MS 250
|
#define LUBE_PULSE_LENGHT_MS 160
|
||||||
#define LUBE_PULSE_PAUSE_MS 250
|
#define LUBE_PULSE_PAUSE_MS 100
|
||||||
|
#define STARTUP_DELAY 5000
|
||||||
|
|
||||||
void RunLubeApp(volatile uint32_t * wheelPulseCounter);
|
void RunLubeApp(volatile uint32_t * wheelPulseCounter);
|
||||||
void LubePulse();
|
void LubePulse();
|
||||||
|
@@ -2,7 +2,6 @@
|
|||||||
#include <Wire.h>
|
#include <Wire.h>
|
||||||
#include <U8g2lib.h>
|
#include <U8g2lib.h>
|
||||||
#include <ESP8266WiFi.h>
|
#include <ESP8266WiFi.h>
|
||||||
#include <ESP8266WiFiMulti.h>
|
|
||||||
#include <ESP8266mDNS.h>
|
#include <ESP8266mDNS.h>
|
||||||
#include <ArduinoOTA.h>
|
#include <ArduinoOTA.h>
|
||||||
#include <RemoteDebug.h>
|
#include <RemoteDebug.h>
|
||||||
@@ -16,11 +15,17 @@
|
|||||||
#include "config.h"
|
#include "config.h"
|
||||||
#include "globals.h"
|
#include "globals.h"
|
||||||
|
|
||||||
|
#ifdef WIFI_CLIENT
|
||||||
|
#include <ESP8266WiFiMulti.h>
|
||||||
|
|
||||||
const char *ssid = QUOTE(WIFI_SSID);
|
const char *ssid = QUOTE(WIFI_SSID);
|
||||||
const char *password = QUOTE(WIFI_PASSWORD);
|
const char *password = QUOTE(WIFI_PASSWORD);
|
||||||
|
|
||||||
const uint32_t connectTimeoutMs = 5000;
|
const uint32_t connectTimeoutMs = 5000;
|
||||||
|
|
||||||
|
ESP8266WiFiMulti wifiMulti;
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef DEBUG
|
#ifdef DEBUG
|
||||||
const bool debug_flag = true;
|
const bool debug_flag = true;
|
||||||
#else
|
#else
|
||||||
@@ -36,7 +41,6 @@ volatile uint32_t wheel_pulse = 0;
|
|||||||
|
|
||||||
U8X8_SSD1306_128X64_NONAME_HW_I2C u8x8(-1);
|
U8X8_SSD1306_128X64_NONAME_HW_I2C u8x8(-1);
|
||||||
RemoteDebug Debug;
|
RemoteDebug Debug;
|
||||||
ESP8266WiFiMulti wifiMulti;
|
|
||||||
CRGB leds[1];
|
CRGB leds[1];
|
||||||
|
|
||||||
// Function-Prototypes
|
// Function-Prototypes
|
||||||
@@ -44,12 +48,18 @@ String IpAddress2String(const IPAddress &ipAddress);
|
|||||||
void processCmdRemoteDebug();
|
void processCmdRemoteDebug();
|
||||||
void RemotDebug_printSystemInfo();
|
void RemotDebug_printSystemInfo();
|
||||||
void RemoteDebug_printWifiInfo();
|
void RemoteDebug_printWifiInfo();
|
||||||
void wifiMaintainConnectionTicker_callback();
|
void updateWebUITicker_callback();
|
||||||
void IRAM_ATTR trigger_ISR();
|
void IRAM_ATTR trigger_ISR();
|
||||||
void LED_Process(tSystem_Status newStatus = sysStat_NOP);
|
void LED_Process(uint8_t override = false, CRGB setColor = CRGB::White);
|
||||||
void DisplayProcess();
|
void Display_Process();
|
||||||
|
void Button_Process();
|
||||||
|
void startWiFiAP();
|
||||||
|
|
||||||
|
#ifdef WIFI_CLIENT
|
||||||
|
void wifiMaintainConnectionTicker_callback();
|
||||||
Ticker WiFiMaintainConnectionTicker(wifiMaintainConnectionTicker_callback, 1000, 0, MILLIS);
|
Ticker WiFiMaintainConnectionTicker(wifiMaintainConnectionTicker_callback, 1000, 0, MILLIS);
|
||||||
|
#endif
|
||||||
|
Ticker UpdateWebUITicker(updateWebUITicker_callback, 5000, 0, MILLIS);
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
@@ -57,9 +67,17 @@ void setup()
|
|||||||
|
|
||||||
snprintf(DeviceName, 32, HOST_NAME, ESP.getChipId());
|
snprintf(DeviceName, 32, HOST_NAME, ESP.getChipId());
|
||||||
|
|
||||||
WiFi.mode(WIFI_OFF);
|
|
||||||
WiFi.persistent(false);
|
WiFi.persistent(false);
|
||||||
|
|
||||||
|
#ifdef WIFI_CLIENT
|
||||||
|
WiFi.mode(WIFI_STA);
|
||||||
|
WiFi.setHostname(DeviceName);
|
||||||
|
wifiMulti.addAP(QUOTE(WIFI_SSID), QUOTE(WIFI_PASSWORD));
|
||||||
|
WiFiMaintainConnectionTicker.start();
|
||||||
|
#else
|
||||||
|
WiFi.mode(WIFI_OFF);
|
||||||
|
#endif
|
||||||
|
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
Serial.setDebugOutput(true);
|
Serial.setDebugOutput(true);
|
||||||
|
|
||||||
@@ -79,12 +97,6 @@ void setup()
|
|||||||
|
|
||||||
attachInterrupt(digitalPinToInterrupt(GPIO_TRIGGER), trigger_ISR, FALLING);
|
attachInterrupt(digitalPinToInterrupt(GPIO_TRIGGER), trigger_ISR, FALLING);
|
||||||
|
|
||||||
WiFi.mode(WIFI_STA);
|
|
||||||
WiFi.setHostname(DeviceName);
|
|
||||||
wifiMulti.addAP(QUOTE(WIFI_SSID), QUOTE(WIFI_PASSWORD));
|
|
||||||
|
|
||||||
WiFiMaintainConnectionTicker.start();
|
|
||||||
|
|
||||||
if (MDNS.begin(DeviceName))
|
if (MDNS.begin(DeviceName))
|
||||||
MDNS.addService("telnet", "tcp", 23);
|
MDNS.addService("telnet", "tcp", 23);
|
||||||
|
|
||||||
@@ -135,19 +147,23 @@ void setup()
|
|||||||
u8x8.refreshDisplay();
|
u8x8.refreshDisplay();
|
||||||
|
|
||||||
initWebUI();
|
initWebUI();
|
||||||
|
UpdateWebUITicker.start();
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
LED_Process(globals.systemStatus);
|
|
||||||
RunLubeApp(&wheel_pulse);
|
RunLubeApp(&wheel_pulse);
|
||||||
|
UpdateWebUITicker.update();
|
||||||
|
|
||||||
WiFiMaintainConnectionTicker.update();
|
Display_Process();
|
||||||
|
Button_Process();
|
||||||
DisplayProcess();
|
LED_Process();
|
||||||
|
|
||||||
ArduinoOTA.handle();
|
ArduinoOTA.handle();
|
||||||
Debug.handle();
|
Debug.handle();
|
||||||
|
#ifdef WIFI_CLIENT
|
||||||
|
WiFiMaintainConnectionTicker.update();
|
||||||
|
#endif
|
||||||
yield();
|
yield();
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -194,6 +210,7 @@ void RemoteDebug_printWifiInfo()
|
|||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef WIFI_CLIENT
|
||||||
void wifiMaintainConnectionTicker_callback()
|
void wifiMaintainConnectionTicker_callback()
|
||||||
{
|
{
|
||||||
static uint32_t WiFiFailCount = 0;
|
static uint32_t WiFiFailCount = 0;
|
||||||
@@ -211,21 +228,24 @@ void wifiMaintainConnectionTicker_callback()
|
|||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
Serial.println("WiFi not connected! - Start AP");
|
debugV("WiFi not connected! - Start AP");
|
||||||
WiFi.mode(WIFI_OFF);
|
startWiFiAP();
|
||||||
WiFi.softAP(DeviceName, QUOTE(WIFI_AP_PASSWORD));
|
|
||||||
WiFiMaintainConnectionTicker.stop();
|
|
||||||
Serial.println("WiFi AP started, stopped Maintain-Timer");
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
void updateWebUITicker_callback()
|
||||||
|
{
|
||||||
|
UpdateWebUI();
|
||||||
|
}
|
||||||
|
|
||||||
void trigger_ISR()
|
void trigger_ISR()
|
||||||
{
|
{
|
||||||
wheel_pulse++;
|
wheel_pulse++;
|
||||||
}
|
}
|
||||||
|
|
||||||
void LED_Process(tSystem_Status newSysStatus)
|
void LED_Process(uint8_t override, CRGB SetColor)
|
||||||
{
|
{
|
||||||
|
|
||||||
typedef enum
|
typedef enum
|
||||||
@@ -236,59 +256,94 @@ void LED_Process(tSystem_Status newSysStatus)
|
|||||||
LED_Rain,
|
LED_Rain,
|
||||||
LED_Confirm_Rain,
|
LED_Confirm_Rain,
|
||||||
LED_Purge,
|
LED_Purge,
|
||||||
LED_Error
|
LED_Error,
|
||||||
|
LED_Override
|
||||||
} tLED_Status;
|
} tLED_Status;
|
||||||
|
|
||||||
static tSystem_Status oldSysStatus = sysStat_NOP;
|
static tSystem_Status oldSysStatus = sysStat_NOP;
|
||||||
static tLED_Status LED_Status = LED_Startup;
|
static tLED_Status LED_Status = LED_Startup;
|
||||||
|
static CRGB LED_override_color = 0;
|
||||||
|
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 timestamp = 0;
|
static uint32_t timestamp = 0;
|
||||||
|
timer = millis();
|
||||||
|
|
||||||
if (oldSysStatus != newSysStatus)
|
if (override == 1)
|
||||||
{
|
{
|
||||||
switch (newSysStatus)
|
if (LED_Status != LED_Override)
|
||||||
|
{
|
||||||
|
LED_ResumeOverrideStatus = LED_Status;
|
||||||
|
debugV("Override LED_Status");
|
||||||
|
}
|
||||||
|
LED_Status = LED_Override;
|
||||||
|
LED_override_color = SetColor;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (override == 2)
|
||||||
|
{
|
||||||
|
if (LED_Status == LED_Override)
|
||||||
|
{
|
||||||
|
LED_Status = LED_ResumeOverrideStatus;
|
||||||
|
debugV("Resume LED_Status");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (oldSysStatus != globals.systemStatus)
|
||||||
|
{
|
||||||
|
switch (globals.systemStatus)
|
||||||
{
|
{
|
||||||
case sysStat_Startup:
|
case sysStat_Startup:
|
||||||
LED_Status = LED_Startup;
|
LED_Status = LED_Startup;
|
||||||
|
debugV("sysStat: Startup");
|
||||||
break;
|
break;
|
||||||
case sysStat_Normal:
|
case sysStat_Normal:
|
||||||
timestamp = millis() + 1500;
|
timestamp = timer + 3500;
|
||||||
LED_Status = LED_Confirm_Normal;
|
LED_Status = LED_Confirm_Normal;
|
||||||
|
debugV("sysStat: Normal");
|
||||||
break;
|
break;
|
||||||
case sysStat_Rain:
|
case sysStat_Rain:
|
||||||
timestamp = millis() + 1500;
|
timestamp = timer + 3500;
|
||||||
LED_Status = LED_Confirm_Rain;
|
LED_Status = LED_Confirm_Rain;
|
||||||
|
debugV("sysStat: Rain");
|
||||||
break;
|
break;
|
||||||
case sysStat_Purge:
|
case sysStat_Purge:
|
||||||
LED_Status = LED_Purge;
|
LED_Status = LED_Purge;
|
||||||
|
debugV("sysStat: Purge");
|
||||||
break;
|
break;
|
||||||
case sysStat_Error:
|
case sysStat_Error:
|
||||||
LED_Status = LED_Error;
|
LED_Status = LED_Error;
|
||||||
|
debugV("sysStat: Error");
|
||||||
|
break;
|
||||||
|
case sysStat_NOP:
|
||||||
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
oldSysStatus = newSysStatus;
|
oldSysStatus = globals.systemStatus;
|
||||||
}
|
}
|
||||||
|
|
||||||
timer = millis();
|
uint32_t percentage = LubeConfig.tankRemain_µl / (LubeConfig.tankCapacity_ml * 10);
|
||||||
|
|
||||||
switch (LED_Status)
|
switch (LED_Status)
|
||||||
{
|
{
|
||||||
case LED_Startup:
|
case LED_Startup:
|
||||||
FastLED.setBrightness(255);
|
FastLED.setBrightness(255);
|
||||||
timer = timer % 2000;
|
|
||||||
color = timer > 500 ? 0 : (uint8_t)(timer / 2);
|
if (percentage < LubeConfig.TankRemindAtPercentage)
|
||||||
leds[0] = CRGB(color, color, color);
|
leds[0] = CRGB::OrangeRed;
|
||||||
|
else
|
||||||
|
leds[0] = CRGB::White;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case LED_Confirm_Normal:
|
case LED_Confirm_Normal:
|
||||||
FastLED.setBrightness(255);
|
FastLED.setBrightness(255);
|
||||||
leds[0] = timer % 500 > 250 ? CRGB(0, 255, 0) : CRGB(0, 4, 0);
|
leds[0] = timer % 250 > 125 ? CRGB(0, 255, 0) : CRGB(0, 4, 0);
|
||||||
if (timestamp < timer)
|
if (timestamp < timer)
|
||||||
{
|
{
|
||||||
LED_Status = LED_Normal;
|
LED_Status = LED_Normal;
|
||||||
FastLED.setBrightness(64);
|
FastLED.setBrightness(64);
|
||||||
|
debugV("LED_Status: Confirm -> Normal");
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@@ -298,11 +353,12 @@ void LED_Process(tSystem_Status newSysStatus)
|
|||||||
|
|
||||||
case LED_Confirm_Rain:
|
case LED_Confirm_Rain:
|
||||||
FastLED.setBrightness(255);
|
FastLED.setBrightness(255);
|
||||||
leds[0] = timer % 500 > 250 ? CRGB(0, 0, 255) : CRGB(0, 0, 4);
|
leds[0] = timer % 250 > 125 ? CRGB(0, 0, 255) : CRGB(0, 0, 4);
|
||||||
if (timestamp < timer)
|
if (timestamp < timer)
|
||||||
{
|
{
|
||||||
LED_Status = LED_Rain;
|
LED_Status = LED_Rain;
|
||||||
FastLED.setBrightness(64);
|
FastLED.setBrightness(64);
|
||||||
|
debugV("LED_Status: Confirm -> Rain");
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@@ -324,19 +380,139 @@ void LED_Process(tSystem_Status newSysStatus)
|
|||||||
leds[0] = timer % 500 > 250 ? CRGB::Red : CRGB::Black;
|
leds[0] = timer % 500 > 250 ? CRGB::Red : CRGB::Black;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case LED_Override:
|
||||||
|
leds[0] = LED_override_color;
|
||||||
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
FastLED.show();
|
FastLED.show();
|
||||||
}
|
}
|
||||||
|
|
||||||
void DisplayProcess()
|
void Display_Process()
|
||||||
{
|
{
|
||||||
u8x8.setCursor(0, 3);
|
u8x8.setCursor(0, 3);
|
||||||
uint32_t DistRemain = globals.systemStatus == sysStat_Normal ? LubeConfig.DistancePerLube_Default : LubeConfig.DistancePerLube_Rain;
|
uint32_t DistRemain = globals.systemStatus == sysStat_Normal ? LubeConfig.DistancePerLube_Default : LubeConfig.DistancePerLube_Rain;
|
||||||
DistRemain -= TravelDistance_highRes / 1000;
|
DistRemain -= TravelDistance_highRes / 1000;
|
||||||
u8x8.printf("next Lube: %4dm\n", DistRemain);
|
u8x8.printf("Mode: %10s\n\n", globals.systemStatustxt);
|
||||||
u8x8.printf("Tank: %8dml\n", LubeConfig.tankRemain_µl / 1000);
|
u8x8.printf("next Lube: %4dm\n\n", DistRemain);
|
||||||
u8x8.printf("Purges: %8d\n", globals.purgePulses);
|
u8x8.printf("Tank: %8dml\n\n", LubeConfig.tankRemain_µl / 1000);
|
||||||
u8x8.refreshDisplay();
|
u8x8.refreshDisplay();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void Button_Process()
|
||||||
|
{
|
||||||
|
|
||||||
|
#define BUTTON_ACTION_DELAY_TOGGLEMODE 500
|
||||||
|
#define BUTTON_ACTION_DELAY_PURGE 3500
|
||||||
|
#define BUTTON_ACTION_DELAY_WIFI 6500
|
||||||
|
#define BUTTON_ACTION_DELAY_NOTHING 9500
|
||||||
|
|
||||||
|
typedef enum buttonAction_e
|
||||||
|
{
|
||||||
|
BTN_INACTIVE,
|
||||||
|
BTN_NOTHING,
|
||||||
|
BTN_TOGGLEMODE,
|
||||||
|
BTN_TOGGLEWIFI,
|
||||||
|
BTN_STARTPURGE
|
||||||
|
} buttonAction_t;
|
||||||
|
|
||||||
|
static uint32_t buttonTimestamp = 0;
|
||||||
|
static buttonAction_t buttonAction = BTN_INACTIVE;
|
||||||
|
|
||||||
|
if (digitalRead(GPIO_BUTTON) == LOW)
|
||||||
|
{
|
||||||
|
|
||||||
|
if (buttonTimestamp == 0)
|
||||||
|
buttonTimestamp = millis();
|
||||||
|
|
||||||
|
if (buttonTimestamp + BUTTON_ACTION_DELAY_NOTHING < millis())
|
||||||
|
{
|
||||||
|
LED_Process(1, CRGB::White);
|
||||||
|
buttonAction = BTN_NOTHING;
|
||||||
|
}
|
||||||
|
else if (buttonTimestamp + BUTTON_ACTION_DELAY_WIFI < millis())
|
||||||
|
{
|
||||||
|
LED_Process(1, CRGB::Yellow);
|
||||||
|
buttonAction = BTN_TOGGLEWIFI;
|
||||||
|
}
|
||||||
|
else if (buttonTimestamp + BUTTON_ACTION_DELAY_PURGE < millis())
|
||||||
|
{
|
||||||
|
LED_Process(1, CRGB::DeepPink);
|
||||||
|
buttonAction = BTN_STARTPURGE;
|
||||||
|
}
|
||||||
|
else if (buttonTimestamp + BUTTON_ACTION_DELAY_TOGGLEMODE < millis())
|
||||||
|
{
|
||||||
|
CRGB color = globals.systemStatus == sysStat_Normal ? CRGB::Blue : CRGB::Green;
|
||||||
|
LED_Process(1, color);
|
||||||
|
buttonAction = BTN_TOGGLEMODE;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
if (buttonAction != BTN_INACTIVE)
|
||||||
|
{
|
||||||
|
switch (buttonAction)
|
||||||
|
{
|
||||||
|
case BTN_TOGGLEWIFI:
|
||||||
|
startWiFiAP();
|
||||||
|
debugV("Starting WiFi AP");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case BTN_STARTPURGE:
|
||||||
|
globals.systemStatus = sysStat_Purge;
|
||||||
|
globals.purgePulses = LubeConfig.BleedingPulses;
|
||||||
|
debugV("Starting Purge");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case BTN_TOGGLEMODE:
|
||||||
|
switch (globals.systemStatus)
|
||||||
|
{
|
||||||
|
case sysStat_Normal:
|
||||||
|
globals.systemStatus = sysStat_Rain;
|
||||||
|
globals.resumeStatus = sysStat_Rain;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case sysStat_Rain:
|
||||||
|
globals.systemStatus = sysStat_Normal;
|
||||||
|
globals.resumeStatus = sysStat_Normal;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
debugV("Toggling Mode");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case BTN_NOTHING:
|
||||||
|
default:
|
||||||
|
debugV("Nothing or invalid");
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
LED_Process(2);
|
||||||
|
}
|
||||||
|
buttonAction = BTN_INACTIVE;
|
||||||
|
buttonTimestamp = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void startWiFiAP()
|
||||||
|
{
|
||||||
|
if (WiFi.getMode() != WIFI_OFF)
|
||||||
|
{
|
||||||
|
WiFi.mode(WIFI_OFF);
|
||||||
|
debugV("WiFi turned off");
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
WiFi.mode(WIFI_AP);
|
||||||
|
WiFi.softAPConfig(IPAddress(WIFI_AP_IP_GW), IPAddress(WIFI_AP_IP_GW), IPAddress(255, 255, 255, 0));
|
||||||
|
WiFi.softAP(DeviceName, QUOTE(WIFI_AP_PASSWORD));
|
||||||
|
#ifdef WIFI_CLIENT
|
||||||
|
WiFiMaintainConnectionTicker.stop();
|
||||||
|
debugV("WiFi AP started, stopped Maintain-Timer");
|
||||||
|
#else
|
||||||
|
debugV("WiFi AP started");
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
@@ -52,6 +52,8 @@ void SettingChanged_Callback(Control *sender, int type)
|
|||||||
LubeConfig.TankRemindAtPercentage = ESPUI.getControl(num_tank_notify)->value.toInt();
|
LubeConfig.TankRemindAtPercentage = ESPUI.getControl(num_tank_notify)->value.toInt();
|
||||||
else if (sender->id == num_dose_per_pulse)
|
else if (sender->id == num_dose_per_pulse)
|
||||||
LubeConfig.amountPerDose_µl = ESPUI.getControl(num_dose_per_pulse)->value.toInt();
|
LubeConfig.amountPerDose_µl = ESPUI.getControl(num_dose_per_pulse)->value.toInt();
|
||||||
|
else if (sender->id == num_purge_pulses)
|
||||||
|
LubeConfig.BleedingPulses = ESPUI.getControl(num_purge_pulses)->value.toInt();
|
||||||
}
|
}
|
||||||
|
|
||||||
void buttons_Callback(Control *sender, int type)
|
void buttons_Callback(Control *sender, int type)
|
||||||
@@ -76,9 +78,8 @@ void buttons_Callback(Control *sender, int type)
|
|||||||
|
|
||||||
if (sender->id == button_purge)
|
if (sender->id == button_purge)
|
||||||
{
|
{
|
||||||
int pulses = ESPUI.getControl(num_purge_pulses)->value.toInt();
|
Serial.printf("Starting to Purge with %d pulses", LubeConfig.BleedingPulses);
|
||||||
Serial.printf("Starting to Purge with %d pulses", pulses);
|
globals.purgePulses = LubeConfig.BleedingPulses;
|
||||||
globals.purgePulses = pulses;
|
|
||||||
globals.resumeStatus = globals.systemStatus;
|
globals.resumeStatus = globals.systemStatus;
|
||||||
globals.systemStatus = sysStat_Purge;
|
globals.systemStatus = sysStat_Purge;
|
||||||
}
|
}
|
||||||
@@ -120,7 +121,7 @@ void initWebUI()
|
|||||||
|
|
||||||
label_tankRemain = ESPUI.addControl(ControlType::Label, "Tankinhalt verbleibend (ml, geschätzt)", String(LubeConfig.tankRemain_µl / 1000), ControlColor::Alizarin, tab_maintenance);
|
label_tankRemain = ESPUI.addControl(ControlType::Label, "Tankinhalt verbleibend (ml, geschätzt)", String(LubeConfig.tankRemain_µl / 1000), ControlColor::Alizarin, tab_maintenance);
|
||||||
button_reset_tank = ESPUI.addControl(ControlType::Button, "Tankinhalt zurücksetzen", "Reset", ControlColor::Alizarin, tab_maintenance, &buttons_Callback);
|
button_reset_tank = ESPUI.addControl(ControlType::Button, "Tankinhalt zurücksetzen", "Reset", ControlColor::Alizarin, tab_maintenance, &buttons_Callback);
|
||||||
num_purge_pulses = ESPUI.addControl(ControlType::Number, "Entlüftung Impulse", "10", ControlColor::Alizarin, tab_maintenance);
|
num_purge_pulses = ESPUI.addControl(ControlType::Number, "Entlüftung Impulse", String(LubeConfig.BleedingPulses), ControlColor::Alizarin, tab_maintenance, &SettingChanged_Callback);
|
||||||
button_purge = ESPUI.addControl(ControlType::Button, "Leitung Entlüften", "Start", ControlColor::Alizarin, tab_maintenance, &buttons_Callback);
|
button_purge = ESPUI.addControl(ControlType::Button, "Leitung Entlüften", "Start", ControlColor::Alizarin, tab_maintenance, &buttons_Callback);
|
||||||
|
|
||||||
button_store = ESPUI.addControl(ControlType::Button, "Einstellungen permanent speichern", "Speichern", ControlColor::Turquoise, tab_store, &buttons_Callback);
|
button_store = ESPUI.addControl(ControlType::Button, "Einstellungen permanent speichern", "Speichern", ControlColor::Turquoise, tab_store, &buttons_Callback);
|
||||||
@@ -129,3 +130,8 @@ void initWebUI()
|
|||||||
|
|
||||||
ESPUI.begin("Souko's ChainLube Mk1");
|
ESPUI.begin("Souko's ChainLube Mk1");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void UpdateWebUI()
|
||||||
|
{
|
||||||
|
ESPUI.print(label_tankRemain, String(LubeConfig.tankRemain_µl / 1000) + " ml" );
|
||||||
|
}
|
@@ -7,6 +7,7 @@
|
|||||||
#include "globals.h"
|
#include "globals.h"
|
||||||
|
|
||||||
void initWebUI();
|
void initWebUI();
|
||||||
|
void UpdateWebUI();
|
||||||
|
|
||||||
|
|
||||||
#endif
|
#endif
|
Reference in New Issue
Block a user