#include #include #include #include // Configuración WiFi const char* ssid = "ESP_AP"; const char* password = "123456789"; // Definición de pines #define STBY_PIN 10 #define AIN1_PIN 2 #define AIN2_PIN 3 #define PWMA_PIN 4 #define BIN1_PIN 5 #define BIN2_PIN 6 #define PWMB_PIN 7 #define TRIG_PIN 8 #define ECHO_PIN 9 #define SERVO_PIN 21 #define LED_PIN 20 // GPIO para la tira LED #define LED_COUNT 96 // Número de LEDs en tu matriz WebServer server(80); Servo obstacleServo; Adafruit_NeoPixel strip(LED_COUNT, LED_PIN, NEO_GRB + NEO_KHZ800); // Variables para el modo autónomo bool autonomousMode = false; String currentDirection = "stop"; const int motorSpeed = 255; const float safeDistance = 30.0; // Configuración del servo const int servoMinAngle = -45; const int servoMaxAngle = 45; const int servoCenter = 0; int currentServoAngle = servoCenter; bool servoMoving = false; unsigned long lastServoMove = 0; const int servoMoveInterval = 100; int servoDelay = 40; // Sensor ultrasónico unsigned long lastPingTime = 0; const int pingInterval = 100; float currentDistances[3] = {0, 0, 0}; bool waitingForEcho = false; unsigned long echoStartTime = 0; // Estados enum State { SCANNING, PROCESSING, MOVING }; State currentState = SCANNING; unsigned long stateStartTime = 0; // Red neuronal const int InputNodes = 3; const int HiddenNodes = 4; const int OutputNodes = 4; double Hidden[HiddenNodes]; double Output[OutputNodes]; float HiddenWeights[3][4] = { {1.8991509504079183, -0.4769472541445052, -0.6483690220539764, -0.38609165249078925}, {-0.2818610915467527, 4.040695699457223, 3.2291858058243843, -2.894301104732614}, {0.3340650864625773, -1.4016114422346901, 1.3580053902963762, -0.981415976256285} }; float OutputWeights[4][4] = { {1.136072297461121, 1.54602394937381, 1.6194612259569254, 1.8819066696635067}, {-1.546966506764457, 1.3951930739494225, 0.19393826092602756, 0.30992504138547006}, {-0.7755982417649826, 0.9390808625728915, 2.0862510744685485, -1.1229484266101883}, {-1.2357090352280826, 0.8583930286034466, 0.724702079881947, 0.9762852709700459} }; // Matrices de imágenes para la tira LED (¡COMPLÉTALAS CON TUS VALORES!) uint32_t frameForward[LED_COUNT] = { 0xFFFFFF, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0xFFFFFF, 0x000000, 0x0000FF, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x0000FF, 0x000000, 0x000000, 0x00FF00, 0x0000FF, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x0000FF, 0x00FF00, 0x000000, 0x000000, 0x00FF00, 0xFF0000, 0x0000FF, 0x000000, 0x000000, 0x000000, 0x000000, 0x0000FF, 0xFF0000, 0x00FF00, 0x000000, 0x000000, 0x000000, 0x00FF00, 0x00FF00, 0x000000, 0x007FFF, 0x007FFF, 0x000000, 0x00FF00, 0x00FF00, 0x00FF00, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0xFFFFFF, 0xFFFFFF, 0x000000, 0x000000, 0xFFFF00, 0xFFFF00, 0xFFFF00, 0xFFFF00, 0x000000, 0x000000, 0xFFFFFF, 0xFFFFFF, 0xFFFFFF, 0xFFFFFF, 0x000000, 0xFFFF00, 0x000000, 0x000000, 0x000000, 0x000000, 0xFFFF00, 0x000000, 0xFFFFFF, 0xFFFFFF }; uint32_t frameBackward[LED_COUNT] = { 0xFFFFFF, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0xFFFFFF, 0x000000, 0x0000FF, 0x0000FF, 0x0000FF, 0x000000, 0x000000, 0x000000, 0x000000, 0x0000FF, 0x0000FF, 0x0000FF, 0x000000, 0x000000, 0x00FF00, 0xFF0000, 0x00FF00, 0x000000, 0x000000, 0x000000, 0x000000, 0x00FF00, 0xFF0000, 0x00FF00, 0x000000, 0x000000, 0x00FF00, 0xFF0000, 0x00FF00, 0x000000, 0x007FFF, 0x007FFF, 0x000000, 0x00FF00, 0xFF0000, 0x00FF00, 0x000000, 0x000000, 0x00FF00, 0x00FF00, 0x00FF00, 0x000000, 0x007FFF, 0x007FFF, 0x000000, 0x00FF00, 0x00FF00, 0x00FF00, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0xFFFFFF, 0xFFFFFF, 0x000000, 0xFFFF00, 0x000000, 0x000000, 0x000000, 0x000000, 0xFFFF00, 0x000000, 0xFFFFFF, 0xFFFFFF, 0xFFFFFF, 0xFFFFFF, 0x000000, 0x000000, 0xFFFF00, 0xFFFF00, 0xFFFF00, 0xFFFF00, 0x000000, 0x000000, 0xFFFFFF, 0xFFFFFF }; uint32_t frameLeft[LED_COUNT] = { 0xFFFFFF, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0xFFFFFF, 0x000000, 0x0000FF, 0x0000FF, 0x0000FF, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x00FF00, 0xFF0000, 0x00FF00, 0x000000, 0x000000, 0x00FF00, 0xFF0000, 0x00FF00, 0x000000, 0x000000, 0x000000, 0x000000, 0x0000FF, 0x0000FF, 0x0000FF, 0x000000, 0x000000, 0x00FF00, 0x00FF00, 0x00FF00, 0x000000, 0x007FFF, 0x007FFF, 0x000000, 0x00FF00, 0x00FF00, 0x00FF00, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0xFFFFFF, 0xFFFFFF, 0x000000, 0xFFFF00, 0x000000, 0x000000, 0x000000, 0x000000, 0xFFFF00, 0x000000, 0xFFFFFF, 0xFFFFFF, 0xFFFFFF, 0xFFFFFF, 0x000000, 0x000000, 0xFFFF00, 0xFFFF00, 0xFFFF00, 0xFFFF00, 0x000000, 0x000000, 0xFFFFFF, 0xFFFFFF }; uint32_t frameRight[LED_COUNT] = { 0xFFFFFF, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0xFFFFFF, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x0000FF, 0x0000FF, 0x0000FF, 0x000000, 0x000000, 0x00FF00, 0xFF0000, 0x00FF00, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x0000FF, 0x0000FF, 0x0000FF, 0x000000, 0x000000, 0x000000, 0x000000, 0x00FF00, 0xFF0000, 0x00FF00, 0x000000, 0x000000, 0x00FF00, 0x00FF00, 0x00FF00, 0x000000, 0x007FFF, 0x007FFF, 0x000000, 0x00FF00, 0x00FF00, 0x00FF00, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0xFFFFFF, 0xFFFFFF, 0x000000, 0xFFFF00, 0x000000, 0x000000, 0x000000, 0x000000, 0xFFFF00, 0x000000, 0xFFFFFF, 0xFFFFFF, 0xFFFFFF, 0xFFFFFF, 0x000000, 0x000000, 0xFFFF00, 0xFFFF00, 0xFFFF00, 0xFFFF00, 0x000000, 0x000000, 0xFFFFFF, 0xFFFFFF }; uint32_t frameStop[LED_COUNT] = { 0xFFFFFF, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0xFFFFFF, 0x000000, 0x0000FF, 0x0000FF, 0x0000FF, 0x000000, 0x000000, 0x000000, 0x000000, 0x0000FF, 0x0000FF, 0x0000FF, 0x000000, 0x000000, 0x00FF00, 0xFF0000, 0x00FF00, 0x000000, 0x000000, 0x000000, 0x000000, 0x00FF00, 0xFF0000, 0x00FF00, 0x000000, 0x000000, 0x00FF00, 0xFF0000, 0x00FF00, 0x000000, 0x000000, 0x000000, 0x000000, 0x00FF00, 0xFF0000, 0x00FF00, 0x000000, 0x000000, 0x00FF00, 0x00FF00, 0x00FF00, 0x000000, 0x007FFF, 0x007FFF, 0x000000, 0x00FF00, 0x00FF00, 0x00FF00, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x007FFF, 0x007FFF, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0xFFFFFF, 0xFFFFFF, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0xFFFFFF, 0xFFFFFF, 0xFFFFFF, 0xFFFFFF, 0x000000, 0x000000, 0xFFFF00, 0xFFFF00, 0xFFFF00, 0xFFFF00, 0x000000, 0x000000, 0xFFFFFF, 0xFFFFFF }; // Función para mostrar imágenes en la tira LED void showLEDFrame(uint32_t frame[]) { for(int i = 0; i < LED_COUNT; i++) { strip.setPixelColor(i, frame[i]); } strip.show(); } void setup() { Serial.begin(115200); // Configuración de pines pinMode(STBY_PIN, OUTPUT); pinMode(AIN1_PIN, OUTPUT); pinMode(AIN2_PIN, OUTPUT); pinMode(PWMA_PIN, OUTPUT); pinMode(BIN1_PIN, OUTPUT); pinMode(BIN2_PIN, OUTPUT); pinMode(PWMB_PIN, OUTPUT); digitalWrite(STBY_PIN, HIGH); pinMode(TRIG_PIN, OUTPUT); pinMode(ECHO_PIN, INPUT); digitalWrite(TRIG_PIN, LOW); obstacleServo.attach(SERVO_PIN, 500, 2500); obstacleServo.write(servoCenter); // Inicializa la tira LED strip.begin(); strip.setBrightness(50); // Ajusta el brillo (0-255) strip.show(); // Apaga todos los LEDs inicialmente WiFi.softAP(ssid, password); Serial.print("IP del Access Point: "); Serial.println(WiFi.softAPIP()); // Configura rutas del servidor web server.on("/", handleRoot); server.on("/forward", []() { if(!autonomousMode) moveRobot("forward"); server.send(200, "text/plain", "OK"); }); server.on("/backward", []() { if(!autonomousMode) moveRobot("backward"); server.send(200, "text/plain", "OK"); }); server.on("/left", []() { if(!autonomousMode) moveRobot("left"); server.send(200, "text/plain", "OK"); }); server.on("/right", []() { if(!autonomousMode) moveRobot("right"); server.send(200, "text/plain", "OK"); }); server.on("/stop", []() { if(!autonomousMode) moveRobot("stop"); server.send(200, "text/plain", "OK"); }); server.on("/autonomous", []() { autonomousMode = true; currentState = SCANNING; server.send(200, "text/plain", "OK"); }); server.on("/manual", []() { autonomousMode = false; moveRobot("stop"); server.send(200, "text/plain", "OK"); }); server.on("/autonomousData", handleAutonomousData); server.begin(); } void loop() { server.handleClient(); if(autonomousMode) autonomousRoutine(); } void autonomousRoutine() { unsigned long currentTime = millis(); switch(currentState) { case SCANNING: handleScanningState(currentTime); break; case PROCESSING: handleProcessingState(currentTime); break; case MOVING: handleMovingState(currentTime); break; } handleUltrasonicSensor(currentTime); } void handleScanningState(unsigned long currentTime) { static int scanStep = 0; const int scanAngles[3] = {servoMinAngle, servoCenter, servoMaxAngle}; if(!servoMoving && currentTime - lastServoMove >= servoMoveInterval) { if(scanStep < 3) { currentServoAngle = scanAngles[scanStep]; obstacleServo.write(currentServoAngle); servoMoving = true; lastServoMove = currentTime; servoDelay = (scanStep == 0 || scanStep == 2) ? 80 : 40; startPing(); } else { currentState = PROCESSING; stateStartTime = currentTime; scanStep = 0; } } if(servoMoving && currentTime - lastServoMove >= servoDelay) { servoMoving = false; scanStep++; } } void handleProcessingState(unsigned long currentTime) { if(currentTime - stateStartTime >= 100) { processNeuralNetwork(currentDistances); currentState = MOVING; stateStartTime = currentTime; } } void handleMovingState(unsigned long currentTime) { if(currentTime - stateStartTime >= 300) { currentState = SCANNING; stateStartTime = currentTime; } } void handleUltrasonicSensor(unsigned long currentTime) { static bool waitingForEcho = false; static unsigned long pingTime = 0; if(!waitingForEcho && currentTime - lastPingTime >= pingInterval) { startPing(); lastPingTime = currentTime; waitingForEcho = true; pingTime = currentTime; } if(waitingForEcho) { long duration = pulseIn(ECHO_PIN, HIGH, 10000); if(duration > 0) { float distance = duration * 0.034 / 2.0; if(currentServoAngle <= -30) { currentDistances[0] = distance; } else if(currentServoAngle >= 30) { currentDistances[2] = distance; } else { currentDistances[1] = distance; } waitingForEcho = false; } else if(currentTime - pingTime > 50) { waitingForEcho = false; } } } void startPing() { digitalWrite(TRIG_PIN, LOW); delayMicroseconds(2); digitalWrite(TRIG_PIN, HIGH); delayMicroseconds(10); digitalWrite(TRIG_PIN, LOW); } void moveRobot(String direction) { currentDirection = direction; // Mostrar imagen en la tira LED según el movimiento if(direction == "forward") { showLEDFrame(frameForward); digitalWrite(AIN1_PIN, HIGH); digitalWrite(AIN2_PIN, LOW); analogWrite(PWMA_PIN, motorSpeed); digitalWrite(BIN1_PIN, HIGH); digitalWrite(BIN2_PIN, LOW); analogWrite(PWMB_PIN, motorSpeed); } else if(direction == "backward") { showLEDFrame(frameBackward); digitalWrite(AIN1_PIN, LOW); digitalWrite(AIN2_PIN, HIGH); analogWrite(PWMA_PIN, motorSpeed); digitalWrite(BIN1_PIN, LOW); digitalWrite(BIN2_PIN, HIGH); analogWrite(PWMB_PIN, motorSpeed); } else if(direction == "left") { showLEDFrame(frameLeft); digitalWrite(AIN1_PIN, LOW); digitalWrite(AIN2_PIN, HIGH); analogWrite(PWMA_PIN, motorSpeed); digitalWrite(BIN1_PIN, HIGH); digitalWrite(BIN2_PIN, LOW); analogWrite(PWMB_PIN, motorSpeed); } else if(direction == "right") { showLEDFrame(frameRight); digitalWrite(AIN1_PIN, HIGH); digitalWrite(AIN2_PIN, LOW); analogWrite(PWMA_PIN, motorSpeed); digitalWrite(BIN1_PIN, LOW); digitalWrite(BIN2_PIN, HIGH); analogWrite(PWMB_PIN, motorSpeed); } else { // stop showLEDFrame(frameStop); digitalWrite(AIN1_PIN, LOW); digitalWrite(AIN2_PIN, LOW); analogWrite(PWMA_PIN, 0); digitalWrite(BIN1_PIN, LOW); digitalWrite(BIN2_PIN, LOW); analogWrite(PWMB_PIN, 0); } } void processNeuralNetwork(float* inputs) { float normalizedInputs[3]; for(int i = 0; i < 3; i++) { normalizedInputs[i] = constrain(inputs[i], 0, 100) / 100.0; } for(int h = 0; h < HiddenNodes; h++) { Hidden[h] = 0; for(int i = 0; i < InputNodes; i++) { Hidden[h] += normalizedInputs[i] * HiddenWeights[i][h]; } Hidden[h] = tanh(Hidden[h]); } for(int o = 0; o < OutputNodes; o++) { Output[o] = 0; for(int h = 0; h < HiddenNodes; h++) { Output[o] += Hidden[h] * OutputWeights[h][o]; } Output[o] = tanh(Output[o]); } executeNeuralDecision(); } void executeNeuralDecision() { const float minDistance = 25.0; if(currentDistances[1] > minDistance) { moveRobot("forward"); // Mostrará frameForward } else { if(currentDistances[0] > currentDistances[2]) { moveRobot("left"); // Mostrará frameLeft } else { moveRobot("right"); // Mostrará frameRight } } } void handleAutonomousData() { String decision; if(currentDirection == "forward") decision = "Avanzando"; else if(currentDirection == "backward") decision = "Retrocediendo"; else if(currentDirection == "left") decision = "Girando izquierda"; else if(currentDirection == "right") decision = "Girando derecha"; else decision = "Detenido"; String json = "{"; json += "\"distances\":[" + String(currentDistances[0]) + "," + String(currentDistances[1]) + "," + String(currentDistances[2]) + "],"; json += "\"decision\":\"" + decision + "\","; json += "\"servoAngle\":" + String(currentServoAngle); json += "}"; server.send(200, "application/json", json); } void handleRoot() { String html = R"rawliteral( Control Robot

Control del Robot

Modo: MANUAL
Movimiento: Detenido
Izquierda: -- cm
Centro: -- cm
Derecha: -- cm
Angulo Servo: --°
)rawliteral"; server.send(200, "text/html", html); }