Compare commits
4 Commits
SlEggBotE3
...
SlEggBotEL
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
a85bf19885 | ||
|
|
f862672a81 | ||
|
|
870456c17b | ||
|
|
400edb45e5 |
@@ -21,44 +21,51 @@
|
|||||||
#ifdef ESP32
|
#ifdef ESP32
|
||||||
|
|
||||||
// Rotational Stepper
|
// Rotational Stepper
|
||||||
#define dir1 16
|
static const int kDefaultRotDirPin = 16;
|
||||||
#define enableRotMotor 12
|
static const int kDefaultRotEnablePin = 12;
|
||||||
#define step1 26
|
static const int kDefaultRotStepPin = 26;
|
||||||
#define rotMicrostep 32
|
#define rotMicrostep 32
|
||||||
|
static const int kDefaultRotMicrostep = rotMicrostep;
|
||||||
|
|
||||||
// Pen Stepper
|
// Pen Stepper
|
||||||
#define step2 25
|
static const int kDefaultPenStepPin = 25;
|
||||||
#define dir2 27
|
static const int kDefaultPenDirPin = 27;
|
||||||
#define enablePenMotor 12
|
static const int kDefaultPenEnablePin = 12;
|
||||||
#define penMicrostep 32
|
#define penMicrostep 32
|
||||||
|
static const int kDefaultPenMicrostep = penMicrostep;
|
||||||
|
|
||||||
#define servoPin 17
|
static const int kDefaultServoPin = 17;
|
||||||
|
|
||||||
|
|
||||||
#else
|
#else
|
||||||
|
|
||||||
// Rotational Stepper
|
// Rotational Stepper
|
||||||
#define step1 2
|
static const int kDefaultRotStepPin = 2;
|
||||||
#define dir1 5
|
static const int kDefaultRotDirPin = 5;
|
||||||
#define enableRotMotor 8
|
static const int kDefaultRotEnablePin = 8;
|
||||||
#define rotMicrostep 16
|
#define rotMicrostep 16
|
||||||
|
static const int kDefaultRotMicrostep = rotMicrostep;
|
||||||
|
|
||||||
// Pen Stepper
|
// Pen Stepper
|
||||||
#define step2 3
|
static const int kDefaultPenStepPin = 3;
|
||||||
#define dir2 6
|
static const int kDefaultPenDirPin = 6;
|
||||||
#define enablePenMotor 8
|
static const int kDefaultPenEnablePin = 8;
|
||||||
#define penMicrostep 16
|
#define penMicrostep 16
|
||||||
|
static const int kDefaultPenMicrostep = penMicrostep;
|
||||||
|
|
||||||
#define servoPin 4
|
static const int kDefaultServoPin = 4;
|
||||||
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
struct ConfigParameter {
|
struct ConfigParameter {
|
||||||
|
const char *type;
|
||||||
const char *key;
|
const char *key;
|
||||||
int *value;
|
void *value;
|
||||||
String description;
|
String description;
|
||||||
int defaultValue;
|
int defaultValue;
|
||||||
|
const char *defaultText;
|
||||||
|
bool secret;
|
||||||
};
|
};
|
||||||
|
|
||||||
extern FastAccelStepperEngine g_stepEngine;
|
extern FastAccelStepperEngine g_stepEngine;
|
||||||
@@ -81,6 +88,18 @@ extern boolean g_bPrgButtonState;
|
|||||||
extern float fROT_STEP_CORRECTION;
|
extern float fROT_STEP_CORRECTION;
|
||||||
extern float fPEN_STEP_CORRECTION;
|
extern float fPEN_STEP_CORRECTION;
|
||||||
extern boolean g_bMotorsEnabled;
|
extern boolean g_bMotorsEnabled;
|
||||||
|
extern int g_iRotDirPin;
|
||||||
|
extern int g_iRotEnablePin;
|
||||||
|
extern int g_iRotStepPin;
|
||||||
|
extern int g_iPenStepPin;
|
||||||
|
extern int g_iPenDirPin;
|
||||||
|
extern int g_iPenEnablePin;
|
||||||
|
extern int g_iServoPin;
|
||||||
|
extern int g_iRotMicrostep;
|
||||||
|
extern int g_iPenMicrostep;
|
||||||
|
extern String g_sHostname;
|
||||||
|
extern String g_sWifiSsid;
|
||||||
|
extern String g_sWifiPassword;
|
||||||
|
|
||||||
extern ConfigParameter configParameters[];
|
extern ConfigParameter configParameters[];
|
||||||
extern const size_t configParameterCount;
|
extern const size_t configParameterCount;
|
||||||
@@ -100,6 +119,7 @@ bool parseSMArgs(uint16_t *duration, int *penStepsEBB, int *rotStepsEBB);
|
|||||||
void prepareMove(uint16_t duration, int penStepsEBB, int rotStepsEBB);
|
void prepareMove(uint16_t duration, int penStepsEBB, int rotStepsEBB);
|
||||||
void storePenUpPosInEE();
|
void storePenUpPosInEE();
|
||||||
void storePenDownPosInEE();
|
void storePenDownPosInEE();
|
||||||
|
void updateStepCorrectionFactors();
|
||||||
|
|
||||||
bool initConfigStore();
|
bool initConfigStore();
|
||||||
bool loadConfigFromFile();
|
bool loadConfigFromFile();
|
||||||
|
|||||||
@@ -1,13 +1,39 @@
|
|||||||
#include "EggDuino.h"
|
#include "EggDuino.h"
|
||||||
#include <ArduinoJson.h>
|
#include <ArduinoJson.h>
|
||||||
#include "credentials.h"
|
#include <DNSServer.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
namespace
|
namespace
|
||||||
{
|
{
|
||||||
const char *kConfigPath = "/config.json";
|
const char *kConfigPath = "/config.json";
|
||||||
|
const size_t kConfigJsonCapacity = 4096;
|
||||||
|
const byte kDnsPort = 53;
|
||||||
|
|
||||||
WebServer server(80);
|
WebServer server(80);
|
||||||
|
DNSServer dnsServer;
|
||||||
bool configStoreReady = false;
|
bool configStoreReady = false;
|
||||||
|
bool apModeActive = false;
|
||||||
|
|
||||||
|
void redirectToRoot()
|
||||||
|
{
|
||||||
|
server.sendHeader("Location", String("http://") + WiFi.softAPIP().toString() + "/", true);
|
||||||
|
server.send(302, "text/plain", "");
|
||||||
|
}
|
||||||
|
|
||||||
|
bool isIntType(const ConfigParameter ¶m)
|
||||||
|
{
|
||||||
|
return strcmp(param.type, "int") == 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
int *asIntPtr(ConfigParameter ¶m)
|
||||||
|
{
|
||||||
|
return static_cast<int *>(param.value);
|
||||||
|
}
|
||||||
|
|
||||||
|
String *asStringPtr(ConfigParameter ¶m)
|
||||||
|
{
|
||||||
|
return static_cast<String *>(param.value);
|
||||||
|
}
|
||||||
|
|
||||||
ConfigParameter *findParameter(const String &key)
|
ConfigParameter *findParameter(const String &key)
|
||||||
{
|
{
|
||||||
@@ -25,7 +51,15 @@ namespace
|
|||||||
{
|
{
|
||||||
for (size_t i = 0; i < configParameterCount; ++i)
|
for (size_t i = 0; i < configParameterCount; ++i)
|
||||||
{
|
{
|
||||||
*configParameters[i].value = configParameters[i].defaultValue;
|
if (isIntType(configParameters[i]))
|
||||||
|
{
|
||||||
|
*asIntPtr(configParameters[i]) = configParameters[i].defaultValue;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
const char *fallback = configParameters[i].defaultText == nullptr ? "" : configParameters[i].defaultText;
|
||||||
|
*asStringPtr(configParameters[i]) = String(fallback);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -43,7 +77,7 @@ body { font-family: "Segoe UI", sans-serif; margin: 20px; background: #f3f6fb; c
|
|||||||
main { max-width: 760px; margin: 0 auto; background: #fff; border-radius: 12px; padding: 20px; box-shadow: 0 8px 24px rgba(0,0,0,0.08); }
|
main { max-width: 760px; 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; }
|
h1 { margin-top: 0; font-size: 1.35rem; }
|
||||||
label { display: block; margin: 14px 0 6px; font-weight: 600; }
|
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; }
|
input[type='number'], input[type='text'], input[type='password'] { 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; }
|
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; }
|
#status { margin-top: 12px; min-height: 1.2em; }
|
||||||
#log { margin-top: 20px; border: 1px solid #d6dfef; border-radius: 8px; background: #0f172a; color: #d2e3ff; padding: 10px; height: 220px; overflow-y: auto; white-space: pre-wrap; font-family: ui-monospace, SFMono-Regular, Menlo, Monaco, Consolas, monospace; font-size: 0.9rem; }
|
#log { margin-top: 20px; border: 1px solid #d6dfef; border-radius: 8px; background: #0f172a; color: #d2e3ff; padding: 10px; height: 220px; overflow-y: auto; white-space: pre-wrap; font-family: ui-monospace, SFMono-Regular, Menlo, Monaco, Consolas, monospace; font-size: 0.9rem; }
|
||||||
@@ -75,9 +109,23 @@ function renderForm(config) {
|
|||||||
const label = document.createElement('label');
|
const label = document.createElement('label');
|
||||||
label.textContent = p.description || p.key;
|
label.textContent = p.description || p.key;
|
||||||
const input = document.createElement('input');
|
const input = document.createElement('input');
|
||||||
input.type = 'number';
|
const paramType = p.type || 'int';
|
||||||
input.value = p.value;
|
input.type = paramType === 'int' ? 'number' : paramType;
|
||||||
|
if (paramType === 'password') {
|
||||||
|
input.value = '';
|
||||||
|
if (p.hasValue) {
|
||||||
|
input.placeholder = '(gespeichert)';
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
input.value = p.value ?? '';
|
||||||
|
}
|
||||||
input.dataset.key = p.key;
|
input.dataset.key = p.key;
|
||||||
|
input.dataset.ptype = paramType;
|
||||||
|
input.dataset.secret = p.secret ? '1' : '0';
|
||||||
|
input.dataset.touched = '0';
|
||||||
|
input.addEventListener('input', () => {
|
||||||
|
input.dataset.touched = '1';
|
||||||
|
});
|
||||||
form.appendChild(label);
|
form.appendChild(label);
|
||||||
form.appendChild(input);
|
form.appendChild(input);
|
||||||
});
|
});
|
||||||
@@ -87,7 +135,19 @@ async function saveConfig() {
|
|||||||
const status = document.getElementById('status');
|
const status = document.getElementById('status');
|
||||||
const inputs = [...document.querySelectorAll('input[data-key]')];
|
const inputs = [...document.querySelectorAll('input[data-key]')];
|
||||||
const payload = {
|
const payload = {
|
||||||
parameters: inputs.map(i => ({ key: i.dataset.key, value: Number(i.value) }))
|
parameters: inputs
|
||||||
|
.map(i => {
|
||||||
|
const type = i.dataset.ptype || 'int';
|
||||||
|
const secret = i.dataset.secret === '1';
|
||||||
|
if (type === 'int') {
|
||||||
|
return { key: i.dataset.key, value: Number(i.value) };
|
||||||
|
}
|
||||||
|
if (secret && i.dataset.touched !== '1') {
|
||||||
|
return null;
|
||||||
|
}
|
||||||
|
return { key: i.dataset.key, value: i.value };
|
||||||
|
})
|
||||||
|
.filter(Boolean)
|
||||||
};
|
};
|
||||||
const resp = await fetch('/api/config', {
|
const resp = await fetch('/api/config', {
|
||||||
method: 'POST',
|
method: 'POST',
|
||||||
@@ -188,7 +248,6 @@ async function pollLogs() {
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
Log(String("Config gespeichert: penUpPos=") + g_iPenUpPos + ", penDownPos=" + g_iPenDownPos);
|
|
||||||
server.send(200, "application/json", buildConfigJson());
|
server.send(200, "application/json", buildConfigJson());
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -204,6 +263,11 @@ async function pollLogs() {
|
|||||||
|
|
||||||
void handleNotFound()
|
void handleNotFound()
|
||||||
{
|
{
|
||||||
|
if (apModeActive)
|
||||||
|
{
|
||||||
|
redirectToRoot();
|
||||||
|
return;
|
||||||
|
}
|
||||||
if (server.uri().startsWith("/api/"))
|
if (server.uri().startsWith("/api/"))
|
||||||
{
|
{
|
||||||
server.send(404, "text/plain", "API endpoint not found");
|
server.send(404, "text/plain", "API endpoint not found");
|
||||||
@@ -214,8 +278,20 @@ async function pollLogs() {
|
|||||||
} // namespace
|
} // namespace
|
||||||
|
|
||||||
ConfigParameter configParameters[] = {
|
ConfigParameter configParameters[] = {
|
||||||
// {"penUpPos", &g_iPEN_UP_POS, "Pen Up Position", 5},
|
{"int", "penUpPos", &g_iPenUpPos, "Pen Up Position", 40, "", false},
|
||||||
// {"penDownPos", &g_iPEN_DOWN_POS, "Pen Down Position", 20},
|
{"int", "penDownPos", &g_iPenDownPos, "Pen Down Position", 10, "", false},
|
||||||
|
{"int", "rotStepPin", &g_iRotStepPin, "Rotational Stepper Step Pin", kDefaultRotStepPin, "", false},
|
||||||
|
{"int", "rotDirPin", &g_iRotDirPin, "Rotational Stepper Direction Pin", kDefaultRotDirPin, "", false},
|
||||||
|
{"int", "rotEnablePin", &g_iRotEnablePin, "Rotational Stepper Enable Pin", kDefaultRotEnablePin, "", false},
|
||||||
|
{"int", "penStepPin", &g_iPenStepPin, "Pen Stepper Step Pin", kDefaultPenStepPin, "", false},
|
||||||
|
{"int", "penDirPin", &g_iPenDirPin, "Pen Stepper Direction Pin", kDefaultPenDirPin, "", false},
|
||||||
|
{"int", "penEnablePin", &g_iPenEnablePin, "Pen Stepper Enable Pin", kDefaultPenEnablePin, "", false},
|
||||||
|
{"int", "rotMicrostep", &g_iRotMicrostep, "Rotational Stepper Microsteps", kDefaultRotMicrostep, "", false},
|
||||||
|
{"int", "penMicrostep", &g_iPenMicrostep, "Pen Stepper Microsteps", kDefaultPenMicrostep, "", false},
|
||||||
|
{"int", "servoPin", &g_iServoPin, "Servo Pin", kDefaultServoPin, "", false},
|
||||||
|
{"text", "Name", &g_sHostname, "Name", 0, "EggDuino", false},
|
||||||
|
{"text", "wifiSsid", &g_sWifiSsid, "WLAN SSID", 0, "", false},
|
||||||
|
{"password", "wifiPassword", &g_sWifiPassword, "WLAN Passwort", 0, "", true},
|
||||||
};
|
};
|
||||||
|
|
||||||
const size_t configParameterCount = sizeof(configParameters) / sizeof(configParameters[0]);
|
const size_t configParameterCount = sizeof(configParameters) / sizeof(configParameters[0]);
|
||||||
@@ -242,12 +318,12 @@ bool loadConfigFromFile()
|
|||||||
return saveConfigToFile();
|
return saveConfigToFile();
|
||||||
}
|
}
|
||||||
|
|
||||||
StaticJsonDocument<1024> doc;
|
StaticJsonDocument<kConfigJsonCapacity> doc;
|
||||||
DeserializationError err = deserializeJson(doc, file);
|
DeserializationError err = deserializeJson(doc, file);
|
||||||
file.close();
|
file.close();
|
||||||
if (err)
|
if (err)
|
||||||
{
|
{
|
||||||
Log("config.json ist ungueltig, defaults werden gespeichert");
|
Log(String("config.json ist ungueltig (") + err.c_str() + "), defaults werden gespeichert");
|
||||||
return saveConfigToFile();
|
return saveConfigToFile();
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -266,13 +342,21 @@ bool loadConfigFromFile()
|
|||||||
}
|
}
|
||||||
if (item.containsKey("value"))
|
if (item.containsKey("value"))
|
||||||
{
|
{
|
||||||
*param->value = item["value"].as<int>();
|
if (isIntType(*param))
|
||||||
|
{
|
||||||
|
*asIntPtr(*param) = item["value"].as<int>();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
*asStringPtr(*param) = item["value"].as<String>();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
if (item.containsKey("description"))
|
if (item.containsKey("description"))
|
||||||
{
|
{
|
||||||
param->description = item["description"].as<String>();
|
param->description = item["description"].as<String>();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
updateStepCorrectionFactors();
|
||||||
Log(String("Config geladen: penUpPos=") + g_iPenUpPos + ", penDownPos=" + g_iPenDownPos);
|
Log(String("Config geladen: penUpPos=") + g_iPenUpPos + ", penDownPos=" + g_iPenDownPos);
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
@@ -287,15 +371,30 @@ bool saveConfigToFile()
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
StaticJsonDocument<1024> doc;
|
StaticJsonDocument<kConfigJsonCapacity> doc;
|
||||||
JsonArray params = doc.createNestedArray("parameters");
|
JsonArray params = doc.createNestedArray("parameters");
|
||||||
for (size_t i = 0; i < configParameterCount; ++i)
|
for (size_t i = 0; i < configParameterCount; ++i)
|
||||||
{
|
{
|
||||||
JsonObject item = params.createNestedObject();
|
JsonObject item = params.createNestedObject();
|
||||||
item["key"] = configParameters[i].key;
|
item["key"] = configParameters[i].key;
|
||||||
item["value"] = *configParameters[i].value;
|
item["type"] = configParameters[i].type;
|
||||||
|
item["secret"] = configParameters[i].secret;
|
||||||
|
if (isIntType(configParameters[i]))
|
||||||
|
{
|
||||||
|
item["value"] = *asIntPtr(configParameters[i]);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
item["value"] = *asStringPtr(configParameters[i]);
|
||||||
|
}
|
||||||
item["description"] = configParameters[i].description;
|
item["description"] = configParameters[i].description;
|
||||||
}
|
}
|
||||||
|
if (doc.overflowed())
|
||||||
|
{
|
||||||
|
Log("Config JSON Dokument zu klein beim Speichern");
|
||||||
|
file.close();
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
bool ok = serializeJsonPretty(doc, file) > 0;
|
bool ok = serializeJsonPretty(doc, file) > 0;
|
||||||
file.flush();
|
file.flush();
|
||||||
@@ -309,15 +408,34 @@ bool saveConfigToFile()
|
|||||||
|
|
||||||
String buildConfigJson()
|
String buildConfigJson()
|
||||||
{
|
{
|
||||||
StaticJsonDocument<1024> doc;
|
StaticJsonDocument<kConfigJsonCapacity> doc;
|
||||||
JsonArray params = doc.createNestedArray("parameters");
|
JsonArray params = doc.createNestedArray("parameters");
|
||||||
for (size_t i = 0; i < configParameterCount; ++i)
|
for (size_t i = 0; i < configParameterCount; ++i)
|
||||||
{
|
{
|
||||||
JsonObject item = params.createNestedObject();
|
JsonObject item = params.createNestedObject();
|
||||||
item["key"] = configParameters[i].key;
|
item["key"] = configParameters[i].key;
|
||||||
item["value"] = *configParameters[i].value;
|
item["type"] = configParameters[i].type;
|
||||||
|
item["secret"] = configParameters[i].secret;
|
||||||
|
if (isIntType(configParameters[i]))
|
||||||
|
{
|
||||||
|
item["value"] = *asIntPtr(configParameters[i]);
|
||||||
|
}
|
||||||
|
else if (configParameters[i].secret)
|
||||||
|
{
|
||||||
|
item["value"] = "";
|
||||||
|
item["hasValue"] = !asStringPtr(configParameters[i])->isEmpty();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
item["value"] = *asStringPtr(configParameters[i]);
|
||||||
|
}
|
||||||
item["description"] = configParameters[i].description;
|
item["description"] = configParameters[i].description;
|
||||||
}
|
}
|
||||||
|
if (doc.overflowed())
|
||||||
|
{
|
||||||
|
Log("Config JSON Dokument zu klein beim Lesen");
|
||||||
|
return String("{\"parameters\":[]}");
|
||||||
|
}
|
||||||
|
|
||||||
String output;
|
String output;
|
||||||
serializeJson(doc, output);
|
serializeJson(doc, output);
|
||||||
@@ -326,7 +444,7 @@ String buildConfigJson()
|
|||||||
|
|
||||||
bool applyConfigJson(const String &payload, String &errorMessage)
|
bool applyConfigJson(const String &payload, String &errorMessage)
|
||||||
{
|
{
|
||||||
StaticJsonDocument<1024> doc;
|
StaticJsonDocument<kConfigJsonCapacity> doc;
|
||||||
DeserializationError err = deserializeJson(doc, payload);
|
DeserializationError err = deserializeJson(doc, payload);
|
||||||
if (err)
|
if (err)
|
||||||
{
|
{
|
||||||
@@ -344,7 +462,7 @@ bool applyConfigJson(const String &payload, String &errorMessage)
|
|||||||
for (JsonObject item : params)
|
for (JsonObject item : params)
|
||||||
{
|
{
|
||||||
const char *key = item["key"];
|
const char *key = item["key"];
|
||||||
if (key == nullptr || !item.containsKey("value"))
|
if (key == nullptr)
|
||||||
{
|
{
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
@@ -355,12 +473,24 @@ bool applyConfigJson(const String &payload, String &errorMessage)
|
|||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
*param->value = item["value"].as<int>();
|
if (!item.containsKey("value"))
|
||||||
|
{
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
if (isIntType(*param))
|
||||||
|
{
|
||||||
|
*asIntPtr(*param) = item["value"].as<int>();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
*asStringPtr(*param) = item["value"].as<String>();
|
||||||
|
}
|
||||||
if (item.containsKey("description"))
|
if (item.containsKey("description"))
|
||||||
{
|
{
|
||||||
param->description = item["description"].as<String>();
|
param->description = item["description"].as<String>();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
updateStepCorrectionFactors();
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@@ -368,11 +498,22 @@ bool applyConfigJson(const String &payload, String &errorMessage)
|
|||||||
void startWebInterface()
|
void startWebInterface()
|
||||||
{
|
{
|
||||||
initConfigStore();
|
initConfigStore();
|
||||||
if (kWifiSsid != 0)
|
bool staConnected = false;
|
||||||
|
apModeActive = false;
|
||||||
|
dnsServer.stop();
|
||||||
|
String hostName = g_sHostname;
|
||||||
|
hostName.trim();
|
||||||
|
if (hostName.isEmpty())
|
||||||
{
|
{
|
||||||
|
hostName = "EggDuino";
|
||||||
|
}
|
||||||
|
g_sHostname = hostName;
|
||||||
|
|
||||||
|
if (!g_sWifiSsid.isEmpty())
|
||||||
|
{
|
||||||
WiFi.mode(WIFI_STA);
|
WiFi.mode(WIFI_STA);
|
||||||
WiFi.begin(kWifiSsid, kWifiPassword);
|
WiFi.setHostname(hostName.c_str());
|
||||||
|
WiFi.begin(g_sWifiSsid.c_str(), g_sWifiPassword.c_str());
|
||||||
|
|
||||||
const unsigned long connectStart = millis();
|
const unsigned long connectStart = millis();
|
||||||
const unsigned long connectTimeoutMs = 10000;
|
const unsigned long connectTimeoutMs = 10000;
|
||||||
@@ -380,9 +521,8 @@ void startWebInterface()
|
|||||||
{
|
{
|
||||||
delay(250);
|
delay(250);
|
||||||
}
|
}
|
||||||
|
staConnected = (WiFi.status() == WL_CONNECTED);
|
||||||
|
if (staConnected)
|
||||||
if (WiFi.status() == WL_CONNECTED)
|
|
||||||
{
|
{
|
||||||
Serial.println(String("http://") + WiFi.localIP().toString());
|
Serial.println(String("http://") + WiFi.localIP().toString());
|
||||||
}
|
}
|
||||||
@@ -390,24 +530,44 @@ void startWebInterface()
|
|||||||
{
|
{
|
||||||
Serial.println("WLAN Verbindung fehlgeschlagen");
|
Serial.println("WLAN Verbindung fehlgeschlagen");
|
||||||
}
|
}
|
||||||
|
|
||||||
server.on("/", HTTP_GET, handleRoot);
|
|
||||||
server.on("/api/config", HTTP_GET, handleGetConfig);
|
|
||||||
server.on("/api/config", HTTP_POST, handlePostConfig);
|
|
||||||
server.on("/api/logs", HTTP_GET, handleGetLogs);
|
|
||||||
server.onNotFound(handleNotFound);
|
|
||||||
server.begin();
|
|
||||||
}
|
}
|
||||||
else
|
if (!staConnected)
|
||||||
{
|
{
|
||||||
Serial.println("Verwende kein WLAN.");
|
WiFi.mode(WIFI_AP);
|
||||||
|
#ifdef ESP32
|
||||||
|
WiFi.softAPsetHostname(hostName.c_str());
|
||||||
|
#endif
|
||||||
|
if (WiFi.softAP("EggDuino"))
|
||||||
|
{
|
||||||
|
apModeActive = true;
|
||||||
|
dnsServer.start(kDnsPort, "*", WiFi.softAPIP());
|
||||||
|
Serial.println(String("AP aktiv: EggDuino / http://") + WiFi.softAPIP().toString() + " (Name: " + hostName + ")");
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
Serial.println("AP konnte nicht gestartet werden");
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
server.on("/", HTTP_GET, handleRoot);
|
||||||
|
server.on("/api/config", HTTP_GET, handleGetConfig);
|
||||||
|
server.on("/api/config", HTTP_POST, handlePostConfig);
|
||||||
|
server.on("/api/logs", HTTP_GET, handleGetLogs);
|
||||||
|
server.on("/generate_204", HTTP_GET, redirectToRoot);
|
||||||
|
server.on("/gen_204", HTTP_GET, redirectToRoot);
|
||||||
|
server.on("/hotspot-detect.html", HTTP_GET, redirectToRoot);
|
||||||
|
server.on("/connecttest.txt", HTTP_GET, redirectToRoot);
|
||||||
|
server.on("/ncsi.txt", HTTP_GET, redirectToRoot);
|
||||||
|
server.on("/fwlink", HTTP_GET, redirectToRoot);
|
||||||
|
server.onNotFound(handleNotFound);
|
||||||
|
server.begin();
|
||||||
}
|
}
|
||||||
|
|
||||||
void handleWebInterface()
|
void handleWebInterface()
|
||||||
{
|
{
|
||||||
if (kWifiSsid != NULL)
|
if (apModeActive)
|
||||||
{
|
{
|
||||||
server.handleClient();
|
dnsServer.processNextRequest();
|
||||||
}
|
}
|
||||||
|
server.handleClient();
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,5 +1,19 @@
|
|||||||
#include "EggDuino.h"
|
#include "EggDuino.h"
|
||||||
|
|
||||||
|
void updateStepCorrectionFactors()
|
||||||
|
{
|
||||||
|
if (g_iRotMicrostep <= 0)
|
||||||
|
{
|
||||||
|
g_iRotMicrostep = kDefaultRotMicrostep;
|
||||||
|
}
|
||||||
|
if (g_iPenMicrostep <= 0)
|
||||||
|
{
|
||||||
|
g_iPenMicrostep = kDefaultPenMicrostep;
|
||||||
|
}
|
||||||
|
fROT_STEP_CORRECTION = 16.0f / (float)g_iRotMicrostep;
|
||||||
|
fPEN_STEP_CORRECTION = 16.0f / (float)g_iPenMicrostep;
|
||||||
|
}
|
||||||
|
|
||||||
void initHardware()
|
void initHardware()
|
||||||
{
|
{
|
||||||
if (!initConfigStore())
|
if (!initConfigStore())
|
||||||
@@ -7,35 +21,36 @@ void initHardware()
|
|||||||
g_iPenUpPos = 5;
|
g_iPenUpPos = 5;
|
||||||
g_iPenDownPos = 20;
|
g_iPenDownPos = 20;
|
||||||
}
|
}
|
||||||
|
updateStepCorrectionFactors();
|
||||||
g_iPenState = g_iPenUpPos;
|
g_iPenState = g_iPenUpPos;
|
||||||
|
|
||||||
g_stepEngine.init();
|
g_stepEngine.init();
|
||||||
g_pStepperRotate = g_stepEngine.stepperConnectToPin(step1);
|
g_pStepperRotate = g_stepEngine.stepperConnectToPin(g_iRotStepPin);
|
||||||
if (g_pStepperRotate)
|
if (g_pStepperRotate)
|
||||||
{
|
{
|
||||||
// rotMotor.setMaxSpeed(2000.0);
|
// rotMotor.setMaxSpeed(2000.0);
|
||||||
// rotMotor.setAcceleration(10000.0);
|
// rotMotor.setAcceleration(10000.0);
|
||||||
|
|
||||||
g_pStepperRotate->setDirectionPin(dir1);
|
g_pStepperRotate->setDirectionPin(g_iRotDirPin);
|
||||||
g_pStepperRotate->setEnablePin(enableRotMotor);
|
g_pStepperRotate->setEnablePin(g_iRotEnablePin);
|
||||||
g_pStepperRotate->setAcceleration(10000);
|
g_pStepperRotate->setAcceleration(10000);
|
||||||
g_pStepperRotate->setAutoEnable(false);
|
g_pStepperRotate->setAutoEnable(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Stepper pen init
|
// Stepper pen init
|
||||||
g_pStepperPen = g_stepEngine.stepperConnectToPin(step2);
|
g_pStepperPen = g_stepEngine.stepperConnectToPin(g_iPenStepPin);
|
||||||
if (g_pStepperPen)
|
if (g_pStepperPen)
|
||||||
{
|
{
|
||||||
// penMotor.setMaxSpeed(2000.0);
|
// penMotor.setMaxSpeed(2000.0);
|
||||||
// penMotor.setAcceleration(10000.0);
|
// penMotor.setAcceleration(10000.0);
|
||||||
g_pStepperPen->setDirectionPin(dir2);
|
g_pStepperPen->setDirectionPin(g_iPenDirPin);
|
||||||
g_pStepperPen->setEnablePin(enablePenMotor);
|
g_pStepperPen->setEnablePin(g_iPenEnablePin);
|
||||||
g_pStepperPen->setAcceleration(10000);
|
g_pStepperPen->setAcceleration(10000);
|
||||||
g_pStepperPen->setAutoEnable(false);
|
g_pStepperPen->setAutoEnable(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
motorsOff();
|
motorsOff();
|
||||||
penServo.attach(servoPin);
|
penServo.attach(g_iServoPin);
|
||||||
penServo.write(g_iPenState);
|
penServo.write(g_iPenState);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -51,19 +66,19 @@ void storePenDownPosInEE()
|
|||||||
|
|
||||||
void sendAck()
|
void sendAck()
|
||||||
{
|
{
|
||||||
Log(__FUNCTION__);
|
Log(__FUNCTION__);
|
||||||
Serial.print("OK\r\n");
|
Serial.print("OK\r\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
void sendError()
|
void sendError()
|
||||||
{
|
{
|
||||||
Log(__FUNCTION__);
|
Log(__FUNCTION__);
|
||||||
Serial.print("unknown CMD\r\n");
|
Serial.print("unknown CMD\r\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
void motorsOff()
|
void motorsOff()
|
||||||
{
|
{
|
||||||
Log(__FUNCTION__);
|
Log(__FUNCTION__);
|
||||||
g_pStepperPen->disableOutputs();
|
g_pStepperPen->disableOutputs();
|
||||||
g_pStepperRotate->disableOutputs();
|
g_pStepperRotate->disableOutputs();
|
||||||
g_bMotorsEnabled = 0;
|
g_bMotorsEnabled = 0;
|
||||||
@@ -71,7 +86,7 @@ void motorsOff()
|
|||||||
|
|
||||||
void motorsOn()
|
void motorsOn()
|
||||||
{
|
{
|
||||||
Log(__FUNCTION__);
|
Log(__FUNCTION__);
|
||||||
g_pStepperPen->enableOutputs();
|
g_pStepperPen->enableOutputs();
|
||||||
g_pStepperRotate->enableOutputs();
|
g_pStepperRotate->enableOutputs();
|
||||||
g_bMotorsEnabled = 1;
|
g_bMotorsEnabled = 1;
|
||||||
@@ -79,7 +94,7 @@ void motorsOn()
|
|||||||
|
|
||||||
void toggleMotors()
|
void toggleMotors()
|
||||||
{
|
{
|
||||||
Log(__FUNCTION__);
|
Log(__FUNCTION__);
|
||||||
if (g_bMotorsEnabled)
|
if (g_bMotorsEnabled)
|
||||||
{
|
{
|
||||||
motorsOff();
|
motorsOff();
|
||||||
@@ -123,16 +138,15 @@ void prepareMove(uint16_t duration, int penStepsEBB, int rotStepsEBB)
|
|||||||
motorsOn();
|
motorsOn();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if ((1 == fROT_STEP_CORRECTION) && (1 == fPEN_STEP_CORRECTION))
|
||||||
|
{ // if coordinatessystems are identical
|
||||||
|
// set Coordinates and Speed
|
||||||
|
g_pStepperRotate->setSpeedInTicks(abs((float)rotStepsEBB * (float)1000 / (float)duration));
|
||||||
|
g_pStepperRotate->move(rotStepsEBB);
|
||||||
|
|
||||||
if ((1 == fROT_STEP_CORRECTION) && (1 == fPEN_STEP_CORRECTION))
|
g_pStepperPen->setSpeedInTicks(abs((float)penStepsEBB * (float)1000 / (float)duration));
|
||||||
{ // if coordinatessystems are identical
|
g_pStepperPen->move(penStepsEBB);
|
||||||
// set Coordinates and Speed
|
}
|
||||||
g_pStepperRotate->setSpeedInTicks(abs((float)rotStepsEBB * (float)1000 / (float)duration));
|
|
||||||
g_pStepperRotate->move(rotStepsEBB);
|
|
||||||
|
|
||||||
g_pStepperPen->setSpeedInTicks(abs((float)penStepsEBB * (float)1000 / (float)duration));
|
|
||||||
g_pStepperPen->move(penStepsEBB);
|
|
||||||
}
|
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
// incoming EBB-Steps will be multiplied by 16, then Integer-maths is done, result will be divided by 16
|
// incoming EBB-Steps will be multiplied by 16, then Integer-maths is done, result will be divided by 16
|
||||||
@@ -150,25 +164,27 @@ void prepareMove(uint16_t duration, int penStepsEBB, int rotStepsEBB)
|
|||||||
long temp_penSpeed = ((long)penStepsToGo * (long)1000 / (long)duration);
|
long temp_penSpeed = ((long)penStepsToGo * (long)1000 / (long)duration);
|
||||||
|
|
||||||
float rotSpeed = (float)abs(temp_rotSpeed); // type cast
|
float rotSpeed = (float)abs(temp_rotSpeed); // type cast
|
||||||
float penSpeed = (float)abs(temp_penSpeed);
|
float penSpeed = (float)abs(temp_penSpeed);
|
||||||
|
|
||||||
// set Coordinates and Speed
|
// set Coordinates and Speed
|
||||||
g_pStepperRotate->setSpeedInTicks(rotSpeed);
|
g_pStepperRotate->setSpeedInTicks(rotSpeed);
|
||||||
g_pStepperRotate->move(rotStepsToGo);
|
g_pStepperRotate->move(rotStepsToGo);
|
||||||
|
|
||||||
g_pStepperPen->setSpeedInTicks(penSpeed);
|
g_pStepperPen->setSpeedInTicks(penSpeed);
|
||||||
g_pStepperPen->move(penStepsToGo);
|
g_pStepperPen->move(penStepsToGo);
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void moveOneStep()
|
void moveOneStep()
|
||||||
{
|
{
|
||||||
while (g_pStepperPen->isRunning() || g_pStepperRotate->isRunning());
|
while (g_pStepperPen->isRunning() || g_pStepperRotate->isRunning())
|
||||||
|
;
|
||||||
}
|
}
|
||||||
|
|
||||||
void moveToDestination()
|
void moveToDestination()
|
||||||
{
|
{
|
||||||
while (g_pStepperPen->isRunning() || g_pStepperRotate->isRunning());
|
while (g_pStepperPen->isRunning() || g_pStepperRotate->isRunning())
|
||||||
|
;
|
||||||
}
|
}
|
||||||
|
|
||||||
void setprgButtonState()
|
void setprgButtonState()
|
||||||
|
|||||||
18
src/main.cpp
18
src/main.cpp
@@ -59,9 +59,21 @@ int g_iPenState = g_iPenUpPos;
|
|||||||
uint32_t g_uiNodeCount = 0;
|
uint32_t g_uiNodeCount = 0;
|
||||||
unsigned int g_uiLayer = 0;
|
unsigned int g_uiLayer = 0;
|
||||||
boolean g_bPrgButtonState = 0;
|
boolean g_bPrgButtonState = 0;
|
||||||
float fROT_STEP_CORRECTION = 16.0 / rotMicrostep; // devide EBB-Coordinates by this factor to get EGGduino-Steps
|
|
||||||
float fPEN_STEP_CORRECTION = 16.0 / penMicrostep; // devide EBB-Coordinates by this factor to get EGGduino-Steps
|
|
||||||
boolean g_bMotorsEnabled = 0;
|
boolean g_bMotorsEnabled = 0;
|
||||||
|
int g_iRotDirPin = kDefaultRotDirPin;
|
||||||
|
int g_iRotEnablePin = kDefaultRotEnablePin;
|
||||||
|
int g_iRotStepPin = kDefaultRotStepPin;
|
||||||
|
int g_iPenStepPin = kDefaultPenStepPin;
|
||||||
|
int g_iPenDirPin = kDefaultPenDirPin;
|
||||||
|
int g_iPenEnablePin = kDefaultPenEnablePin;
|
||||||
|
int g_iServoPin = kDefaultServoPin;
|
||||||
|
int g_iRotMicrostep = kDefaultRotMicrostep;
|
||||||
|
int g_iPenMicrostep = kDefaultPenMicrostep;
|
||||||
|
float fROT_STEP_CORRECTION = 16.0 / kDefaultRotMicrostep; // devide EBB-Coordinates by this factor to get EGGduino-Steps
|
||||||
|
float fPEN_STEP_CORRECTION = 16.0 / kDefaultPenMicrostep; // devide EBB-Coordinates by this factor to get EGGduino-Steps
|
||||||
|
String g_sHostname = "EggDuino";
|
||||||
|
String g_sWifiSsid = "";
|
||||||
|
String g_sWifiPassword = "";
|
||||||
|
|
||||||
// Stepper Test
|
// Stepper Test
|
||||||
#ifdef TEST
|
#ifdef TEST
|
||||||
@@ -75,9 +87,9 @@ void setup()
|
|||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
Serial.println("Starting...");
|
Serial.println("Starting...");
|
||||||
Log("Starting...");
|
Log("Starting...");
|
||||||
|
startWebInterface();
|
||||||
makeComInterface();
|
makeComInterface();
|
||||||
initHardware();
|
initHardware();
|
||||||
startWebInterface();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t g_uiState = 0;
|
uint8_t g_uiState = 0;
|
||||||
|
|||||||
Reference in New Issue
Block a user