added web-ui-control
This commit is contained in:
parent
ac4425bb42
commit
3b07486e32
36
README.md
36
README.md
|
|
@ -180,4 +180,40 @@ slow backward
|
||||||
|
|
||||||
r 60
|
r 60
|
||||||
|
|
||||||
|
## Web Control
|
||||||
|
|
||||||
|
### Setup
|
||||||
|
|
||||||
|
ln -s /opt/helva-robot/drive/opt/drive-ctl/ /opt/
|
||||||
|
sudo apt update
|
||||||
|
sudo apt install -y python3-venv
|
||||||
|
python3 -m venv /opt/drive-ctl-venv
|
||||||
|
source /opt/drive-ctl-venv/bin/activate
|
||||||
|
pip install fastapi uvicorn pyserial
|
||||||
|
|
||||||
|
|
||||||
|
### Activate Web Control Interface
|
||||||
|
|
||||||
|
sudo ln -s /opt/helva-robot/drive/etc/nginx/sites-available/drive /etc/nginx/sites-enabled/drive
|
||||||
|
sudo nginx -t && sudo systemctl reload nginx
|
||||||
|
|
||||||
|
|
||||||
|
### Systemd Service for Backend
|
||||||
|
|
||||||
|
ln -s /opt/helva-robot/drive/etc/systemd/system/drive-ctl.service /etc/systemd/system/
|
||||||
|
sudo systemctl daemon-reload
|
||||||
|
sudo systemctl enable --now drive-ctl
|
||||||
|
sudo systemctl status drive-ctl --no-pager -l
|
||||||
|
|
||||||
|
Check Serial device is stable, otherwise create a udev rule
|
||||||
|
|
||||||
|
ls -l /dev/ttyACM0 /dev/ttyUSB0
|
||||||
|
dmesg | tail -n 50
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
### Open Web Control UI
|
||||||
|
|
||||||
|
http://pi-ip/drive/
|
||||||
|
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -0,0 +1,132 @@
|
||||||
|
// ===== Arduino UNO: Differential Drive über 2x BTS7960 =====
|
||||||
|
// Serial command format: "L <int> R <int>\n" where int in [-255..255]
|
||||||
|
// Soft-start ramping + watchdog stop
|
||||||
|
|
||||||
|
// --- Left BTS7960 pins ---
|
||||||
|
const uint8_t L_RPWM = 5; // PWM
|
||||||
|
const uint8_t L_LPWM = 6; // PWM
|
||||||
|
const uint8_t L_REN = 7; // enable
|
||||||
|
const uint8_t L_LEN = 8; // enable
|
||||||
|
|
||||||
|
// --- Right BTS7960 pins ---
|
||||||
|
const uint8_t R_RPWM = 9; // PWM
|
||||||
|
const uint8_t R_LPWM = 10; // PWM
|
||||||
|
const uint8_t R_REN = 11; // enable
|
||||||
|
const uint8_t R_LEN = 12; // enable
|
||||||
|
|
||||||
|
// Ramping
|
||||||
|
const uint8_t RAMP_STEP = 6; // speed change per loop (0..255)
|
||||||
|
const uint16_t LOOP_MS = 15; // ramp update interval
|
||||||
|
const uint16_t CMD_TIMEOUT_MS = 300; // stop if no command within x ms
|
||||||
|
|
||||||
|
int targetL = 0, targetR = 0;
|
||||||
|
int currentL = 0, currentR = 0;
|
||||||
|
|
||||||
|
unsigned long lastCmdMs = 0;
|
||||||
|
unsigned long lastLoopMs = 0;
|
||||||
|
|
||||||
|
void setupPins() {
|
||||||
|
pinMode(L_RPWM, OUTPUT); pinMode(L_LPWM, OUTPUT);
|
||||||
|
pinMode(L_REN, OUTPUT); pinMode(L_LEN, OUTPUT);
|
||||||
|
|
||||||
|
pinMode(R_RPWM, OUTPUT); pinMode(R_LPWM, OUTPUT);
|
||||||
|
pinMode(R_REN, OUTPUT); pinMode(R_LEN, OUTPUT);
|
||||||
|
|
||||||
|
digitalWrite(L_REN, HIGH); digitalWrite(L_LEN, HIGH);
|
||||||
|
digitalWrite(R_REN, HIGH); digitalWrite(R_LEN, HIGH);
|
||||||
|
|
||||||
|
analogWrite(L_RPWM, 0); analogWrite(L_LPWM, 0);
|
||||||
|
analogWrite(R_RPWM, 0); analogWrite(R_LPWM, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
static int clamp255(int v) {
|
||||||
|
if (v > 255) return 255;
|
||||||
|
if (v < -255) return -255;
|
||||||
|
return v;
|
||||||
|
}
|
||||||
|
|
||||||
|
void driveOne(int speed, uint8_t rpwm, uint8_t lpwm) {
|
||||||
|
speed = clamp255(speed);
|
||||||
|
if (speed > 0) {
|
||||||
|
analogWrite(rpwm, (uint8_t)speed);
|
||||||
|
analogWrite(lpwm, 0);
|
||||||
|
} else if (speed < 0) {
|
||||||
|
analogWrite(rpwm, 0);
|
||||||
|
analogWrite(lpwm, (uint8_t)(-speed));
|
||||||
|
} else {
|
||||||
|
analogWrite(rpwm, 0);
|
||||||
|
analogWrite(lpwm, 0);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static int rampTowards(int current, int target, uint8_t step) {
|
||||||
|
if (current < target) {
|
||||||
|
int n = current + step;
|
||||||
|
return (n > target) ? target : n;
|
||||||
|
}
|
||||||
|
if (current > target) {
|
||||||
|
int n = current - step;
|
||||||
|
return (n < target) ? target : n;
|
||||||
|
}
|
||||||
|
return current;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool parseLine(const String& line, int &outL, int &outR) {
|
||||||
|
// expected: "L <int> R <int>"
|
||||||
|
int idxL = line.indexOf('L');
|
||||||
|
int idxR = line.indexOf('R');
|
||||||
|
if (idxL < 0 || idxR < 0) return false;
|
||||||
|
|
||||||
|
// crude parse; robust enough for our simple format
|
||||||
|
String partL = line.substring(idxL + 1, idxR);
|
||||||
|
String partR = line.substring(idxR + 1);
|
||||||
|
|
||||||
|
partL.trim();
|
||||||
|
partR.trim();
|
||||||
|
|
||||||
|
outL = partL.toInt();
|
||||||
|
outR = partR.toInt();
|
||||||
|
outL = clamp255(outL);
|
||||||
|
outR = clamp255(outR);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
Serial.begin(115200);
|
||||||
|
setupPins();
|
||||||
|
lastCmdMs = millis();
|
||||||
|
lastLoopMs = millis();
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
// --- read serial lines ---
|
||||||
|
while (Serial.available()) {
|
||||||
|
String line = Serial.readStringUntil('\n');
|
||||||
|
line.trim();
|
||||||
|
if (line.length() == 0) continue;
|
||||||
|
|
||||||
|
int l, r;
|
||||||
|
if (parseLine(line, l, r)) {
|
||||||
|
targetL = l;
|
||||||
|
targetR = r;
|
||||||
|
lastCmdMs = millis();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// --- watchdog stop ---
|
||||||
|
if (millis() - lastCmdMs > CMD_TIMEOUT_MS) {
|
||||||
|
targetL = 0;
|
||||||
|
targetR = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// --- ramp update ---
|
||||||
|
if (millis() - lastLoopMs >= LOOP_MS) {
|
||||||
|
lastLoopMs = millis();
|
||||||
|
|
||||||
|
currentL = rampTowards(currentL, targetL, RAMP_STEP);
|
||||||
|
currentR = rampTowards(currentR, targetR, RAMP_STEP);
|
||||||
|
|
||||||
|
driveOne(currentL, L_RPWM, L_LPWM);
|
||||||
|
driveOne(currentR, R_RPWM, R_LPWM);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
@ -0,0 +1,18 @@
|
||||||
|
|
||||||
|
location /drive/ {
|
||||||
|
alias /opt/helva-robot/drive/var/www/drive/;
|
||||||
|
try_files $uri $uri/ /drive/index.html;
|
||||||
|
}
|
||||||
|
|
||||||
|
location /drive-ws {
|
||||||
|
proxy_pass http://127.0.0.1:8002/ws;
|
||||||
|
proxy_http_version 1.1;
|
||||||
|
proxy_set_header Upgrade $http_upgrade;
|
||||||
|
proxy_set_header Connection "Upgrade";
|
||||||
|
proxy_set_header Host $host;
|
||||||
|
}
|
||||||
|
|
||||||
|
location /drive-health {
|
||||||
|
proxy_pass http://127.0.0.1:8002/health;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
@ -0,0 +1,13 @@
|
||||||
|
[Unit]
|
||||||
|
Description=Robot Drive Controller (FastAPI -> Serial)
|
||||||
|
After=network.target
|
||||||
|
|
||||||
|
[Service]
|
||||||
|
WorkingDirectory=/opt/drive-ctl
|
||||||
|
ExecStart=/opt/drive-ctl-venv/bin/uvicorn server:app --host 127.0.0.1 --port 8002 --app-dir /opt/drive-ctl
|
||||||
|
Restart=always
|
||||||
|
RestartSec=1
|
||||||
|
|
||||||
|
[Install]
|
||||||
|
WantedBy=multi-user.target
|
||||||
|
|
||||||
Binary file not shown.
|
After Width: | Height: | Size: 36 KiB |
|
|
@ -0,0 +1,65 @@
|
||||||
|
import asyncio
|
||||||
|
import json
|
||||||
|
import time
|
||||||
|
import serial
|
||||||
|
from fastapi import FastAPI, WebSocket, WebSocketDisconnect
|
||||||
|
from fastapi.responses import HTMLResponse
|
||||||
|
|
||||||
|
SERIAL_PORT = "/dev/ttyACM0" # ggf. /dev/ttyUSB0
|
||||||
|
BAUD = 115200
|
||||||
|
|
||||||
|
# Safety: if websocket stops sending, we also stop.
|
||||||
|
STOP_AFTER_SEC = 0.35
|
||||||
|
|
||||||
|
app = FastAPI()
|
||||||
|
|
||||||
|
ser = serial.Serial(SERIAL_PORT, BAUD, timeout=0)
|
||||||
|
|
||||||
|
last_msg_ts = 0.0
|
||||||
|
|
||||||
|
def clamp255(v: int) -> int:
|
||||||
|
return max(-255, min(255, int(v)))
|
||||||
|
|
||||||
|
def send_lr(l: int, r: int):
|
||||||
|
l = clamp255(l)
|
||||||
|
r = clamp255(r)
|
||||||
|
line = f"L {l} R {r}\n".encode("ascii")
|
||||||
|
ser.write(line)
|
||||||
|
|
||||||
|
@app.get("/health")
|
||||||
|
def health():
|
||||||
|
return {"ok": True, "serial": SERIAL_PORT}
|
||||||
|
|
||||||
|
@app.websocket("/ws")
|
||||||
|
async def ws(websocket: WebSocket):
|
||||||
|
global last_msg_ts
|
||||||
|
await websocket.accept()
|
||||||
|
|
||||||
|
async def watchdog():
|
||||||
|
while True:
|
||||||
|
await asyncio.sleep(0.05)
|
||||||
|
if time.time() - last_msg_ts > STOP_AFTER_SEC:
|
||||||
|
send_lr(0, 0)
|
||||||
|
|
||||||
|
wd_task = asyncio.create_task(watchdog())
|
||||||
|
|
||||||
|
try:
|
||||||
|
while True:
|
||||||
|
msg = await websocket.receive_text()
|
||||||
|
last_msg_ts = time.time()
|
||||||
|
|
||||||
|
try:
|
||||||
|
data = json.loads(msg)
|
||||||
|
l = clamp255(data.get("l", 0))
|
||||||
|
r = clamp255(data.get("r", 0))
|
||||||
|
send_lr(l, r)
|
||||||
|
except Exception:
|
||||||
|
# On parse errors: stop
|
||||||
|
send_lr(0, 0)
|
||||||
|
|
||||||
|
await websocket.send_text("ok")
|
||||||
|
except WebSocketDisconnect:
|
||||||
|
send_lr(0, 0)
|
||||||
|
finally:
|
||||||
|
wd_task.cancel()
|
||||||
|
|
||||||
|
|
@ -0,0 +1,315 @@
|
||||||
|
<!doctype html>
|
||||||
|
<html lang="de">
|
||||||
|
<head>
|
||||||
|
<meta charset="utf-8" />
|
||||||
|
<meta name="viewport" content="width=device-width, initial-scale=1, viewport-fit=cover">
|
||||||
|
<title>Robot Dual Stick</title>
|
||||||
|
<style>
|
||||||
|
html, body { height: 100%; margin: 0; background: #0b0f14; color: #e8eef6; font-family: system-ui, -apple-system, Segoe UI, Roboto, Arial; }
|
||||||
|
.wrap { height: 100%; display: grid; grid-template-rows: auto 1fr auto; padding: 14px; gap: 12px; }
|
||||||
|
.top { display:flex; align-items:center; justify-content:space-between; gap: 10px; }
|
||||||
|
.badge { padding: 8px 12px; border-radius: 999px; background: #152033; font-weight: 700; }
|
||||||
|
.status { font-family: ui-monospace, SFMono-Regular, Menlo, Monaco, Consolas, monospace; }
|
||||||
|
|
||||||
|
.panel { background:#101826; border-radius: 18px; padding: 12px; }
|
||||||
|
.sticks {
|
||||||
|
display: grid;
|
||||||
|
grid-template-columns: 1fr 1fr;
|
||||||
|
gap: 12px;
|
||||||
|
align-items: center;
|
||||||
|
justify-items: center;
|
||||||
|
touch-action: none;
|
||||||
|
user-select: none;
|
||||||
|
}
|
||||||
|
.stickBox { width: min(46vw, 340px); aspect-ratio: 1/1; }
|
||||||
|
canvas { width: 100%; height: 100%; background:#0f1726; border-radius: 22px; }
|
||||||
|
|
||||||
|
.row { display:flex; gap: 12px; align-items:center; justify-content:space-between; flex-wrap: wrap; }
|
||||||
|
.btn { padding: 14px 16px; border-radius: 14px; border: 0; background:#1e2b44; color:#fff; font-weight: 800; font-size: 16px; }
|
||||||
|
.btn:active { transform: scale(0.98); }
|
||||||
|
.btnStop { background:#7a1f2a; }
|
||||||
|
|
||||||
|
input[type="range"]{ width: 220px; }
|
||||||
|
.small { opacity: 0.85; font-size: 14px; }
|
||||||
|
.mono { font-family: ui-monospace, SFMono-Regular, Menlo, Monaco, Consolas, monospace; }
|
||||||
|
.hint { margin-top: 8px; opacity: 0.85; font-size: 14px; text-align: center; }
|
||||||
|
</style>
|
||||||
|
</head>
|
||||||
|
<body>
|
||||||
|
<div class="wrap">
|
||||||
|
<div class="top">
|
||||||
|
<div class="badge">🎮 Dual Stick Drive</div>
|
||||||
|
<div class="badge status" id="status">offline</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="panel">
|
||||||
|
<div class="sticks">
|
||||||
|
<div class="stickBox">
|
||||||
|
<canvas id="leftStick" width="600" height="600"></canvas>
|
||||||
|
<div class="hint">Links: Gas (↑/↓)</div>
|
||||||
|
</div>
|
||||||
|
<div class="stickBox">
|
||||||
|
<canvas id="rightStick" width="600" height="600"></canvas>
|
||||||
|
<div class="hint">Rechts: Lenken (←/→)</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="panel row">
|
||||||
|
<div>
|
||||||
|
<div style="font-weight:900">Max Speed: <span id="maxv">180</span></div>
|
||||||
|
<input id="max" type="range" min="60" max="255" value="180">
|
||||||
|
<div class="small mono" id="readout">T 0 | Turn 0 → L 0 | R 0</div>
|
||||||
|
</div>
|
||||||
|
<div style="display:flex; gap:10px">
|
||||||
|
<button class="btn" id="btnConnect">Connect</button>
|
||||||
|
<button class="btn btnStop" id="btnStop">STOP</button>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="small" style="text-align:center; opacity:0.8">
|
||||||
|
Loslassen = STOP. Wenn Verbindung/Tab weg: STOP (Watchdog).
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<script>
|
||||||
|
(() => {
|
||||||
|
const statusEl = document.getElementById('status');
|
||||||
|
const maxEl = document.getElementById('max');
|
||||||
|
const maxvEl = document.getElementById('maxv');
|
||||||
|
const readoutEl = document.getElementById('readout');
|
||||||
|
const btnConnect = document.getElementById('btnConnect');
|
||||||
|
const btnStop = document.getElementById('btnStop');
|
||||||
|
|
||||||
|
const cL = document.getElementById('leftStick');
|
||||||
|
const cR = document.getElementById('rightStick');
|
||||||
|
const gL = cL.getContext('2d');
|
||||||
|
const gR = cR.getContext('2d');
|
||||||
|
|
||||||
|
let ws = null;
|
||||||
|
let connected = false;
|
||||||
|
|
||||||
|
// Stick states (normalized)
|
||||||
|
// Left stick: throttle in [-1..1] (up = +1)
|
||||||
|
// Right stick: turn in [-1..1] (right = +1)
|
||||||
|
let throttle = 0;
|
||||||
|
let turn = 0;
|
||||||
|
|
||||||
|
// For touch handling
|
||||||
|
function makeStick(canvas, mode /* 'throttle' or 'turn' */) {
|
||||||
|
const ctx = canvas.getContext('2d');
|
||||||
|
const cx = canvas.width / 2;
|
||||||
|
const cy = canvas.height / 2;
|
||||||
|
const radius = canvas.width * 0.32;
|
||||||
|
|
||||||
|
let active = false;
|
||||||
|
let px = cx, py = cy;
|
||||||
|
|
||||||
|
function clamp(v, a, b){ return Math.max(a, Math.min(b, v)); }
|
||||||
|
|
||||||
|
function pointerPos(evt){
|
||||||
|
const r = canvas.getBoundingClientRect();
|
||||||
|
return {
|
||||||
|
x: (evt.clientX - r.left) * (canvas.width / r.width),
|
||||||
|
y: (evt.clientY - r.top) * (canvas.height / r.height),
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
function apply(nx, ny) {
|
||||||
|
// nx, ny in [-1..1] where ny is +down
|
||||||
|
if (mode === 'throttle') {
|
||||||
|
// Up should be +throttle, so invert ny
|
||||||
|
throttle = clamp(-ny, -1, 1);
|
||||||
|
} else {
|
||||||
|
turn = clamp(nx, -1, 1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
function stopSelf() {
|
||||||
|
active = false;
|
||||||
|
px = cx; py = cy;
|
||||||
|
if (mode === 'throttle') throttle = 0;
|
||||||
|
if (mode === 'turn') turn = 0;
|
||||||
|
draw();
|
||||||
|
updateAndSend(true);
|
||||||
|
}
|
||||||
|
|
||||||
|
function onDown(evt){
|
||||||
|
evt.preventDefault();
|
||||||
|
active = true;
|
||||||
|
canvas.setPointerCapture(evt.pointerId);
|
||||||
|
onMove(evt);
|
||||||
|
}
|
||||||
|
|
||||||
|
function onMove(evt){
|
||||||
|
if (!active) return;
|
||||||
|
evt.preventDefault();
|
||||||
|
const p = pointerPos(evt);
|
||||||
|
const dx = p.x - cx;
|
||||||
|
const dy = p.y - cy;
|
||||||
|
const dist = Math.hypot(dx, dy);
|
||||||
|
const k = dist > radius ? (radius / dist) : 1;
|
||||||
|
|
||||||
|
px = cx + dx * k;
|
||||||
|
py = cy + dy * k;
|
||||||
|
|
||||||
|
const nx = clamp((px - cx) / radius, -1, 1);
|
||||||
|
const ny = clamp((py - cy) / radius, -1, 1);
|
||||||
|
|
||||||
|
apply(nx, ny);
|
||||||
|
draw();
|
||||||
|
updateAndSend(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
function onUp(evt){
|
||||||
|
evt.preventDefault();
|
||||||
|
stopSelf();
|
||||||
|
}
|
||||||
|
|
||||||
|
canvas.addEventListener('pointerdown', onDown);
|
||||||
|
canvas.addEventListener('pointermove', onMove);
|
||||||
|
canvas.addEventListener('pointerup', onUp);
|
||||||
|
canvas.addEventListener('pointercancel', onUp);
|
||||||
|
canvas.addEventListener('contextmenu', e => e.preventDefault());
|
||||||
|
|
||||||
|
function drawBase() {
|
||||||
|
ctx.clearRect(0,0,canvas.width,canvas.height);
|
||||||
|
|
||||||
|
// Outer circle
|
||||||
|
ctx.lineWidth = 10;
|
||||||
|
ctx.strokeStyle = "#24324d";
|
||||||
|
ctx.beginPath();
|
||||||
|
ctx.arc(cx, cy, radius, 0, Math.PI*2);
|
||||||
|
ctx.stroke();
|
||||||
|
|
||||||
|
// Crosshair
|
||||||
|
ctx.lineWidth = 4;
|
||||||
|
ctx.strokeStyle = "#1c263b";
|
||||||
|
ctx.beginPath();
|
||||||
|
ctx.moveTo(cx, cy - radius); ctx.lineTo(cx, cy + radius);
|
||||||
|
ctx.moveTo(cx - radius, cy); ctx.lineTo(cx + radius, cy);
|
||||||
|
ctx.stroke();
|
||||||
|
|
||||||
|
// Mode hint line
|
||||||
|
ctx.lineWidth = 6;
|
||||||
|
ctx.strokeStyle = "#152033";
|
||||||
|
ctx.beginPath();
|
||||||
|
if (mode === 'throttle') {
|
||||||
|
ctx.moveTo(cx, cy - radius); ctx.lineTo(cx, cy + radius);
|
||||||
|
} else {
|
||||||
|
ctx.moveTo(cx - radius, cy); ctx.lineTo(cx + radius, cy);
|
||||||
|
}
|
||||||
|
ctx.stroke();
|
||||||
|
}
|
||||||
|
|
||||||
|
function drawKnob() {
|
||||||
|
// Knob
|
||||||
|
ctx.fillStyle = "#3b82f6";
|
||||||
|
ctx.beginPath();
|
||||||
|
ctx.arc(px, py, canvas.width*0.065, 0, Math.PI*2);
|
||||||
|
ctx.fill();
|
||||||
|
|
||||||
|
// Inner dot
|
||||||
|
ctx.fillStyle = "#0b0f14";
|
||||||
|
ctx.beginPath();
|
||||||
|
ctx.arc(px, py, canvas.width*0.03, 0, Math.PI*2);
|
||||||
|
ctx.fill();
|
||||||
|
}
|
||||||
|
|
||||||
|
function draw(){
|
||||||
|
drawBase();
|
||||||
|
drawKnob();
|
||||||
|
}
|
||||||
|
|
||||||
|
draw();
|
||||||
|
return { draw, stopSelf };
|
||||||
|
}
|
||||||
|
|
||||||
|
function setStatus(txt, ok=false){
|
||||||
|
statusEl.textContent = txt;
|
||||||
|
statusEl.style.background = ok ? "#16331d" : "#3a1a1a";
|
||||||
|
}
|
||||||
|
|
||||||
|
function clamp(v, a, b){ return Math.max(a, Math.min(b, v)); }
|
||||||
|
|
||||||
|
// Mix throttle + turn to left/right [-1..1]
|
||||||
|
function mix(throttle, turn) {
|
||||||
|
let l = throttle + turn;
|
||||||
|
let r = throttle - turn;
|
||||||
|
|
||||||
|
// normalize to keep within [-1..1]
|
||||||
|
const m = Math.max(1, Math.abs(l), Math.abs(r));
|
||||||
|
l /= m; r /= m;
|
||||||
|
return { l, r };
|
||||||
|
}
|
||||||
|
|
||||||
|
let lastSend = 0;
|
||||||
|
let lastL = 0, lastR = 0;
|
||||||
|
|
||||||
|
function sendLR(l, r, force=false){
|
||||||
|
const now = performance.now();
|
||||||
|
if (!connected) return;
|
||||||
|
if (!force && (now - lastSend < 35)) return; // ~28Hz
|
||||||
|
lastSend = now;
|
||||||
|
|
||||||
|
try { ws.send(JSON.stringify({l, r})); } catch(e) {}
|
||||||
|
}
|
||||||
|
|
||||||
|
function updateAndSend(force) {
|
||||||
|
const maxSpeed = parseInt(maxEl.value, 10);
|
||||||
|
const m = mix(throttle, turn);
|
||||||
|
|
||||||
|
const L = Math.round(clamp(m.l, -1, 1) * maxSpeed);
|
||||||
|
const R = Math.round(clamp(m.r, -1, 1) * maxSpeed);
|
||||||
|
|
||||||
|
lastL = L; lastR = R;
|
||||||
|
readoutEl.textContent = `T ${throttle.toFixed(2)} | Turn ${turn.toFixed(2)} → L ${L} | R ${R}`;
|
||||||
|
|
||||||
|
sendLR(L, R, force);
|
||||||
|
}
|
||||||
|
|
||||||
|
function hardStop() {
|
||||||
|
throttle = 0; turn = 0;
|
||||||
|
updateAndSend(true);
|
||||||
|
left.stopSelf();
|
||||||
|
right.stopSelf();
|
||||||
|
}
|
||||||
|
|
||||||
|
function connect(){
|
||||||
|
if (connected) return;
|
||||||
|
const proto = (location.protocol === "https:") ? "wss" : "ws";
|
||||||
|
const url = `${proto}://${location.host}/drive-ws`;
|
||||||
|
ws = new WebSocket(url);
|
||||||
|
|
||||||
|
ws.onopen = () => { connected = true; setStatus("online", true); updateAndSend(true); };
|
||||||
|
ws.onclose = () => { connected = false; setStatus("offline", false); hardStop(); };
|
||||||
|
ws.onerror = () => { connected = false; setStatus("error", false); hardStop(); };
|
||||||
|
ws.onmessage = () => {};
|
||||||
|
}
|
||||||
|
|
||||||
|
btnConnect.addEventListener('click', connect);
|
||||||
|
btnStop.addEventListener('click', hardStop);
|
||||||
|
|
||||||
|
maxEl.addEventListener('input', () => {
|
||||||
|
maxvEl.textContent = maxEl.value;
|
||||||
|
updateAndSend(true);
|
||||||
|
});
|
||||||
|
|
||||||
|
// Create sticks
|
||||||
|
const left = makeStick(cL, 'throttle');
|
||||||
|
const right = makeStick(cR, 'turn');
|
||||||
|
|
||||||
|
// Auto-connect
|
||||||
|
connect();
|
||||||
|
setStatus("connecting...", false);
|
||||||
|
|
||||||
|
// Safety: stop when page hidden
|
||||||
|
document.addEventListener("visibilitychange", () => {
|
||||||
|
if (document.hidden) hardStop();
|
||||||
|
});
|
||||||
|
|
||||||
|
})();
|
||||||
|
</script>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
|
|
||||||
|
|
@ -30,5 +30,7 @@ server {
|
||||||
|
|
||||||
add_header Cache-Control no-cache;
|
add_header Cache-Control no-cache;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
include /opt/helva-robot/drive/etc/nginx/snippets/drive.conf;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue