En este tutorial aprenderás a crear un carrito robótico controlado desde tu celular usando la placa UNIT Pulsar ESP32-C6, empleando una conexión WiFi mediante un Punto de Acceso y un WebSockets para lograr un control instantáneo y sin retraso a través de un joystick virtual.
Al finalizar, tendrás un robot móvil totalmente funcional y listo para personalizar con sensores, más funciones o incluso autonomía para futuros proyectos de robótica e IoT.
INTRODUCCIÓN
En el mundo de la robótica educativa y el Internet de las Cosas (IoT), el uso de microcontroladores con conectividad inalámbrica se ha vuelto indispensable. La UNIT Pulsar ESP32-C6 es una de las tarjetas más modernas para este tipo de proyectos, ya que integra WiFi y Bluetooth de bajo consumo, lo que permite desarrollar sistemas interactivos y remotos con gran facilidad.
En este tutorial aprenderás a crear un carrito robótico WiFi capaz de comunicarse directamente con tu celular mediante una red inalámbrica generada por el propio microcontrolador, sin necesidad de Internet ni aplicaciones externas. Utilizaremos WebSockets para una comunicación en tiempo real y un joystick virtual desarrollado con tecnologías web (HTML, CSS y JavaScript), lo cual permitirá controlar los motores con una respuesta rápida y estable.
También exploraremos el manejo del driver L298N, responsable de controlar la dirección y velocidad de los motores mediante PWM, y agregaremos un sistema watchdog que detendrá el carrito automáticamente si se pierde la conexión. Este proyecto combina electrónica, redes inalámbricas y desarrollo web en un solo dispositivo, ofreciendo una experiencia completa y práctica que te permitirá dar tus primeros pasos en la robótica móvil inteligente.
Comencemos con el desarrollo paso a paso. Sigue cada sección con atención para que puedas replicar el tutorial sin complicaciones.
MATERIALES
- UNIT Pulsar ESP32-C6
- L298N Módulo Driver Motor DC
- Kit Mini Robot Educacional
- Shield para Nano
- Cables Dupont Cortos 10cm MH
- Cable Dupont 20cm M-M
- KCD11-2P Interruptor ON OFF Rojo
- Batería 18650 de 7.4V 2S1P 2200mAh
- Alambre para Protoboard 1 Metro Rojo
- Alambre para Protoboard 1 Metro Negro
- Cincho Negro 15cm
- Cinta de Montaje Doble Cara
- Separador de Nylon para PCB M3 x 10mm
REFERENCIA DE ENSAMBLE
El ensamblaje del carrito es muy sencillo. Puedes guiarte con el video de referencia incluido en este tutorial, donde se muestra paso a paso cómo montar el chasis y colocar correctamente cada componente.
La UNIT Pulsar ESP32-C6 con el Shield Nano se fija al chasis utilizando separadores de nylon.
El driver L298N puede sujetarse fácilmente con un cincho de plástico y la batería se recomienda fijarla mediante cinta doble cara para mantenerla estable durante el movimiento. Con esta guía visual, podrás armar tu carrito sin complicaciones y dejarlo listo para realizar las conexiones entre los elementos.
DIAGRAMA DE CONEXIÓN
A continuación se muestra el diagrama de conexiones del carrito utilizando la UNIT Pulsar ESP32-C6, el driver L298N y la batería 18650 en configuración 2S (7.4V). Este esquema te permitirá cablear correctamente los motores, el driver y la alimentación para que el carrito funcione.
- La UNIT Pulsar ESP32-C6 se encarga del control y la comunicación WiFi.
- El L298N recibe las señales de dirección y PWM para controlar la velocidad y el sentido de giro de ambos motores.
- La batería 7.4V alimenta el sistema completo y pasa primero por un interruptor ON/OFF para mayor seguridad.
- Los pines de control de motores están asignados según el programa del tutorial, por lo que es importante conectar exactamente igual que en el diagrama.

