webrtc_example / index.html
cduss's picture
use main branch for JS lib import
6d2749a
<!doctype html>
<html lang="en">
<head>
<meta charset="utf-8" />
<meta name="viewport" content="width=device-width, initial-scale=1, maximum-scale=1, user-scalable=no" />
<title>Reachy Mini - Pollen Robotics</title>
<link rel="preconnect" href="https://fonts.googleapis.com">
<link rel="preconnect" href="https://fonts.gstatic.com" crossorigin>
<link href="https://fonts.googleapis.com/css2?family=Inter:wght@400;500;600;700&display=swap" rel="stylesheet">
<link rel="stylesheet" href="style.css">
</head>
<body>
<!-- Login View -->
<div id="loginView" class="login-view">
<div class="login-card">
<img class="login-logo" src="https://raw.githubusercontent.com/pollen-robotics/reachy-mini-desktop-app/develop/src-tauri/icons/128x128.png" alt="Reachy Mini">
<h2>Reachy Mini</h2>
<p>Sign in with your HuggingFace account to connect and control your robot remotely.</p>
<button class="btn-hf" onclick="loginToHuggingFace()">
<svg width="18" height="18" viewBox="0 0 95 88" fill="currentColor">
<path d="M47.5 0C26.3 0 9.1 17.2 9.1 38.4v2.9c0 4.5 1.1 9 3.2 13L0 88h95L82.7 54.3c2.1-4 3.2-8.5 3.2-13v-2.9C85.9 17.2 68.7 0 47.5 0z"/>
</svg>
Sign in with Hugging Face
</button>
</div>
</div>
<!-- Main App -->
<div id="mainApp" class="hidden">
<header class="header">
<div class="logo">
<img src="https://raw.githubusercontent.com/pollen-robotics/reachy-mini-desktop-app/develop/src-tauri/icons/128x128.png" alt="Reachy Mini">
<div class="logo-text">Reachy Mini <span>by Pollen Robotics</span></div>
</div>
<div class="user-section">
<!-- Daemon version is filled in once the WebRTC data channel
is open (via robot.getVersion()). Hidden until then so
we don't show a stale/empty badge during connect. -->
<div id="daemonVersion" class="user-badge hidden" title="Daemon version"></div>
<div class="user-badge"><span id="username">@user</span></div>
<button class="btn-logout" onclick="logout()">Sign out</button>
</div>
</header>
<div class="app-container">
<!-- Video -->
<div class="video-container">
<video id="remoteVideo" autoplay playsinline muted></video>
<div class="video-overlay-top">
<div class="connection-badge">
<div class="status-indicator" id="statusIndicator"></div>
<span id="statusText">Disconnected</span>
</div>
<div class="robot-name" id="robotName"></div>
<div class="latency-badge hidden" id="latencyBadge">
<span id="latencyValue">--</span>
</div>
</div>
<div class="video-overlay-bottom">
<div class="video-controls">
<button class="btn btn-secondary" id="connectBtn" onclick="connectSignaling()">Connect</button>
<button class="btn btn-primary" id="startBtn" onclick="startStream()" disabled>Start</button>
<button class="btn btn-danger" id="stopBtn" onclick="stopStream()" disabled>Stop</button>
<button class="btn btn-mute muted" id="muteBtn" onclick="toggleMute()" disabled>
<svg id="speakerOffIcon" viewBox="0 0 24 24" fill="none" stroke="currentColor" stroke-width="2">
<polygon points="11 5 6 9 2 9 2 15 6 15 11 19 11 5"></polygon>
<line x1="23" y1="9" x2="17" y2="15"></line>
<line x1="17" y1="9" x2="23" y2="15"></line>
</svg>
<svg id="speakerOnIcon" class="hidden" viewBox="0 0 24 24" fill="none" stroke="currentColor" stroke-width="2">
<polygon points="11 5 6 9 2 9 2 15 6 15 11 19 11 5"></polygon>
<path d="M19.07 4.93a10 10 0 0 1 0 14.14M15.54 8.46a5 5 0 0 1 0 7.07"></path>
</svg>
<span id="muteText">Unmute</span>
</button>
<button class="btn btn-mute muted" id="micBtn" onclick="toggleMic()" disabled>
<svg id="micOffIcon" viewBox="0 0 24 24" fill="none" stroke="currentColor" stroke-width="2">
<line x1="1" y1="1" x2="23" y2="23"></line>
<path d="M9 9v3a3 3 0 0 0 5.12 2.12M15 9.34V4a3 3 0 0 0-5.94-.6"></path>
<path d="M17 16.95A7 7 0 0 1 5 12v-2m14 0v2c0 .76-.13 1.49-.35 2.17"></path>
<line x1="12" y1="19" x2="12" y2="23"></line>
<line x1="8" y1="23" x2="16" y2="23"></line>
</svg>
<svg id="micOnIcon" class="hidden" viewBox="0 0 24 24" fill="none" stroke="currentColor" stroke-width="2">
<path d="M12 1a3 3 0 0 0-3 3v8a3 3 0 0 0 6 0V4a3 3 0 0 0-3-3z"></path>
<path d="M19 10v2a7 7 0 0 1-14 0v-2"></path>
<line x1="12" y1="19" x2="12" y2="23"></line>
<line x1="8" y1="23" x2="16" y2="23"></line>
</svg>
<span id="micText">Mic Off</span>
</button>
</div>
</div>
</div>
<!-- Robot Selector -->
<div id="robotSelector" class="panel hidden">
<div class="panel-header">Available Robots</div>
<div class="panel-content">
<div id="robotList" class="robot-list">
<div style="color: var(--text-muted); font-size: 0.85em;">Searching...</div>
</div>
</div>
</div>
<!-- Head Control - RPY Sliders -->
<div class="panel">
<div class="panel-header">Head Orientation</div>
<div class="panel-content">
<div class="slider-row">
<span class="slider-label">Roll</span>
<input type="range" class="slider" id="rollSlider" min="-20" max="20" value="0" step="0.5">
<span class="slider-value" id="rollValue">0.0°</span>
</div>
<div class="slider-row">
<span class="slider-label">Pitch</span>
<input type="range" class="slider" id="pitchSlider" min="-30" max="30" value="0" step="0.5">
<span class="slider-value" id="pitchValue">0.0°</span>
</div>
<div class="slider-row">
<span class="slider-label">Yaw</span>
<input type="range" class="slider" id="yawSlider" min="-160" max="160" value="0" step="0.5">
<span class="slider-value" id="yawValue">0.0°</span>
</div>
</div>
</div>
<!-- Body / Base Yaw -->
<div class="panel">
<div class="panel-header">Body</div>
<div class="panel-content">
<div class="slider-row">
<span class="slider-label">Yaw</span>
<input type="range" class="slider" id="bodyYawSlider" min="-160" max="160" value="0" step="1">
<span class="slider-value" id="bodyYawValue"></span>
</div>
</div>
</div>
<!-- Antennas -->
<div class="panel">
<div class="panel-header">Antennas</div>
<div class="panel-content">
<div class="slider-row">
<span class="slider-label">Right</span>
<input type="range" class="slider" id="rightAntSlider" min="-175" max="175" value="0">
<span class="slider-value" id="rightAntValue"></span>
</div>
<div class="slider-row">
<span class="slider-label">Left</span>
<input type="range" class="slider" id="leftAntSlider" min="-175" max="175" value="0">
<span class="slider-value" id="leftAntValue"></span>
</div>
</div>
</div>
<!-- Animations -->
<div class="panel">
<div class="panel-header">Animations</div>
<div class="panel-content">
<div class="sound-row">
<button class="btn btn-primary" id="btnWakeUp" onclick="playWakeUp()" disabled>Wake up</button>
<button class="btn btn-secondary" id="btnGotoSleep" onclick="playGotoSleep()" disabled>Go to sleep</button>
</div>
</div>
</div>
<!-- Torque -->
<div class="panel">
<div class="panel-header">Torque</div>
<div class="panel-content">
<div class="sound-row">
<!-- Label and action flip based on the current motor
mode, which is surfaced via the 'state' event. -->
<button class="btn btn-primary" id="btnTorqueToggle" onclick="toggleTorque()" disabled>Torque …</button>
</div>
</div>
</div>
<!-- Sound -->
<div class="panel">
<div class="panel-header">Sound</div>
<div class="panel-content">
<div class="sound-row">
<input type="text" class="sound-input" id="soundInput" placeholder="Sound file...">
<button class="btn btn-primary" id="btnPlaySound" onclick="playSound()" disabled>Play</button>
</div>
<div class="sound-presets">
<span class="preset-chip" onclick="playSoundPreset('wake_up.wav')">wake_up</span>
<span class="preset-chip" onclick="playSoundPreset('go_sleep.wav')">go_sleep</span>
<span class="preset-chip" onclick="playSoundPreset('yes.wav')">yes</span>
<span class="preset-chip" onclick="playSoundPreset('no.wav')">no</span>
</div>
</div>
</div>
<!-- Volume -->
<div class="panel">
<div class="panel-header">Volume</div>
<div class="panel-content">
<div class="slider-row">
<span class="slider-label">Speaker</span>
<input type="range" class="slider" id="volumeSlider" min="0" max="100" value="50" disabled>
<span class="slider-value" id="volumeValue">--</span>
</div>
</div>
</div>
</div>
</div>
<script type="module">
import { ReachyMini, matrixToRpy, radToDeg, rpyToMatrix, degToRad } from "https://cdn.jsdelivr.net/gh/pollen-robotics/reachy_mini@main/js/reachy-mini.js";
const robot = new ReachyMini({ appName: "Reachy Mini WebRTC Demo" });
let selectedRobotId = null;
let headSlidersActive = false;
let bodyYawSliderActive = false;
// Last body yaw the user committed via the slider, in degrees.
// Used to compute the delta we need to subtract from the head yaw
// command so the head visually fixates a point in world frame
// while the base rotates.
let lastBodyYawDeg = 0;
let detachVideo = null;
let latencyIntervalId = null;
// Export functions for inline onclick handlers
window.loginToHuggingFace = () => robot.login();
window.logout = logout;
window.connectSignaling = connectSignaling;
window.startStream = startStream;
window.stopStream = stopStream;
window.playSound = playSound;
window.playSoundPreset = playSoundPreset;
window.playWakeUp = playWakeUp;
window.playGotoSleep = playGotoSleep;
window.toggleTorque = toggleTorque;
window.toggleMute = toggleMute;
window.toggleMic = toggleMic;
document.addEventListener('DOMContentLoaded', async () => {
if (await robot.authenticate()) {
showMainApp();
} else {
showLogin();
}
initSliders();
initRobotEvents();
});
// ===================== Auth =====================
function logout() {
if (detachVideo) { detachVideo(); detachVideo = null; }
robot.logout();
showLogin();
}
function showLogin() {
document.getElementById('loginView').classList.remove('hidden');
document.getElementById('mainApp').classList.add('hidden');
}
function showMainApp() {
document.getElementById('loginView').classList.add('hidden');
document.getElementById('mainApp').classList.remove('hidden');
document.getElementById('username').textContent = '@' + robot.username;
}
// ===================== Robot Events =====================
function initRobotEvents() {
robot.addEventListener('robotsChanged', (e) => displayRobots(e.detail.robots));
robot.addEventListener('streaming', () => {
updateStatus('connected', 'Connected');
enableControls(true);
document.getElementById('robotSelector').classList.add('hidden');
startLatencyDisplay();
// Data channel is open — fetch daemon version (one-shot) and
// sync the volume slider to the robot's current level. Both
// swallow failures so a missing command handler or an
// unsupported audio platform doesn't break the UI.
fetchDaemonVersionOnce();
syncVolumeSlider();
ensureAwakeOnce();
});
robot.addEventListener('sessionStopped', (e) => {
document.getElementById('startBtn').disabled = !selectedRobotId;
document.getElementById('stopBtn').disabled = true;
document.getElementById('robotSelector').classList.remove('hidden');
enableControls(false);
// e.detail.message is set when the stop was server-initiated (e.g.
// a local Python app took over the robot). null for user-initiated.
updateStatus('connected', e.detail?.message || 'Connected');
updateMicButton();
stopLatencyDisplay();
// Disable the volume slider and clear the version pill — they
// only make sense while the data channel is open.
document.getElementById('volumeSlider').disabled = true;
document.getElementById('volumeValue').textContent = '--';
document.getElementById('daemonVersion').classList.add('hidden');
// Reset the torque button label so it doesn't claim a stale
// state between sessions.
const tb = document.getElementById('btnTorqueToggle');
tb.textContent = 'Torque …';
delete tb.dataset.currentMode;
});
robot.addEventListener('state', (e) => updateStateDisplay(e.detail));
robot.addEventListener('micSupported', () => {
enableControls(robot.state === 'streaming');
});
robot.addEventListener('disconnected', () => {
updateStatus('', 'Disconnected');
document.getElementById('connectBtn').disabled = false;
document.getElementById('robotSelector').classList.add('hidden');
});
robot.addEventListener('error', (e) => {
console.error(`[${e.detail.source}]`, e.detail.error);
if (e.detail.source === 'webrtc') {
updateStatus('', 'Connection lost');
}
});
}
// ===================== Connection =====================
function updateStatus(status, text) {
document.getElementById('statusIndicator').className = 'status-indicator ' + status;
document.getElementById('statusText').textContent = text;
}
// ---- Auto-wake on session start ----
//
// If the robot is in the sleep pose (torque off, head resting on
// base), every setHeadRpyDeg / setAntennasDeg call from the UI is
// silently ignored and the app looks broken. ensureAwake() is a
// no-op when already awake (including gravity-compensation), so
// we call it unconditionally after the data channel opens.
async function ensureAwakeOnce() {
// Guard for a stale CDN-cached lib predating ensureAwake.
if (typeof robot.ensureAwake !== 'function') {
console.warn(
'robot.ensureAwake is not a function — the reachy-mini.js ' +
'lib loaded from CDN is older than the webrtc_example UI. ' +
'Purge jsdelivr and hard-refresh the page.'
);
return;
}
try {
await robot.ensureAwake();
} catch (e) {
// Data channel may have closed mid-wake; non-fatal.
console.warn('ensureAwake failed:', e);
}
}
// ---- Daemon version (fetched once per session over WebRTC) ----
async function fetchDaemonVersionOnce() {
try {
const v = await robot.getVersion();
if (!v) return;
const el = document.getElementById('daemonVersion');
el.textContent = `Daemon v${v}`;
el.classList.remove('hidden');
} catch (e) {
// Data channel closed mid-request, or lib version too old
// to support get_version. Non-fatal — but log at WARN so
// a stale CDN-cached lib (missing the method) is visible
// in the browser console without "Verbose" level turned on.
console.warn('getVersion failed:', e);
}
}
// ---- Volume slider wiring ----
//
// Two events matter:
// - 'input' fires continuously while dragging — used for the
// live "75%" label so the UI feels responsive.
// - 'change' fires on release — the only moment we actually
// call setVolume over WebRTC. Avoids spamming the
// robot with one command per pixel of drag.
//
// syncVolumeSlider() runs on streaming-start to pull the robot's
// real current volume so the slider reflects reality rather than
// the default "50" in the markup.
async function syncVolumeSlider() {
const slider = document.getElementById('volumeSlider');
const label = document.getElementById('volumeValue');
// Early detection: if the loaded JS lib predates the volume
// commands (stale jsdelivr cache, old branch), fail loudly
// rather than silently rendering "n/a".
if (typeof robot.getVolume !== 'function') {
console.warn(
'robot.getVolume is not a function — the reachy-mini.js ' +
'lib loaded from CDN is older than the webrtc_example UI. ' +
'Purge jsdelivr and hard-refresh the page.'
);
label.textContent = 'lib';
return;
}
try {
const v = await robot.getVolume();
if (v == null) {
// Volume control unavailable (unsupported platform or
// audio stack down) — keep the slider disabled.
label.textContent = 'n/a';
return;
}
slider.value = v;
label.textContent = `${v}%`;
slider.disabled = false;
} catch (e) {
// Log at WARN so it's visible without "Verbose" level.
console.warn('getVolume failed:', e);
label.textContent = 'n/a';
}
}
(function initVolumeSlider() {
const slider = document.getElementById('volumeSlider');
const label = document.getElementById('volumeValue');
slider.addEventListener('input', () => {
label.textContent = `${slider.value}%`;
});
slider.addEventListener('change', async () => {
const requested = parseInt(slider.value, 10);
if (typeof robot.setVolume !== 'function') {
console.warn(
'robot.setVolume is not a function — old JS lib on CDN; ' +
'purge jsdelivr and hard-refresh.'
);
return;
}
try {
const applied = await robot.setVolume(requested);
if (applied != null) {
// Server may clamp/round — reflect the truth back
// into the UI so the slider isn't a lie.
slider.value = applied;
label.textContent = `${applied}%`;
}
} catch (e) {
console.warn('setVolume failed:', e);
}
});
})();
async function connectSignaling() {
if (!robot.isAuthenticated) return;
updateStatus('connecting', 'Connecting...');
document.getElementById('connectBtn').disabled = true;
try {
await robot.connect();
updateStatus('connected', 'Connected');
document.getElementById('robotSelector').classList.remove('hidden');
} catch (e) {
console.error('Connection failed:', e);
updateStatus('', 'Disconnected');
document.getElementById('connectBtn').disabled = false;
}
}
function displayRobots(robots) {
const list = document.getElementById('robotList');
list.innerHTML = '';
if (!robots?.length) {
list.innerHTML = '<div style="color: var(--text-muted);">No robots online</div>';
document.getElementById('startBtn').disabled = true;
return;
}
for (const r of robots) {
const div = document.createElement('div');
div.className = 'robot-card' + (r.id === selectedRobotId ? ' selected' : '');
div.innerHTML = `<div class="name">${r.meta?.name || 'Reachy Mini'}</div><div class="id">${r.id.slice(0, 12)}...</div>`;
div.onclick = () => {
document.querySelectorAll('.robot-card').forEach(e => e.classList.remove('selected'));
div.classList.add('selected');
selectedRobotId = r.id;
document.getElementById('robotName').textContent = r.meta?.name || 'Reachy Mini';
document.getElementById('startBtn').disabled = false;
};
list.appendChild(div);
}
}
// ===================== Latency =====================
function startLatencyDisplay() {
const badge = document.getElementById('latencyBadge');
const label = document.getElementById('latencyValue');
badge.classList.remove('hidden');
latencyIntervalId = setInterval(async () => {
const video = document.getElementById('remoteVideo');
let bufLagMs = null;
let rttMs = null;
let vidJitterMs = null;
let audJitterMs = null;
// Buffer lag (how far behind live edge)
if (video && video.buffered && video.buffered.length > 0) {
const end = video.buffered.end(video.buffered.length - 1);
bufLagMs = Math.round((end - video.currentTime) * 1000);
}
// WebRTC stats: RTT + jitter buffer delay (video & audio)
if (robot._pc) {
try {
const stats = await robot._pc.getStats();
stats.forEach(report => {
if (report.type === 'candidate-pair' && report.currentRoundTripTime != null) {
rttMs = Math.round(report.currentRoundTripTime * 1000);
}
if (report.type === 'inbound-rtp' && report.jitterBufferDelay != null && report.jitterBufferEmittedCount > 0) {
const jMs = Math.round((report.jitterBufferDelay / report.jitterBufferEmittedCount) * 1000);
if (report.kind === 'video') vidJitterMs = jMs;
if (report.kind === 'audio') audJitterMs = jMs;
}
});
} catch (_) { /* no stats yet */ }
}
// Display
const parts = [];
if (bufLagMs != null) parts.push(`buf ${bufLagMs}ms`);
if (rttMs != null) parts.push(`rtt ${rttMs}ms`);
if (vidJitterMs != null) parts.push(`v-jit ${vidJitterMs}ms`);
if (audJitterMs != null) parts.push(`a-jit ${audJitterMs}ms`);
label.textContent = parts.length ? parts.join(' · ') : '--';
// Color based on buffer lag
badge.classList.remove('good', 'ok', 'bad');
if (bufLagMs != null) {
if (bufLagMs < 200) badge.classList.add('good');
else if (bufLagMs < 500) badge.classList.add('ok');
else badge.classList.add('bad');
}
}, 1000);
}
function stopLatencyDisplay() {
if (latencyIntervalId) { clearInterval(latencyIntervalId); latencyIntervalId = null; }
const badge = document.getElementById('latencyBadge');
badge.classList.add('hidden');
badge.classList.remove('good', 'ok', 'bad');
}
// ===================== Session =====================
async function startStream() {
if (!selectedRobotId) return;
updateStatus('connecting', 'Connecting...');
updateMuteButton();
detachVideo = robot.attachVideo(document.getElementById('remoteVideo'));
document.getElementById('startBtn').disabled = true;
document.getElementById('stopBtn').disabled = false;
try {
await robot.startSession(selectedRobotId);
} catch (e) {
console.error('Session failed:', e);
if (detachVideo) { detachVideo(); detachVideo = null; }
document.getElementById('startBtn').disabled = !selectedRobotId;
document.getElementById('stopBtn').disabled = true;
// "robot_busy" → central refused: another remote JS app is connected.
// "robot_busy_local_app" → relay refused: a local Python app holds the robot.
// "local_app_started" → we were streaming; a local Python app evicted us.
// "robot_busy_local" → relay safety net; another session slipped in.
let msg;
if (e.reason === 'robot_busy') {
msg = `Robot busy — "${e.activeApp}" is already connected`;
} else if ((e.reason && e.reason.startsWith('robot_busy')) || e.reason === 'local_app_started') {
msg = e.message;
} else {
msg = `Session failed: ${e.message}`;
}
updateStatus('disconnected', msg);
}
}
async function stopStream() {
if (detachVideo) { detachVideo(); detachVideo = null; }
await robot.stopSession();
}
// ===================== Audio =====================
function toggleMute() {
robot.setAudioMuted(!robot.audioMuted);
updateMuteButton();
}
function toggleMic() {
robot.setMicMuted(!robot.micMuted);
updateMicButton();
}
function updateMuteButton() {
const muted = robot.audioMuted;
const btn = document.getElementById('muteBtn');
btn.classList.toggle('muted', muted);
document.getElementById('speakerOffIcon').classList.toggle('hidden', !muted);
document.getElementById('speakerOnIcon').classList.toggle('hidden', muted);
document.getElementById('muteText').textContent = muted ? 'Unmute' : 'Mute';
}
function updateMicButton() {
const muted = robot.micMuted;
const btn = document.getElementById('micBtn');
btn.classList.toggle('muted', muted);
document.getElementById('micOffIcon').classList.toggle('hidden', !muted);
document.getElementById('micOnIcon').classList.toggle('hidden', muted);
document.getElementById('micText').textContent = muted ? 'Mic Off' : 'Mic On';
}
function enableControls(enabled) {
document.getElementById('btnPlaySound').disabled = !enabled;
document.getElementById('btnWakeUp').disabled = !enabled;
document.getElementById('btnGotoSleep').disabled = !enabled;
document.getElementById('btnTorqueToggle').disabled = !enabled;
document.getElementById('muteBtn').disabled = !enabled;
document.getElementById('micBtn').disabled = !enabled || !robot.micSupported;
}
// ===================== State Display =====================
// The "state" event ships raw wire units (flat 4×4 matrix, radians);
// the UI works in degrees, so we convert at the boundary.
function updateStateDisplay(state) {
// Also gate on bodyYawSliderActive: dragging the body slider
// mutates yawSlider.value (head/body rotate together), and the
// daemon's mid-IK present_head_pose lags the target. Without
// this gate, matrixToRpy of the in-flight pose pumps drifted
// roll/pitch/yaw back into the head sliders, which the next
// body-input event reads and re-sends — visible as pitch/roll
// jitter while the body slider is being dragged.
if (state.head && !headSlidersActive && !bodyYawSliderActive) {
// state.head is number[16] (flat row-major 4×4); matrixToRpy
// wants nested 4×4, so unflatten.
const m = [
state.head.slice(0, 4),
state.head.slice(4, 8),
state.head.slice(8, 12),
state.head.slice(12, 16),
];
const rpy = matrixToRpy(m);
document.getElementById('rollSlider').value = rpy.roll;
document.getElementById('rollValue').textContent = rpy.roll.toFixed(1) + '°';
document.getElementById('pitchSlider').value = rpy.pitch;
document.getElementById('pitchValue').textContent = rpy.pitch.toFixed(1) + '°';
document.getElementById('yawSlider').value = rpy.yaw;
document.getElementById('yawValue').textContent = rpy.yaw.toFixed(1) + '°';
}
if (state.antennas) {
const r = radToDeg(state.antennas[0]).toFixed(0);
const l = radToDeg(state.antennas[1]).toFixed(0);
document.getElementById('rightAntSlider').value = r;
document.getElementById('rightAntValue').textContent = r + '°';
document.getElementById('leftAntSlider').value = l;
document.getElementById('leftAntValue').textContent = l + '°';
}
if (typeof state.body_yaw === 'number' && !bodyYawSliderActive) {
const y = radToDeg(state.body_yaw).toFixed(0);
document.getElementById('bodyYawSlider').value = y;
document.getElementById('bodyYawValue').textContent = y + '°';
// Sync the delta baseline so the next drag computes from
// the robot's actual current yaw, not whatever the slider
// happened to be at on page load.
lastBodyYawDeg = parseFloat(y);
}
if (state.motor_mode) updateTorqueButton(state.motor_mode);
}
function updateTorqueButton(mode) {
const btn = document.getElementById('btnTorqueToggle');
if (!btn) return;
// Normalise: anything other than "disabled" is considered "on"
// for toggle purposes. gravity_compensation is torque-on too.
const isOn = mode && mode !== 'disabled';
btn.textContent = isOn ? 'Torque: On (click to disable)' : 'Torque: Off (click to enable)';
// Stash the current intent so the click handler knows which
// direction to flip without rereading _robotState.
btn.dataset.currentMode = mode;
}
// ===================== Sliders =====================
function initSliders() {
// Head
const rollSlider = document.getElementById('rollSlider');
const pitchSlider = document.getElementById('pitchSlider');
const yawSlider = document.getElementById('yawSlider');
const rollValue = document.getElementById('rollValue');
const pitchValue = document.getElementById('pitchValue');
const yawValue = document.getElementById('yawValue');
// Body yaw
const bodyYawSlider = document.getElementById('bodyYawSlider');
const bodyYawValue = document.getElementById('bodyYawValue');
// Antennas
const rightSlider = document.getElementById('rightAntSlider');
const leftSlider = document.getElementById('leftAntSlider');
const rightAntValue = document.getElementById('rightAntValue');
const leftAntValue = document.getElementById('leftAntValue');
// Single source of truth: read every slider's DOM state and
// ship it in one atomic setTarget command. Per-slider input
// handlers update their label, optionally run cross-slider
// compensation (body-yaw drag → head-yaw counter-rotation),
// then call this. One round-trip per gesture, no chance for
// the daemon to see a half-applied target between components.
function sendCurrentTarget() {
robot.setTarget({
head: rpyToMatrix(
parseFloat(rollSlider.value),
parseFloat(pitchSlider.value),
parseFloat(yawSlider.value),
).flat(),
antennas: [
degToRad(parseFloat(rightSlider.value)),
degToRad(parseFloat(leftSlider.value)),
],
body_yaw: degToRad(parseFloat(bodyYawSlider.value)),
});
}
const onStart = () => { headSlidersActive = true; };
const onEnd = () => { headSlidersActive = false; };
for (const s of [rollSlider, pitchSlider, yawSlider]) {
s.addEventListener('mousedown', onStart);
s.addEventListener('touchstart', onStart);
s.addEventListener('mouseup', onEnd);
s.addEventListener('touchend', onEnd);
}
rollSlider.addEventListener('input', () => { rollValue.textContent = parseFloat(rollSlider.value).toFixed(1) + '°'; sendCurrentTarget(); });
pitchSlider.addEventListener('input', () => { pitchValue.textContent = parseFloat(pitchSlider.value).toFixed(1) + '°'; sendCurrentTarget(); });
yawSlider.addEventListener('input', () => { yawValue.textContent = parseFloat(yawSlider.value).toFixed(1) + '°'; sendCurrentTarget(); });
// Body yaw — the head pose in setTarget is interpreted in world
// frame (see look_at_world in the Python SDK), so the IK splits
// the requested world yaw between body rotation and the stewart
// platform. Mechanical limit: |head_yaw_world − body_yaw| ≤ 65°.
//
// To keep that relative yaw constant as the user drags the body
// slider, we move the head's commanded world yaw by the same
// delta — head and body rotate together (tank-style). The
// per-component values are then shipped atomically by
// sendCurrentTarget().
const onBodyStart = () => { bodyYawSliderActive = true; };
const onBodyEnd = () => { bodyYawSliderActive = false; };
bodyYawSlider.addEventListener('mousedown', onBodyStart);
bodyYawSlider.addEventListener('touchstart', onBodyStart);
bodyYawSlider.addEventListener('mouseup', onBodyEnd);
bodyYawSlider.addEventListener('touchend', onBodyEnd);
const yawMin = parseFloat(yawSlider.min);
const yawMax = parseFloat(yawSlider.max);
bodyYawSlider.addEventListener('input', () => {
const newBodyDeg = parseFloat(bodyYawSlider.value);
const delta = newBodyDeg - lastBodyYawDeg;
// Add the body-yaw delta to the head-yaw slider, clamped
// to its range. Once the head slider saturates, the head's
// world yaw stops keeping up with the body, the relative
// yaw starts to grow, and beyond ~65° the daemon's safe-IK
// will modulate body_yaw to stay within mechanical limits.
const newHeadYaw = Math.max(yawMin, Math.min(yawMax,
parseFloat(yawSlider.value) + delta));
yawSlider.value = newHeadYaw;
yawValue.textContent = newHeadYaw.toFixed(1) + '°';
bodyYawValue.textContent = newBodyDeg.toFixed(0) + '°';
sendCurrentTarget();
lastBodyYawDeg = newBodyDeg;
});
rightSlider.addEventListener('input', () => {
rightAntValue.textContent = rightSlider.value + '°';
sendCurrentTarget();
});
leftSlider.addEventListener('input', () => {
leftAntValue.textContent = leftSlider.value + '°';
sendCurrentTarget();
});
}
// ===================== Sound =====================
function playSound() {
const file = document.getElementById('soundInput').value.trim();
if (file) robot.playSound(file);
}
function playSoundPreset(file) {
document.getElementById('soundInput').value = file;
robot.playSound(file);
}
// ===================== Animations =====================
//
// Fire-and-forget: the robot plays the full trajectory (~2 s) and
// we don't await completion. The buttons are briefly disabled
// during the motion to prevent the user from spamming the same
// animation on top of itself, using is_move_running from the
// state event as the authoritative "busy" signal.
//
// Staleness detection: if the lib loaded from CDN predates these
// methods (typeof check), warn instead of silently failing. Same
// pattern as the volume controls.
function playWakeUp() {
// Click receipt log: present so that "no log at all" definitively
// means the click event never reached this function (button still
// disabled, stale HTML in browser cache, or redeploy not live).
console.log('[animations] playWakeUp clicked; robot.state=', robot.state,
'; robot.wakeUp typeof=', typeof robot.wakeUp);
if (typeof robot.wakeUp !== 'function') {
console.warn('robot.wakeUp is not a function — stale JS lib; purge jsdelivr + hard-refresh.');
return;
}
const ok = robot.wakeUp();
console.log('[animations] robot.wakeUp() returned', ok);
}
function playGotoSleep() {
console.log('[animations] playGotoSleep clicked; robot.state=', robot.state,
'; robot.gotoSleep typeof=', typeof robot.gotoSleep);
if (typeof robot.gotoSleep !== 'function') {
console.warn('robot.gotoSleep is not a function — stale JS lib; purge jsdelivr + hard-refresh.');
return;
}
const ok = robot.gotoSleep();
console.log('[animations] robot.gotoSleep() returned', ok);
}
// ===================== Torque =====================
//
// The "current mode" read from the button's dataset is populated by
// updateTorqueButton() on every state-event. If a user clicks before
// the first state tick arrives, currentMode is falsy and we default
// to enabling — the safe-ish choice that matches what wakeUp() would
// do. The label then self-corrects on the next state tick.
function toggleTorque() {
if (typeof robot.setMotorMode !== 'function') {
console.warn('robot.setMotorMode is not a function — stale JS lib; purge jsdelivr + hard-refresh.');
return;
}
const btn = document.getElementById('btnTorqueToggle');
const currentMode = btn.dataset.currentMode;
const next = (currentMode && currentMode !== 'disabled') ? 'disabled' : 'enabled';
console.log('[torque] toggle click; currentMode=', currentMode, '→ sending', next);
robot.setMotorMode(next);
// Optimistic UI update. If the robot rejects or differs, the
// next state tick (within ~500 ms) will overwrite.
updateTorqueButton(next);
}
</script>
</body>
</html>