Moved to ESP32 and added webinterface for PenConfiguration.
Not working and removed: - AccelStepper: Move to FastAccelStepper for ESP32 - Servo: Changed to ESP32 - check if that is ok - Serial Comm Interface now at 115200 -> change back to 9600 later
This commit is contained in:
311
src/Config_Web.cpp
Normal file
311
src/Config_Web.cpp
Normal file
@@ -0,0 +1,311 @@
|
||||
#include "EggDuino.h"
|
||||
#include <ArduinoJson.h>
|
||||
#include <DNSServer.h>
|
||||
|
||||
namespace {
|
||||
const char *kConfigPath = "/config.json";
|
||||
const char *kApSsid = "EggDuino";
|
||||
const uint16_t kDnsPort = 53;
|
||||
const IPAddress kApIp(192, 168, 4, 1);
|
||||
const IPAddress kApSubnet(255, 255, 255, 0);
|
||||
|
||||
WebServer server(80);
|
||||
DNSServer dnsServer;
|
||||
bool configStoreReady = false;
|
||||
|
||||
ConfigParameter *findParameter(const String &key) {
|
||||
for (size_t i = 0; i < configParameterCount; ++i) {
|
||||
if (key.equals(configParameters[i].key)) {
|
||||
return &configParameters[i];
|
||||
}
|
||||
}
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void applyDefaults() {
|
||||
for (size_t i = 0; i < configParameterCount; ++i) {
|
||||
*configParameters[i].value = configParameters[i].defaultValue;
|
||||
}
|
||||
}
|
||||
|
||||
void handleRoot() {
|
||||
static const char kPage[] PROGMEM = R"HTML(
|
||||
<!doctype html>
|
||||
<html lang="de">
|
||||
<head>
|
||||
<meta charset="utf-8" />
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1" />
|
||||
<title>EggDuino Konfiguration</title>
|
||||
<style>
|
||||
body { font-family: "Segoe UI", sans-serif; margin: 20px; background: #f3f6fb; color: #1a1a1a; }
|
||||
main { max-width: 560px; margin: 0 auto; background: #fff; border-radius: 12px; padding: 20px; box-shadow: 0 8px 24px rgba(0,0,0,0.08); }
|
||||
h1 { margin-top: 0; font-size: 1.35rem; }
|
||||
label { display: block; margin: 14px 0 6px; font-weight: 600; }
|
||||
input[type='number'] { width: 100%; padding: 10px; border: 1px solid #c7d2e5; border-radius: 8px; box-sizing: border-box; }
|
||||
button { margin-top: 18px; border: 0; background: #0b5ed7; color: white; padding: 10px 14px; border-radius: 8px; cursor: pointer; }
|
||||
#status { margin-top: 12px; min-height: 1.2em; }
|
||||
</style>
|
||||
</head>
|
||||
<body>
|
||||
<main>
|
||||
<h1>EggDuino Parameter</h1>
|
||||
<form id="cfgForm"></form>
|
||||
<button id="saveBtn" type="button">Speichern</button>
|
||||
<div id="status"></div>
|
||||
</main>
|
||||
<script>
|
||||
async function loadConfig() {
|
||||
const resp = await fetch('/api/config');
|
||||
if (!resp.ok) throw new Error('Konfiguration konnte nicht geladen werden');
|
||||
return resp.json();
|
||||
}
|
||||
|
||||
function renderForm(config) {
|
||||
const form = document.getElementById('cfgForm');
|
||||
form.innerHTML = '';
|
||||
(config.parameters || []).forEach(p => {
|
||||
const label = document.createElement('label');
|
||||
label.textContent = p.description || p.key;
|
||||
const input = document.createElement('input');
|
||||
input.type = 'number';
|
||||
input.value = p.value;
|
||||
input.dataset.key = p.key;
|
||||
form.appendChild(label);
|
||||
form.appendChild(input);
|
||||
});
|
||||
}
|
||||
|
||||
async function saveConfig() {
|
||||
const status = document.getElementById('status');
|
||||
const inputs = [...document.querySelectorAll('input[data-key]')];
|
||||
const payload = {
|
||||
parameters: inputs.map(i => ({ key: i.dataset.key, value: Number(i.value) }))
|
||||
};
|
||||
const resp = await fetch('/api/config', {
|
||||
method: 'POST',
|
||||
headers: { 'Content-Type': 'application/json' },
|
||||
body: JSON.stringify(payload)
|
||||
});
|
||||
if (!resp.ok) {
|
||||
const text = await resp.text();
|
||||
throw new Error(text || 'Speichern fehlgeschlagen');
|
||||
}
|
||||
status.textContent = 'Gespeichert';
|
||||
}
|
||||
|
||||
(async function init() {
|
||||
const status = document.getElementById('status');
|
||||
try {
|
||||
const cfg = await loadConfig();
|
||||
renderForm(cfg);
|
||||
status.textContent = 'Bereit';
|
||||
} catch (e) {
|
||||
status.textContent = e.message;
|
||||
}
|
||||
document.getElementById('saveBtn').addEventListener('click', async () => {
|
||||
try {
|
||||
await saveConfig();
|
||||
} catch (e) {
|
||||
status.textContent = e.message;
|
||||
}
|
||||
});
|
||||
})();
|
||||
</script>
|
||||
</body>
|
||||
</html>
|
||||
)HTML";
|
||||
|
||||
server.send(200, "text/html", kPage);
|
||||
}
|
||||
|
||||
void redirectToPortal() {
|
||||
server.sendHeader("Cache-Control", "no-cache, no-store, must-revalidate");
|
||||
server.sendHeader("Pragma", "no-cache");
|
||||
server.sendHeader("Expires", "-1");
|
||||
server.sendHeader("Location", String("http://") + WiFi.softAPIP().toString() + "/", true);
|
||||
server.send(302, "text/plain", "");
|
||||
}
|
||||
|
||||
void handleGetConfig() {
|
||||
if (!configStoreReady && !initConfigStore()) {
|
||||
server.send(500, "text/plain", "Config storage not available");
|
||||
return;
|
||||
}
|
||||
server.send(200, "application/json", buildConfigJson());
|
||||
}
|
||||
|
||||
void handlePostConfig() {
|
||||
if (!configStoreReady && !initConfigStore()) {
|
||||
server.send(500, "text/plain", "Config storage not available");
|
||||
return;
|
||||
}
|
||||
|
||||
if (!server.hasArg("plain")) {
|
||||
server.send(400, "text/plain", "Missing JSON body");
|
||||
return;
|
||||
}
|
||||
|
||||
String error;
|
||||
if (!applyConfigJson(server.arg("plain"), error)) {
|
||||
server.send(400, "text/plain", error);
|
||||
return;
|
||||
}
|
||||
|
||||
if (!saveConfigToFile()) {
|
||||
server.send(500, "text/plain", "Could not save config");
|
||||
return;
|
||||
}
|
||||
|
||||
// penState = penUpPos;
|
||||
// penServo.write(penState);
|
||||
server.send(200, "application/json", buildConfigJson());
|
||||
}
|
||||
} // namespace
|
||||
|
||||
ConfigParameter configParameters[] = {
|
||||
{"penUpPos", &penUpPos, "Pen Up Position", 5},
|
||||
{"penDownPos", &penDownPos, "Pen Down Position", 20},
|
||||
};
|
||||
|
||||
const size_t configParameterCount = sizeof(configParameters) / sizeof(configParameters[0]);
|
||||
|
||||
bool initConfigStore() {
|
||||
if (!SPIFFS.begin(true)) {
|
||||
configStoreReady = false;
|
||||
return false;
|
||||
}
|
||||
configStoreReady = loadConfigFromFile();
|
||||
return configStoreReady;
|
||||
}
|
||||
|
||||
bool loadConfigFromFile() {
|
||||
applyDefaults();
|
||||
|
||||
File file = SPIFFS.open(kConfigPath, "r");
|
||||
if (!file) {
|
||||
return saveConfigToFile();
|
||||
}
|
||||
|
||||
StaticJsonDocument<1024> doc;
|
||||
DeserializationError err = deserializeJson(doc, file);
|
||||
file.close();
|
||||
if (err) {
|
||||
return saveConfigToFile();
|
||||
}
|
||||
|
||||
JsonArray params = doc["parameters"].as<JsonArray>();
|
||||
for (JsonObject item : params) {
|
||||
const char *key = item["key"];
|
||||
if (key == nullptr) {
|
||||
continue;
|
||||
}
|
||||
ConfigParameter *param = findParameter(String(key));
|
||||
if (param == nullptr) {
|
||||
continue;
|
||||
}
|
||||
if (item.containsKey("value")) {
|
||||
*param->value = item["value"].as<int>();
|
||||
}
|
||||
if (item.containsKey("description")) {
|
||||
param->description = item["description"].as<String>();
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool saveConfigToFile() {
|
||||
File file = SPIFFS.open(kConfigPath, "w");
|
||||
if (!file) {
|
||||
return false;
|
||||
}
|
||||
|
||||
StaticJsonDocument<1024> doc;
|
||||
JsonArray params = doc.createNestedArray("parameters");
|
||||
for (size_t i = 0; i < configParameterCount; ++i) {
|
||||
JsonObject item = params.createNestedObject();
|
||||
item["key"] = configParameters[i].key;
|
||||
item["value"] = *configParameters[i].value;
|
||||
item["description"] = configParameters[i].description;
|
||||
}
|
||||
|
||||
bool ok = serializeJsonPretty(doc, file) > 0;
|
||||
file.close();
|
||||
return ok;
|
||||
}
|
||||
|
||||
String buildConfigJson() {
|
||||
StaticJsonDocument<1024> doc;
|
||||
JsonArray params = doc.createNestedArray("parameters");
|
||||
for (size_t i = 0; i < configParameterCount; ++i) {
|
||||
JsonObject item = params.createNestedObject();
|
||||
item["key"] = configParameters[i].key;
|
||||
item["value"] = *configParameters[i].value;
|
||||
item["description"] = configParameters[i].description;
|
||||
}
|
||||
|
||||
String output;
|
||||
serializeJson(doc, output);
|
||||
return output;
|
||||
}
|
||||
|
||||
bool applyConfigJson(const String &payload, String &errorMessage) {
|
||||
StaticJsonDocument<1024> doc;
|
||||
DeserializationError err = deserializeJson(doc, payload);
|
||||
if (err) {
|
||||
errorMessage = "Invalid JSON payload";
|
||||
return false;
|
||||
}
|
||||
|
||||
JsonArray params = doc["parameters"].as<JsonArray>();
|
||||
if (params.isNull()) {
|
||||
errorMessage = "JSON must contain 'parameters' array";
|
||||
return false;
|
||||
}
|
||||
|
||||
for (JsonObject item : params) {
|
||||
const char *key = item["key"];
|
||||
if (key == nullptr || !item.containsKey("value")) {
|
||||
continue;
|
||||
}
|
||||
|
||||
ConfigParameter *param = findParameter(String(key));
|
||||
if (param == nullptr) {
|
||||
continue;
|
||||
}
|
||||
|
||||
*param->value = item["value"].as<int>();
|
||||
if (item.containsKey("description")) {
|
||||
param->description = item["description"].as<String>();
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void startWebInterface() {
|
||||
WiFi.mode(WIFI_AP);
|
||||
WiFi.softAPConfig(kApIp, kApIp, kApSubnet);
|
||||
WiFi.softAP(kApSsid);
|
||||
dnsServer.start(kDnsPort, "*", WiFi.softAPIP());
|
||||
initConfigStore();
|
||||
Serial.print("Config AP IP: ");
|
||||
Serial.println(WiFi.softAPIP());
|
||||
|
||||
server.on("/", HTTP_GET, handleRoot);
|
||||
server.on("/api/config", HTTP_GET, handleGetConfig);
|
||||
server.on("/api/config", HTTP_POST, handlePostConfig);
|
||||
server.on("/generate_204", HTTP_GET, redirectToPortal);
|
||||
server.on("/gen_204", HTTP_GET, redirectToPortal);
|
||||
server.on("/hotspot-detect.html", HTTP_GET, redirectToPortal);
|
||||
server.on("/library/test/success.html", HTTP_GET, redirectToPortal);
|
||||
server.on("/ncsi.txt", HTTP_GET, redirectToPortal);
|
||||
server.on("/connecttest.txt", HTTP_GET, redirectToPortal);
|
||||
server.onNotFound(redirectToPortal);
|
||||
server.begin();
|
||||
}
|
||||
|
||||
void handleWebInterface() {
|
||||
dnsServer.processNextRequest();
|
||||
server.handleClient();
|
||||
}
|
||||
@@ -1,16 +1,11 @@
|
||||
#include "EggDuino.h"
|
||||
|
||||
inline void loadPenPosFromEE() {
|
||||
penUpPos = eeprom_read_word(penUpPosEEAddress);
|
||||
penDownPos = eeprom_read_word(penDownPosEEAddress);
|
||||
penState = penUpPos;
|
||||
}
|
||||
|
||||
void initHardware(){
|
||||
// enable eeprom wait in avr/eeprom.h functions
|
||||
SPMCSR &= ~SELFPRGEN;
|
||||
|
||||
loadPenPosFromEE();
|
||||
if (!initConfigStore()) {
|
||||
penUpPos = 5;
|
||||
penDownPos = 20;
|
||||
}
|
||||
penState = penUpPos;
|
||||
|
||||
pinMode(enableRotMotor, OUTPUT);
|
||||
pinMode(enablePenMotor, OUTPUT);
|
||||
@@ -24,14 +19,12 @@ void initHardware(){
|
||||
penServo.write(penState);
|
||||
}
|
||||
|
||||
|
||||
|
||||
void storePenUpPosInEE() {
|
||||
eeprom_update_word(penUpPosEEAddress, penUpPos);
|
||||
saveConfigToFile();
|
||||
}
|
||||
|
||||
void storePenDownPosInEE() {
|
||||
eeprom_update_word(penDownPosEEAddress, penDownPos);
|
||||
saveConfigToFile();
|
||||
}
|
||||
|
||||
void sendAck(){
|
||||
27
src/main.cpp
27
src/main.cpp
@@ -30,10 +30,10 @@
|
||||
//-----------------------------------------------------------------------------------------------------------
|
||||
|
||||
//make Objects
|
||||
AccelStepper rotMotor(AccelStepper::DRIVER, step1, dir1);
|
||||
AccelStepper penMotor(AccelStepper::DRIVER, step2, dir2);
|
||||
Servo penServo;
|
||||
SerialCommand SCmd;
|
||||
// AccelStepper rotMotor(AccelStepper::DRIVER, step1, dir1);
|
||||
// AccelStepper penMotor(AccelStepper::DRIVER, step2, dir2);
|
||||
// Servo penServo;
|
||||
// SerialCommand SCmd;
|
||||
//create Buttons
|
||||
#ifdef prgButton
|
||||
Button prgButtonToggle(prgButton, setprgButtonState);
|
||||
@@ -63,19 +63,18 @@ float rotSpeed=0;
|
||||
float penSpeed=0; // these are local variables for Function SteppermotorMove-Command, but for performance-reasons it will be initialized here
|
||||
boolean motorsEnabled = 0;
|
||||
|
||||
void setup() {
|
||||
Serial.begin(9600);
|
||||
makeComInterface();
|
||||
initHardware();
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
Serial.print("Starting...");
|
||||
//makeComInterface();
|
||||
//initHardware();
|
||||
startWebInterface();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
|
||||
|
||||
moveOneStep();
|
||||
SCmd.readSerial();
|
||||
|
||||
|
||||
// moveOneStep();
|
||||
// SCmd.readSerial();
|
||||
handleWebInterface();
|
||||
|
||||
#ifdef penToggleButton
|
||||
penToggle.check();
|
||||
|
||||
Reference in New Issue
Block a user