En el siguiente video se muestra como debe quedar el carrito armado y con las conexiones realizadas:
CÓDIGO
Una vez ensamblado el carrito y realizadas todas las conexiones, es momento de programarlo. Antes de cargar el código en la UNIT Pulsar ESP32-C6, realiza las siguientes configuraciones:
1. Configuración de entorno de programación
Usaremos Arduino IDE como entorno de desarrollo. Sigue estos pasos:
- Instala el Arduino IDE
Descárgalo desde el sitio oficial:
👉 https://www.arduino.cc/en/software
⚠️(Si ya lo tienes instalado, puedes omitir este paso).
- Agrega la placas de desarrollo UNIT Electronics ESP32 a Arduino IDE
Abre el IDE y ve a Archivo > Preferencias
En el campo “Gestor de URLs adicionales de tarjetas”, agrega la siguiente dirección:
👉 https://raw.githubusercontent.com/UNIT-Electronics/Uelectronics-ESP32-Arduino-Package/main/package_Uelectronics_esp32_index.json

- Instala las placas UNIT Electronics ESP32 desde el Gestor de placas de Arduino IDE
Después la URL al preferencias dirígete a la pestaña Herramientas > Placa > Gestor de placas, busca “UNIT Electronics ESP32” e instala las placas. En la siguiente imagen tienes la referencia.

- Instalar la librería WebSockets
Descarga la librería desde el siguiente repositorio y agrégala como ZIP:
👉ArduinoWebsokets

- Seleccionar la placa UNIT Pulsar ESP32 C6
Antes de compilar y cargar el código, verifica que tengas seleccionada la siguiente tarjeta:
Herramientas > Placa > UNIT Electronics ESP32-C6 > Pulsar ESP32 C6

