changed drive ramping from arduino to steering for better control
This commit is contained in:
parent
4b040391da
commit
c2bb45ac5a
|
|
@ -1,303 +1,163 @@
|
|||
/*
|
||||
4WD Robot Motor Control (2x BTS7960: Left + Right)
|
||||
- Soft start/stop via ramping (slew-rate limiter)
|
||||
- Differential drive mixing: throttle + turn
|
||||
- Serial control (USB): f/b/l/r/s or m <throttle> <turn>
|
||||
- Watchdog: stops if no command received in time
|
||||
|
||||
Wiring (per BTS7960 module):
|
||||
- LPWM -> Arduino PWM pin
|
||||
- RPWM -> Arduino PWM pin
|
||||
- LEN/REN (or L_EN/R_EN) -> Arduino digital pins (or permanently HIGH to 5V)
|
||||
- VCC -> 5V (logic)
|
||||
- GND -> GND common with Arduino and motor supply
|
||||
- B+ / B- -> motor supply (e.g. 12V)
|
||||
- M+ / M- -> motor output
|
||||
|
||||
NOTE:
|
||||
Each side is one BTS7960 module driving two motors in parallel (front+rear) on that side.
|
||||
Arduino Drive "Safe Executor"
|
||||
- Receives: L <int> R <int> (-255..255)
|
||||
- Outputs PWM immediately (no ramping here)
|
||||
- Safety: watchdog stop if no command
|
||||
- Deadzone + Min PWM mapping to avoid motor buzzing at low PWM
|
||||
- Optional direction-change protection (short stop)
|
||||
*/
|
||||
|
||||
#include <Arduino.h>
|
||||
#include <PS2X_lib.h>
|
||||
PS2X ps2x;
|
||||
// ===== Left BTS7960 pins =====
|
||||
const uint8_t L_RPWM = 5;
|
||||
const uint8_t L_LPWM = 6;
|
||||
const uint8_t L_REN = 7;
|
||||
const uint8_t L_LEN = 8;
|
||||
|
||||
// ------ PS2 Controller Pins -------------
|
||||
const uint8_t PS2_CLK = 2;
|
||||
const uint8_t PS2_ATT = 3;
|
||||
const uint8_t PS2_CMD = 4;
|
||||
const uint8_t PS2_DAT = 12;
|
||||
// ===== Right BTS7960 pins =====
|
||||
const uint8_t R_RPWM = 9;
|
||||
const uint8_t R_LPWM = 10;
|
||||
const uint8_t R_REN = 11;
|
||||
const uint8_t R_LEN = 12;
|
||||
|
||||
// ------- USE PS2 Controller or Serial Input --------------
|
||||
#define USE_PS2 1
|
||||
// ===== Safety / feel =====
|
||||
const uint16_t CMD_TIMEOUT_MS = 600; // Web sendet regelmäßig; 600ms ist entspannt
|
||||
const uint8_t DEADZONE = 10; // kleine Werte -> 0
|
||||
const uint8_t MIN_PWM = 70; // anpassen: 60..110 typisch (gegen "brummen")
|
||||
|
||||
// ----------------------------- Pins (ANPASSEN) -----------------------------
|
||||
// LEFT BTS7960
|
||||
const uint8_t L_LPWM = 5; // PWM pin
|
||||
const uint8_t L_RPWM = 6; // PWM pin
|
||||
const uint8_t L_LEN = 7; // enable pin (LEN)
|
||||
const uint8_t L_REN = 8; // enable pin (REN)
|
||||
// Optional: beim Richtungswechsel kurz stoppen (schont Treiber/Getriebe)
|
||||
const bool PROTECT_DIR_CHANGE = true;
|
||||
const uint16_t DIR_CHANGE_STOP_MS = 60;
|
||||
|
||||
// RIGHT BTS7960
|
||||
const uint8_t R_LPWM = 9; // PWM pin
|
||||
const uint8_t R_RPWM = 10; // PWM pin
|
||||
const uint8_t R_LEN = 11; // enable pin (LEN)
|
||||
const uint8_t R_REN = 12; // enable pin (REN)
|
||||
int targetL = 0, targetR = 0;
|
||||
unsigned long lastCmdMs = 0;
|
||||
|
||||
// --------------------------- Tuning / Limits -------------------------------
|
||||
// PWM range: 0..255
|
||||
const int PWM_MAX = 255;
|
||||
int lastOutL = 0, lastOutR = 0;
|
||||
|
||||
// Ramp speed: PWM units per second (z.B. 300 => ~0.85s von 0 auf 255)
|
||||
const float RAMP_UP_PER_SEC = 320.0f;
|
||||
const float RAMP_DOWN_PER_SEC = 520.0f; // meist darf bremsen/stoppen schneller sein
|
||||
|
||||
// Deadband: kleine Werte ignorieren (gegen "Zittern")
|
||||
const int INPUT_DEADBAND = 10;
|
||||
|
||||
// Watchdog: wenn so lange kein Command kommt -> STOP
|
||||
const uint32_t COMMAND_TIMEOUT_MS = 600;
|
||||
|
||||
// Loop interval (Ramping arbeitet zeitbasiert; häufig genug aufrufen)
|
||||
const uint32_t CONTROL_INTERVAL_MS = 10;
|
||||
|
||||
// ---------------------------- State ----------------------------------------
|
||||
volatile int targetLeft = 0; // -255..255
|
||||
volatile int targetRight = 0; // -255..255
|
||||
|
||||
float currentLeft = 0.0f; // ramped output -255..255
|
||||
float currentRight = 0.0f;
|
||||
|
||||
uint32_t lastCmdMs = 0;
|
||||
uint32_t lastControlMs = 0;
|
||||
|
||||
// ------------------------- Helpers -----------------------------------------
|
||||
static int clampInt(int v, int lo, int hi) {
|
||||
if (v < lo) return lo;
|
||||
if (v > hi) return hi;
|
||||
static int clamp255(int v) {
|
||||
if (v > 255) return 255;
|
||||
if (v < -255) return -255;
|
||||
return v;
|
||||
}
|
||||
|
||||
static int applyDeadband(int v, int db) {
|
||||
if (abs(v) < db) return 0;
|
||||
return v;
|
||||
int applyMinPwm(int v) {
|
||||
v = clamp255(v);
|
||||
int a = abs(v);
|
||||
if (a <= DEADZONE) return 0;
|
||||
|
||||
int s = (v >= 0) ? 1 : -1;
|
||||
|
||||
// map: DEADZONE..255 -> MIN_PWM..255
|
||||
long mapped = MIN_PWM + (long)(a - DEADZONE) * (255 - MIN_PWM) / (255 - DEADZONE);
|
||||
if (mapped > 255) mapped = 255;
|
||||
|
||||
return s * (int)mapped;
|
||||
}
|
||||
|
||||
// Ramp current towards target based on dt
|
||||
static float rampTo(float current, float target, float dtSec) {
|
||||
float diff = target - current;
|
||||
if (diff == 0.0f) return current;
|
||||
|
||||
const float rate = (abs(target) > abs(current)) ? RAMP_UP_PER_SEC : RAMP_DOWN_PER_SEC;
|
||||
float step = rate * dtSec;
|
||||
|
||||
if (abs(diff) <= step) return target;
|
||||
return current + (diff > 0 ? step : -step);
|
||||
}
|
||||
|
||||
// Send signed speed (-255..255) to one BTS7960
|
||||
static void driveBTS7960(uint8_t lpwm, uint8_t rpwm, uint8_t len, uint8_t ren, int speed) {
|
||||
speed = clampInt(speed, -PWM_MAX, PWM_MAX);
|
||||
|
||||
// Enable driver
|
||||
digitalWrite(len, HIGH);
|
||||
digitalWrite(ren, HIGH);
|
||||
|
||||
int pwm = abs(speed);
|
||||
|
||||
// IMPORTANT: never drive both PWM pins at the same time
|
||||
void setBTS7960(int speed, uint8_t rpwm, uint8_t lpwm) {
|
||||
speed = clamp255(speed);
|
||||
if (speed > 0) {
|
||||
analogWrite(lpwm, pwm);
|
||||
analogWrite(rpwm, 0);
|
||||
analogWrite(rpwm, (uint8_t)speed);
|
||||
analogWrite(lpwm, 0);
|
||||
} else if (speed < 0) {
|
||||
analogWrite(lpwm, 0);
|
||||
analogWrite(rpwm, pwm);
|
||||
} else {
|
||||
analogWrite(lpwm, 0);
|
||||
analogWrite(rpwm, 0);
|
||||
analogWrite(lpwm, (uint8_t)(-speed));
|
||||
} else {
|
||||
analogWrite(rpwm, 0);
|
||||
analogWrite(lpwm, 0);
|
||||
}
|
||||
}
|
||||
|
||||
static void stopAll() {
|
||||
targetLeft = 0;
|
||||
targetRight = 0;
|
||||
bool parseLine(const String& line, int &outL, int &outR) {
|
||||
int idxL = line.indexOf('L');
|
||||
int idxR = line.indexOf('R');
|
||||
if (idxL < 0 || idxR < 0) return false;
|
||||
|
||||
String partL = line.substring(idxL + 1, idxR);
|
||||
String partR = line.substring(idxR + 1);
|
||||
partL.trim(); partR.trim();
|
||||
|
||||
outL = clamp255(partL.toInt());
|
||||
outR = clamp255(partR.toInt());
|
||||
return true;
|
||||
}
|
||||
|
||||
// Differential drive mixing:
|
||||
// throttle: -255..255, turn: -255..255
|
||||
static void setMix(int throttle, int turn) {
|
||||
throttle = clampInt(throttle, -PWM_MAX, PWM_MAX);
|
||||
turn = clampInt(turn, -PWM_MAX, PWM_MAX);
|
||||
void setupPins() {
|
||||
pinMode(L_RPWM, OUTPUT); pinMode(L_LPWM, OUTPUT);
|
||||
pinMode(L_REN, OUTPUT); pinMode(L_LEN, OUTPUT);
|
||||
|
||||
throttle = applyDeadband(throttle, INPUT_DEADBAND);
|
||||
turn = applyDeadband(turn, INPUT_DEADBAND);
|
||||
pinMode(R_RPWM, OUTPUT); pinMode(R_LPWM, OUTPUT);
|
||||
pinMode(R_REN, OUTPUT); pinMode(R_LEN, OUTPUT);
|
||||
|
||||
// Classic mix
|
||||
int left = throttle + turn;
|
||||
int right = throttle - turn;
|
||||
digitalWrite(L_REN, HIGH); digitalWrite(L_LEN, HIGH);
|
||||
digitalWrite(R_REN, HIGH); digitalWrite(R_LEN, HIGH);
|
||||
|
||||
// Normalize if exceeds range
|
||||
int maxMag = max(abs(left), abs(right));
|
||||
if (maxMag > PWM_MAX) {
|
||||
// scale down proportionally
|
||||
left = (int)((float)left * ((float)PWM_MAX / (float)maxMag));
|
||||
right = (int)((float)right * ((float)PWM_MAX / (float)maxMag));
|
||||
setBTS7960(0, L_RPWM, L_LPWM);
|
||||
setBTS7960(0, R_RPWM, R_LPWM);
|
||||
}
|
||||
|
||||
targetLeft = left;
|
||||
targetRight = right;
|
||||
}
|
||||
void outputLR(int l, int r) {
|
||||
l = applyMinPwm(l);
|
||||
r = applyMinPwm(r);
|
||||
|
||||
// ------------------------- Serial command parser ---------------------------
|
||||
// Commands:
|
||||
// f <pwm> -> forward
|
||||
// b <pwm> -> backward
|
||||
// l <pwm> -> turn left (in place)
|
||||
// r <pwm> -> turn right (in place)
|
||||
// s -> stop
|
||||
// m <throttle> <turn> -> mix mode (-255..255 each)
|
||||
// Examples:
|
||||
// f 140
|
||||
// m 120 -40
|
||||
// s
|
||||
static void handleSerialLine(String line) {
|
||||
line.trim();
|
||||
if (line.length() == 0) return;
|
||||
if (PROTECT_DIR_CHANGE) {
|
||||
// if sign changes across 0 while moving -> brief stop
|
||||
auto sign = [](int v) -> int { return (v > 0) - (v < 0); };
|
||||
|
||||
char cmd = tolower(line.charAt(0));
|
||||
bool lFlip = (sign(lastOutL) != 0) && (sign(l) != 0) && (sign(lastOutL) != sign(l));
|
||||
bool rFlip = (sign(lastOutR) != 0) && (sign(r) != 0) && (sign(lastOutR) != sign(r));
|
||||
|
||||
// Update watchdog timestamp on any valid-looking input
|
||||
lastCmdMs = millis();
|
||||
|
||||
if (cmd == 's') {
|
||||
stopAll();
|
||||
return;
|
||||
}
|
||||
|
||||
// Split by spaces
|
||||
// Simple parsing:
|
||||
// cmd + integers
|
||||
int a = 0, b = 0;
|
||||
int n = 0;
|
||||
|
||||
// Try parse "m a b"
|
||||
if (cmd == 'm') {
|
||||
n = sscanf(line.c_str(), "m %d %d", &a, &b);
|
||||
if (n == 2) {
|
||||
setMix(a, b);
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
// Parse "f a" / "b a" / "l a" / "r a"
|
||||
n = sscanf(line.c_str(), "%c %d", &cmd, &a);
|
||||
if (n < 2) return;
|
||||
|
||||
a = clampInt(a, 0, PWM_MAX);
|
||||
|
||||
switch (tolower(cmd)) {
|
||||
case 'f': setMix(+a, 0); break;
|
||||
case 'b': setMix(-a, 0); break;
|
||||
case 'l': setMix(0, +a); break; // left turn in place
|
||||
case 'r': setMix(0, -a); break; // right turn in place
|
||||
default: break;
|
||||
if (lFlip || rFlip) {
|
||||
setBTS7960(0, L_RPWM, L_LPWM);
|
||||
setBTS7960(0, R_RPWM, R_LPWM);
|
||||
delay(DIR_CHANGE_STOP_MS);
|
||||
}
|
||||
}
|
||||
|
||||
// ------------------------------ Arduino ------------------------------------
|
||||
setBTS7960(l, L_RPWM, L_LPWM);
|
||||
setBTS7960(r, R_RPWM, R_LPWM);
|
||||
|
||||
lastOutL = l;
|
||||
lastOutR = r;
|
||||
}
|
||||
|
||||
void setup() {
|
||||
int err = ps2x.config_gamepad(PS2_CLK, PS2_CMD, PS2_ATT, PS2_DAT, false, false);
|
||||
Serial.print("PS2 init: "); Serial.println(err);
|
||||
|
||||
pinMode(L_LPWM, OUTPUT);
|
||||
pinMode(L_RPWM, OUTPUT);
|
||||
pinMode(L_LEN, OUTPUT);
|
||||
pinMode(L_REN, OUTPUT);
|
||||
|
||||
pinMode(R_LPWM, OUTPUT);
|
||||
pinMode(R_RPWM, OUTPUT);
|
||||
pinMode(R_LEN, OUTPUT);
|
||||
pinMode(R_REN, OUTPUT);
|
||||
|
||||
// Init: disabled PWM = 0, enables on
|
||||
analogWrite(L_LPWM, 0); analogWrite(L_RPWM, 0);
|
||||
analogWrite(R_LPWM, 0); analogWrite(R_RPWM, 0);
|
||||
|
||||
digitalWrite(L_LEN, HIGH); digitalWrite(L_REN, HIGH);
|
||||
digitalWrite(R_LEN, HIGH); digitalWrite(R_REN, HIGH);
|
||||
|
||||
Serial.begin(115200);
|
||||
Serial.println(F("BTS7960 Robot Control ready."));
|
||||
Serial.println(F("Commands: f/b/l/r <0..255>, m <throttle -255..255> <turn -255..255>, s"));
|
||||
setupPins();
|
||||
delay(200);
|
||||
|
||||
Serial.println(F("Drive Ready. Send: L <val> R <val> (-255..255)"));
|
||||
Serial.print(F("DEADZONE=")); Serial.print(DEADZONE);
|
||||
Serial.print(F(" MIN_PWM=")); Serial.println(MIN_PWM);
|
||||
|
||||
lastCmdMs = millis();
|
||||
lastControlMs = millis();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
#if USE_PS2
|
||||
// -------- PS2 Controller Input -------
|
||||
ps2x.read_gamepad(false, 0);
|
||||
|
||||
// Not-Stop z.B. START
|
||||
if (ps2x.ButtonPressed(PSB_START)) {
|
||||
stopAll();
|
||||
lastCmdMs = millis(); // watchdog “füttern”
|
||||
}
|
||||
|
||||
// Sticks lesen
|
||||
int ly = ps2x.Analog(PSS_LY); // 0..255
|
||||
int rx = ps2x.Analog(PSS_RX); // 0..255
|
||||
|
||||
// 0..255 -> -255..255
|
||||
auto stickToSigned = [](int v) {
|
||||
int x = (v - 128) * 2;
|
||||
if (x > 255) x = 255;
|
||||
if (x < -255) x = -255;
|
||||
return x;
|
||||
};
|
||||
|
||||
// Mapping: LY nach oben = vorwärts (invertieren)
|
||||
int throttle = -stickToSigned(ly);
|
||||
int turn = stickToSigned(rx);
|
||||
|
||||
lastCmdMs = millis(); // watchdog “füttern”
|
||||
setMix(throttle, turn); // das ist dein Original-Mixer
|
||||
|
||||
#else
|
||||
// -------- Serial input (line based) --------
|
||||
static String buf;
|
||||
while (Serial.available()) {
|
||||
char c = (char)Serial.read();
|
||||
if (c == '\n' || c == '\r') {
|
||||
if (buf.length() > 0) {
|
||||
handleSerialLine(buf);
|
||||
buf = "";
|
||||
}
|
||||
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();
|
||||
|
||||
outputLR(targetL, targetR);
|
||||
|
||||
Serial.print(F("RX/OUT L=")); Serial.print(lastOutL);
|
||||
Serial.print(F(" R=")); Serial.println(lastOutR);
|
||||
} else {
|
||||
// avoid huge line
|
||||
if (buf.length() < 80) buf += c;
|
||||
Serial.println(F("Parse error -> STOP"));
|
||||
targetL = 0; targetR = 0;
|
||||
lastCmdMs = millis();
|
||||
outputLR(0, 0);
|
||||
}
|
||||
}
|
||||
#ENDIF
|
||||
|
||||
// -------- Watchdog --------
|
||||
if (millis() - lastCmdMs > COMMAND_TIMEOUT_MS) {
|
||||
stopAll();
|
||||
}
|
||||
|
||||
// -------- Control update (ramping + output) --------
|
||||
uint32_t now = millis();
|
||||
if (now - lastControlMs >= CONTROL_INTERVAL_MS) {
|
||||
float dt = (now - lastControlMs) / 1000.0f;
|
||||
lastControlMs = now;
|
||||
|
||||
// ramp current values towards target
|
||||
currentLeft = rampTo(currentLeft, (float)targetLeft, dt);
|
||||
currentRight = rampTo(currentRight, (float)targetRight, dt);
|
||||
|
||||
// apply to drivers
|
||||
driveBTS7960(L_LPWM, L_RPWM, L_LEN, L_REN, (int)round(currentLeft));
|
||||
driveBTS7960(R_LPWM, R_RPWM, R_LEN, R_REN, (int)round(currentRight));
|
||||
// Watchdog stop
|
||||
if (millis() - lastCmdMs > CMD_TIMEOUT_MS) {
|
||||
outputLR(0, 0);
|
||||
}
|
||||
}
|
||||
|
|
|
|||
|
|
@ -1,132 +0,0 @@
|
|||
// ===== 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);
|
||||
}
|
||||
}
|
||||
|
|
@ -3,12 +3,12 @@
|
|||
<head>
|
||||
<meta charset="utf-8" />
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1, viewport-fit=cover">
|
||||
<title>Robot Dual Stick</title>
|
||||
<title>Robot Dual Stick (Ramping)</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; }
|
||||
.wrap { height: 100%; display: grid; grid-template-rows: auto 1fr auto 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; }
|
||||
.badge { padding: 8px 12px; border-radius: 999px; background: #152033; font-weight: 800; }
|
||||
.status { font-family: ui-monospace, SFMono-Regular, Menlo, Monaco, Consolas, monospace; }
|
||||
|
||||
.panel { background:#101826; border-radius: 18px; padding: 12px; }
|
||||
|
|
@ -22,17 +22,22 @@
|
|||
user-select: none;
|
||||
}
|
||||
.stickBox { width: min(46vw, 340px); aspect-ratio: 1/1; }
|
||||
canvas { width: 100%; height: 100%; background:#0f1726; border-radius: 22px; }
|
||||
canvas { width: 100%; height: 100%; background:#0f1726; border-radius: 22px; touch-action: none; }
|
||||
|
||||
.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 { padding: 14px 16px; border-radius: 14px; border: 0; background:#1e2b44; color:#fff; font-weight: 900; font-size: 16px; }
|
||||
.btn:active { transform: scale(0.98); }
|
||||
.btnStop { background:#7a1f2a; }
|
||||
.btnOn { outline: 3px solid rgba(59,130,246,0.7); }
|
||||
|
||||
input[type="range"]{ width: 220px; }
|
||||
.small { opacity: 0.85; font-size: 14px; }
|
||||
input[type="range"]{ width: 240px; }
|
||||
.small { opacity: 0.86; 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; }
|
||||
|
||||
.grid2 { display:grid; grid-template-columns: 1fr 1fr; gap: 10px; }
|
||||
.kv { display:flex; gap:10px; align-items:center; justify-content:space-between; }
|
||||
.kv label { font-weight:800; }
|
||||
</style>
|
||||
</head>
|
||||
<body>
|
||||
|
|
@ -56,46 +61,180 @@
|
|||
</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 style="min-width: 320px;">
|
||||
<div class="kv">
|
||||
<label>Max Speed:</label>
|
||||
<span class="mono"><span id="maxv">180</span></span>
|
||||
</div>
|
||||
<div style="display:flex; gap:10px">
|
||||
<input id="max" type="range" min="60" max="255" value="180">
|
||||
|
||||
<div class="grid2" style="margin-top:12px">
|
||||
<div class="kv">
|
||||
<label>Accel:</label>
|
||||
<span class="mono"><span id="accv">2.2</span>/s</span>
|
||||
</div>
|
||||
<input id="acc" type="range" min="0.8" max="6.0" step="0.1" value="2.2">
|
||||
|
||||
<div class="kv">
|
||||
<label>Decel:</label>
|
||||
<span class="mono"><span id="decv">3.6</span>/s</span>
|
||||
</div>
|
||||
<input id="dec" type="range" min="0.8" max="8.0" step="0.1" value="3.6">
|
||||
|
||||
<div class="kv">
|
||||
<label>Turn:</label>
|
||||
<span class="mono"><span id="turnv">6.0</span>/s</span>
|
||||
</div>
|
||||
<input id="turn" type="range" min="1.0" max="12.0" step="0.1" value="6.0">
|
||||
|
||||
<div class="kv">
|
||||
<label>Expo:</label>
|
||||
<span class="mono"><span id="expov">0.35</span></span>
|
||||
</div>
|
||||
<input id="expo" type="range" min="0.0" max="0.8" step="0.05" value="0.35">
|
||||
</div>
|
||||
</div>
|
||||
|
||||
<div style="display:flex; gap:10px; align-items:center; flex-wrap:wrap;">
|
||||
<button class="btn" id="btnConnect">Connect</button>
|
||||
<button class="btn" id="btnSlow">SLOW</button>
|
||||
<button class="btn btnStop" id="btnStop">STOP</button>
|
||||
</div>
|
||||
</div>
|
||||
|
||||
<div class="panel small mono" id="readout">
|
||||
target: T 0.00 | Turn 0.00 || smooth: T 0.00 | Turn 0.00 || L 0 | R 0
|
||||
</div>
|
||||
|
||||
<div class="small" style="text-align:center; opacity:0.8">
|
||||
Loslassen = STOP. Wenn Verbindung/Tab weg: STOP (Watchdog).
|
||||
Loslassen = STOP. Tab/Verbindung weg = STOP. (Web sendet laufend, damit Arduino-Watchdog nicht stoppt.)
|
||||
</div>
|
||||
</div>
|
||||
|
||||
<script>
|
||||
(() => {
|
||||
// ===== UI refs =====
|
||||
const statusEl = document.getElementById('status');
|
||||
const readoutEl = document.getElementById('readout');
|
||||
|
||||
const maxEl = document.getElementById('max');
|
||||
const maxvEl = document.getElementById('maxv');
|
||||
const readoutEl = document.getElementById('readout');
|
||||
|
||||
const accEl = document.getElementById('acc');
|
||||
const accvEl = document.getElementById('accv');
|
||||
|
||||
const decEl = document.getElementById('dec');
|
||||
const decvEl = document.getElementById('decv');
|
||||
|
||||
const turnRateEl = document.getElementById('turn');
|
||||
const turnvEl = document.getElementById('turnv');
|
||||
|
||||
const expoEl = document.getElementById('expo');
|
||||
const expovEl = document.getElementById('expov');
|
||||
|
||||
const btnConnect = document.getElementById('btnConnect');
|
||||
const btnStop = document.getElementById('btnStop');
|
||||
const btnSlow = document.getElementById('btnSlow');
|
||||
|
||||
const cL = document.getElementById('leftStick');
|
||||
const cR = document.getElementById('rightStick');
|
||||
const gL = cL.getContext('2d');
|
||||
const gR = cR.getContext('2d');
|
||||
|
||||
// ===== WebSocket =====
|
||||
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)
|
||||
function setStatus(txt, ok=false){
|
||||
statusEl.textContent = txt;
|
||||
statusEl.style.background = ok ? "#16331d" : "#3a1a1a";
|
||||
}
|
||||
|
||||
function connect(){
|
||||
if (connected) return;
|
||||
const proto = (location.protocol === "https:") ? "wss" : "ws";
|
||||
const url = `${proto}://${location.host}/drive-ws`; // <— NGINX path
|
||||
ws = new WebSocket(url);
|
||||
|
||||
ws.onopen = () => { connected = true; setStatus("online", true); };
|
||||
ws.onclose = () => { connected = false; setStatus("offline", false); hardStop(); };
|
||||
ws.onerror = () => { connected = false; setStatus("error", false); hardStop(); };
|
||||
ws.onmessage = () => {};
|
||||
}
|
||||
|
||||
btnConnect.addEventListener('click', connect);
|
||||
|
||||
// ===== Control state =====
|
||||
// Targets come directly from sticks
|
||||
let throttleTarget = 0; // -1..+1 (up = +)
|
||||
let turnTarget = 0; // -1..+1 (right = +)
|
||||
|
||||
// Smoothed (ramped) values
|
||||
let throttle = 0;
|
||||
let turn = 0;
|
||||
|
||||
// For touch handling
|
||||
// last motor outputs
|
||||
let lastL = 0, lastR = 0;
|
||||
|
||||
// slow mode
|
||||
let slowMode = false;
|
||||
btnSlow.addEventListener('click', () => {
|
||||
slowMode = !slowMode;
|
||||
btnSlow.classList.toggle('btnOn', slowMode);
|
||||
});
|
||||
|
||||
// ===== Helpers =====
|
||||
function clamp(v, a, b){ return Math.max(a, Math.min(b, v)); }
|
||||
|
||||
// Expo curve: 0 = linear, higher = finer around center
|
||||
// Returns in [-1..1]
|
||||
function expo(v, e){
|
||||
v = clamp(v, -1, 1);
|
||||
e = clamp(e, 0, 0.95);
|
||||
// cubic blend
|
||||
return (1 - e) * v + e * v * v * v;
|
||||
}
|
||||
|
||||
// Differential mix: throttle + turn -> left/right in [-1..1]
|
||||
function mix(th, tr){
|
||||
let l = th + tr;
|
||||
let r = th - tr;
|
||||
const m = Math.max(1, Math.abs(l), Math.abs(r));
|
||||
return { l: l / m, r: r / m };
|
||||
}
|
||||
|
||||
function stepTowards(cur, target, maxDelta){
|
||||
const d = target - cur;
|
||||
if (Math.abs(d) <= maxDelta) return target;
|
||||
return cur + Math.sign(d) * maxDelta;
|
||||
}
|
||||
|
||||
// Send helper with simple rate limit (force bypasses)
|
||||
let lastSendMs = 0;
|
||||
function sendLR(l, r, force=false){
|
||||
if (!connected) return;
|
||||
const now = performance.now();
|
||||
if (!force && (now - lastSendMs < 35)) return; // ~28Hz max
|
||||
lastSendMs = now;
|
||||
|
||||
try { ws.send(JSON.stringify({ l, r })); } catch(e) {}
|
||||
}
|
||||
|
||||
function hardStop(){
|
||||
throttleTarget = 0; turnTarget = 0;
|
||||
throttle = 0; turn = 0;
|
||||
lastL = 0; lastR = 0;
|
||||
sendLR(0, 0, true);
|
||||
leftStick.reset();
|
||||
rightStick.reset();
|
||||
renderReadout();
|
||||
}
|
||||
|
||||
btnStop.addEventListener('click', hardStop);
|
||||
|
||||
document.addEventListener("visibilitychange", () => {
|
||||
if (document.hidden) hardStop();
|
||||
});
|
||||
|
||||
// ===== Stick widgets =====
|
||||
function makeStick(canvas, mode /* 'throttle' or 'turn' */) {
|
||||
const ctx = canvas.getContext('2d');
|
||||
const cx = canvas.width / 2;
|
||||
|
|
@ -105,8 +244,6 @@
|
|||
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 {
|
||||
|
|
@ -115,23 +252,61 @@
|
|||
};
|
||||
}
|
||||
|
||||
function apply(nx, ny) {
|
||||
// nx, ny in [-1..1] where ny is +down
|
||||
function draw(){
|
||||
ctx.clearRect(0,0,canvas.width,canvas.height);
|
||||
|
||||
// base 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 line
|
||||
ctx.lineWidth = 6;
|
||||
ctx.strokeStyle = "#152033";
|
||||
ctx.beginPath();
|
||||
if (mode === 'throttle') {
|
||||
// Up should be +throttle, so invert ny
|
||||
throttle = clamp(-ny, -1, 1);
|
||||
ctx.moveTo(cx, cy - radius); ctx.lineTo(cx, cy + radius);
|
||||
} else {
|
||||
turn = clamp(nx, -1, 1);
|
||||
ctx.moveTo(cx - radius, cy); ctx.lineTo(cx + radius, cy);
|
||||
}
|
||||
ctx.stroke();
|
||||
|
||||
// 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 apply(nx, ny){
|
||||
// nx,ny in [-1..1], ny is +down
|
||||
if (mode === 'throttle') {
|
||||
throttleTarget = clamp(-ny, -1, 1); // up = +
|
||||
} else {
|
||||
turnTarget = clamp(nx, -1, 1); // right = +
|
||||
}
|
||||
}
|
||||
|
||||
function stopSelf() {
|
||||
function reset(){
|
||||
active = false;
|
||||
px = cx; py = cy;
|
||||
if (mode === 'throttle') throttle = 0;
|
||||
if (mode === 'turn') turn = 0;
|
||||
draw();
|
||||
updateAndSend(true);
|
||||
}
|
||||
|
||||
function onDown(evt){
|
||||
|
|
@ -144,9 +319,11 @@
|
|||
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;
|
||||
|
||||
|
|
@ -158,12 +335,16 @@
|
|||
|
||||
apply(nx, ny);
|
||||
draw();
|
||||
updateAndSend(false);
|
||||
}
|
||||
|
||||
function onUp(evt){
|
||||
evt.preventDefault();
|
||||
stopSelf();
|
||||
active = false;
|
||||
px = cx; py = cy;
|
||||
// Release = target back to 0 for that axis
|
||||
if (mode === 'throttle') throttleTarget = 0;
|
||||
if (mode === 'turn') turnTarget = 0;
|
||||
draw();
|
||||
}
|
||||
|
||||
canvas.addEventListener('pointerdown', onDown);
|
||||
|
|
@ -172,157 +353,77 @@
|
|||
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 };
|
||||
return { reset };
|
||||
}
|
||||
|
||||
function setStatus(txt, ok=false){
|
||||
statusEl.textContent = txt;
|
||||
statusEl.style.background = ok ? "#16331d" : "#3a1a1a";
|
||||
const leftStick = makeStick(cL, 'throttle');
|
||||
const rightStick = makeStick(cR, 'turn');
|
||||
|
||||
// ===== UI sliders text =====
|
||||
function refreshLabels(){
|
||||
maxvEl.textContent = maxEl.value;
|
||||
accvEl.textContent = accEl.value;
|
||||
decvEl.textContent = decEl.value;
|
||||
turnvEl.textContent = turnRateEl.value;
|
||||
expovEl.textContent = expoEl.value;
|
||||
}
|
||||
[maxEl, accEl, decEl, turnRateEl, expoEl].forEach(el => el.addEventListener('input', refreshLabels));
|
||||
refreshLabels();
|
||||
|
||||
// ===== Main control loop (RAMPING happens HERE) =====
|
||||
function renderReadout(){
|
||||
readoutEl.textContent =
|
||||
`target: T ${throttleTarget.toFixed(2)} | Turn ${turnTarget.toFixed(2)} || ` +
|
||||
`smooth: T ${throttle.toFixed(2)} | Turn ${turn.toFixed(2)} || ` +
|
||||
`L ${lastL} | R ${lastR}`;
|
||||
}
|
||||
|
||||
function clamp(v, a, b){ return Math.max(a, Math.min(b, v)); }
|
||||
let lastTick = performance.now();
|
||||
|
||||
// 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){
|
||||
setInterval(() => {
|
||||
const now = performance.now();
|
||||
if (!connected) return;
|
||||
if (!force && (now - lastSend < 35)) return; // ~28Hz
|
||||
lastSend = now;
|
||||
const dt = Math.max(0.001, (now - lastTick) / 1000);
|
||||
lastTick = now;
|
||||
|
||||
try { ws.send(JSON.stringify({l, r})); } catch(e) {}
|
||||
}
|
||||
// rates from UI
|
||||
const ACCEL_PER_SEC = parseFloat(accEl.value);
|
||||
const DECEL_PER_SEC = parseFloat(decEl.value);
|
||||
const TURN_PER_SEC = parseFloat(turnRateEl.value);
|
||||
const EXPO = parseFloat(expoEl.value);
|
||||
|
||||
function updateAndSend(force) {
|
||||
const maxSpeed = parseInt(maxEl.value, 10);
|
||||
const m = mix(throttle, turn);
|
||||
// ramp throttle
|
||||
const rateT = (Math.abs(throttleTarget) > Math.abs(throttle)) ? ACCEL_PER_SEC : DECEL_PER_SEC;
|
||||
throttle = stepTowards(throttle, throttleTarget, rateT * dt);
|
||||
|
||||
const L = Math.round(clamp(m.l, -1, 1) * maxSpeed);
|
||||
const R = Math.round(clamp(m.r, -1, 1) * maxSpeed);
|
||||
// ramp turn
|
||||
turn = stepTowards(turn, turnTarget, TURN_PER_SEC * dt);
|
||||
|
||||
// apply expo AFTER ramp (feels nicer)
|
||||
const th = expo(throttle, EXPO);
|
||||
const tr = expo(turn, EXPO);
|
||||
|
||||
// mix
|
||||
let { l, r } = mix(th, tr);
|
||||
|
||||
// scale
|
||||
let maxSpeed = parseInt(maxEl.value, 10);
|
||||
if (slowMode) maxSpeed = Math.round(maxSpeed * 0.45);
|
||||
|
||||
const L = Math.round(clamp(l, -1, 1) * maxSpeed);
|
||||
const R = Math.round(clamp(r, -1, 1) * maxSpeed);
|
||||
|
||||
lastL = L; lastR = R;
|
||||
readoutEl.textContent = `T ${throttle.toFixed(2)} | Turn ${turn.toFixed(2)} → L ${L} | R ${R}`;
|
||||
renderReadout();
|
||||
|
||||
// sendLR(L, R, force);
|
||||
// always send with a gentle cap (force keeps Arduino alive)
|
||||
// This is both "control output" and heartbeat.
|
||||
sendLR(L, R, true);
|
||||
}, 20); // 50 Hz smoothing + sending
|
||||
|
||||
// ---- Heartbeat: keep sending current values while driving ----
|
||||
setInterval(() => {
|
||||
// wenn nicht verbunden -> nix
|
||||
if (!connected) return;
|
||||
|
||||
// Wenn du NUR beim aktiven Fahren senden willst:
|
||||
const driving = (Math.abs(throttle) > 0.02) || (Math.abs(turn) > 0.02);
|
||||
|
||||
if (driving) {
|
||||
// erzwinge Senden auch wenn sich nichts geändert hat
|
||||
sendLR(lastL, lastR, true);
|
||||
}
|
||||
}, 400); // 40 Hz
|
||||
|
||||
}
|
||||
|
||||
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
|
||||
// ===== Start =====
|
||||
connect();
|
||||
setStatus("connecting...", false);
|
||||
|
||||
// Safety: stop when page hidden
|
||||
document.addEventListener("visibilitychange", () => {
|
||||
if (document.hidden) hardStop();
|
||||
});
|
||||
|
||||
})();
|
||||
</script>
|
||||
</body>
|
||||
|
|
|
|||
Loading…
Reference in New Issue