diff --git a/ui/settings_panel.css b/ui/settings_panel.css
new file mode 100644
index 0000000..168ea93
--- /dev/null
+++ b/ui/settings_panel.css
@@ -0,0 +1,343 @@
+/* settings_panel.css — Saltybot Settings (Issue #614) */
+
+*, *::before, *::after { box-sizing: border-box; margin: 0; padding: 0; }
+
+:root {
+ --bg0: #050510;
+ --bg1: #070712;
+ --bg2: #0a0a1a;
+ --bd: #0c2a3a;
+ --bd2: #1e3a5f;
+ --dim: #374151;
+ --mid: #6b7280;
+ --base: #9ca3af;
+ --hi: #d1d5db;
+ --cyan: #06b6d4;
+ --green: #22c55e;
+ --amber: #f59e0b;
+ --red: #ef4444;
+}
+
+body {
+ font-family: 'Courier New', Courier, monospace;
+ font-size: 12px;
+ background: var(--bg0);
+ color: var(--base);
+ height: 100dvh;
+ display: flex;
+ flex-direction: column;
+ overflow: hidden;
+}
+
+/* ── Header ── */
+#header {
+ display: flex;
+ align-items: center;
+ padding: 5px 12px;
+ background: var(--bg1);
+ border-bottom: 1px solid var(--bd);
+ flex-shrink: 0;
+ gap: 8px;
+ flex-wrap: wrap;
+}
+.logo { color: #f97316; font-weight: bold; letter-spacing: .15em; font-size: 13px; flex-shrink: 0; }
+
+#conn-dot {
+ width: 8px; height: 8px; border-radius: 50%;
+ background: var(--dim); flex-shrink: 0; transition: background .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:.3} }
+@keyframes fadeout { 0%{opacity:1} 70%{opacity:1} 100%{opacity:0} }
+
+.save-ind {
+ font-size: 10px; font-weight: bold; letter-spacing: .1em;
+ color: var(--green); padding: 2px 8px;
+ border: 1px solid var(--green); border-radius: 3px;
+ animation: fadeout 2s forwards;
+}
+.save-ind.hidden { display: none; }
+
+#ws-input {
+ background: var(--bg2); border: 1px solid var(--bd2); border-radius: 4px;
+ color: #67e8f9; padding: 2px 7px; font-family: monospace; font-size: 11px; width: 185px;
+}
+#ws-input:focus { outline: none; border-color: var(--cyan); }
+
+.hbtn {
+ padding: 2px 8px; border-radius: 4px; border: 1px solid var(--bd2);
+ background: var(--bg2); color: #67e8f9; font-family: monospace;
+ font-size: 10px; font-weight: bold; cursor: pointer; transition: background .15s;
+ white-space: nowrap;
+}
+.hbtn:hover { background: #0e4f69; }
+.apply-btn { border-color: #14532d; color: #86efac; }
+.apply-btn:hover { background: #052010; }
+.del-btn { border-color: #7f1d1d; color: #fca5a5; }
+.del-btn:hover { background: #1c0505; }
+
+/* ── Tab bar ── */
+#tab-bar {
+ display: flex;
+ background: var(--bg1);
+ border-bottom: 1px solid var(--bd);
+ flex-shrink: 0;
+ padding: 0 12px;
+ gap: 2px;
+}
+.tab-btn {
+ padding: 6px 14px;
+ background: none;
+ border: none;
+ border-bottom: 2px solid transparent;
+ color: var(--mid);
+ font-family: 'Courier New', monospace;
+ font-size: 11px;
+ font-weight: bold;
+ letter-spacing: .1em;
+ cursor: pointer;
+ transition: color .15s, border-color .15s;
+}
+.tab-btn:hover { color: var(--base); }
+.tab-btn.active { color: var(--cyan); border-bottom-color: var(--cyan); }
+
+/* ── Main ── */
+#main {
+ flex: 1;
+ overflow-y: auto;
+ padding: 12px;
+ min-height: 0;
+}
+
+/* ── Tab panels ── */
+.tab-panel { display: none; }
+.tab-panel.active { display: block; }
+
+.panel-col {
+ display: flex;
+ flex-direction: column;
+ gap: 12px;
+ max-width: 860px;
+ margin: 0 auto;
+}
+
+/* ── Section card ── */
+.section-card {
+ background: var(--bg2);
+ border: 1px solid var(--bd2);
+ border-radius: 8px;
+ padding: 12px;
+}
+.sec-header {
+ display: flex;
+ justify-content: space-between;
+ align-items: flex-start;
+ margin-bottom: 10px;
+ gap: 8px;
+ flex-wrap: wrap;
+}
+.sec-title {
+ font-size: 11px; font-weight: bold; letter-spacing: .1em;
+ color: #67e8f9; text-transform: uppercase;
+}
+.sec-node {
+ font-size: 9px; color: var(--mid); margin-top: 2px;
+}
+.sec-actions { display: flex; gap: 6px; flex-shrink: 0; }
+
+/* ── Parameter fields ── */
+.param-row {
+ display: grid;
+ grid-template-columns: 180px 1fr 80px 50px;
+ align-items: center;
+ gap: 8px;
+ padding: 5px 0;
+ border-bottom: 1px solid var(--bd);
+}
+.param-row:last-child { border-bottom: none; }
+.param-label { font-size: 10px; color: var(--mid); }
+.param-unit { font-size: 9px; color: var(--dim); text-align: right; }
+
+/* Slider */
+.param-slider {
+ -webkit-appearance: none;
+ width: 100%; height: 4px; border-radius: 2px;
+ background: var(--bd2); outline: none; cursor: pointer;
+}
+.param-slider::-webkit-slider-thumb {
+ -webkit-appearance: none;
+ width: 12px; height: 12px; border-radius: 50%;
+ background: var(--cyan); cursor: pointer;
+}
+.param-slider::-moz-range-thumb {
+ width: 12px; height: 12px; border-radius: 50%;
+ background: var(--cyan); cursor: pointer; border: none;
+}
+.param-slider.changed::-webkit-slider-thumb { background: var(--amber); }
+.param-slider.changed::-moz-range-thumb { background: var(--amber); }
+
+/* Number input */
+.param-input {
+ background: var(--bg0); border: 1px solid var(--bd2);
+ border-radius: 3px; color: var(--hi); padding: 2px 5px;
+ font-family: monospace; font-size: 10px; text-align: right;
+ width: 72px;
+}
+.param-input:focus { outline: none; border-color: var(--cyan); }
+.param-input.changed { border-color: var(--amber); color: var(--amber); }
+
+/* Toggle switch */
+.toggle-row {
+ display: grid;
+ grid-template-columns: 180px 1fr auto;
+ align-items: center;
+ gap: 8px;
+ padding: 6px 0;
+ border-bottom: 1px solid var(--bd);
+}
+.toggle-row:last-child { border-bottom: none; }
+.toggle-desc { font-size: 9px; color: var(--dim); }
+
+.toggle-switch {
+ position: relative;
+ width: 36px; height: 18px; flex-shrink: 0;
+}
+.toggle-switch input { opacity: 0; width: 0; height: 0; }
+.toggle-track {
+ position: absolute; inset: 0;
+ background: var(--dim); border-radius: 9px; cursor: pointer;
+ transition: background .2s;
+}
+.toggle-track::after {
+ content: '';
+ position: absolute;
+ left: 2px; top: 2px;
+ width: 14px; height: 14px;
+ border-radius: 50%;
+ background: #fff;
+ transition: transform .2s;
+}
+.toggle-switch input:checked + .toggle-track { background: var(--cyan); }
+.toggle-switch input:checked + .toggle-track::after { transform: translateX(18px); }
+
+/* Status / feedback line */
+.sec-status {
+ margin-top: 6px;
+ font-size: 9px;
+ min-height: 14px;
+ transition: color .3s;
+}
+.sec-status.ok { color: var(--green); }
+.sec-status.err { color: var(--red); }
+.sec-status.loading { color: var(--amber); }
+
+/* ── System tab ── */
+.diag-placeholder {
+ color: var(--dim); font-size: 10px; padding: 12px 0; text-align: center;
+}
+#diag-grid {
+ display: grid;
+ grid-template-columns: repeat(auto-fill, minmax(180px, 1fr));
+ gap: 8px;
+}
+.diag-card {
+ background: var(--bg0);
+ border: 1px solid var(--bd);
+ border-radius: 5px;
+ padding: 8px;
+}
+.diag-card-title {
+ font-size: 9px; font-weight: bold; letter-spacing: .08em;
+ color: #0891b2; margin-bottom: 5px; text-transform: uppercase;
+}
+.diag-kv {
+ display: flex; justify-content: space-between;
+ padding: 2px 0; font-size: 9px;
+ border-bottom: 1px solid var(--bd);
+}
+.diag-kv:last-child { border-bottom: none; }
+.diag-k { color: var(--mid); }
+.diag-v { color: var(--hi); font-family: monospace; }
+.diag-v.ok { color: var(--green); }
+.diag-v.warn { color: var(--amber); }
+.diag-v.err { color: var(--red); }
+
+#net-grid {
+ display: grid;
+ grid-template-columns: repeat(auto-fill, minmax(180px, 1fr));
+ gap: 8px;
+}
+
+/* Signal bars */
+.sig-bars {
+ display: inline-flex; align-items: flex-end; gap: 2px; height: 14px;
+}
+.sig-bar {
+ width: 4px; border-radius: 1px; background: var(--dim);
+}
+.sig-bar.lit { background: var(--cyan); }
+
+/* Node list */
+#node-list-wrap {
+ display: flex; flex-wrap: wrap; gap: 4px;
+ max-height: 160px; overflow-y: auto;
+}
+.node-chip {
+ font-size: 9px; padding: 1px 6px; border-radius: 2px;
+ border: 1px solid var(--bd); background: var(--bg0);
+ color: var(--mid);
+}
+.node-chip.active-node { border-color: var(--bd2); color: var(--base); }
+
+/* ── Preset bar ── */
+#preset-bar {
+ display: flex;
+ align-items: center;
+ gap: 8px;
+ padding: 5px 12px;
+ background: var(--bg1);
+ border-top: 1px solid var(--bd);
+ flex-shrink: 0;
+ flex-wrap: wrap;
+}
+.plbl { font-size: 10px; color: var(--mid); letter-spacing: .08em; }
+
+#preset-select {
+ background: var(--bg2); border: 1px solid var(--bd2); border-radius: 4px;
+ color: #67e8f9; padding: 2px 6px; font-family: monospace; font-size: 10px;
+ cursor: pointer;
+}
+#preset-select:focus { outline: none; }
+
+#preset-name {
+ background: var(--bg2); border: 1px solid var(--bd2); border-radius: 4px;
+ color: var(--hi); padding: 2px 7px; font-family: monospace; font-size: 11px; width: 140px;
+}
+#preset-name:focus { outline: none; border-color: var(--cyan); }
+
+/* ── Footer ── */
+#footer {
+ background: var(--bg1); border-top: 1px solid var(--bd);
+ padding: 3px 12px;
+ display: flex; align-items: center; justify-content: space-between;
+ flex-shrink: 0; font-size: 10px; color: var(--dim);
+}
+
+/* ── Responsive ── */
+@media (max-width: 640px) {
+ .param-row {
+ grid-template-columns: 140px 1fr 70px 44px;
+ gap: 5px;
+ }
+ #diag-grid { grid-template-columns: 1fr 1fr; }
+}
+@media (max-width: 420px) {
+ .param-row {
+ grid-template-columns: 1fr 1fr;
+ grid-template-rows: auto auto;
+ }
+ .param-label { grid-column: 1 / 3; }
+ .param-unit { text-align: left; }
+}
diff --git a/ui/settings_panel.html b/ui/settings_panel.html
new file mode 100644
index 0000000..740c9a8
--- /dev/null
+++ b/ui/settings_panel.html
@@ -0,0 +1,313 @@
+
+
+
+
+
+Saltybot — Settings
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
Connect to rosbridge to view diagnostics.
+
+
+
+
+
+
+
+
Waiting for network data…
+
+
+
+
+
+
+
+
Click refresh to list active nodes.
+
+
+
+
+
+
+
+
+
+
+
PRESETS:
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/ui/settings_panel.js b/ui/settings_panel.js
new file mode 100644
index 0000000..ce40887
--- /dev/null
+++ b/ui/settings_panel.js
@@ -0,0 +1,716 @@
+/* settings_panel.js — Saltybot Settings Panel (Issue #614) */
+'use strict';
+
+// ── ROS2 parameter type constants ──────────────────────────────────────────
+const P_BOOL = 1;
+const P_INT = 2;
+const P_DOUBLE = 3;
+
+// ── Section / parameter definitions ───────────────────────────────────────
+// Each section: { id, node, params: [{name, label, type, min, max, step, unit, def}] }
+const SECTIONS = {
+
+ balance_pid: {
+ node: 'balance_controller',
+ params: [
+ { name: 'pid_p', label: 'Proportional (Kp)', type: P_DOUBLE, min: 0, max: 5, step: 0.01, unit: '', def: 0.5 },
+ { name: 'pid_i', label: 'Integral (Ki)', type: P_DOUBLE, min: 0, max: 2, step: 0.005, unit: '', def: 0.1 },
+ { name: 'pid_d', label: 'Derivative (Kd)', type: P_DOUBLE, min: 0, max: 1, step: 0.005, unit: '', def: 0.05 },
+ { name: 'i_clamp',label:'I clamp', type: P_DOUBLE, min: 0, max: 50, step: 0.5, unit: '', def: 10.0 },
+ { name: 'frequency',label:'Control rate', type: P_INT, min: 10, max: 200, step: 10, unit: 'Hz', def: 50 },
+ ],
+ },
+
+ adaptive_pid_empty: {
+ node: 'adaptive_pid',
+ params: [
+ { name: 'kp_empty', label: 'Kp (empty load)', type: P_DOUBLE, min: 0, max: 50, step: 0.5, unit: '', def: 15.0 },
+ { name: 'ki_empty', label: 'Ki (empty load)', type: P_DOUBLE, min: 0, max: 5, step: 0.05, unit: '', def: 0.5 },
+ { name: 'kd_empty', label: 'Kd (empty load)', type: P_DOUBLE, min: 0, max: 10, step: 0.1, unit: '', def: 1.5 },
+ { name: 'kp_light', label: 'Kp (light load)', type: P_DOUBLE, min: 0, max: 50, step: 0.5, unit: '', def: 18.0 },
+ { name: 'ki_light', label: 'Ki (light load)', type: P_DOUBLE, min: 0, max: 5, step: 0.05, unit: '', def: 0.6 },
+ { name: 'kd_light', label: 'Kd (light load)', type: P_DOUBLE, min: 0, max: 10, step: 0.1, unit: '', def: 2.0 },
+ { name: 'kp_heavy', label: 'Kp (heavy load)', type: P_DOUBLE, min: 0, max: 50, step: 0.5, unit: '', def: 22.0 },
+ { name: 'ki_heavy', label: 'Ki (heavy load)', type: P_DOUBLE, min: 0, max: 5, step: 0.05, unit: '', def: 0.8 },
+ { name: 'kd_heavy', label: 'Kd (heavy load)', type: P_DOUBLE, min: 0, max: 10, step: 0.1, unit: '', def: 2.5 },
+ ],
+ },
+
+ adaptive_pid_bounds: {
+ node: 'adaptive_pid',
+ params: [
+ { name: 'kp_min', label: 'Kp min', type: P_DOUBLE, min: 0, max: 20, step: 0.5, unit: '', def: 5.0 },
+ { name: 'kp_max', label: 'Kp max', type: P_DOUBLE, min: 0, max: 80, step: 1, unit: '', def: 40.0 },
+ { name: 'ki_min', label: 'Ki min', type: P_DOUBLE, min: 0, max: 5, step: 0.05, unit: '', def: 0.0 },
+ { name: 'ki_max', label: 'Ki max', type: P_DOUBLE, min: 0, max: 10, step: 0.1, unit: '', def: 5.0 },
+ { name: 'kd_min', label: 'Kd min', type: P_DOUBLE, min: 0, max: 5, step: 0.05, unit: '', def: 0.0 },
+ { name: 'kd_max', label: 'Kd max', type: P_DOUBLE, min: 0, max: 20, step: 0.2, unit: '', def: 10.0 },
+ { name: 'output_min', label: 'Output min', type: P_DOUBLE, min: -100, max: 0, step: 1, unit: '', def: -50.0},
+ { name: 'output_max', label: 'Output max', type: P_DOUBLE, min: 0, max: 100, step: 1, unit: '', def: 50.0 },
+ ],
+ },
+
+ tank_limits: {
+ node: 'tank_driver',
+ params: [
+ { name: 'max_linear_vel', label: 'Max linear vel', type: P_DOUBLE, min: 0.1, max: 3.0, step: 0.05, unit: 'm/s', def: 1.0 },
+ { name: 'max_angular_vel', label: 'Max angular vel', type: P_DOUBLE, min: 0.1, max: 5.0, step: 0.1, unit: 'rad/s', def: 2.5 },
+ { name: 'max_speed_ms', label: 'Max drive speed', type: P_DOUBLE, min: 0.1, max: 5.0, step: 0.1, unit: 'm/s', def: 1.5 },
+ { name: 'slip_factor', label: 'Track slip factor',type: P_DOUBLE,min: 0, max: 0.5, step: 0.01, unit: '', def: 0.3 },
+ { name: 'watchdog_timeout_s',label:'Watchdog timeout',type:P_DOUBLE, min: 0.1, max: 2.0, step: 0.05, unit: 's', def: 0.3 },
+ ],
+ },
+
+ smooth_vel: {
+ node: 'smooth_velocity_controller',
+ params: [
+ { name: 'max_linear_accel', label: 'Max linear accel', type: P_DOUBLE, min: 0.1, max: 5.0, step: 0.05, unit: 'm/s²', def: 0.5 },
+ { name: 'max_linear_decel', label: 'Max linear decel', type: P_DOUBLE, min: 0.1, max: 5.0, step: 0.05, unit: 'm/s²', def: 0.8 },
+ { name: 'max_angular_accel', label: 'Max angular accel', type: P_DOUBLE, min: 0.1, max: 5.0, step: 0.1, unit: 'rad/s²', def: 1.0 },
+ { name: 'max_angular_decel', label: 'Max angular decel', type: P_DOUBLE, min: 0.1, max: 5.0, step: 0.1, unit: 'rad/s²', def: 1.0 },
+ ],
+ },
+
+ batt_speed: {
+ node: 'battery_speed_limiter',
+ params: [
+ { name: 'speed_factor_full', label: 'Speed factor (full)', type: P_DOUBLE, min: 0, max: 1, step: 0.05, unit: '', def: 1.0 },
+ { name: 'speed_factor_reduced', label: 'Speed factor (reduced)', type: P_DOUBLE, min: 0, max: 1, step: 0.05, unit: '', def: 0.7 },
+ { name: 'speed_factor_critical', label: 'Speed factor (critical)', type: P_DOUBLE, min: 0, max: 1, step: 0.05, unit: '', def: 0.4 },
+ ],
+ },
+
+ safety_zone: {
+ node: 'safety_zone',
+ params: [
+ { name: 'danger_range_m', label: 'Danger range', type: P_DOUBLE, min: 0.05, max: 1.0, step: 0.01, unit: 'm', def: 0.30 },
+ { name: 'warn_range_m', label: 'Warn range', type: P_DOUBLE, min: 0.2, max: 5.0, step: 0.05, unit: 'm', def: 1.00 },
+ { name: 'forward_arc_deg', label: 'Forward arc (±)', type: P_DOUBLE, min: 10, max: 180, step: 5, unit: '°', def: 60.0 },
+ { name: 'estop_debounce_frames',label: 'E-stop debounce', type: P_INT, min: 1, max: 20, step: 1, unit: 'frames', def: 2 },
+ { name: 'min_valid_range_m', label: 'Min valid range', type: P_DOUBLE, min: 0.01, max: 0.5, step: 0.01, unit: 'm', def: 0.05 },
+ { name: 'publish_rate', label: 'Publish rate', type: P_DOUBLE, min: 1, max: 50, step: 1, unit: 'Hz', def: 10.0 },
+ ],
+ },
+
+ power_sup: {
+ node: 'power_supervisor_node',
+ params: [
+ { name: 'warning_pct', label: 'Warning threshold', type: P_DOUBLE, min: 5, max: 60, step: 1, unit: '%', def: 30.0 },
+ { name: 'dock_search_pct', label: 'Dock-search threshold',type: P_DOUBLE, min: 5, max: 50, step: 1, unit: '%', def: 20.0 },
+ { name: 'critical_pct', label: 'Critical threshold', type: P_DOUBLE, min: 2, max: 30, step: 1, unit: '%', def: 10.0 },
+ { name: 'emergency_pct', label: 'Emergency threshold', type: P_DOUBLE, min: 1, max: 15, step: 1, unit: '%', def: 5.0 },
+ { name: 'warn_speed_factor', label: 'Speed factor (warn)',type: P_DOUBLE, min: 0, max: 1, step: 0.05, unit: '', def: 0.6 },
+ { name: 'critical_speed_factor',label:'Speed factor (crit)',type: P_DOUBLE, min: 0, max: 1, step: 0.05, unit: '', def: 0.3 },
+ ],
+ },
+
+ lidar_avoid: {
+ node: 'lidar_avoidance',
+ params: [
+ { name: 'emergency_stop_distance', label: 'E-stop distance', type: P_DOUBLE, min: 0.1, max: 3.0, step: 0.05, unit: 'm', def: 0.5 },
+ { name: 'min_safety_zone', label: 'Min safety zone', type: P_DOUBLE, min: 0.1, max: 2.0, step: 0.05, unit: 'm', def: 0.6 },
+ { name: 'safety_zone_at_max_speed',label: 'Zone at max speed', type: P_DOUBLE, min: 0.5, max: 10, step: 0.1, unit: 'm', def: 3.0 },
+ { name: 'max_speed_reference', label: 'Max speed reference',type: P_DOUBLE, min: 0.5, max: 20, step: 0.1, unit: 'm/s', def: 5.56 },
+ ],
+ },
+
+ sensor_toggles: {
+ node: 'safety_zone', // placeholder — booleans often live on their own node
+ params: [
+ { name: 'estop_all_arcs', label: 'E-stop all arcs', type: P_BOOL, unit: '', def: false, desc: 'Any sector triggers e-stop' },
+ { name: 'lidar_enabled', label: 'LIDAR enabled', type: P_BOOL, unit: '', def: true, desc: '/scan input active' },
+ { name: 'uwb_enabled', label: 'UWB positioning', type: P_BOOL, unit: '', def: true, desc: 'UWB anchors active' },
+ ],
+ },
+
+ imu_fusion: {
+ node: 'uwb_imu_fusion',
+ params: [
+ { name: 'uwb_weight', label: 'UWB weight', type: P_DOUBLE, min: 0, max: 1, step: 0.05, unit: '', def: 0.7 },
+ { name: 'imu_weight', label: 'IMU weight', type: P_DOUBLE, min: 0, max: 1, step: 0.05, unit: '', def: 0.3 },
+ { name: 'publish_rate', label: 'Publish rate', type: P_DOUBLE, min: 1, max: 200, step: 1, unit: 'Hz', def: 50.0 },
+ ],
+ },
+
+};
+
+// ── Runtime state: current values per section ──────────────────────────────
+const values = {}; // values[sectionId][paramName] = currentValue
+const dirty = {}; // dirty[sectionId][paramName] = true if changed vs loaded
+
+// Initialise values from defaults
+Object.keys(SECTIONS).forEach(sid => {
+ values[sid] = {};
+ dirty[sid] = {};
+ SECTIONS[sid].params.forEach(p => {
+ values[sid][p.name] = p.def;
+ dirty[sid][p.name] = false;
+ });
+});
+
+// ── ROS ────────────────────────────────────────────────────────────────────
+let ros = null;
+
+function getService(nodeName, type) {
+ return new ROSLIB.Service({ ros, name: `/${nodeName}/${type}`, serviceType: `rcl_interfaces/srv/${type === 'get_parameters' ? 'GetParameters' : 'SetParameters'}` });
+}
+
+function extractValue(rosVal) {
+ switch (rosVal.type) {
+ case P_BOOL: return rosVal.bool_value;
+ case P_INT: return rosVal.integer_value;
+ case P_DOUBLE: return rosVal.double_value;
+ default: return undefined;
+ }
+}
+
+function makeRosValue(type, value) {
+ const v = { type };
+ if (type === P_BOOL) v.bool_value = !!value;
+ if (type === P_INT) v.integer_value = Math.round(value);
+ if (type === P_DOUBLE) v.double_value = parseFloat(value);
+ return v;
+}
+
+// ── Section load / apply ───────────────────────────────────────────────────
+window.loadSection = function(sid) {
+ if (!ros) { setStatus(sid, 'err', 'Not connected'); return; }
+ const sec = SECTIONS[sid];
+ const svc = getService(sec.node, 'get_parameters');
+ const names = sec.params.map(p => p.name);
+
+ setStatus(sid, 'loading', `Loading from /${sec.node}…`);
+
+ svc.callService({ names }, (resp) => {
+ if (!resp || !resp.values) {
+ setStatus(sid, 'err', 'No response'); return;
+ }
+ sec.params.forEach((p, i) => {
+ const v = extractValue(resp.values[i]);
+ if (v !== undefined) {
+ values[sid][p.name] = v;
+ dirty[sid][p.name] = false;
+ updateFieldUI(sid, p.name, v, false);
+ }
+ });
+ setStatus(sid, 'ok', `Loaded ${resp.values.length} params`);
+ }, (err) => {
+ setStatus(sid, 'err', `Error: ${err}`);
+ });
+};
+
+window.applySection = function(sid) {
+ if (!ros) { setStatus(sid, 'err', 'Not connected'); return; }
+ const sec = SECTIONS[sid];
+ const svc = getService(sec.node, 'set_parameters');
+
+ const parameters = sec.params.map(p => ({
+ name: p.name,
+ value: makeRosValue(p.type, values[sid][p.name]),
+ }));
+
+ setStatus(sid, 'loading', `Applying to /${sec.node}…`);
+
+ svc.callService({ parameters }, (resp) => {
+ if (!resp || !resp.results) {
+ setStatus(sid, 'err', 'No response'); return;
+ }
+ const failures = resp.results.filter(r => !r.successful);
+ if (failures.length === 0) {
+ sec.params.forEach(p => { dirty[sid][p.name] = false; });
+ refreshFieldDirty(sid);
+ setStatus(sid, 'ok', `Applied ${parameters.length} params ✓`);
+ } else {
+ const reasons = failures.map(r => r.reason).join('; ');
+ setStatus(sid, 'err', `${failures.length} failed: ${reasons}`);
+ }
+ }, (err) => {
+ setStatus(sid, 'err', `Error: ${err}`);
+ });
+};
+
+// ── UI builder ─────────────────────────────────────────────────────────────
+function buildFields() {
+ Object.keys(SECTIONS).forEach(sid => {
+ const sec = SECTIONS[sid];
+ const container = document.getElementById(`${sid}-fields`);
+ if (!container) return;
+
+ sec.params.forEach(p => {
+ if (p.type === P_BOOL) {
+ // Toggle row
+ const row = document.createElement('div');
+ row.className = 'toggle-row';
+ row.innerHTML = `
+ ${p.label}
+ ${p.desc || ''}
+ `;
+ container.appendChild(row);
+
+ const cb = row.querySelector(`#tgl-${sid}-${p.name}`);
+ cb.addEventListener('change', () => {
+ values[sid][p.name] = cb.checked;
+ dirty[sid][p.name] = true;
+ });
+ } else {
+ // Slider + number input row
+ const row = document.createElement('div');
+ row.className = 'param-row';
+ const sliderMin = p.min !== undefined ? p.min : 0;
+ const sliderMax = p.max !== undefined ? p.max : 100;
+ const sliderStep = p.step || 0.01;
+ const defVal = p.def !== undefined ? p.def : 0;
+
+ row.innerHTML = `
+ ${p.label}
+
+
+ ${p.unit || ''}`;
+ container.appendChild(row);
+
+ const slider = row.querySelector(`#sld-${sid}-${p.name}`);
+ const input = row.querySelector(`#inp-${sid}-${p.name}`);
+
+ slider.addEventListener('input', () => {
+ const v = parseFloat(slider.value);
+ input.value = v;
+ values[sid][p.name] = v;
+ dirty[sid][p.name] = true;
+ input.classList.add('changed');
+ slider.classList.add('changed');
+ });
+
+ input.addEventListener('change', () => {
+ let v = parseFloat(input.value);
+ v = Math.max(sliderMin, Math.min(sliderMax, v));
+ input.value = v;
+ slider.value = v;
+ values[sid][p.name] = v;
+ dirty[sid][p.name] = true;
+ input.classList.add('changed');
+ slider.classList.add('changed');
+ });
+ }
+ });
+ });
+}
+
+function updateFieldUI(sid, paramName, value, markDirty) {
+ const sec = SECTIONS[sid];
+ const p = sec.params.find(x => x.name === paramName);
+ if (!p) return;
+
+ if (p.type === P_BOOL) {
+ const cb = document.getElementById(`tgl-${sid}-${paramName}`);
+ if (cb) cb.checked = !!value;
+ } else {
+ const sld = document.getElementById(`sld-${sid}-${paramName}`);
+ const inp = document.getElementById(`inp-${sid}-${paramName}`);
+ if (sld) sld.value = value;
+ if (inp) inp.value = value;
+ if (!markDirty) {
+ if (sld) sld.classList.remove('changed');
+ if (inp) inp.classList.remove('changed');
+ }
+ }
+}
+
+function refreshFieldDirty(sid) {
+ const sec = SECTIONS[sid];
+ sec.params.forEach(p => {
+ if (p.type !== P_BOOL) {
+ const sld = document.getElementById(`sld-${sid}-${p.name}`);
+ const inp = document.getElementById(`inp-${sid}-${p.name}`);
+ if (!dirty[sid][p.name]) {
+ if (sld) sld.classList.remove('changed');
+ if (inp) inp.classList.remove('changed');
+ }
+ }
+ });
+}
+
+function setStatus(sid, cls, msg) {
+ const el = document.getElementById(`${sid}-status`);
+ if (!el) return;
+ el.className = `sec-status ${cls}`;
+ el.textContent = msg;
+ if (cls === 'ok') setTimeout(() => { el.textContent = ''; el.className = 'sec-status'; }, 4000);
+}
+
+// ── Tabs ───────────────────────────────────────────────────────────────────
+document.querySelectorAll('.tab-btn').forEach(btn => {
+ btn.addEventListener('click', () => {
+ document.querySelectorAll('.tab-btn').forEach(b => b.classList.remove('active'));
+ document.querySelectorAll('.tab-panel').forEach(p => p.classList.remove('active'));
+ btn.classList.add('active');
+ document.getElementById(`tab-${btn.dataset.tab}`).classList.add('active');
+ if (btn.dataset.tab === 'system') startDiagRefresh();
+ });
+});
+
+// ── Presets ────────────────────────────────────────────────────────────────
+const PRESET_KEY = 'saltybot_settings_presets';
+
+function getPresets() {
+ try { return JSON.parse(localStorage.getItem(PRESET_KEY) || '{}'); } catch(_) { return {}; }
+}
+
+function savePresetsToStorage(presets) {
+ localStorage.setItem(PRESET_KEY, JSON.stringify(presets));
+}
+
+function refreshPresetSelect() {
+ const sel = document.getElementById('preset-select');
+ const cur = sel.value;
+ sel.innerHTML = '';
+ const presets = getPresets();
+ Object.keys(presets).sort().forEach(name => {
+ const opt = document.createElement('option');
+ opt.value = name;
+ opt.textContent = name;
+ sel.appendChild(opt);
+ });
+ if (cur) sel.value = cur;
+}
+
+function snapshotAllValues() {
+ const snap = {};
+ Object.keys(values).forEach(sid => {
+ snap[sid] = Object.assign({}, values[sid]);
+ });
+ return snap;
+}
+
+window.savePreset = function() {
+ const nameInput = document.getElementById('preset-name');
+ const name = nameInput.value.trim();
+ if (!name) { alert('Enter a preset name'); return; }
+ const presets = getPresets();
+ presets[name] = snapshotAllValues();
+ savePresetsToStorage(presets);
+ nameInput.value = '';
+ refreshPresetSelect();
+ document.getElementById('preset-select').value = name;
+ flashSaved();
+};
+
+window.loadPreset = function() {
+ const name = document.getElementById('preset-select').value;
+ if (!name) return;
+ const presets = getPresets();
+ const snap = presets[name];
+ if (!snap) return;
+ Object.keys(snap).forEach(sid => {
+ if (!values[sid]) return;
+ Object.keys(snap[sid]).forEach(paramName => {
+ values[sid][paramName] = snap[sid][paramName];
+ dirty[sid][paramName] = true;
+ updateFieldUI(sid, paramName, snap[sid][paramName], true);
+ });
+ });
+ flashSaved();
+};
+
+window.deletePreset = function() {
+ const name = document.getElementById('preset-select').value;
+ if (!name) return;
+ if (!confirm(`Delete preset "${name}"?`)) return;
+ const presets = getPresets();
+ delete presets[name];
+ savePresetsToStorage(presets);
+ refreshPresetSelect();
+};
+
+window.resetAllToDefaults = function() {
+ if (!confirm('Reset all fields to built-in defaults?')) return;
+ Object.keys(SECTIONS).forEach(sid => {
+ SECTIONS[sid].params.forEach(p => {
+ values[sid][p.name] = p.def;
+ dirty[sid][p.name] = false;
+ updateFieldUI(sid, p.name, p.def, false);
+ });
+ });
+};
+
+function flashSaved() {
+ const el = document.getElementById('save-indicator');
+ el.classList.remove('hidden');
+ el.style.animation = 'none';
+ void el.offsetHeight;
+ el.style.animation = 'fadeout 2s forwards';
+ setTimeout(() => el.classList.add('hidden'), 2100);
+}
+
+// ── System tab: diagnostics ────────────────────────────────────────────────
+let diagTopic = null;
+let diagRefreshTimer = null;
+let diagState = {
+ cpuTemp: null, gpuTemp: null, boardTemp: null,
+ motorTempL: null, motorTempR: null,
+ ramUsed: null, ramTotal: null,
+ gpuUsed: null, gpuTotal: null,
+ diskUsed: null, diskTotal: null,
+ rssi: null, latency: null, mqttConnected: null,
+ nodes: [],
+ lastUpdate: null,
+};
+
+function startDiagRefresh() {
+ if (!ros || diagTopic) return;
+ diagTopic = new ROSLIB.Topic({
+ ros, name: '/diagnostics', messageType: 'diagnostic_msgs/DiagnosticArray',
+ throttle_rate: 2000,
+ });
+ diagTopic.subscribe(onDiagnostics);
+}
+
+function stopDiagRefresh() {
+ if (diagTopic) { diagTopic.unsubscribe(); diagTopic = null; }
+}
+
+function onDiagnostics(msg) {
+ const kv = {};
+ (msg.status || []).forEach(status => {
+ (status.values || []).forEach(pair => {
+ kv[pair.key] = pair.value;
+ });
+ diagState.nodes.push({ name: status.name, level: status.level, msg: status.message });
+ if (diagState.nodes.length > 40) diagState.nodes.splice(0, diagState.nodes.length - 40);
+ });
+
+ // Extract known keys
+ if (kv.cpu_temp_c) diagState.cpuTemp = parseFloat(kv.cpu_temp_c);
+ if (kv.gpu_temp_c) diagState.gpuTemp = parseFloat(kv.gpu_temp_c);
+ if (kv.board_temp_c) diagState.boardTemp = parseFloat(kv.board_temp_c);
+ if (kv.motor_temp_l_c) diagState.motorTempL = parseFloat(kv.motor_temp_l_c);
+ if (kv.motor_temp_r_c) diagState.motorTempR = parseFloat(kv.motor_temp_r_c);
+ if (kv.ram_used_mb) diagState.ramUsed = parseFloat(kv.ram_used_mb);
+ if (kv.ram_total_mb) diagState.ramTotal = parseFloat(kv.ram_total_mb);
+ if (kv.gpu_used_mb) diagState.gpuUsed = parseFloat(kv.gpu_used_mb);
+ if (kv.gpu_total_mb) diagState.gpuTotal = parseFloat(kv.gpu_total_mb);
+ if (kv.disk_used_gb) diagState.diskUsed = parseFloat(kv.disk_used_gb);
+ if (kv.disk_total_gb) diagState.diskTotal = parseFloat(kv.disk_total_gb);
+ if (kv.wifi_rssi_dbm) diagState.rssi = parseFloat(kv.wifi_rssi_dbm);
+ if (kv.wifi_latency_ms) diagState.latency = parseFloat(kv.wifi_latency_ms);
+ if (kv.mqtt_connected !== undefined) diagState.mqttConnected = kv.mqtt_connected === 'true';
+
+ diagState.lastUpdate = new Date();
+ renderDiag();
+ renderNet();
+}
+
+window.refreshDiag = function() {
+ startDiagRefresh();
+ renderDiag();
+};
+
+function tempColor(t) {
+ if (t === null) return '';
+ if (t > 80) return 'err';
+ if (t > 65) return 'warn';
+ return 'ok';
+}
+
+function pct(used, total) {
+ if (!total) return '—';
+ return ((used / total) * 100).toFixed(0) + '%';
+}
+
+function renderDiag() {
+ const g = document.getElementById('diag-grid');
+ if (!g) return;
+ const d = diagState;
+ if (d.lastUpdate === null) {
+ g.innerHTML = 'Waiting for /diagnostics…
';
+ return;
+ }
+
+ const cards = [
+ {
+ title: 'Temperature',
+ rows: [
+ { k: 'CPU', v: d.cpuTemp !== null ? d.cpuTemp.toFixed(1) + ' °C' : '—', cls: tempColor(d.cpuTemp) },
+ { k: 'GPU', v: d.gpuTemp !== null ? d.gpuTemp.toFixed(1) + ' °C' : '—', cls: tempColor(d.gpuTemp) },
+ { k: 'Board',v:d.boardTemp !== null ? d.boardTemp.toFixed(1)+' °C':'—', cls:tempColor(d.boardTemp)},
+ { k: 'Motor L', v: d.motorTempL !== null ? d.motorTempL.toFixed(1)+' °C':'—', cls:tempColor(d.motorTempL)},
+ { k: 'Motor R', v: d.motorTempR !== null ? d.motorTempR.toFixed(1)+' °C':'—', cls:tempColor(d.motorTempR)},
+ ],
+ },
+ {
+ title: 'Memory',
+ rows: [
+ { k: 'RAM used', v: d.ramUsed !== null ? d.ramUsed.toFixed(0)+' MB': '—', cls:'' },
+ { k: 'RAM total', v: d.ramTotal !== null ? d.ramTotal.toFixed(0)+' MB': '—', cls:'' },
+ { k: 'RAM %', v: pct(d.ramUsed, d.ramTotal), cls: d.ramUsed/d.ramTotal > 0.85 ? 'warn' : 'ok' },
+ { k: 'GPU mem', v: d.gpuUsed !== null ? d.gpuUsed.toFixed(0)+' MB': '—', cls:'' },
+ { k: 'GPU %', v: pct(d.gpuUsed, d.gpuTotal), cls:'' },
+ ],
+ },
+ {
+ title: 'Storage',
+ rows: [
+ { k: 'Disk used', v: d.diskUsed !== null ? d.diskUsed.toFixed(1)+' GB': '—', cls:'' },
+ { k: 'Disk total', v: d.diskTotal !== null ? d.diskTotal.toFixed(1)+' GB': '—', cls:'' },
+ { k: 'Disk %', v: pct(d.diskUsed, d.diskTotal), cls: d.diskUsed/d.diskTotal > 0.9 ? 'err' : d.diskUsed/d.diskTotal > 0.75 ? 'warn' : 'ok' },
+ ],
+ },
+ {
+ title: 'Updated',
+ rows: [
+ { k: 'Last msg', v: d.lastUpdate ? d.lastUpdate.toLocaleTimeString() : '—', cls:'' },
+ ],
+ },
+ ];
+
+ g.innerHTML = cards.map(c => `
+
+
${c.title}
+ ${c.rows.map(r => `
${r.k}${r.v}
`).join('')}
+
`).join('');
+}
+
+function rssiColor(rssi) {
+ if (rssi === null) return '';
+ if (rssi > -50) return 'ok';
+ if (rssi > -70) return 'warn';
+ return 'err';
+}
+
+function rssiBarCount(rssi) {
+ if (rssi === null) return 0;
+ if (rssi > -50) return 5;
+ if (rssi > -60) return 4;
+ if (rssi > -70) return 3;
+ if (rssi > -80) return 2;
+ return 1;
+}
+
+function latencyColor(ms) {
+ if (ms === null) return '';
+ if (ms < 50) return 'ok';
+ if (ms < 150) return 'warn';
+ return 'err';
+}
+
+function renderNet() {
+ const g = document.getElementById('net-grid');
+ if (!g) return;
+ const d = diagState;
+ const bars = rssiBarCount(d.rssi);
+ const heights = [4, 6, 9, 12, 15];
+
+ const barsHtml = heights.map((h, i) =>
+ ``
+ ).join('');
+
+ g.innerHTML = `
+
+
WiFi
+
+ RSSI
+
+
+
+
+ Latency
+ ${d.latency !== null ? d.latency.toFixed(0) + ' ms' : '—'}
+
+
+
+
Services
+
+ MQTT
+
+ ${d.mqttConnected === null ? '—' : d.mqttConnected ? 'Connected' : 'Disconnected'}
+
+
+
+ rosbridge
+ ${ros ? 'Connected' : 'Disconnected'}
+
+
`;
+}
+
+// ── Node list ──────────────────────────────────────────────────────────────
+window.loadNodeList = function() {
+ if (!ros) return;
+ const svc = new ROSLIB.Service({
+ ros, name: '/rosapi/nodes', serviceType: 'rosapi/Nodes',
+ });
+ svc.callService({}, (resp) => {
+ const wrap = document.getElementById('node-list-wrap');
+ if (!resp || !resp.nodes) { wrap.innerHTML = 'No response
'; return; }
+ const sorted = [...resp.nodes].sort();
+ wrap.innerHTML = sorted.map(n =>
+ `${n}`
+ ).join('');
+ }, () => {
+ document.getElementById('node-list-wrap').innerHTML =
+ 'Service unavailable — ensure rosapi is running
';
+ });
+};
+
+// ── Connection ─────────────────────────────────────────────────────────────
+const $connDot = document.getElementById('conn-dot');
+const $connLabel = document.getElementById('conn-label');
+
+function connect() {
+ const url = document.getElementById('ws-input').value.trim() || 'ws://localhost:9090';
+ if (ros) { stopDiagRefresh(); try { ros.close(); } catch(_){} }
+
+ $connLabel.textContent = 'Connecting…';
+ $connLabel.style.color = '#d97706';
+ $connDot.className = '';
+
+ ros = new ROSLIB.Ros({ url });
+
+ ros.on('connection', () => {
+ $connDot.className = 'connected';
+ $connLabel.style.color = '#22c55e';
+ $connLabel.textContent = 'Connected';
+ localStorage.setItem('settings_ws_url', url);
+ // Auto-start diagnostics if system tab visible
+ const sysPanel = document.getElementById('tab-system');
+ if (sysPanel && sysPanel.classList.contains('active')) startDiagRefresh();
+ });
+
+ ros.on('error', () => {
+ $connDot.className = 'error';
+ $connLabel.style.color = '#ef4444';
+ $connLabel.textContent = 'Error';
+ });
+
+ ros.on('close', () => {
+ $connDot.className = '';
+ $connLabel.style.color = '#6b7280';
+ $connLabel.textContent = 'Disconnected';
+ stopDiagRefresh();
+ ros = null;
+ });
+}
+
+document.getElementById('btn-connect').addEventListener('click', connect);
+
+// ── Init ───────────────────────────────────────────────────────────────────
+buildFields();
+refreshPresetSelect();
+
+const savedUrl = localStorage.getItem('settings_ws_url');
+if (savedUrl) {
+ document.getElementById('ws-input').value = savedUrl;
+ document.getElementById('footer-ws').textContent = savedUrl;
+ connect();
+}