Con estas configuraciones completadas, tu entorno estará listo para compilar y cargar el programa en la Pulsar.
/*
UNIT CAR PULSAR - Control por WebSockets + Joystick virtual
Este archivo contiene:
- Librerías principales
- Definición de pines, variables globales y configuración
- setup() y loop()
- Watchdog para evitar que el carrito se quede corriendo si se pierde la conexión
*/
#include <WiFi.h>
#include <WebServer.h>
#include <WebSocketsServer.h>
#include <math.h> // Para fabs(), max(), etc.
// =============================
// PINES DEL DRIVER L298N
// =============================
// Pines de dirección del puente H
#define IN1 15 // Motor A - IN1 - D4
#define IN2 19 // Motor A - IN2 - D5
#define IN3 20 // Motor B - IN3 - D6
#define IN4 21 // Motor B - IN4 - D7
// Pines PWM para ENA / ENB
#define ENA 7 // PWM Motor A (izquierdo) - D11
#define ENB 18 // PWM Motor B (derecho) - D10
// =============================
// VELOCIDAD Y WATCHDOG
// =============================
// Velocidad base (0-255). Se usan para corregir diferencias entre motores.
uint8_t baseSpeedA = 210; // Motor A (izquierdo)
uint8_t baseSpeedB = 200; // Motor B (derecho)
// Tiempo máximo sin recibir comando antes de detener (ms)
const unsigned long COMMAND_TIMEOUT = 500;
// Última vez que llegó un comando de movimiento
unsigned long lastCommandTime = 0;
// =============================
// RED WiFi (Modo Access Point)
// =============================
const char* ssid = "UNIT CAR PULSAR"; // Nombre de la red WiFi
const char* password = "UNIT-Robot-01"; // Contraseña
// Servidor HTTP (solo para servir la página)
WebServer server(80);
// Servidor WebSocket (para control en tiempo real)
WebSocketsServer webSocket(81);
// ==== Prototipos de funciones que están en otras pestañas ====
// (No son estrictamente necesarios, pero ayudan a entender)
void stopAllMotors(); // Definida en Motors.ino
void handleRoot(); // Definida en WebApp.ino
void webSocketEvent(uint8_t num, WStype_t type, uint8_t * payload, size_t length); // WebApp.ino
// ==================================================
// SETUP: se ejecuta una sola vez al encender el ESP
// ==================================================
void setup() {
// Configurar pines de dirección como salidas
pinMode(IN1, OUTPUT);
pinMode(IN2, OUTPUT);
pinMode(IN3, OUTPUT);
pinMode(IN4, OUTPUT);
// Configurar pines PWM como salidas
pinMode(ENA, OUTPUT);
pinMode(ENB, OUTPUT);
// Detener motores por seguridad
stopAllMotors();
lastCommandTime = millis();
// Iniciar WiFi en modo Punto de Acceso (AP)
// El celular se conectará directamente al ESP32-C6
WiFi.softAP(ssid, password);
// Configurar la ruta principal del servidor HTTP
// Al abrir http://192.168.4.1 se servirá la página con el joystick
server.on("/", handleRoot);
server.begin();
// Iniciar servidor WebSocket en el puerto 81
webSocket.begin();
webSocket.onEvent(webSocketEvent); // Función que manejará los mensajes del joystick
}
// ==================================================
// LOOP: se ejecuta continuamente
// ==================================================
void loop() {
// Atender peticiones HTTP (para servir la página)
server.handleClient();
// Atender mensajes WebSocket (joystick)
webSocket.loop();
// Watchdog:
// Si pasa demasiado tiempo sin recibir comandos de joystick,
// detenemos los motores para evitar que el carro se quede corriendo.
if (millis() - lastCommandTime > COMMAND_TIMEOUT) {
stopAllMotors();
}
}
/*
Motors.ino
----------
Aquí está toda la lógica de control de motores:
- Función setSpeed() para PWM
- stopAllMotors() para detener el carrito
- setMotorSpeeds() que recibe joyX, joyY y calcula velocidades
*/
// ========== FUNCIONES DE MOTORES ==========
// Ajusta el PWM de ENA y ENB según las velocidades (0-255)
void setSpeed(uint8_t sa, uint8_t sb) {
analogWrite(ENA, sa); // Motor A (izquierdo)
analogWrite(ENB, sb); // Motor B (derecho)
}
// Detiene todos los motores (PWM en 0 y pines en LOW)
void stopAllMotors() {
setSpeed(0, 0);
digitalWrite(IN1, LOW);
digitalWrite(IN2, LOW);
digitalWrite(IN3, LOW);
digitalWrite(IN4, LOW);
}
/*
setMotorSpeeds(float joyX, float joyY)
Recibe la posición del joystick:
joyX: entre -1.0 y 1.0 (izquierda / derecha)
joyY: entre -1.0 y 1.0 (atrás / adelante)
- Combina joyX y joyY en un control diferencial:
v = joyY (velocidad lineal)
w = joyX (velocidad de giro)
left = v - w
right = v + w
- left/right se normalizan a -1..1
- Según el signo (+/-) de cada motor, se decide el sentido
- La magnitud se lleva a un valor PWM usando baseSpeedA / baseSpeedB
*/
void setMotorSpeeds(float joyX, float joyY) {
// Pequeña zona muerta para evitar vibraciones cerca del centro
const float deadZone = 0.10;
if (fabs(joyX) < deadZone && fabs(joyY) < deadZone) {
// Joystick prácticamente en el centro -> detener
stopAllMotors();
return;
}
// Componentes de movimiento:
// joyY: adelante(+), atrás(-)
// joyX: derecha(+), izquierda(-)
float v = joyY; // movimiento lineal
float w = joyX; // giro
// Mezcla diferencial
float left = v - w; // Motor A (izquierdo)
float right = v + w; // Motor B (derecho)
// Normalizar para que ningún valor supere 1.0 en magnitud
float maxVal = max(1.0f, max(fabs(left), fabs(right)));
left /= maxVal;
right /= maxVal;
// ===== Motor A (izquierdo) =====
if (left >= 0) {
// Hacia adelante
// (ajusta estos HIGH/LOW si tu cableado es diferente)
digitalWrite(IN1, LOW);
digitalWrite(IN2, HIGH);
} else {
// Hacia atrás
digitalWrite(IN1, HIGH);
digitalWrite(IN2, LOW);
}
// ===== Motor B (derecho) =====
if (right >= 0) {
// Hacia adelante
digitalWrite(IN3, HIGH);
digitalWrite(IN4, LOW);
} else {
// Hacia atrás
digitalWrite(IN3, LOW);
digitalWrite(IN4, HIGH);
}
// Convertir magnitud (0..1) a PWM (0..baseSpeedX)
uint8_t speedA = (uint8_t)(fabs(left) * baseSpeedA);
uint8_t speedB = (uint8_t)(fabs(right) * baseSpeedB);
setSpeed(speedA, speedB);
}
/*
WebApp.ino
----------
- Maneja el evento de WebSocket (webSocketEvent)
- Envía/recibe datos del joystick
- Define la página HTML con el joystick virtual
*/
// ========== MANEJADOR DE EVENTOS WEBSOCKET ==========
/*
webSocketEvent:
- type == WStype_TEXT => llega un mensaje de texto desde el navegador.
- El mensaje esperado es "x,y" con x e y entre -1.0 y 1.0
Por ejemplo: "0.25,-0.80"
*/
void webSocketEvent(uint8_t num, WStype_t type, uint8_t * payload, size_t length) {
switch (type) {
case WStype_TEXT: {
// Convertir el payload (char*) en String
String msg = String((char*)payload).substring(0, length);
// Buscar la coma que separa x,y
int commaIndex = msg.indexOf(',');
if (commaIndex > 0) {
float x = msg.substring(0, commaIndex).toFloat();
float y = msg.substring(commaIndex + 1).toFloat();
// Actualizar motores según la posición del joystick
setMotorSpeeds(x, y);
// Actualizar tiempo del último comando recibido
lastCommandTime = millis();
}
break;
}
case WStype_DISCONNECTED:
// Si el cliente se desconecta, por seguridad, detenemos el carrito
stopAllMotors();
break;
default:
break;
}
}
// ========== INTERFAZ HTML + JOYSTICK ==========
void handleRoot() {
String html = R"rawliteral(
<!DOCTYPE html>
<html>
<head>
<meta charset="UTF-8">
<title>UNIT CAR PULSAR</title>
<meta name="viewport" content="width=device-width, initial-scale=1">
<style>
body {
font-family: sans-serif;
text-align: center;
background: #f5f5f5;
margin: 0;
padding: 20px;
touch-action: none; /* evita scroll mientras mueves el joystick */
}
h1 { margin-bottom: 10px; }
p { margin: 5px 0; }
#joystick-container {
position: relative;
width: 220px;
height: 220px;
margin: 40px auto;
border-radius: 50%;
background: #ddd;
box-shadow: 0 0 8px rgba(0,0,0,0.3);
touch-action: none;
}
#joystick-handle {
position: absolute;
width: 80px;
height: 80px;
margin-left: -40px; /* la mitad para centrar horizontal */
margin-top: -40px; /* la mitad para centrar vertical */
top: 50%;
left: 50%;
border-radius: 50%;
background: #007bff;
box-shadow: 0 0 8px rgba(0,0,0,0.4);
display: flex;
align-items: center;
justify-content: center;
color: #fff;
font-size: 30px;
user-select: none;
}
#status {
margin-top: 10px;
color: #333;
}
</style>
</head>
<body>
<h1>UNIT CAR PULSAR</h1>
<p>Mueve el joystick para controlar el carrito</p>
<div id="joystick-container">
<div id="joystick-handle">🚗</div>
</div>
<p id="status">Conectando...</p>
<script>
let ws;
let joystickContainer = document.getElementById('joystick-container');
let joystickHandle = document.getElementById('joystick-handle');
let statusText = document.getElementById('status');
let centerX, centerY, radius;
let isPointerDown = false;
// Conexión WebSocket al ESP32-C6
function connectWS() {
ws = new WebSocket('ws://' + window.location.hostname + ':81/');
ws.onopen = () => {
statusText.textContent = 'Conectado ✅';
};
ws.onclose = () => {
statusText.textContent = 'Desconectado ❌, reintentando...';
// Reintentar conexión automáticamente
setTimeout(connectWS, 1000);
};
ws.onerror = () => {
statusText.textContent = 'Error WebSocket';
};
}
connectWS();
// Enviar los valores normalizados x,y (-1..1) al ESP por WebSocket
function sendJoy(x, y) {
if (!ws || ws.readyState !== WebSocket.OPEN) return;
ws.send(x.toFixed(2) + ',' + y.toFixed(2));
}
// Calcular el centro y el radio del joystick
function updateCenter() {
const rect = joystickContainer.getBoundingClientRect();
centerX = rect.left + rect.width / 2;
centerY = rect.top + rect.height / 2;
radius = rect.width / 2;
}
window.addEventListener('resize', updateCenter);
window.addEventListener('load', updateCenter);
// Actualizar la posición del handle y mandar datos al ESP
function setHandlePosition(clientX, clientY) {
let dx = clientX - centerX;
let dy = clientY - centerY;
// Limitar el joystick al círculo
const dist = Math.sqrt(dx*dx + dy*dy);
if (dist > radius) {
dx = dx * radius / dist;
dy = dy * radius / dist;
}
// Posicionar visualmente el handle
joystickHandle.style.left = (50 + (dx / radius)*50) + '%';
joystickHandle.style.top = (50 + (dy / radius)*50) + '%';
// Normalizar a -1..1
const x = dx / radius;
const y = -(dy / radius); // invertimos Y: arriba debe ser +1
// Enviar al ESP32-C6
sendJoy(x, y);
}
// Volver el joystick al centro y enviar STOP (0,0)
function resetHandle() {
joystickHandle.style.left = '50%';
joystickHandle.style.top = '50%';
sendJoy(0, 0);
}
// Eventos de puntero (funciona con mouse y touch)
joystickContainer.addEventListener('pointerdown', (e) => {
e.preventDefault();
isPointerDown = true;
updateCenter();
setHandlePosition(e.clientX, e.clientY);
});
window.addEventListener('pointermove', (e) => {
if (!isPointerDown) return;
e.preventDefault();
setHandlePosition(e.clientX, e.clientY);
});
window.addEventListener('pointerup', (e) => {
if (!isPointerDown) return;
e.preventDefault();
isPointerDown = false;
resetHandle();
});
window.addEventListener('pointercancel', () => {
isPointerDown = false;
resetHandle();
});
</script>
</body>
</html>
)rawliteral";
// Enviar la página al navegador
server.send(200, "text/html", html);
}
Este código permite controlar el carrito UNIT Car Pulsar de manera inalámbrica utilizando WebSockets y un joystick virtual desde cualquier navegador web. El ESP32-C6 se configura como un Punto de Acceso WiFi (AP) al cual puedes conectar tu celular para controlar el carrito en tiempo real sin necesidad de internet. La comunicación se procesa en milisegundos para lograr un control fluido, mientras que un watchdog de seguridad evita que el carrito siga avanzando si se pierde la conexión. Además, implementa control diferencial para maniobras como avanzar, retroceder y girar, ajustando la velocidad de cada motor mediante PWM.
Cómo conectarte al carrito y controlar desde el navegador
Una vez que hayas cargado el código a la UNIT Pulsar ESP32-C6 y el carrito esté encendido, sigue estos pasos para controlarlo desde tu celular o laptop:
- Enciende el carrito
- Coloca el interruptor en posición ON para alimentar la Pulsar y el driver L298N.
- Conéctate a la red WiFi del carrito
- En tu celular o computadora, abre la configuración de WiFi.
- Busca la red con el nombre:
UNIT CAR PULSAR - Selecciónala e ingresa la contraseña:
UNIT-Robot-01 - Espera a que se marque como Conectado.
- Abrir la interfaz de control en el navegador
- Abre un navegador (Chrome, Edge, Firefox, etc.) en el dispositivo que conectaste a la red del carrito.
- En la barra de direcciones escribe la siguiente IP:
👉http://192.168.4.1 - Presiona Enter.
- Se cargará la página con el joystick virtual para controlar el carrito.
- Controlar el carrito con el joystick
- Toca y arrastra el joystick en la pantalla:
- Hacia arriba: el carrito avanza.
- Hacia abajo: el carrito retrocede.
- Izquierda / derecha: el carrito gira.
- Al soltar el joystick, éste vuelve al centro y el carrito se detiene.
- Toca y arrastra el joystick en la pantalla:
- Seguridad (Watchdog)
- Si por alguna razón se pierde la conexión o cierras el navegador, el código incluye un watchdog que detiene automáticamente los motores después de un breve tiempo sin recibir comandos.
CONCLUSIONES
En este tutorial construimos un carrito robótico que se controla desde un celular mediante una página web, gracias a la conectividad WiFi del UNIT Pulsar ESP32-C6. Usamos WebSockets para lograr un control rápido y sin retrasos, además de un joystick virtual muy fácil de usar. También aprendimos a manejar los motores con el driver L298N y a aplicar PWM para ajustarlos según la dirección del movimiento. Para mayor seguridad, integramos un sistema que detiene los motores si el celular se desconecta o deja de enviar comandos.
Este proyecto es una excelente introducción al mundo de la robótica y el IoT, ya que combina programación, electrónica y control inalámbrico en un solo equipo. Ahora tienes una plataforma funcional que puedes mejorar con sensores, cámara, inteligencia artificial o nuevas funciones.

