Compare commits
1 Commits
c3ada4a156
...
4827d3cd55
| Author | SHA1 | Date | |
|---|---|---|---|
| 4827d3cd55 |
@ -68,10 +68,8 @@ void mpu6000_calibrate(void) {
|
||||
sum_gy += raw.gy;
|
||||
sum_gz += raw.gz;
|
||||
HAL_Delay(1);
|
||||
/* Refresh IWDG every 40ms, starting immediately (i=0) — the gap between
|
||||
* safety_refresh() at the top of the main loop and entry here can be
|
||||
* ~10ms, so we must refresh on i=0 to avoid the 50ms IWDG window. */
|
||||
if (i % 40 == 0) safety_refresh();
|
||||
/* Refresh IWDG every 40ms — safe during re-cal with watchdog running */
|
||||
if (i % 40 == 39) safety_refresh();
|
||||
}
|
||||
|
||||
s_bias_gx = (float)sum_gx / GYRO_CAL_SAMPLES;
|
||||
|
||||
@ -38,9 +38,6 @@ import { FleetPanel } from './components/FleetPanel.jsx';
|
||||
// Mission planner (issue #145)
|
||||
import { MissionPlanner } from './components/MissionPlanner.jsx';
|
||||
|
||||
// Settings panel (issue #160)
|
||||
import { SettingsPanel } from './components/SettingsPanel.jsx';
|
||||
|
||||
const TAB_GROUPS = [
|
||||
{
|
||||
label: 'SOCIAL',
|
||||
@ -73,17 +70,8 @@ const TAB_GROUPS = [
|
||||
{ id: 'missions', label: 'Missions' },
|
||||
],
|
||||
},
|
||||
{
|
||||
label: 'CONFIG',
|
||||
color: 'text-purple-600',
|
||||
tabs: [
|
||||
{ id: 'settings', label: 'Settings' },
|
||||
],
|
||||
},
|
||||
];
|
||||
|
||||
const FLEET_TABS = new Set(['fleet', 'missions']);
|
||||
|
||||
const DEFAULT_WS_URL = 'ws://localhost:9090';
|
||||
|
||||
function ConnectionBar({ url, setUrl, connected, error }) {
|
||||
@ -154,7 +142,7 @@ export default function App() {
|
||||
<span className="text-orange-500 font-bold tracking-widest text-sm">⚡ SALTYBOT</span>
|
||||
<span className="text-cyan-800 text-xs hidden sm:inline">DASHBOARD</span>
|
||||
</div>
|
||||
{!FLEET_TABS.has(activeTab) && (
|
||||
{activeTab !== 'fleet' && (
|
||||
<ConnectionBar url={wsUrl} setUrl={setWsUrl} connected={connected} error={error} />
|
||||
)}
|
||||
</header>
|
||||
@ -209,13 +197,11 @@ export default function App() {
|
||||
|
||||
{activeTab === 'fleet' && <FleetPanel />}
|
||||
{activeTab === 'missions' && <MissionPlanner />}
|
||||
|
||||
{activeTab === 'settings' && <SettingsPanel subscribe={subscribe} callService={callService} connected={connected} wsUrl={wsUrl} />}
|
||||
</main>
|
||||
|
||||
{/* ── Footer ── */}
|
||||
<footer className="bg-[#070712] border-t border-cyan-950 px-4 py-1.5 flex items-center justify-between text-xs text-gray-700 shrink-0">
|
||||
{!FLEET_TABS.has(activeTab) ? (
|
||||
{activeTab !== 'fleet' ? (
|
||||
<>
|
||||
<span>rosbridge: <code className="text-gray-600">{wsUrl}</code></span>
|
||||
<span className={connected ? 'text-green-700' : 'text-red-900'}>
|
||||
|
||||
@ -1,452 +0,0 @@
|
||||
/**
|
||||
* SettingsPanel.jsx — System configuration dashboard.
|
||||
*
|
||||
* Sub-views: PID | Sensors | Network | Firmware | Diagnostics | Backup
|
||||
*
|
||||
* Props:
|
||||
* subscribe, callService — from useRosbridge
|
||||
* connected — rosbridge connection status
|
||||
* wsUrl — current rosbridge WebSocket URL
|
||||
*/
|
||||
|
||||
import { useState, useEffect, useRef, useCallback } from 'react';
|
||||
import {
|
||||
useSettings, PID_PARAMS, SENSOR_PARAMS, PID_NODE,
|
||||
simulateStepResponse, validatePID,
|
||||
} from '../hooks/useSettings.js';
|
||||
|
||||
const VIEWS = ['PID', 'Sensors', 'Network', 'Firmware', 'Diagnostics', 'Backup'];
|
||||
|
||||
function ValidationBadges({ warnings }) {
|
||||
if (!warnings?.length) return (
|
||||
<div className="flex items-center gap-1.5 text-xs text-green-400">
|
||||
<span className="w-1.5 h-1.5 rounded-full bg-green-400 inline-block"/>
|
||||
All gains within safe bounds
|
||||
</div>
|
||||
);
|
||||
return (
|
||||
<div className="space-y-1">
|
||||
{warnings.map((w, i) => (
|
||||
<div key={i} className={`flex items-start gap-2 text-xs rounded px-2 py-1 border ${
|
||||
w.level === 'error'
|
||||
? 'bg-red-950 border-red-800 text-red-400'
|
||||
: 'bg-amber-950 border-amber-800 text-amber-300'
|
||||
}`}>
|
||||
<span className="shrink-0">{w.level === 'error' ? '✕' : '⚠'}</span>
|
||||
{w.msg}
|
||||
</div>
|
||||
))}
|
||||
</div>
|
||||
);
|
||||
}
|
||||
|
||||
function ApplyResult({ result }) {
|
||||
if (!result) return null;
|
||||
return (
|
||||
<div className={`text-xs rounded px-2 py-1 border ${
|
||||
result.ok
|
||||
? 'bg-green-950 border-green-800 text-green-400'
|
||||
: 'bg-red-950 border-red-800 text-red-400'
|
||||
}`}>{result.ok ? '✓ ' : '✕ '}{result.msg}</div>
|
||||
);
|
||||
}
|
||||
|
||||
function StepResponseCanvas({ kp, ki, kd }) {
|
||||
const canvasRef = useRef(null);
|
||||
|
||||
useEffect(() => {
|
||||
const canvas = canvasRef.current;
|
||||
if (!canvas) return;
|
||||
const ctx = canvas.getContext('2d');
|
||||
const W = canvas.width, H = canvas.height;
|
||||
const PAD = { top: 12, right: 16, bottom: 24, left: 40 };
|
||||
const CW = W - PAD.left - PAD.right;
|
||||
const CH = H - PAD.top - PAD.bottom;
|
||||
|
||||
ctx.clearRect(0, 0, W, H);
|
||||
ctx.fillStyle = '#050510';
|
||||
ctx.fillRect(0, 0, W, H);
|
||||
|
||||
const data = simulateStepResponse(kp, ki, kd);
|
||||
if (!data.length) return;
|
||||
|
||||
const tail = data.slice(-20);
|
||||
const maxTail = Math.max(...tail.map(d => Math.abs(d.theta)));
|
||||
const finalMax = Math.max(...data.map(d => Math.abs(d.theta)));
|
||||
const isUnstable = finalMax > 45;
|
||||
const isOscillating = !isUnstable && maxTail > 1.0;
|
||||
const lineColor = isUnstable ? '#ef4444' : isOscillating ? '#f59e0b' : '#22c55e';
|
||||
|
||||
const yMax = Math.min(90, Math.max(10, finalMax * 1.2));
|
||||
const yMin = -Math.min(5, yMax * 0.1);
|
||||
const tx = (t) => PAD.left + (t / 2.4) * CW;
|
||||
const ty = (v) => PAD.top + CH - ((v - yMin) / (yMax - yMin)) * CH;
|
||||
|
||||
ctx.strokeStyle = '#0d1b2a'; ctx.lineWidth = 1;
|
||||
for (let v = -10; v <= 90; v += 5) {
|
||||
if (v < yMin || v > yMax) continue;
|
||||
ctx.beginPath(); ctx.moveTo(PAD.left, ty(v)); ctx.lineTo(PAD.left + CW, ty(v)); ctx.stroke();
|
||||
}
|
||||
for (let t = 0; t <= 2.4; t += 0.4) {
|
||||
ctx.beginPath(); ctx.moveTo(tx(t), PAD.top); ctx.lineTo(tx(t), PAD.top + CH); ctx.stroke();
|
||||
}
|
||||
|
||||
ctx.strokeStyle = lineColor; ctx.lineWidth = 2;
|
||||
ctx.shadowBlur = isUnstable ? 0 : 4; ctx.shadowColor = lineColor;
|
||||
ctx.beginPath();
|
||||
data.forEach((d, i) => {
|
||||
const x = tx(d.t), y = ty(Math.max(yMin, Math.min(yMax, d.theta)));
|
||||
i === 0 ? ctx.moveTo(x, y) : ctx.lineTo(x, y);
|
||||
});
|
||||
ctx.stroke(); ctx.shadowBlur = 0;
|
||||
|
||||
ctx.fillStyle = '#4b5563'; ctx.font = '8px monospace'; ctx.textAlign = 'right';
|
||||
[0, 5, 10, 20, 45, 90].filter(v => v >= yMin && v <= yMax).forEach(v => {
|
||||
ctx.fillText(`${v}°`, PAD.left - 3, ty(v) + 3);
|
||||
});
|
||||
ctx.textAlign = 'center';
|
||||
[0, 0.5, 1.0, 1.5, 2.0, 2.4].forEach(t => {
|
||||
ctx.fillText(`${t.toFixed(1)}`, tx(t), PAD.top + CH + 14);
|
||||
});
|
||||
|
||||
const label = isUnstable ? 'UNSTABLE' : isOscillating ? 'OSCILLATING' : 'STABLE';
|
||||
ctx.fillStyle = lineColor; ctx.font = 'bold 9px monospace'; ctx.textAlign = 'right';
|
||||
ctx.fillText(label, PAD.left + CW, PAD.top + 10);
|
||||
}, [kp, ki, kd]);
|
||||
|
||||
return (
|
||||
<canvas ref={canvasRef} width={380} height={140}
|
||||
className="w-full block rounded bg-gray-950 border border-gray-800" />
|
||||
);
|
||||
}
|
||||
|
||||
function GainSlider({ param, value, onChange }) {
|
||||
const pct = ((value - param.min) / (param.max - param.min)) * 100;
|
||||
return (
|
||||
<div className="space-y-0.5">
|
||||
<div className="flex items-center justify-between text-xs">
|
||||
<span className="text-gray-500">{param.label}</span>
|
||||
<input type="number"
|
||||
className="w-16 text-right bg-gray-900 border border-gray-700 rounded px-1 py-0.5 text-xs text-cyan-200 focus:outline-none focus:border-cyan-700"
|
||||
value={typeof value === 'boolean' ? value : Number(value).toFixed(param.step < 0.1 ? 3 : param.step < 1 ? 2 : 1)}
|
||||
step={param.step} min={param.min} max={param.max}
|
||||
onChange={e => onChange(param.key, param.type === 'bool' ? e.target.checked : parseFloat(e.target.value))}
|
||||
/>
|
||||
</div>
|
||||
{param.type !== 'bool' && (
|
||||
<div className="relative h-1.5 bg-gray-800 rounded overflow-hidden">
|
||||
<div className="absolute h-full rounded" style={{ width: `${pct}%`, background: '#06b6d4' }} />
|
||||
<input type="range" className="absolute inset-0 w-full opacity-0 cursor-pointer h-full"
|
||||
min={param.min} max={param.max} step={param.step} value={value}
|
||||
onChange={e => onChange(param.key, parseFloat(e.target.value))} />
|
||||
</div>
|
||||
)}
|
||||
</div>
|
||||
);
|
||||
}
|
||||
|
||||
function PIDView({ gains, setGains, applyPIDGains, applying, applyResult, connected }) {
|
||||
const [activeClass, setActiveClass] = useState('empty');
|
||||
const warnings = validatePID(gains);
|
||||
const classKeys = {
|
||||
empty: ['kp_empty','ki_empty','kd_empty'],
|
||||
light: ['kp_light','ki_light','kd_light'],
|
||||
heavy: ['kp_heavy','ki_heavy','kd_heavy'],
|
||||
};
|
||||
const overrideKeys = ['override_enabled','override_kp','override_ki','override_kd'];
|
||||
const clampKeys = ['kp_min','kp_max','ki_min','ki_max','kd_min','kd_max'];
|
||||
const miscKeys = ['control_rate','balance_setpoint_rad'];
|
||||
const handleChange = (key, val) => setGains(g => ({ ...g, [key]: val }));
|
||||
const previewKp = gains.override_enabled ? gains.override_kp : gains[`kp_${activeClass}`] ?? 15;
|
||||
const previewKi = gains.override_enabled ? gains.override_ki : gains[`ki_${activeClass}`] ?? 0.5;
|
||||
const previewKd = gains.override_enabled ? gains.override_kd : gains[`kd_${activeClass}`] ?? 1.5;
|
||||
const paramsByKey = Object.fromEntries(PID_PARAMS.map(p => [p.key, p]));
|
||||
|
||||
return (
|
||||
<div className="space-y-4">
|
||||
<div className="flex items-center gap-2 flex-wrap">
|
||||
<div className="text-cyan-700 text-xs font-bold tracking-widest">PID GAIN EDITOR</div>
|
||||
<span className={`text-xs px-1.5 py-0.5 rounded border ml-auto ${connected ? 'text-green-400 border-green-800' : 'text-gray-600 border-gray-700'}`}>
|
||||
{connected ? 'LIVE' : 'OFFLINE'}
|
||||
</span>
|
||||
</div>
|
||||
<div className="space-y-1">
|
||||
<div className="text-gray-600 text-xs">Simulated step response ({gains.override_enabled ? 'override' : activeClass} gains · 5° disturbance)</div>
|
||||
<StepResponseCanvas kp={previewKp} ki={previewKi} kd={previewKd} />
|
||||
</div>
|
||||
<div className="flex gap-0.5 border-b border-gray-800">
|
||||
{Object.keys(classKeys).map(c => (
|
||||
<button key={c} onClick={() => setActiveClass(c)}
|
||||
className={`px-3 py-1.5 text-xs font-bold tracking-wide border-b-2 transition-colors ${activeClass===c?'border-cyan-500 text-cyan-300':'border-transparent text-gray-600 hover:text-gray-300'}`}
|
||||
>{c.toUpperCase()}</button>
|
||||
))}
|
||||
{[['override','border-amber-500 text-amber-300'],['clamp','border-purple-500 text-purple-300'],['misc','border-gray-400 text-gray-200']].map(([id, activeStyle]) => (
|
||||
<button key={id} onClick={() => setActiveClass(id)}
|
||||
className={`px-3 py-1.5 text-xs font-bold tracking-wide border-b-2 transition-colors ${activeClass===id?activeStyle:'border-transparent text-gray-600 hover:text-gray-300'}`}
|
||||
>{id.toUpperCase()}</button>
|
||||
))}
|
||||
</div>
|
||||
<div className="grid grid-cols-1 sm:grid-cols-3 gap-3">
|
||||
{(activeClass==='override'?overrideKeys:activeClass==='clamp'?clampKeys:activeClass==='misc'?miscKeys:classKeys[activeClass]).map(key => {
|
||||
const p = paramsByKey[key]; if (!p) return null;
|
||||
return <GainSlider key={key} param={p} value={gains[key]??p.default} onChange={handleChange} />;
|
||||
})}
|
||||
</div>
|
||||
<ValidationBadges warnings={warnings} />
|
||||
<div className="flex gap-2 items-center flex-wrap">
|
||||
<button onClick={() => applyPIDGains()} disabled={applying||warnings.some(w=>w.level==='error')}
|
||||
className="px-4 py-1.5 rounded bg-cyan-950 border border-cyan-700 text-cyan-300 hover:bg-cyan-900 text-xs font-bold disabled:opacity-40">
|
||||
{applying?'Applying…':connected?'Apply to Robot':'Save Locally'}
|
||||
</button>
|
||||
{warnings.some(w=>w.level==='error')&&<span className="text-red-500 text-xs">Fix errors before applying</span>}
|
||||
<ApplyResult result={applyResult} />
|
||||
</div>
|
||||
</div>
|
||||
);
|
||||
}
|
||||
|
||||
function SensorsView({ sensors, setSensors, applySensorParams, applying, applyResult, connected }) {
|
||||
const handleChange = (key, val) => setSensors(s => ({ ...s, [key]: val }));
|
||||
const grouped = {};
|
||||
SENSOR_PARAMS.forEach(p => { if (!grouped[p.node]) grouped[p.node] = []; grouped[p.node].push(p); });
|
||||
|
||||
return (
|
||||
<div className="space-y-4">
|
||||
<div className="text-cyan-700 text-xs font-bold tracking-widest">SENSOR CONFIGURATION</div>
|
||||
{Object.entries(grouped).map(([node, params]) => (
|
||||
<div key={node} className="bg-gray-950 border border-gray-800 rounded-lg p-3 space-y-3">
|
||||
<div className="text-gray-500 text-xs font-bold font-mono">{node}</div>
|
||||
<div className="grid grid-cols-1 sm:grid-cols-2 gap-3">
|
||||
{params.map(p => p.type === 'bool' ? (
|
||||
<label key={p.key} className="flex items-center gap-2 text-xs cursor-pointer">
|
||||
<div onClick={() => handleChange(p.key, !sensors[p.key])}
|
||||
className={`w-8 h-4 rounded-full relative cursor-pointer transition-colors ${sensors[p.key]?'bg-cyan-700':'bg-gray-700'}`}>
|
||||
<span className={`absolute top-0.5 w-3 h-3 rounded-full bg-white transition-all ${sensors[p.key]?'left-4':'left-0.5'}`}/>
|
||||
</div>
|
||||
<span className="text-gray-400">{p.label}</span>
|
||||
</label>
|
||||
) : (
|
||||
<GainSlider key={p.key} param={p} value={sensors[p.key]??p.default} onChange={handleChange} />
|
||||
))}
|
||||
</div>
|
||||
</div>
|
||||
))}
|
||||
<div className="flex gap-2 items-center flex-wrap">
|
||||
<button onClick={() => applySensorParams()} disabled={applying}
|
||||
className="px-4 py-1.5 rounded bg-cyan-950 border border-cyan-700 text-cyan-300 hover:bg-cyan-900 text-xs font-bold disabled:opacity-40">
|
||||
{applying?'Applying…':connected?'Apply to Robot':'Save Locally'}
|
||||
</button>
|
||||
<ApplyResult result={applyResult} />
|
||||
</div>
|
||||
</div>
|
||||
);
|
||||
}
|
||||
|
||||
function NetworkView({ wsUrl, connected }) {
|
||||
const [ddsDomain, setDdsDomain] = useState(() => parseInt(localStorage.getItem('saltybot_dds_domain')||'0',10));
|
||||
const [saved, setSaved] = useState(false);
|
||||
const urlObj = (() => { try { return new URL(wsUrl); } catch { return null; } })();
|
||||
const saveDDS = () => { localStorage.setItem('saltybot_dds_domain', String(ddsDomain)); setSaved(true); setTimeout(()=>setSaved(false),2000); };
|
||||
|
||||
return (
|
||||
<div className="space-y-4">
|
||||
<div className="text-cyan-700 text-xs font-bold tracking-widest">NETWORK SETTINGS</div>
|
||||
<div className="bg-gray-950 border border-gray-800 rounded-lg p-3 space-y-2">
|
||||
<div className="text-gray-500 text-xs font-bold">ROSBRIDGE WEBSOCKET</div>
|
||||
<div className="grid grid-cols-2 gap-2 text-xs">
|
||||
{[['URL', wsUrl, 'text-cyan-300 font-mono truncate'], ['Host', urlObj?.hostname??'—', 'text-gray-300 font-mono'],
|
||||
['Port', urlObj?.port??'9090', 'text-gray-300 font-mono'],
|
||||
['Status', connected?'CONNECTED':'DISCONNECTED', connected?'text-green-400':'text-red-400']
|
||||
].map(([k, v, cls]) => (<><div key={k} className="text-gray-600">{k}</div><div className={cls}>{v}</div></>))}
|
||||
</div>
|
||||
</div>
|
||||
<div className="bg-gray-950 border border-gray-800 rounded-lg p-3 space-y-3">
|
||||
<div className="text-gray-500 text-xs font-bold">ROS2 DDS DOMAIN</div>
|
||||
<div className="flex items-center gap-3">
|
||||
<label className="text-gray-500 text-xs w-24">Domain ID</label>
|
||||
<input type="number" min="0" max="232"
|
||||
className="w-20 bg-gray-900 border border-gray-700 rounded px-2 py-1 text-xs text-gray-200 focus:outline-none focus:border-cyan-700"
|
||||
value={ddsDomain} onChange={e=>setDdsDomain(parseInt(e.target.value)||0)} />
|
||||
<button onClick={saveDDS} className="px-3 py-1 rounded bg-cyan-950 border border-cyan-700 text-cyan-300 hover:bg-cyan-900 text-xs">Save</button>
|
||||
{saved && <span className="text-green-400 text-xs">Saved</span>}
|
||||
</div>
|
||||
<div className="text-gray-700 text-xs">Set ROS_DOMAIN_ID on the robot to match. Range 0–232.</div>
|
||||
</div>
|
||||
<div className="bg-gray-950 border border-gray-800 rounded-lg p-3 space-y-1 text-xs text-gray-600">
|
||||
<div className="text-gray-500 font-bold text-xs">REFERENCE PORTS</div>
|
||||
<div>Web dashboard: <code className="text-gray-400">8080</code></div>
|
||||
<div>Rosbridge: <code className="text-gray-400">ws://<host>:9090</code></div>
|
||||
<div>RTSP: <code className="text-gray-400">rtsp://<host>:8554/panoramic</code></div>
|
||||
<div>MJPEG: <code className="text-gray-400">http://<host>:8080/stream?topic=/camera/panoramic/compressed</code></div>
|
||||
</div>
|
||||
</div>
|
||||
);
|
||||
}
|
||||
|
||||
function FirmwareView({ firmwareInfo, startFirmwareWatch, connected }) {
|
||||
useEffect(() => { if (!connected) return; const unsub = startFirmwareWatch(); return unsub; }, [connected, startFirmwareWatch]);
|
||||
const formatUptime = (s) => { if (!s) return '—'; return `${Math.floor(s/3600)}h ${Math.floor((s%3600)/60)}m`; };
|
||||
const rows = [
|
||||
['STM32 Firmware', firmwareInfo?.stm32Version ?? '—'],
|
||||
['Jetson SW', firmwareInfo?.jetsonVersion ?? '—'],
|
||||
['Last OTA Update',firmwareInfo?.lastOtaDate ?? '—'],
|
||||
['Hostname', firmwareInfo?.hostname ?? '—'],
|
||||
['ROS Distro', firmwareInfo?.rosDistro ?? '—'],
|
||||
['Uptime', formatUptime(firmwareInfo?.uptimeS)],
|
||||
];
|
||||
return (
|
||||
<div className="space-y-4">
|
||||
<div className="flex items-center gap-2">
|
||||
<div className="text-cyan-700 text-xs font-bold tracking-widest">FIRMWARE INFO</div>
|
||||
{!connected && <span className="text-gray-600 text-xs">(connect to robot to fetch live info)</span>}
|
||||
</div>
|
||||
<div className="bg-gray-950 border border-gray-800 rounded-lg overflow-hidden">
|
||||
{rows.map(([label, value], i) => (
|
||||
<div key={label} className={`flex items-center px-4 py-2.5 text-xs ${i%2===0?'bg-gray-950':'bg-[#070712]'}`}>
|
||||
<span className="text-gray-500 w-36 shrink-0">{label}</span>
|
||||
<span className={`font-mono ${value==='—'?'text-gray-700':'text-cyan-300'}`}>{value}</span>
|
||||
</div>
|
||||
))}
|
||||
</div>
|
||||
{!firmwareInfo && connected && (
|
||||
<div className="text-amber-700 text-xs border border-amber-900 rounded p-2">
|
||||
Waiting for /diagnostics… Ensure firmware diagnostics keys (stm32_fw_version etc.) are published.
|
||||
</div>
|
||||
)}
|
||||
</div>
|
||||
);
|
||||
}
|
||||
|
||||
function DiagnosticsView({ exportDiagnosticsBundle, subscribe, connected }) {
|
||||
const [diagData, setDiagData] = useState(null);
|
||||
const [balanceData, setBalanceData] = useState(null);
|
||||
const [exporting, setExporting] = useState(false);
|
||||
|
||||
useEffect(() => {
|
||||
if (!connected || !subscribe) return;
|
||||
const u1 = subscribe('/diagnostics', 'diagnostic_msgs/DiagnosticArray', msg => setDiagData(msg));
|
||||
const u2 = subscribe('/saltybot/balance_state', 'std_msgs/String', msg => {
|
||||
try { setBalanceData(JSON.parse(msg.data)); } catch {}
|
||||
});
|
||||
return () => { u1?.(); u2?.(); };
|
||||
}, [connected, subscribe]);
|
||||
|
||||
const errorCount = (diagData?.status??[]).filter(s=>s.level>=2).length;
|
||||
const warnCount = (diagData?.status??[]).filter(s=>s.level===1).length;
|
||||
|
||||
const handleExport = () => {
|
||||
setExporting(true);
|
||||
exportDiagnosticsBundle(balanceData?{'live':{balanceState:balanceData}}:{}, {});
|
||||
setTimeout(()=>setExporting(false), 1000);
|
||||
};
|
||||
|
||||
return (
|
||||
<div className="space-y-4">
|
||||
<div className="text-cyan-700 text-xs font-bold tracking-widest">DIAGNOSTICS EXPORT</div>
|
||||
<div className="grid grid-cols-3 gap-3">
|
||||
{[['ERRORS',errorCount,errorCount?'text-red-400':'text-gray-600'],['WARNINGS',warnCount,warnCount?'text-amber-400':'text-gray-600'],['NODES',diagData?.status?.length??0,'text-gray-400']].map(([l,c,cl])=>(
|
||||
<div key={l} className="bg-gray-950 border border-gray-800 rounded p-3 text-center">
|
||||
<div className={`text-2xl font-bold ${cl}`}>{c}</div>
|
||||
<div className="text-gray-600 text-xs mt-0.5">{l}</div>
|
||||
</div>
|
||||
))}
|
||||
</div>
|
||||
<div className="bg-gray-950 border border-gray-800 rounded-lg p-4 space-y-3">
|
||||
<div className="text-gray-400 text-sm font-bold">Download Diagnostics Bundle</div>
|
||||
<div className="text-gray-600 text-xs">Bundle: PID gains, sensor settings, firmware info, live /diagnostics, balance state, timestamp.</div>
|
||||
<button onClick={handleExport} disabled={exporting}
|
||||
className="px-4 py-2 rounded bg-cyan-950 border border-cyan-700 text-cyan-300 hover:bg-cyan-900 text-xs font-bold disabled:opacity-40">
|
||||
{exporting?'Preparing…':'Download JSON Bundle'}
|
||||
</button>
|
||||
<div className="text-gray-700 text-xs">
|
||||
For rosbag: <code className="text-gray-600">ros2 bag record -o saltybot_diag /diagnostics /saltybot/balance_state /odom</code>
|
||||
</div>
|
||||
</div>
|
||||
{diagData?.status?.length>0 && (
|
||||
<div className="space-y-1 max-h-64 overflow-y-auto">
|
||||
{[...diagData.status].sort((a,b)=>(b.level??0)-(a.level??0)).map((s,i)=>(
|
||||
<div key={i} className={`flex items-center gap-2 px-3 py-1.5 rounded border text-xs ${s.level>=2?'bg-red-950 border-red-800':s.level===1?'bg-amber-950 border-amber-800':'bg-gray-950 border-gray-800'}`}>
|
||||
<div className={`w-1.5 h-1.5 rounded-full shrink-0 ${s.level>=2?'bg-red-400':s.level===1?'bg-amber-400':'bg-green-400'}`}/>
|
||||
<span className="text-gray-300 font-bold truncate flex-1">{s.name}</span>
|
||||
<span className={s.level>=2?'text-red-400':s.level===1?'text-amber-400':'text-gray-600'}>{s.message||(s.level===0?'OK':`L${s.level}`)}</span>
|
||||
</div>
|
||||
))}
|
||||
</div>
|
||||
)}
|
||||
</div>
|
||||
);
|
||||
}
|
||||
|
||||
function BackupView({ exportSettingsJSON, importSettingsJSON }) {
|
||||
const [importText, setImportText] = useState('');
|
||||
const [showImport, setShowImport] = useState(false);
|
||||
const [msg, setMsg] = useState(null);
|
||||
const showMsg = (text, ok=true) => { setMsg({text,ok}); setTimeout(()=>setMsg(null),4000); };
|
||||
|
||||
const handleExport = () => {
|
||||
const a = document.createElement('a');
|
||||
a.href = URL.createObjectURL(new Blob([exportSettingsJSON()],{type:'application/json'}));
|
||||
a.download = `saltybot-settings-${new Date().toISOString().slice(0,10)}.json`;
|
||||
a.click(); showMsg('Settings exported');
|
||||
};
|
||||
const handleImport = () => {
|
||||
try { importSettingsJSON(importText); setImportText(''); setShowImport(false); showMsg('Settings imported'); }
|
||||
catch(e) { showMsg('Import failed: '+e.message, false); }
|
||||
};
|
||||
|
||||
return (
|
||||
<div className="space-y-4 max-w-lg">
|
||||
<div className="text-cyan-700 text-xs font-bold tracking-widest">BACKUP & RESTORE</div>
|
||||
<div className="bg-gray-950 border border-gray-800 rounded-lg p-4 space-y-3">
|
||||
<div className="text-gray-400 text-sm font-bold">Export Settings</div>
|
||||
<div className="text-gray-600 text-xs">Saves PID gains, sensor config and UI preferences to JSON.</div>
|
||||
<button onClick={handleExport} className="px-4 py-2 rounded bg-cyan-950 border border-cyan-700 text-cyan-300 hover:bg-cyan-900 text-xs font-bold">Export JSON</button>
|
||||
</div>
|
||||
<div className="bg-gray-950 border border-gray-800 rounded-lg p-4 space-y-3">
|
||||
<div className="text-gray-400 text-sm font-bold">Restore Settings</div>
|
||||
<div className="text-gray-600 text-xs">Load a previously exported settings JSON. Click Apply after import to push to the robot.</div>
|
||||
<button onClick={() => setShowImport(s=>!s)} className="px-4 py-2 rounded border border-gray-700 text-gray-400 hover:text-gray-200 text-xs">
|
||||
{showImport?'Cancel':'Import JSON…'}
|
||||
</button>
|
||||
{showImport && (
|
||||
<div className="space-y-2">
|
||||
<textarea rows={8} className="w-full bg-gray-900 border border-gray-700 rounded px-2 py-1.5 text-xs text-gray-200 focus:outline-none font-mono"
|
||||
placeholder="Paste exported settings JSON here…" value={importText} onChange={e=>setImportText(e.target.value)} />
|
||||
<button disabled={!importText.trim()} onClick={handleImport}
|
||||
className="px-3 py-1 rounded bg-cyan-950 border border-cyan-700 text-cyan-300 hover:bg-cyan-900 text-xs disabled:opacity-40">Restore</button>
|
||||
</div>
|
||||
)}
|
||||
</div>
|
||||
{msg && (
|
||||
<div className={`text-xs rounded px-2 py-1 border ${msg.ok?'bg-green-950 border-green-800 text-green-400':'bg-red-950 border-red-800 text-red-400'}`}>{msg.text}</div>
|
||||
)}
|
||||
<div className="bg-gray-950 border border-gray-800 rounded-lg p-3 text-xs text-gray-600">
|
||||
Settings stored in localStorage key <code className="text-gray-500">saltybot_settings_v1</code>. Export to persist across browsers.
|
||||
</div>
|
||||
</div>
|
||||
);
|
||||
}
|
||||
|
||||
export function SettingsPanel({ subscribe, callService, connected = false, wsUrl = '' }) {
|
||||
const [view, setView] = useState('PID');
|
||||
const settings = useSettings({ callService, subscribe });
|
||||
|
||||
return (
|
||||
<div className="space-y-4">
|
||||
<div className="flex gap-0.5 border-b border-gray-800 overflow-x-auto">
|
||||
{VIEWS.map(v => (
|
||||
<button key={v} onClick={() => setView(v)}
|
||||
className={`px-3 py-2 text-xs font-bold tracking-wider whitespace-nowrap border-b-2 transition-colors ${
|
||||
view===v ? 'border-cyan-500 text-cyan-300' : 'border-transparent text-gray-600 hover:text-gray-300'
|
||||
}`}>{v.toUpperCase()}</button>
|
||||
))}
|
||||
</div>
|
||||
{view==='PID' && <PIDView gains={settings.gains} setGains={settings.setGains} applyPIDGains={settings.applyPIDGains} applying={settings.applying} applyResult={settings.applyResult} connected={connected} />}
|
||||
{view==='Sensors' && <SensorsView sensors={settings.sensors} setSensors={settings.setSensors} applySensorParams={settings.applySensorParams} applying={settings.applying} applyResult={settings.applyResult} connected={connected} />}
|
||||
{view==='Network' && <NetworkView wsUrl={wsUrl} connected={connected} />}
|
||||
{view==='Firmware' && <FirmwareView firmwareInfo={settings.firmwareInfo} startFirmwareWatch={settings.startFirmwareWatch} connected={connected} />}
|
||||
{view==='Diagnostics' && <DiagnosticsView exportDiagnosticsBundle={settings.exportDiagnosticsBundle} subscribe={subscribe} connected={connected} />}
|
||||
{view==='Backup' && <BackupView exportSettingsJSON={settings.exportSettingsJSON} importSettingsJSON={settings.importSettingsJSON} />}
|
||||
</div>
|
||||
);
|
||||
}
|
||||
@ -1,273 +0,0 @@
|
||||
/**
|
||||
* useSettings.js — ROS2 parameter I/O + settings persistence + validation.
|
||||
*
|
||||
* Wraps rcl_interfaces/srv/GetParameters and SetParameters calls via
|
||||
* the rosbridge callService helper passed from useRosbridge.
|
||||
*
|
||||
* Known nodes and their parameters:
|
||||
* adaptive_pid_node — PID gains (empty/light/heavy), clamp bounds, overrides
|
||||
* rtsp_server_node — video fps, bitrate, resolution, RTSP port
|
||||
* uwb_driver_node — baudrate, range limits, Kalman filter noise
|
||||
*
|
||||
* Validation rules:
|
||||
* kp_min 5–40, ki_min 0–5, kd_min 0–10
|
||||
* override gains must be within [min, max]
|
||||
* control_rate: 50–200 Hz
|
||||
* balance_setpoint_rad: ±0.1 rad
|
||||
*
|
||||
* PID step-response simulator (pure JS, no ROS):
|
||||
* Inverted pendulum: θ''(t) = g/L · θ(t) − 1/m·L² · u(t)
|
||||
* Parameters: L≈0.40 m, m≈3 kg, g=9.81
|
||||
* Simulate 120 steps at dt=0.02 s (2.4 s total) with 5° step input.
|
||||
*/
|
||||
|
||||
import { useState, useCallback } from 'react';
|
||||
|
||||
const STORAGE_KEY = 'saltybot_settings_v1';
|
||||
|
||||
// ── Parameter catalogue ────────────────────────────────────────────────────────
|
||||
|
||||
export const PID_NODE = 'adaptive_pid_node';
|
||||
|
||||
export const PID_PARAMS = [
|
||||
{ key: 'kp_empty', default: 15.0, min: 0, max: 60, step: 0.5, label: 'Kp empty' },
|
||||
{ key: 'ki_empty', default: 0.5, min: 0, max: 10, step: 0.05, label: 'Ki empty' },
|
||||
{ key: 'kd_empty', default: 1.5, min: 0, max: 20, step: 0.1, label: 'Kd empty' },
|
||||
{ key: 'kp_light', default: 18.0, min: 0, max: 60, step: 0.5, label: 'Kp light' },
|
||||
{ key: 'ki_light', default: 0.6, min: 0, max: 10, step: 0.05, label: 'Ki light' },
|
||||
{ key: 'kd_light', default: 2.0, min: 0, max: 20, step: 0.1, label: 'Kd light' },
|
||||
{ key: 'kp_heavy', default: 22.0, min: 0, max: 60, step: 0.5, label: 'Kp heavy' },
|
||||
{ key: 'ki_heavy', default: 0.8, min: 0, max: 10, step: 0.05, label: 'Ki heavy' },
|
||||
{ key: 'kd_heavy', default: 2.5, min: 0, max: 20, step: 0.1, label: 'Kd heavy' },
|
||||
{ key: 'kp_min', default: 5.0, min: 0, max: 60, step: 0.5, label: 'Kp min (clamp)' },
|
||||
{ key: 'kp_max', default: 40.0, min: 0, max: 80, step: 0.5, label: 'Kp max (clamp)' },
|
||||
{ key: 'ki_min', default: 0.0, min: 0, max: 10, step: 0.05, label: 'Ki min (clamp)' },
|
||||
{ key: 'ki_max', default: 5.0, min: 0, max: 20, step: 0.05, label: 'Ki max (clamp)' },
|
||||
{ key: 'kd_min', default: 0.0, min: 0, max: 20, step: 0.1, label: 'Kd min (clamp)' },
|
||||
{ key: 'kd_max', default: 10.0, min: 0, max: 40, step: 0.1, label: 'Kd max (clamp)' },
|
||||
{ key: 'override_enabled', default: false, type: 'bool', label: 'Override gains' },
|
||||
{ key: 'override_kp', default: 15.0, min: 0, max: 60, step: 0.5, label: 'Override Kp' },
|
||||
{ key: 'override_ki', default: 0.5, min: 0, max: 10, step: 0.05, label: 'Override Ki' },
|
||||
{ key: 'override_kd', default: 1.5, min: 0, max: 20, step: 0.1, label: 'Override Kd' },
|
||||
{ key: 'control_rate', default: 100.0, min: 50, max: 200, step: 5, label: 'Control rate (Hz)' },
|
||||
{ key: 'balance_setpoint_rad', default: 0.0, min: -0.1, max: 0.1, step: 0.001, label: 'Balance setpoint (rad)' },
|
||||
];
|
||||
|
||||
export const SENSOR_PARAMS = [
|
||||
{ node: 'rtsp_server_node', key: 'fps', default: 15, min: 5, max: 60, step: 1, label: 'Camera FPS' },
|
||||
{ node: 'rtsp_server_node', key: 'bitrate_kbps',default: 4000, min: 500,max: 20000,step: 500, label: 'Camera bitrate (kbps)' },
|
||||
{ node: 'rtsp_server_node', key: 'rtsp_port', default: 8554, min: 1024,max: 65535,step: 1, label: 'RTSP port' },
|
||||
{ node: 'rtsp_server_node', key: 'use_nvenc', default: true, type: 'bool', label: 'NVENC hardware encode' },
|
||||
{ node: 'uwb_driver_node', key: 'max_range_m', default: 8.0, min: 1, max: 20, step: 0.5, label: 'UWB max range (m)' },
|
||||
{ node: 'uwb_driver_node', key: 'kf_process_noise', default: 0.1, min: 0.001, max: 1.0, step: 0.001, label: 'UWB Kalman noise' },
|
||||
];
|
||||
|
||||
// ── Validation ─────────────────────────────────────────────────────────────────
|
||||
|
||||
export function validatePID(gains) {
|
||||
const warnings = [];
|
||||
const { kp_empty, ki_empty, kd_empty, kp_max, ki_max, kd_max,
|
||||
override_enabled, override_kp, override_ki, override_kd,
|
||||
control_rate, balance_setpoint_rad } = gains;
|
||||
|
||||
if (kp_empty > 35)
|
||||
warnings.push({ level: 'warn', msg: `Kp empty (${kp_empty}) is high — risk of oscillation.` });
|
||||
if (ki_empty > 3)
|
||||
warnings.push({ level: 'warn', msg: `Ki empty (${ki_empty}) is high — risk of integral windup.` });
|
||||
if (kp_empty > kp_max)
|
||||
warnings.push({ level: 'error', msg: `Kp empty (${kp_empty}) exceeds kp_max (${kp_max}).` });
|
||||
if (ki_empty > ki_max)
|
||||
warnings.push({ level: 'error', msg: `Ki empty (${ki_empty}) exceeds ki_max (${ki_max}).` });
|
||||
if (kp_empty > 0 && kd_empty / kp_empty < 0.05)
|
||||
warnings.push({ level: 'warn', msg: `Low Kd/Kp ratio — under-damped response likely.` });
|
||||
if (override_enabled) {
|
||||
if (override_kp > kp_max)
|
||||
warnings.push({ level: 'error', msg: `Override Kp (${override_kp}) exceeds kp_max (${kp_max}).` });
|
||||
if (override_ki > ki_max)
|
||||
warnings.push({ level: 'error', msg: `Override Ki (${override_ki}) exceeds ki_max (${ki_max}).` });
|
||||
if (override_kd > kd_max)
|
||||
warnings.push({ level: 'error', msg: `Override Kd (${override_kd}) exceeds kd_max (${kd_max}).` });
|
||||
}
|
||||
if (control_rate > 150)
|
||||
warnings.push({ level: 'warn', msg: `Control rate ${control_rate} Hz — ensure STM32 UART can keep up.` });
|
||||
if (Math.abs(balance_setpoint_rad) > 0.05)
|
||||
warnings.push({ level: 'warn', msg: `Setpoint |${balance_setpoint_rad?.toFixed(3)}| rad > 3° — intentional lean?` });
|
||||
return warnings;
|
||||
}
|
||||
|
||||
// ── Step-response simulation ───────────────────────────────────────────────────
|
||||
|
||||
export function simulateStepResponse(kp, ki, kd) {
|
||||
const dt = 0.02;
|
||||
const N = 120;
|
||||
const g = 9.81;
|
||||
const L = 0.40;
|
||||
const m = 3.0;
|
||||
const step = 5 * Math.PI / 180;
|
||||
|
||||
let theta = step;
|
||||
let omega = 0;
|
||||
let integral = 0;
|
||||
let prevErr = theta;
|
||||
const result = [];
|
||||
|
||||
for (let i = 0; i < N; i++) {
|
||||
const t = i * dt;
|
||||
const err = -theta;
|
||||
integral += err * dt;
|
||||
integral = Math.max(-2, Math.min(2, integral));
|
||||
const deriv = (err - prevErr) / dt;
|
||||
prevErr = err;
|
||||
|
||||
const u = kp * err + ki * integral + kd * deriv;
|
||||
const alpha = (g / L) * theta - u / (m * L * L);
|
||||
omega += alpha * dt;
|
||||
theta += omega * dt;
|
||||
|
||||
result.push({ t, theta: theta * 180 / Math.PI, u: Math.min(100, Math.max(-100, u)) });
|
||||
|
||||
if (Math.abs(theta) > Math.PI / 2) {
|
||||
for (let j = i + 1; j < N; j++)
|
||||
result.push({ t: j * dt, theta: theta > 0 ? 90 : -90, u: 0 });
|
||||
break;
|
||||
}
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
// ── Hook ──────────────────────────────────────────────────────────────────────
|
||||
|
||||
export function useSettings({ callService, subscribe } = {}) {
|
||||
const [gains, setGains] = useState(() => {
|
||||
try {
|
||||
const s = JSON.parse(localStorage.getItem(STORAGE_KEY));
|
||||
return s?.gains ?? Object.fromEntries(PID_PARAMS.map(p => [p.key, p.default]));
|
||||
} catch { return Object.fromEntries(PID_PARAMS.map(p => [p.key, p.default])); }
|
||||
});
|
||||
const [sensors, setSensors] = useState(() => {
|
||||
try {
|
||||
const s = JSON.parse(localStorage.getItem(STORAGE_KEY));
|
||||
return s?.sensors ?? Object.fromEntries(SENSOR_PARAMS.map(p => [p.key, p.default]));
|
||||
} catch { return Object.fromEntries(SENSOR_PARAMS.map(p => [p.key, p.default])); }
|
||||
});
|
||||
const [firmwareInfo, setFirmwareInfo] = useState(null);
|
||||
const [applying, setApplying] = useState(false);
|
||||
const [applyResult, setApplyResult] = useState(null);
|
||||
|
||||
const persist = useCallback((newGains, newSensors) => {
|
||||
localStorage.setItem(STORAGE_KEY, JSON.stringify({
|
||||
gains: newGains ?? gains,
|
||||
sensors: newSensors ?? sensors,
|
||||
savedAt: Date.now(),
|
||||
}));
|
||||
}, [gains, sensors]);
|
||||
|
||||
const buildSetRequest = useCallback((params) => ({
|
||||
parameters: params.map(({ name, value }) => {
|
||||
let type = 3; let v = { double_value: value };
|
||||
if (typeof value === 'boolean') { type = 1; v = { bool_value: value }; }
|
||||
else if (Number.isInteger(value)) { type = 2; v = { integer_value: value }; }
|
||||
return { name, value: { type, ...v } };
|
||||
}),
|
||||
}), []);
|
||||
|
||||
const applyPIDGains = useCallback(async (overrideGains) => {
|
||||
const toApply = overrideGains ?? gains;
|
||||
setApplying(true); setApplyResult(null);
|
||||
const params = PID_PARAMS.map(p => ({ name: p.key, value: toApply[p.key] ?? p.default }));
|
||||
if (!callService) {
|
||||
setGains(toApply); persist(toApply, null); setApplying(false);
|
||||
setApplyResult({ ok: true, msg: 'Saved locally (not connected)' }); return;
|
||||
}
|
||||
try {
|
||||
await new Promise((resolve, reject) => {
|
||||
callService(`/${PID_NODE}/set_parameters`, 'rcl_interfaces/srv/SetParameters',
|
||||
buildSetRequest(params), (res) => {
|
||||
res.results?.every(r => r.successful) ? resolve() :
|
||||
reject(new Error(res.results?.find(r => !r.successful)?.reason ?? 'failed'));
|
||||
});
|
||||
setTimeout(() => reject(new Error('timeout')), 5000);
|
||||
});
|
||||
setGains(toApply); persist(toApply, null);
|
||||
setApplyResult({ ok: true, msg: 'Parameters applied to adaptive_pid_node' });
|
||||
} catch (e) {
|
||||
setApplyResult({ ok: false, msg: String(e.message) });
|
||||
}
|
||||
setApplying(false);
|
||||
}, [gains, callService, buildSetRequest, persist]);
|
||||
|
||||
const applySensorParams = useCallback(async (overrideParams) => {
|
||||
const toApply = overrideParams ?? sensors;
|
||||
setApplying(true); setApplyResult(null);
|
||||
if (!callService) {
|
||||
setSensors(toApply); persist(null, toApply); setApplying(false);
|
||||
setApplyResult({ ok: true, msg: 'Saved locally (not connected)' }); return;
|
||||
}
|
||||
const byNode = {};
|
||||
SENSOR_PARAMS.forEach(p => {
|
||||
if (!byNode[p.node]) byNode[p.node] = [];
|
||||
byNode[p.node].push({ name: p.key, value: toApply[p.key] ?? p.default });
|
||||
});
|
||||
try {
|
||||
for (const [node, params] of Object.entries(byNode)) {
|
||||
await new Promise((resolve, reject) => {
|
||||
callService(`/${node}/set_parameters`, 'rcl_interfaces/srv/SetParameters',
|
||||
buildSetRequest(params), resolve);
|
||||
setTimeout(() => reject(new Error(`timeout on ${node}`)), 5000);
|
||||
});
|
||||
}
|
||||
setSensors(toApply); persist(null, toApply);
|
||||
setApplyResult({ ok: true, msg: 'Sensor parameters applied' });
|
||||
} catch (e) { setApplyResult({ ok: false, msg: String(e.message) }); }
|
||||
setApplying(false);
|
||||
}, [sensors, callService, buildSetRequest, persist]);
|
||||
|
||||
const startFirmwareWatch = useCallback(() => {
|
||||
if (!subscribe) return () => {};
|
||||
return subscribe('/diagnostics', 'diagnostic_msgs/DiagnosticArray', (msg) => {
|
||||
const info = {};
|
||||
for (const status of msg.status ?? []) {
|
||||
for (const kv of status.values ?? []) {
|
||||
if (kv.key === 'stm32_fw_version') info.stm32Version = kv.value;
|
||||
if (kv.key === 'jetson_sw_version') info.jetsonVersion = kv.value;
|
||||
if (kv.key === 'last_ota_date') info.lastOtaDate = kv.value;
|
||||
if (kv.key === 'jetson_hostname') info.hostname = kv.value;
|
||||
if (kv.key === 'ros_distro') info.rosDistro = kv.value;
|
||||
if (kv.key === 'uptime_s') info.uptimeS = parseFloat(kv.value);
|
||||
}
|
||||
}
|
||||
if (Object.keys(info).length > 0) setFirmwareInfo(fi => ({ ...fi, ...info }));
|
||||
});
|
||||
}, [subscribe]);
|
||||
|
||||
const exportSettingsJSON = useCallback(() =>
|
||||
JSON.stringify({ gains, sensors, exportedAt: new Date().toISOString() }, null, 2),
|
||||
[gains, sensors]);
|
||||
|
||||
const importSettingsJSON = useCallback((json) => {
|
||||
const data = JSON.parse(json);
|
||||
if (data.gains) { setGains(data.gains); persist(data.gains, null); }
|
||||
if (data.sensors) { setSensors(data.sensors); persist(null, data.sensors); }
|
||||
}, [persist]);
|
||||
|
||||
const exportDiagnosticsBundle = useCallback((robotData, connections) => {
|
||||
const bundle = {
|
||||
exportedAt: new Date().toISOString(),
|
||||
settings: { gains, sensors },
|
||||
firmwareInfo,
|
||||
fleet: Object.entries(connections ?? {}).map(([id, c]) => ({ id, ...c, data: robotData?.[id] })),
|
||||
};
|
||||
const a = document.createElement('a');
|
||||
a.href = URL.createObjectURL(new Blob([JSON.stringify(bundle, null, 2)], { type: 'application/json' }));
|
||||
a.download = `saltybot-diagnostics-${Date.now()}.json`;
|
||||
a.click();
|
||||
}, [gains, sensors, firmwareInfo]);
|
||||
|
||||
return {
|
||||
gains, setGains, sensors, setSensors, firmwareInfo,
|
||||
applying, applyResult,
|
||||
applyPIDGains, applySensorParams, startFirmwareWatch,
|
||||
exportSettingsJSON, importSettingsJSON, exportDiagnosticsBundle,
|
||||
validate: () => validatePID(gains),
|
||||
};
|
||||
}
|
||||
Loading…
x
Reference in New Issue
Block a user