Загрузка данных
#include <WiFi.h>
#include <WebServer.h>
const char* AP_SSID = "ROBOT_CTRL";
const char* AP_PASS = "12345678";
WebServer server(80);
HardwareSerial RobotSerial(1); // RX=15, TX=13
// ===================== СОСТОЯНИЕ =====================
struct StatusData {
char mode = '?';
char motion = '?';
int sector = -1;
int reed = -1;
int hall = -1;
int mag = -1;
int dist = -1;
};
StatusData st;
String latestStatus = "";
String latestEvent = "Ожидание...";
char lastCmdSent = 0;
unsigned long lastCmdMs = 0;
// ===================== СКАН-ТОЧКИ =====================
struct ScanPoint {
uint8_t angle;
uint16_t dist;
};
const int MAX_SCAN_POINTS = 120;
ScanPoint scanPoints[MAX_SCAN_POINTS];
int scanCount = 0;
int scanWriteIndex = 0;
void addScanPoint(uint8_t a, uint16_t d) {
if (scanCount < MAX_SCAN_POINTS) {
scanPoints[scanCount].angle = a;
scanPoints[scanCount].dist = d;
scanCount++;
} else {
scanPoints[scanWriteIndex].angle = a;
scanPoints[scanWriteIndex].dist = d;
scanWriteIndex++;
if (scanWriteIndex >= MAX_SCAN_POINTS) scanWriteIndex = 0;
}
}
// ===================== JSON =====================
String jsonEscape(const String& s) {
String out;
for (size_t i = 0; i < s.length(); i++) {
char ch = s[i];
if (ch == '\\') out += "\\\\";
else if (ch == '"') out += "\\\"";
else if (ch == '\n') out += "\\n";
else if (ch == '\r') out += "\\r";
else out += ch;
}
return out;
}
// ===================== ПАРСИНГ ЛИНИЙ =====================
void parseScanLine(const String& line) {
int a = -1;
int d = -1;
if (sscanf(line.c_str(), "@SCAN a=%d d=%d", &a, &d) == 2) {
if (a >= 0 && a <= 180 && d > 0 && d < 500) {
addScanPoint((uint8_t)a, (uint16_t)d);
}
}
}
void parseStatusLine(const String& line) {
char mode = '?';
char motion = '?';
int sector = -1;
int reed = -1;
int hall = -1;
int mag = -1;
int dist = -1;
int ok = sscanf(
line.c_str(),
"@STATUS mode=%c motion=%c sector=%d reed=%d hall=%d mag=%d dist=%d",
&mode, &motion, §or, &reed, &hall, &mag, &dist
);
if (ok == 7) {
st.mode = mode;
st.motion = motion;
st.sector = sector;
st.reed = reed;
st.hall = hall;
st.mag = mag;
st.dist = dist;
}
}
void readArduinoLines() {
static String line = "";
while (RobotSerial.available()) {
char ch = (char)RobotSerial.read();
if (ch == '\r') continue;
if (ch == '\n') {
line.trim();
if (line.startsWith("@STATUS")) {
latestStatus = line;
parseStatusLine(line);
} else if (line.startsWith("@EVENT")) {
latestEvent = line;
} else if (line.startsWith("@SCAN")) {
parseScanLine(line);
}
line = "";
} else {
line += ch;
if (line.length() > 180) line = "";
}
}
}
// ===================== КОМАНДЫ =====================
bool isSingleCommand(char c) {
switch (c) {
case 'V':
case 'N':
case 'P':
case 'E':
return true;
default:
return false;
}
}
void sendCmd(char c) {
unsigned long now = millis();
if (isSingleCommand(c)) {
if (c == lastCmdSent && (now - lastCmdMs) < 280) return;
}
RobotSerial.write(c);
lastCmdSent = c;
lastCmdMs = now;
}
// ===================== API =====================
String pointsToJson() {
String out = "[";
if (scanCount == 0) {
out += "]";
return out;
}
if (scanCount < MAX_SCAN_POINTS) {
for (int i = 0; i < scanCount; i++) {
if (i) out += ",";
out += "[";
out += String(scanPoints[i].angle);
out += ",";
out += String(scanPoints[i].dist);
out += "]";
}
} else {
for (int k = 0; k < MAX_SCAN_POINTS; k++) {
int i = (scanWriteIndex + k) % MAX_SCAN_POINTS;
if (k) out += ",";
out += "[";
out += String(scanPoints[i].angle);
out += ",";
out += String(scanPoints[i].dist);
out += "]";
}
}
out += "]";
return out;
}
void handleStatus() {
String json = "{";
json += "\"mode\":\""; json += st.mode; json += "\",";
json += "\"motion\":\""; json += st.motion; json += "\",";
json += "\"sector\":"; json += String(st.sector); json += ",";
json += "\"reed\":"; json += String(st.reed); json += ",";
json += "\"hall\":"; json += String(st.hall); json += ",";
json += "\"mag\":"; json += String(st.mag); json += ",";
json += "\"dist\":"; json += String(st.dist); json += ",";
json += "\"raw_status\":\"" + jsonEscape(latestStatus) + "\",";
json += "\"event\":\"" + jsonEscape(latestEvent) + "\",";
json += "\"points_count\":" + String(scanCount) + ",";
json += "\"points\":" + pointsToJson();
json += "}";
server.send(200, "application/json; charset=utf-8", json);
}
void handleCmd() {
if (server.hasArg("c")) {
String s = server.arg("c");
if (s.length() > 0) sendCmd(s.charAt(0));
}
server.send(200, "text/plain; charset=utf-8", "OK");
}
// ===================== HTML =====================
const char PAGE[] PROGMEM = R"rawliteral(
<!DOCTYPE html>
<html lang="ru">
<head>
<meta charset="utf-8">
<title>ROBOT CTRL</title>
<meta name="viewport" content="width=device-width, initial-scale=1, viewport-fit=cover">
<style>
:root{
--bg:#0c0f16;
--card:#151a24;
--card2:#0f1420;
--text:#eef3ff;
--muted:#8fa2c4;
--line:#283244;
--btn:#252c3a;
--btn2:#313b4d;
--accent:#ffd27a;
--dot:#85d8ff;
}
*{ box-sizing:border-box; }
html, body {
margin:0;
padding:0;
background:var(--bg);
color:var(--text);
font-family:Arial, sans-serif;
overflow-x:hidden;
-webkit-text-size-adjust:100%;
}
body {
min-height:100vh;
}
.page {
width:100%;
max-width:1200px;
margin:0 auto;
padding:12px;
}
.wrap{
display:grid;
grid-template-columns: 1fr 1fr;
gap:12px;
align-items:start;
}
.card{
background:var(--card);
border-radius:18px;
padding:14px;
min-width:0;
}
h2{
margin:0 0 10px 0;
font-size:22px;
}
.sub{
color:var(--muted);
font-size:14px;
margin-bottom:10px;
}
.statusBox{
background:var(--card2);
border:1px solid var(--line);
border-radius:14px;
padding:12px;
line-height:1.65;
font-size:17px;
margin-bottom:14px;
word-break:break-word;
}
.event{
margin-top:8px;
color:var(--accent);
font-weight:600;
}
.raw{
margin-top:8px;
color:var(--muted);
font-size:13px;
line-height:1.4;
}
.controls{
display:flex;
flex-direction:column;
gap:10px;
}
.dpad{
width:100%;
max-width:360px;
margin:0 auto;
display:grid;
grid-template-columns: repeat(3, 1fr);
gap:10px;
}
.dpad .empty{
visibility:hidden;
}
.row2{
width:100%;
max-width:360px;
margin:0 auto;
display:grid;
grid-template-columns: 1fr 1fr;
gap:10px;
}
button{
border:none;
border-radius:16px;
background:var(--btn);
color:var(--text);
font-size:18px;
padding:16px 10px;
min-height:58px;
touch-action:none;
user-select:none;
-webkit-user-select:none;
}
button:active{
transform:scale(0.985);
background:var(--btn2);
}
.smallBtn{
font-size:16px;
min-height:54px;
}
.canvasWrap{
width:100%;
overflow:hidden;
border-radius:14px;
background:#0b1018;
border:1px solid var(--line);
padding:8px;
}
#lidarCanvas{
width:100%;
height:auto;
display:block;
background:#0b1018;
border-radius:12px;
}
.legend{
margin-top:10px;
font-size:14px;
color:var(--muted);
line-height:1.5;
}
@media (max-width: 900px){
.wrap{
grid-template-columns: 1fr;
}
.page{
padding:10px;
}
h2{
font-size:20px;
}
.statusBox{
font-size:16px;
}
button{
font-size:17px;
min-height:56px;
padding:14px 8px;
}
}
</style>
</head>
<body>
<div class="page">
<div class="wrap">
<section class="card">
<h2>Управление машинкой</h2>
<div class="statusBox">
<div id="mode">Режим: ...</div>
<div id="motion">Движение: ...</div>
<div id="sector">Сектор: ...</div>
<div id="reed">Геркон: ...</div>
<div id="hall">Холл: ...</div>
<div id="mag">Магнит: ...</div>
<div id="dist">Дистанция: ...</div>
<div id="points">Точек лидара: ...</div>
<div class="event" id="eventText">Ожидание...</div>
<div class="raw" id="rawStatus"></div>
</div>
<div class="controls">
<div class="dpad">
<div class="empty">.</div>
<button id="fwd">ВПЕРЁД</button>
<div class="empty">.</div>
<button id="left">ВЛЕВО</button>
<button id="stop">СТОП</button>
<button id="right">ВПРАВО</button>
<div class="empty">.</div>
<button id="back">НАЗАД</button>
<div class="empty">.</div>
</div>
<div class="row2">
<button class="smallBtn" id="record">ЗАПИСЬ</button>
<button class="smallBtn" id="sectorBtn">СЛЕД. СЕКТОР</button>
</div>
<div class="row2">
<button class="smallBtn" id="replay">ПОВТОР</button>
<button class="smallBtn" id="erase">СТЕРЕТЬ МАРШРУТ</button>
</div>
</div>
</section>
<section class="card">
<h2>Лидар</h2>
<div class="sub">Точки обновляются в реальном времени. На телефоне страница нормально листается вниз.</div>
<div class="canvasWrap">
<canvas id="lidarCanvas" width="520" height="420"></canvas>
</div>
<div class="legend">
Чем больше голубых точек — тем больше пришло данных от TF-Luna.<br>
Если точек нет и поля пустые, значит нет обратной линии Arduino → ESP32.
</div>
</section>
</div>
</div>
<script>
let holdCmd = null;
let holdTimer = null;
let lastTapMs = 0;
let scanPoints = [];
function sendCmd(c) {
fetch('/cmd?c=' + encodeURIComponent(c), { cache: 'no-store' }).catch(() => {});
}
function tapCmd(c) {
const now = Date.now();
if (now - lastTapMs < 260) return;
lastTapMs = now;
sendCmd(c);
}
function startHold(c) {
holdCmd = c;
sendCmd(c);
if (holdTimer) clearInterval(holdTimer);
holdTimer = setInterval(() => {
if (holdCmd) sendCmd(holdCmd);
}, 220);
}
function stopHold() {
holdCmd = null;
if (holdTimer) {
clearInterval(holdTimer);
holdTimer = null;
}
sendCmd('S');
}
function bindHold(id, cmd) {
const el = document.getElementById(id);
el.addEventListener('pointerdown', (e) => {
e.preventDefault();
startHold(cmd);
});
el.addEventListener('pointerup', (e) => {
e.preventDefault();
stopHold();
});
el.addEventListener('pointercancel', (e) => {
e.preventDefault();
stopHold();
});
el.addEventListener('lostpointercapture', (e) => {
e.preventDefault();
stopHold();
});
}
function bindTap(id, cmd) {
const el = document.getElementById(id);
el.addEventListener('pointerdown', (e) => {
e.preventDefault();
tapCmd(cmd);
});
}
function modeRu(v) {
if (v === 'M') return 'Ручной';
if (v === 'V') return 'Запись';
if (v === 'P') return 'Повтор';
return v || '...';
}
function motionRu(v) {
if (v === 'S') return 'Стоп';
if (v === 'F') return 'Вперёд';
if (v === 'B') return 'Назад';
if (v === 'L') return 'Влево';
if (v === 'R') return 'Вправо';
return v || '...';
}
function eventRu(line) {
if (!line) return 'Ожидание...';
if (line.includes('SYSTEM_READY')) return 'Система готова';
if (line.includes('RECORD_ON')) return 'Запись включена';
if (line.includes('RECORD_OFF')) return 'Запись завершена';
if (line.includes('ROUTE_SAVED')) return 'Маршрут сохранён';
if (line.includes('ROUTE_ERASED')) return 'Маршрут стёрт';
if (line.includes('REPLAY_START')) return 'Повтор начат';
if (line.includes('REPLAY_DONE')) return 'Повтор завершён';
if (line.includes('REPLAY_ABORT_STEP')) return 'Повтор остановлен на шаге';
if (line.includes('REPLAY_ABORT_SECTOR')) return 'Повтор остановлен по сектору';
if (line.includes('SECTOR_SCAN_START')) return 'Сканирование сектора...';
if (line.includes('SECTOR_CAPTURED')) return 'Сектор зафиксирован';
if (line.includes('SECTOR_CHECK_START')) return 'Проверка сектора...';
if (line.includes('SECTOR_MATCH')) return 'Сектор совпал';
if (line.includes('SECTOR_MISMATCH')) return 'Сектор не совпал';
if (line.includes('SECTOR_SET')) {
const m = line.match(/sector=(\d+)/);
return m ? ('Новый сектор: ' + m[1]) : 'Сектор изменён';
}
if (line.includes('MAGNET')) return 'Магнит найден';
if (line.includes('OBSTACLE')) return 'Препятствие спереди';
return line;
}
function renderStatus(data) {
document.getElementById('mode').innerText = 'Режим: ' + modeRu(data.mode);
document.getElementById('motion').innerText = 'Движение: ' + motionRu(data.motion);
document.getElementById('sector').innerText = 'Сектор: ' + data.sector;
document.getElementById('reed').innerText = 'Геркон: ' + data.reed;
document.getElementById('hall').innerText = 'Холл: ' + data.hall;
document.getElementById('mag').innerText = 'Магнит: ' + data.mag;
document.getElementById('dist').innerText = 'Дистанция: ' + data.dist + ' см';
document.getElementById('points').innerText = 'Точек лидара: ' + data.points_count;
document.getElementById('eventText').innerText = eventRu(data.event || '');
document.getElementById('rawStatus').innerText = data.raw_status || '';
}
function drawLidar(points) {
const canvas = document.getElementById('lidarCanvas');
const ctx = canvas.getContext('2d');
ctx.clearRect(0, 0, canvas.width, canvas.height);
const cx = canvas.width / 2;
const cy = canvas.height - 18;
const maxR = 180;
const maxDist = 220;
// Сетка
ctx.strokeStyle = '#243248';
ctx.lineWidth = 1;
for (let r = 45; r <= maxR; r += 45) {
ctx.beginPath();
ctx.arc(cx, cy, r, Math.PI, 2 * Math.PI);
ctx.stroke();
}
for (let a = 40; a <= 140; a += 20) {
const rad = a * Math.PI / 180;
const x = cx + Math.cos(rad - Math.PI / 2) * maxR;
const y = cy + Math.sin(rad - Math.PI / 2) * maxR;
ctx.beginPath();
ctx.moveTo(cx, cy);
ctx.lineTo(x, y);
ctx.stroke();
}
// Точки
ctx.fillStyle = '#85d8ff';
for (const p of points) {
const angle = p[0];
const dist = p[1];
if (dist <= 0) continue;
const rr = Math.min(dist, maxDist) / maxDist * maxR;
const rad = angle * Math.PI / 180;
const x = cx + Math.cos(rad - Math.PI / 2) * rr;
const y = cy + Math.sin(rad - Math.PI / 2) * rr;
ctx.beginPath();
ctx.arc(x, y, 4.5, 0, Math.PI * 2);
ctx.fill();
}
// Робот
ctx.fillStyle = '#ffd27a';
ctx.beginPath();
ctx.arc(cx, cy, 8, 0, Math.PI * 2);
ctx.fill();
}
async function poll() {
try {
const r = await fetch('/status', { cache: 'no-store' });
const data = await r.json();
renderStatus(data);
scanPoints = data.points || [];
drawLidar(scanPoints);
} catch (e) {
}
}
bindHold('fwd', 'F');
bindHold('back', 'B');
bindHold('left', 'L');
bindHold('right', 'R');
document.getElementById('stop').addEventListener('pointerdown', (e) => {
e.preventDefault();
stopHold();
});
bindTap('record', 'V');
bindTap('sectorBtn', 'N');
bindTap('replay', 'P');
bindTap('erase', 'E');
document.addEventListener('visibilitychange', () => {
if (document.hidden) stopHold();
});
window.addEventListener('blur', () => stopHold());
setInterval(poll, 250);
poll();
</script>
</body>
</html>
)rawliteral";
void handleRoot() {
server.send_P(200, "text/html; charset=utf-8", PAGE);
}
// ===================== SETUP / LOOP =====================
void setup() {
Serial.begin(115200);
delay(200);
// RX=15, TX=13
RobotSerial.begin(9600, SERIAL_8N1, 15, 13);
WiFi.mode(WIFI_AP);
WiFi.setSleep(false);
WiFi.setTxPower(WIFI_POWER_19_5dBm);
WiFi.softAP(AP_SSID, AP_PASS, 1, 0, 1);
server.on("/", handleRoot);
server.on("/status", handleStatus);
server.on("/cmd", handleCmd);
server.begin();
}
void loop() {
server.handleClient();
readArduinoLines();
}