diff --git a/ui/diagnostics_panel.css b/ui/diagnostics_panel.css
new file mode 100644
index 0000000..e73c624
--- /dev/null
+++ b/ui/diagnostics_panel.css
@@ -0,0 +1,230 @@
+/* diagnostics_panel.css — Saltybot System Diagnostics Dashboard (Issue #562) */
+
+*, *::before, *::after { box-sizing: border-box; margin: 0; padding: 0; }
+
+:root {
+ --bg0: #050510;
+ --bg1: #070712;
+ --bg2: #0a0a1a;
+ --border: #0c2a3a;
+ --border2: #1e3a5f;
+ --text-dim: #374151;
+ --text-mid: #6b7280;
+ --text-base: #9ca3af;
+ --text-hi: #d1d5db;
+ --cyan: #06b6d4;
+ --cyan-dim: #0e4f69;
+ --green: #22c55e;
+ --amber: #f59e0b;
+ --red: #ef4444;
+ --orange: #f97316;
+}
+
+body {
+ font-family: 'Courier New', Courier, monospace;
+ font-size: 12px;
+ background: var(--bg0);
+ color: var(--text-base);
+ min-height: 100dvh;
+ display: flex;
+ flex-direction: column;
+}
+
+/* ── Header ── */
+#header {
+ display: flex;
+ align-items: center;
+ justify-content: space-between;
+ padding: 6px 16px;
+ background: var(--bg1);
+ border-bottom: 1px solid var(--border);
+ flex-shrink: 0;
+ flex-wrap: wrap;
+ gap: 8px;
+}
+.logo { color: #f97316; font-weight: bold; letter-spacing: 0.15em; font-size: 13px; }
+
+#conn-bar { display: flex; align-items: center; gap: 6px; }
+#conn-dot {
+ width: 8px; height: 8px; border-radius: 50%;
+ background: var(--text-dim); flex-shrink: 0; transition: background 0.3s;
+}
+#conn-dot.connected { background: var(--green); }
+#conn-dot.error { background: var(--red); animation: blink 1s infinite; }
+
+@keyframes blink { 0%,100% { opacity:1; } 50% { opacity:0.4; } }
+
+#ws-input {
+ background: var(--bg2); border: 1px solid var(--border2); border-radius: 4px;
+ color: #67e8f9; padding: 2px 8px; font-family: monospace; font-size: 11px; width: 200px;
+}
+#ws-input:focus { outline: none; border-color: var(--cyan); }
+
+.hdr-btn {
+ padding: 3px 10px; border-radius: 4px; border: 1px solid var(--border2);
+ background: var(--bg2); color: #67e8f9; font-family: monospace;
+ font-size: 10px; font-weight: bold; cursor: pointer; transition: background 0.15s;
+}
+.hdr-btn:hover { background: var(--cyan-dim); }
+
+#refresh-info {
+ font-size: 10px; color: var(--text-mid);
+ display: flex; align-items: center; gap: 4px;
+}
+#refresh-dot {
+ width: 6px; height: 6px; border-radius: 50%;
+ background: var(--text-dim); transition: background 0.2s;
+}
+#refresh-dot.pulse { background: var(--cyan); animation: blink 0.4s; }
+
+/* ── Status bar ── */
+#status-bar {
+ display: flex; gap: 8px; align-items: center;
+ padding: 4px 16px; background: var(--bg1);
+ border-bottom: 1px solid var(--border); font-size: 10px; flex-wrap: wrap;
+}
+.sys-badge {
+ padding: 2px 8px; border-radius: 3px; font-weight: bold;
+ border: 1px solid; letter-spacing: 0.05em;
+}
+.badge-ok { background: #052e16; border-color: #166534; color: #4ade80; }
+.badge-warn { background: #451a03; border-color: #92400e; color: #fcd34d; }
+.badge-error { background: #450a0a; border-color: #991b1b; color: #f87171; animation: blink 1s infinite; }
+.badge-stale { background: #111827; border-color: #374151; color: #6b7280; }
+#last-update { color: var(--text-mid); margin-left: auto; }
+
+/* ── Dashboard grid ── */
+#dashboard {
+ flex: 1;
+ display: grid;
+ grid-template-columns: repeat(3, 1fr);
+ grid-template-rows: auto;
+ gap: 12px;
+ padding: 12px;
+ align-content: start;
+ overflow-y: auto;
+}
+
+@media (max-width: 1024px) { #dashboard { grid-template-columns: repeat(2, 1fr); } }
+@media (max-width: 640px) { #dashboard { grid-template-columns: 1fr; } }
+
+/* Spanning cards */
+.span2 { grid-column: span 2; }
+.span3 { grid-column: 1 / -1; }
+
+/* ── Card ── */
+.card {
+ background: var(--bg1);
+ border: 1px solid var(--border);
+ border-radius: 8px;
+ padding: 10px 12px;
+ display: flex;
+ flex-direction: column;
+ gap: 8px;
+}
+.card.alert-warn { border-color: #92400e; }
+.card.alert-error { border-color: #991b1b; }
+
+.card-title {
+ font-size: 9px; font-weight: bold; letter-spacing: 0.15em;
+ color: #0891b2; text-transform: uppercase;
+ display: flex; align-items: center; justify-content: space-between;
+}
+.card-title .badge { font-size: 9px; padding: 1px 6px; border-radius: 3px; }
+
+/* ── Gauge bar ── */
+.gauge-row {
+ display: flex; flex-direction: column; gap: 3px;
+}
+.gauge-label-row {
+ display: flex; justify-content: space-between; font-size: 10px;
+}
+.gauge-label { color: var(--text-mid); }
+.gauge-value { font-family: monospace; }
+.gauge-track {
+ width: 100%; height: 8px;
+ background: var(--bg2); border-radius: 4px;
+ overflow: hidden; border: 1px solid var(--border2);
+}
+.gauge-fill {
+ height: 100%; border-radius: 4px;
+ transition: width 0.5s ease, background 0.5s ease;
+}
+
+/* ── Big metric ── */
+.big-metric {
+ display: flex; align-items: baseline; gap: 4px;
+}
+.big-num { font-size: 28px; font-weight: bold; font-family: monospace; }
+.big-unit { font-size: 11px; color: var(--text-mid); }
+
+/* ── Sparkline ── */
+#batt-sparkline {
+ width: 100%; border-radius: 4px;
+ border: 1px solid var(--border2);
+ background: var(--bg2);
+ display: block;
+}
+
+/* ── Node list ── */
+.node-row {
+ display: flex; align-items: center; justify-content: space-between;
+ padding: 3px 0; border-bottom: 1px solid var(--border);
+ font-size: 10px;
+}
+.node-row:last-child { border-bottom: none; }
+.node-name { color: var(--text-base); font-family: monospace; }
+.node-status {
+ padding: 1px 6px; border-radius: 3px; font-size: 9px; font-weight: bold;
+}
+.ns-ok { background: #052e16; color: #4ade80; }
+.ns-warn { background: #451a03; color: #fcd34d; }
+.ns-error { background: #450a0a; color: #f87171; }
+.ns-stale { background: #111827; color: #6b7280; }
+
+/* ── Temp arc display ── */
+.temp-grid {
+ display: grid; grid-template-columns: repeat(2, 1fr); gap: 6px;
+}
+.temp-box {
+ background: var(--bg2); border: 1px solid var(--border2);
+ border-radius: 6px; padding: 6px; text-align: center;
+}
+.temp-label { font-size: 9px; color: var(--text-mid); margin-bottom: 2px; }
+.temp-value { font-size: 22px; font-weight: bold; font-family: monospace; }
+.temp-bar-track {
+ margin-top: 4px; width: 100%; height: 4px;
+ background: var(--bg0); border-radius: 2px; overflow: hidden;
+}
+.temp-bar-fill { height: 100%; border-radius: 2px; transition: width 0.5s; }
+
+/* ── Motor section ── */
+.motor-grid {
+ display: grid; grid-template-columns: repeat(2, 1fr); gap: 8px;
+}
+.motor-box {
+ background: var(--bg2); border: 1px solid var(--border2);
+ border-radius: 6px; padding: 8px;
+}
+.motor-label { font-size: 9px; color: var(--text-mid); margin-bottom: 4px; }
+
+/* ── WiFi bars ── */
+.rssi-bars { display: flex; align-items: flex-end; gap: 3px; }
+.rssi-bar { width: 6px; border-radius: 2px 2px 0 0; }
+
+/* ── MQTT indicator ── */
+.mqtt-status { display: flex; align-items: center; gap: 6px; }
+.mqtt-dot {
+ width: 10px; height: 10px; border-radius: 50%;
+ background: var(--text-dim); transition: background 0.3s;
+}
+.mqtt-dot.connected { background: var(--green); animation: none; }
+.mqtt-dot.disconnected { background: var(--red); animation: blink 1s infinite; }
+
+/* ── Footer ── */
+#footer {
+ background: var(--bg1); border-top: 1px solid var(--border);
+ padding: 4px 16px;
+ display: flex; align-items: center; justify-content: space-between;
+ flex-shrink: 0; font-size: 10px; color: var(--text-dim);
+}
diff --git a/ui/diagnostics_panel.html b/ui/diagnostics_panel.html
new file mode 100644
index 0000000..8aa5417
--- /dev/null
+++ b/ui/diagnostics_panel.html
@@ -0,0 +1,267 @@
+
+
+
+
+
+Saltybot — System Diagnostics
+
+
+
+
+
+
+
+
+
+
+ SYSTEM
+ STALE
+ │
+ BATTERY
+ —
+ │
+ THERMAL
+ —
+ │
+ NETWORK
+ —
+ Awaiting data…
+
+
+
+
+
+
+
+
+ BATTERY — 4S LiPo (12.0–16.8 V)
+ —
+
+
+
+
+
+
+
+
+ Voltage
+ 12.0–16.8 V
+
+
+
+
+
+ State of Charge
+ 0–100%
+
+
+
+
+
+
+
VOLTAGE HISTORY (last 2 min)
+
+
+
+
+
+
+
TEMPERATURES
+
+
+ Zones: <60°C green · 60–75°C amber · >75°C red
+
+
+
+
+
+
MOTOR CURRENT & CMD
+
+
+
LEFT WHEEL
+
—
+
+
+ CMD: —
+
+
+
+
RIGHT WHEEL
+
—
+
+
+ CMD: —
+
+
+
+
+ Balance state: —
+
+
Thresholds: warn 8A · crit 12A
+
+
+
+
+
RESOURCES
+
+
+
+
Warn ≥80% · Critical ≥95%
+
+
+
+
+
NETWORK
+
+
+
+ Rosbridge Latency
+ —
+
+
+
+
+
MQTT BROKER
+
+
+ Via /diagnostics KeyValue: mqtt_connected
+
+
+
+
+
+
+
+ ROS2 NODE HEALTH — /diagnostics
+ 0 nodes
+
+
+
+ Waiting for /diagnostics data…
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/ui/diagnostics_panel.js b/ui/diagnostics_panel.js
new file mode 100644
index 0000000..616c38c
--- /dev/null
+++ b/ui/diagnostics_panel.js
@@ -0,0 +1,592 @@
+/**
+ * diagnostics_panel.js — Saltybot System Diagnostics Dashboard (Issue #562)
+ *
+ * Connects to rosbridge WebSocket and subscribes to:
+ * /diagnostics diagnostic_msgs/DiagnosticArray — everything
+ * /saltybot/balance_state std_msgs/String (JSON) — motor cmd / state
+ *
+ * Diagnostic KeyValues decoded:
+ * battery_voltage_v, battery_current_a, battery_soc_pct
+ * cpu_temp_c, gpu_temp_c, board_temp_c
+ * motor_temp_l_c, motor_temp_r_c
+ * motor_current_l_a, motor_current_r_a
+ * ram_used_mb, ram_total_mb
+ * gpu_used_mb, gpu_total_mb
+ * disk_used_gb, disk_total_gb
+ * wifi_rssi_dbm, wifi_latency_ms
+ * mqtt_connected
+ *
+ * Auto-refresh: rosbridge subscriptions push at ~2 Hz; UI polls canvas draws
+ * at the same rate and updates DOM elements.
+ */
+
+'use strict';
+
+// ── Constants ─────────────────────────────────────────────────────────────────
+
+const LIPO_MIN = 12.0; // 4S empty
+const LIPO_MAX = 16.8; // 4S full
+
+const BATT_HISTORY_MAX = 120; // ~2 min at 1 Hz
+
+// Alert thresholds
+const THRESHOLDS = {
+ voltage_warn: 13.6,
+ voltage_crit: 13.0,
+ soc_warn: 25,
+ soc_crit: 10,
+ cpu_temp_warn: 75,
+ cpu_temp_crit: 90,
+ gpu_temp_warn: 75,
+ gpu_temp_crit: 90,
+ motor_temp_warn: 70,
+ motor_temp_crit: 85,
+ ram_pct_warn: 80,
+ ram_pct_crit: 95,
+ disk_pct_warn: 80,
+ disk_pct_crit: 95,
+ rssi_warn: -70,
+ rssi_crit: -80,
+ latency_warn: 150,
+ latency_crit: 500,
+ current_warn: 8.0,
+ current_crit: 12.0,
+};
+
+// ── State ─────────────────────────────────────────────────────────────────────
+
+let ros = null;
+let diagSub = null;
+let balanceSub = null;
+
+const state = {
+ // Battery
+ voltage: null,
+ current: null,
+ soc: null,
+ battHistory: [], // [{ts, v}]
+
+ // Temperatures
+ cpuTemp: null,
+ gpuTemp: null,
+ boardTemp: null,
+ motorTempL: null,
+ motorTempR: null,
+
+ // Motor
+ motorCurrentL: null,
+ motorCurrentR: null,
+ motorCmdL: null,
+ motorCmdR: null,
+ balanceState: 'UNKNOWN',
+
+ // Resources
+ ramUsed: null, ramTotal: null,
+ gpuUsed: null, gpuTotal: null,
+ diskUsed: null, diskTotal: null,
+
+ // Network
+ rssi: null,
+ latency: null,
+
+ // MQTT
+ mqttConnected: null,
+
+ // ROS nodes (DiagnosticStatus array)
+ nodes: [],
+
+ // Overall health
+ overallLevel: 3, // 3=STALE by default
+ lastUpdate: null,
+};
+
+// ── Utility ───────────────────────────────────────────────────────────────────
+
+function numOrNull(s) {
+ const n = parseFloat(s);
+ return isNaN(n) ? null : n;
+}
+
+function pct(used, total) {
+ if (!total || total === 0) return 0;
+ return Math.min(100, Math.max(0, (used / total) * 100));
+}
+
+function socFromVoltage(v) {
+ if (v == null || v <= 0) return null;
+ return Math.max(0, Math.min(100, ((v - LIPO_MIN) / (LIPO_MAX - LIPO_MIN)) * 100));
+}
+
+function threshColor(value, warnThr, critThr, invert = false) {
+ // invert: lower is worse (e.g. voltage, SOC, RSSI)
+ if (value == null) return '#6b7280';
+ const warn = invert ? value <= warnThr : value >= warnThr;
+ const crit = invert ? value <= critThr : value >= critThr;
+ if (crit) return '#ef4444';
+ if (warn) return '#f59e0b';
+ return '#22c55e';
+}
+
+function levelClass(level) {
+ return ['ns-ok', 'ns-warn', 'ns-error', 'ns-stale'][level] ?? 'ns-stale';
+}
+
+function levelLabel(level) {
+ return ['OK', 'WARN', 'ERROR', 'STALE'][level] ?? 'STALE';
+}
+
+function setBadgeClass(el, level) {
+ el.className = 'sys-badge ' + ['badge-ok','badge-warn','badge-error','badge-stale'][level ?? 3];
+}
+
+// ── Connection ────────────────────────────────────────────────────────────────
+
+function connect() {
+ const url = document.getElementById('ws-input').value.trim();
+ if (!url) return;
+ if (ros) ros.close();
+
+ ros = new ROSLIB.Ros({ url });
+
+ ros.on('connection', () => {
+ document.getElementById('conn-dot').className = 'connected';
+ document.getElementById('conn-label').textContent = url;
+ setupSubscriptions();
+ });
+
+ ros.on('error', (err) => {
+ document.getElementById('conn-dot').className = 'error';
+ document.getElementById('conn-label').textContent = 'ERROR: ' + (err?.message || err);
+ teardown();
+ });
+
+ ros.on('close', () => {
+ document.getElementById('conn-dot').className = '';
+ document.getElementById('conn-label').textContent = 'Disconnected';
+ teardown();
+ });
+}
+
+function setupSubscriptions() {
+ // /diagnostics — throttle 500ms → ~2 Hz
+ diagSub = new ROSLIB.Topic({
+ ros, name: '/diagnostics',
+ messageType: 'diagnostic_msgs/DiagnosticArray',
+ throttle_rate: 500,
+ });
+ diagSub.subscribe(onDiagnostics);
+
+ // /saltybot/balance_state
+ balanceSub = new ROSLIB.Topic({
+ ros, name: '/saltybot/balance_state',
+ messageType: 'std_msgs/String',
+ throttle_rate: 500,
+ });
+ balanceSub.subscribe(onBalanceState);
+}
+
+function teardown() {
+ if (diagSub) { diagSub.unsubscribe(); diagSub = null; }
+ if (balanceSub) { balanceSub.unsubscribe(); balanceSub = null; }
+ state.overallLevel = 3;
+ state.lastUpdate = null;
+ render();
+}
+
+// ── Message handlers ──────────────────────────────────────────────────────────
+
+function onDiagnostics(msg) {
+ const statuses = msg.status ?? [];
+ state.nodes = [];
+ let overallLevel = 0;
+
+ for (const status of statuses) {
+ const kv = {};
+ for (const { key, value } of (status.values ?? [])) {
+ kv[key] = value;
+ }
+
+ // Battery
+ if ('battery_voltage_v' in kv) state.voltage = numOrNull(kv.battery_voltage_v);
+ if ('battery_current_a' in kv) state.current = numOrNull(kv.battery_current_a);
+ if ('battery_soc_pct' in kv) state.soc = numOrNull(kv.battery_soc_pct);
+
+ // Temperatures
+ if ('cpu_temp_c' in kv) state.cpuTemp = numOrNull(kv.cpu_temp_c);
+ if ('gpu_temp_c' in kv) state.gpuTemp = numOrNull(kv.gpu_temp_c);
+ if ('board_temp_c' in kv) state.boardTemp = numOrNull(kv.board_temp_c);
+ if ('motor_temp_l_c' in kv) state.motorTempL = numOrNull(kv.motor_temp_l_c);
+ if ('motor_temp_r_c' in kv) state.motorTempR = numOrNull(kv.motor_temp_r_c);
+
+ // Motor current
+ if ('motor_current_l_a' in kv) state.motorCurrentL = numOrNull(kv.motor_current_l_a);
+ if ('motor_current_r_a' in kv) state.motorCurrentR = numOrNull(kv.motor_current_r_a);
+
+ // Resources
+ if ('ram_used_mb' in kv) state.ramUsed = numOrNull(kv.ram_used_mb);
+ if ('ram_total_mb' in kv) state.ramTotal = numOrNull(kv.ram_total_mb);
+ if ('gpu_used_mb' in kv) state.gpuUsed = numOrNull(kv.gpu_used_mb);
+ if ('gpu_total_mb' in kv) state.gpuTotal = numOrNull(kv.gpu_total_mb);
+ if ('disk_used_gb' in kv) state.diskUsed = numOrNull(kv.disk_used_gb);
+ if ('disk_total_gb' in kv) state.diskTotal = numOrNull(kv.disk_total_gb);
+
+ // Network
+ if ('wifi_rssi_dbm' in kv) state.rssi = numOrNull(kv.wifi_rssi_dbm);
+ if ('wifi_latency_ms' in kv) state.latency = numOrNull(kv.wifi_latency_ms);
+
+ // MQTT
+ if ('mqtt_connected' in kv) state.mqttConnected = kv.mqtt_connected === 'true';
+
+ // Node health
+ state.nodes.push({
+ name: status.name || status.hardware_id || 'unknown',
+ level: status.level ?? 3,
+ message: status.message || '',
+ });
+
+ overallLevel = Math.max(overallLevel, status.level ?? 0);
+ }
+
+ state.overallLevel = overallLevel;
+ state.lastUpdate = new Date();
+
+ // Battery history
+ if (state.voltage != null) {
+ state.battHistory.push({ ts: Date.now(), v: state.voltage });
+ if (state.battHistory.length > BATT_HISTORY_MAX) {
+ state.battHistory.shift();
+ }
+ }
+
+ // Derive SOC from voltage if not provided
+ if (state.soc == null && state.voltage != null) {
+ state.soc = socFromVoltage(state.voltage);
+ }
+
+ render();
+ flashRefreshDot();
+}
+
+function onBalanceState(msg) {
+ try {
+ const data = JSON.parse(msg.data);
+ state.balanceState = data.state ?? 'UNKNOWN';
+ state.motorCmdL = data.motor_cmd ?? null;
+ state.motorCmdR = data.motor_cmd ?? null; // single motor_cmd field
+ } catch (_) {}
+}
+
+// ── Refresh indicator ─────────────────────────────────────────────────────────
+
+function flashRefreshDot() {
+ const dot = document.getElementById('refresh-dot');
+ dot.classList.add('pulse');
+ setTimeout(() => dot.classList.remove('pulse'), 400);
+}
+
+// ── Sparkline canvas ──────────────────────────────────────────────────────────
+
+function drawSparkline() {
+ const canvas = document.getElementById('batt-sparkline');
+ if (!canvas) return;
+ const ctx = canvas.getContext('2d');
+ const W = canvas.width = canvas.offsetWidth || 300;
+ const H = canvas.height;
+
+ ctx.clearRect(0, 0, W, H);
+ ctx.fillStyle = '#0a0a1a';
+ ctx.fillRect(0, 0, W, H);
+
+ const data = state.battHistory;
+ if (data.length < 2) {
+ ctx.fillStyle = '#374151';
+ ctx.font = '10px Courier New';
+ ctx.textAlign = 'center';
+ ctx.fillText('Awaiting battery data…', W / 2, H / 2 + 4);
+ return;
+ }
+
+ const vMin = LIPO_MIN - 0.2;
+ const vMax = LIPO_MAX + 0.2;
+
+ // Grid lines
+ ctx.strokeStyle = '#1e3a5f';
+ ctx.lineWidth = 0.5;
+ [0.25, 0.5, 0.75].forEach((f) => {
+ const y = H - f * H;
+ ctx.beginPath(); ctx.moveTo(0, y); ctx.lineTo(W, y); ctx.stroke();
+ });
+
+ // Plot
+ ctx.lineWidth = 1.5;
+ ctx.beginPath();
+ data.forEach((pt, i) => {
+ const x = (i / (data.length - 1)) * W;
+ const y = H - ((pt.v - vMin) / (vMax - vMin)) * H;
+ i === 0 ? ctx.moveTo(x, y) : ctx.lineTo(x, y);
+ });
+
+ const lastV = data[data.length - 1].v;
+ ctx.strokeStyle = threshColor(lastV, THRESHOLDS.voltage_warn, THRESHOLDS.voltage_crit, true);
+ ctx.stroke();
+
+ // Fill under
+ ctx.lineTo(W, H); ctx.lineTo(0, H); ctx.closePath();
+ ctx.fillStyle = 'rgba(6,182,212,0.06)';
+ ctx.fill();
+
+ // Labels
+ ctx.fillStyle = '#374151';
+ ctx.font = '9px Courier New';
+ ctx.textAlign = 'left';
+ ctx.fillText(`${LIPO_MAX}V`, 2, 10);
+ ctx.fillText(`${LIPO_MIN}V`, 2, H - 2);
+}
+
+// ── Gauge helpers ─────────────────────────────────────────────────────────────
+
+function setGauge(barId, pctVal, color) {
+ const el = document.getElementById(barId);
+ if (!el) return;
+ el.style.width = `${Math.max(0, Math.min(100, pctVal))}%`;
+ el.style.background = color;
+}
+
+function setText(id, text) {
+ const el = document.getElementById(id);
+ if (el) el.textContent = text ?? '—';
+}
+
+function setColor(id, color) {
+ const el = document.getElementById(id);
+ if (el) el.style.color = color;
+}
+
+function setTempBox(id, tempC, warnT, critT) {
+ const box = document.getElementById(id + '-box');
+ const val = document.getElementById(id + '-val');
+ const bar = document.getElementById(id + '-bar');
+ const color = threshColor(tempC, warnT, critT);
+
+ if (val) { val.textContent = tempC != null ? tempC.toFixed(0) + '°C' : '—'; val.style.color = color; }
+ if (bar) {
+ const p = tempC != null ? Math.min(100, (tempC / 100) * 100) : 0;
+ bar.style.width = p + '%';
+ bar.style.background = color;
+ }
+ if (box && tempC != null) {
+ box.style.borderColor = tempC >= critT ? '#991b1b' : tempC >= warnT ? '#92400e' : '#1e3a5f';
+ }
+}
+
+// ── RSSI bars ─────────────────────────────────────────────────────────────────
+
+function rssiToLevel(dBm) {
+ if (dBm == null) return { label: 'N/A', color: '#374151', bars: 0 };
+ if (dBm >= -50) return { label: 'Excellent', color: '#22c55e', bars: 5 };
+ if (dBm >= -60) return { label: 'Good', color: '#3b82f6', bars: 4 };
+ if (dBm >= -70) return { label: 'Fair', color: '#f59e0b', bars: 3 };
+ if (dBm >= -80) return { label: 'Weak', color: '#ef4444', bars: 2 };
+ return { label: 'Poor', color: '#7f1d1d', bars: 1 };
+}
+
+function drawRssiBars() {
+ const container = document.getElementById('rssi-bars');
+ if (!container) return;
+ const lv = rssiToLevel(state.rssi);
+ const BAR_H = [4, 8, 12, 16, 20];
+
+ container.innerHTML = '';
+ for (let i = 0; i < 5; i++) {
+ const bar = document.createElement('div');
+ bar.className = 'rssi-bar';
+ bar.style.height = BAR_H[i] + 'px';
+ bar.style.width = '7px';
+ bar.style.background = i < lv.bars ? lv.color : '#1f2937';
+ container.appendChild(bar);
+ }
+}
+
+// ── Node list renderer ────────────────────────────────────────────────────────
+
+function renderNodes() {
+ const container = document.getElementById('node-list');
+ if (!container) return;
+
+ if (state.nodes.length === 0) {
+ container.innerHTML = 'No /diagnostics data yet
';
+ return;
+ }
+
+ container.innerHTML = state.nodes.map((n) => `
+
+
${n.name}
+
+ ${n.message ? `${n.message}` : ''}
+ ${levelLabel(n.level)}
+
+
+ `).join('');
+}
+
+// ── Overall status bar ────────────────────────────────────────────────────────
+
+function updateStatusBar() {
+ const lvl = state.overallLevel;
+ const badge = document.getElementById('system-badge');
+ const labels = ['HEALTHY', 'DEGRADED', 'FAULT', 'STALE'];
+ if (badge) {
+ badge.textContent = labels[lvl] ?? 'STALE';
+ setBadgeClass(badge, lvl);
+ }
+
+ // Individual badges
+ updateBattBadge();
+ updateTempBadge();
+ updateNetBadge();
+
+ const upd = document.getElementById('last-update');
+ if (upd && state.lastUpdate) {
+ upd.textContent = 'Updated ' + state.lastUpdate.toLocaleTimeString();
+ }
+}
+
+function updateBattBadge() {
+ const el = document.getElementById('batt-badge');
+ if (!el) return;
+ const v = state.voltage;
+ if (v == null) { el.textContent = 'NO DATA'; setBadgeClass(el, 3); return; }
+ if (v <= THRESHOLDS.voltage_crit) { el.textContent = 'CRITICAL'; setBadgeClass(el, 2); }
+ else if (v <= THRESHOLDS.voltage_warn) { el.textContent = 'LOW'; setBadgeClass(el, 1); }
+ else { el.textContent = 'OK'; setBadgeClass(el, 0); }
+}
+
+function updateTempBadge() {
+ const el = document.getElementById('temp-badge');
+ if (!el) return;
+ const temps = [state.cpuTemp, state.gpuTemp, state.motorTempL, state.motorTempR].filter(t => t != null);
+ if (temps.length === 0) { el.textContent = 'NO DATA'; setBadgeClass(el, 3); return; }
+ const max = Math.max(...temps);
+ if (max >= THRESHOLDS.cpu_temp_crit) { el.textContent = 'CRITICAL'; setBadgeClass(el, 2); }
+ else if (max >= THRESHOLDS.cpu_temp_warn) { el.textContent = 'HOT'; setBadgeClass(el, 1); }
+ else { el.textContent = 'OK'; setBadgeClass(el, 0); }
+}
+
+function updateNetBadge() {
+ const el = document.getElementById('net-badge');
+ if (!el) return;
+ const r = state.rssi;
+ if (r == null) { el.textContent = 'NO DATA'; setBadgeClass(el, 3); return; }
+ if (r <= THRESHOLDS.rssi_crit) { el.textContent = 'POOR'; setBadgeClass(el, 2); }
+ else if (r <= THRESHOLDS.rssi_warn) { el.textContent = 'WEAK'; setBadgeClass(el, 1); }
+ else { el.textContent = 'OK'; setBadgeClass(el, 0); }
+}
+
+// ── Main render ───────────────────────────────────────────────────────────────
+
+function render() {
+ // ── Battery ──
+ const v = state.voltage;
+ const soc = state.soc ?? socFromVoltage(v);
+ const vColor = threshColor(v, THRESHOLDS.voltage_warn, THRESHOLDS.voltage_crit, true);
+ const sColor = threshColor(soc, THRESHOLDS.soc_warn, THRESHOLDS.soc_crit, true);
+
+ setText('batt-voltage', v != null ? v.toFixed(2) + ' V' : '—');
+ setColor('batt-voltage', vColor);
+ setText('batt-soc', soc != null ? soc.toFixed(0) + ' %' : '—');
+ setColor('batt-soc', sColor);
+ setText('batt-current', state.current != null ? state.current.toFixed(2) + ' A' : '—');
+
+ setGauge('batt-soc-bar', soc ?? 0, sColor);
+ setGauge('batt-volt-bar', v != null ? ((v - LIPO_MIN) / (LIPO_MAX - LIPO_MIN)) * 100 : 0, vColor);
+
+ drawSparkline();
+
+ // ── Temperatures ──
+ setTempBox('cpu-temp', state.cpuTemp, THRESHOLDS.cpu_temp_warn, THRESHOLDS.cpu_temp_crit);
+ setTempBox('gpu-temp', state.gpuTemp, THRESHOLDS.gpu_temp_warn, THRESHOLDS.gpu_temp_crit);
+ setTempBox('board-temp', state.boardTemp, 60, 80);
+ setTempBox('motor-temp-l', state.motorTempL, THRESHOLDS.motor_temp_warn, THRESHOLDS.motor_temp_crit);
+ setTempBox('motor-temp-r', state.motorTempR, THRESHOLDS.motor_temp_warn, THRESHOLDS.motor_temp_crit);
+
+ // ── Motor current ──
+ const curL = state.motorCurrentL;
+ const curR = state.motorCurrentR;
+ const curColorL = threshColor(curL, THRESHOLDS.current_warn, THRESHOLDS.current_crit);
+ const curColorR = threshColor(curR, THRESHOLDS.current_warn, THRESHOLDS.current_crit);
+
+ setText('motor-cur-l', curL != null ? curL.toFixed(2) + ' A' : '—');
+ setColor('motor-cur-l', curColorL);
+ setText('motor-cur-r', curR != null ? curR.toFixed(2) + ' A' : '—');
+ setColor('motor-cur-r', curColorR);
+ setGauge('motor-bar-l', curL != null ? (curL / THRESHOLDS.current_crit) * 100 : 0, curColorL);
+ setGauge('motor-bar-r', curR != null ? (curR / THRESHOLDS.current_crit) * 100 : 0, curColorR);
+ setText('motor-cmd-l', state.motorCmdL != null ? state.motorCmdL.toString() : '—');
+ setText('motor-cmd-r', state.motorCmdR != null ? state.motorCmdR.toString() : '—');
+ setText('balance-state', state.balanceState);
+
+ // ── Resources ──
+ const ramPct = pct(state.ramUsed, state.ramTotal);
+ const gpuPct = pct(state.gpuUsed, state.gpuTotal);
+ const diskPct = pct(state.diskUsed, state.diskTotal);
+
+ setText('ram-val',
+ state.ramUsed != null ? `${state.ramUsed.toFixed(0)} / ${state.ramTotal?.toFixed(0) ?? '?'} MB` : '—');
+ setGauge('ram-bar', ramPct, threshColor(ramPct, THRESHOLDS.ram_pct_warn, THRESHOLDS.ram_pct_crit));
+
+ setText('gpu-val',
+ state.gpuUsed != null ? `${state.gpuUsed.toFixed(0)} / ${state.gpuTotal?.toFixed(0) ?? '?'} MB` : '—');
+ setGauge('gpu-bar', gpuPct, threshColor(gpuPct, 70, 90));
+
+ setText('disk-val',
+ state.diskUsed != null ? `${state.diskUsed.toFixed(1)} / ${state.diskTotal?.toFixed(1) ?? '?'} GB` : '—');
+ setGauge('disk-bar', diskPct, threshColor(diskPct, THRESHOLDS.disk_pct_warn, THRESHOLDS.disk_pct_crit));
+
+ // ── WiFi ──
+ const rLevel = rssiToLevel(state.rssi);
+ setText('rssi-val', state.rssi != null ? state.rssi + ' dBm' : '—');
+ setColor('rssi-val', rLevel.color);
+ setText('rssi-label', rLevel.label);
+ setColor('rssi-label', rLevel.color);
+ setText('latency-val', state.latency != null ? state.latency.toFixed(0) + ' ms' : '—');
+ setColor('latency-val', threshColor(state.latency, THRESHOLDS.latency_warn, THRESHOLDS.latency_crit));
+ drawRssiBars();
+
+ // ── MQTT ──
+ const mqttDot = document.getElementById('mqtt-dot');
+ const mqttLbl = document.getElementById('mqtt-label');
+ if (mqttDot) {
+ mqttDot.className = 'mqtt-dot ' + (state.mqttConnected ? 'connected' : 'disconnected');
+ }
+ if (mqttLbl) {
+ mqttLbl.textContent = state.mqttConnected === null ? 'No data'
+ : state.mqttConnected ? 'Broker connected'
+ : 'Broker disconnected';
+ mqttLbl.style.color = state.mqttConnected ? '#4ade80' : '#f87171';
+ }
+
+ // ── Nodes ──
+ renderNodes();
+
+ // ── Status bar ──
+ updateStatusBar();
+}
+
+// ── Init ──────────────────────────────────────────────────────────────────────
+
+document.getElementById('btn-connect').addEventListener('click', connect);
+document.getElementById('ws-input').addEventListener('keydown', (e) => {
+ if (e.key === 'Enter') connect();
+});
+
+const stored = localStorage.getItem('diag_ws_url');
+if (stored) document.getElementById('ws-input').value = stored;
+document.getElementById('ws-input').addEventListener('change', (e) => {
+ localStorage.setItem('diag_ws_url', e.target.value);
+});
+
+// Initial render (blank state)
+render();
+
+// Periodic sparkline resize + redraw on window resize
+window.addEventListener('resize', drawSparkline);