#include #include #include #include #include #include #define moveLedPin 2 #define engine1Pin1 14 #define engine1Pin2 12 #define engine2Pin1 13 #define engine2Pin2 15 #define engine3Pin1 16 #define engine3Pin2 5 #define engine4Pin1 4 #define engine4Pin2 0 bool connected = false; IPAddress IP; StaticJsonDocument<200> doc; AsyncWebServer server(80); AsyncWebSocket ws("/ws"); const char *ssid = "car-esp8266"; const char *password = "password"; int x = 0; int y = 0; bool moveInitialized = false; bool moveUserActive = false; unsigned int moveInterval = 50; unsigned int moveTimeout = 600; unsigned int lastMoveTime = 0; unsigned int currentTime = 0; void onWsEvent(AsyncWebSocket *server, AsyncWebSocketClient *client, AwsEventType type, void *arg, uint8_t *data, size_t len) { if (type == WS_EVT_CONNECT) { connected = true; lastMoveTime = 0; Serial.printf("Client connected [%s][%u]\n", server->url(), client->id()); } else if (type == WS_EVT_DISCONNECT) { connected = false; Serial.printf("Client disconnected [%s][%u]\n", server->url(), client->id()); } else if (type == WS_EVT_ERROR) { connected = false; Serial.printf("ws[%s][%u] error(%u): %s\n", server->url(), client->id(), *((uint16_t *) arg), (char *) data); } else if (type == WS_EVT_DATA) { AwsFrameInfo *info = (AwsFrameInfo *) arg; if (info->final && info->index == 0 && info->len == len) { data[len] = 0; DeserializationError error = deserializeJson(doc, (char *) data); if (error) { Serial.print("deserializeJson() failed: "); Serial.println(error.c_str()); return; } lastMoveTime = millis(); moveInitialized = false; moveInterval = doc["moveInterval"]; if(moveInterval < 50) { moveInterval = 50; } moveTimeout = doc["moveTimeout"]; if(moveTimeout < moveInterval * 2) { moveTimeout = moveInterval * 2; } moveUserActive = doc["active"]; x = doc["x"]; y = doc["y"]; } } } const char indexhtml[] PROGMEM = R"rawliteral( RC Car
[v1.0] Disconnected (0/0) settings
)rawliteral"; void setup() { Serial.begin(115200); IPAddress ip(192, 168, 4, 1); IPAddress gateway(192, 168, 4, 254); IPAddress subnet(255, 255, 255, 0); WiFi.mode(WIFI_AP_STA); WiFi.softAPConfig(ip, gateway, subnet); WiFi.softAP(ssid, password); IP = WiFi.softAPIP(); ws.onEvent(onWsEvent); server.addHandler(&ws); server.on("/", HTTP_GET, [](AsyncWebServerRequest *request) { request->send(200, "text/html", indexhtml); }); server.onNotFound([](AsyncWebServerRequest *request) { request->send(404, "text/plain", "Not found"); }); server.begin(); pinMode(moveLedPin, OUTPUT); pinMode(engine1Pin1, OUTPUT); pinMode(engine1Pin2, OUTPUT); pinMode(engine2Pin1, OUTPUT); pinMode(engine2Pin2, OUTPUT); pinMode(engine3Pin1, OUTPUT); pinMode(engine3Pin2, OUTPUT); pinMode(engine4Pin1, OUTPUT); pinMode(engine4Pin2, OUTPUT); digitalWrite(moveLedPin, LOW); digitalWrite(engine1Pin1, LOW); digitalWrite(engine1Pin2, LOW); digitalWrite(engine2Pin1, LOW); digitalWrite(engine2Pin2, LOW); digitalWrite(engine3Pin1, LOW); digitalWrite(engine3Pin1, LOW); digitalWrite(engine4Pin1, LOW); digitalWrite(engine4Pin2, LOW); } void moveLedEnabled(bool enabled) { if (enabled) { digitalWrite(moveLedPin, HIGH); } else { digitalWrite(moveLedPin, LOW); } } void engineControl(int x, int y) { //forward if (y < -40) { digitalWrite(engine1Pin1, HIGH); digitalWrite(engine1Pin2, LOW); digitalWrite(engine2Pin1, HIGH); digitalWrite(engine2Pin2, LOW); digitalWrite(engine3Pin1, HIGH); digitalWrite(engine3Pin2, LOW); digitalWrite(engine4Pin1, HIGH); digitalWrite(engine4Pin2, LOW); return; } //back if(y > 40) { digitalWrite(engine1Pin1, LOW); digitalWrite(engine1Pin2, HIGH); digitalWrite(engine2Pin1, LOW); digitalWrite(engine2Pin2, HIGH); digitalWrite(engine3Pin1, LOW); digitalWrite(engine3Pin2, HIGH); digitalWrite(engine4Pin1, LOW); digitalWrite(engine4Pin2, HIGH); return; } //right if(x > 40) { digitalWrite(engine1Pin1, LOW); digitalWrite(engine1Pin2, HIGH); digitalWrite(engine2Pin1, LOW); digitalWrite(engine2Pin2, HIGH); digitalWrite(engine3Pin1, HIGH); digitalWrite(engine3Pin2, LOW); digitalWrite(engine4Pin1, HIGH); digitalWrite(engine4Pin2, LOW); return; } //left if(x < -40) { digitalWrite(engine1Pin1, HIGH); digitalWrite(engine1Pin2, LOW); digitalWrite(engine2Pin1, HIGH); digitalWrite(engine2Pin2, LOW); digitalWrite(engine3Pin1, LOW); digitalWrite(engine3Pin2, HIGH); digitalWrite(engine4Pin1, LOW); digitalWrite(engine4Pin2, HIGH); return; } digitalWrite(engine1Pin1, LOW); digitalWrite(engine1Pin2, LOW); digitalWrite(engine2Pin1, LOW); digitalWrite(engine2Pin2, LOW); digitalWrite(engine3Pin1, LOW); digitalWrite(engine3Pin2, LOW); digitalWrite(engine4Pin1, LOW); digitalWrite(engine4Pin2, LOW); } void loop() { if (lastMoveTime == 0) { engineControl(0, 0); return; } currentTime = millis(); if (!connected) { return; } if (currentTime - lastMoveTime < moveInterval && moveInitialized) { return; } if (currentTime - lastMoveTime > moveTimeout) { moveLedEnabled(false); moveInitialized = false; engineControl(0, 0); return; } engineControl(x, y); moveInitialized = true; moveLedEnabled(moveUserActive); }