diff --git a/.gitattributes b/.gitattributes index c4ccd1f825..0c2c7b4217 100644 --- a/.gitattributes +++ b/.gitattributes @@ -18,3 +18,8 @@ *.foxe filter=lfs diff=lfs merge=lfs -text binary docs/capabilities/memory/assets/** filter=lfs diff=lfs merge=lfs -text docs/capabilities/memory/assets/.gitattributes -filter -diff -merge text +# DimSim scene data and agent model +misc/DimSim/public/sims/*.json filter=lfs diff=lfs merge=lfs -text +misc/DimSim/public/embodiment/*.glb filter=lfs diff=lfs merge=lfs -text +misc/DimSim/scenes/**/*.glb filter=lfs diff=lfs merge=lfs -text +misc/DimSim/scenes/**/*.gltf filter=lfs diff=lfs merge=lfs -text diff --git a/.github/workflows/dimsim-check.yml b/.github/workflows/dimsim-check.yml new file mode 100644 index 0000000000..821306cccf --- /dev/null +++ b/.github/workflows/dimsim-check.yml @@ -0,0 +1,45 @@ +name: dimsim-check + +on: + push: + branches: [main] + paths: + - 'misc/DimSim/**' + - '.github/workflows/dimsim-check.yml' + pull_request: + paths: + - 'misc/DimSim/**' + - '.github/workflows/dimsim-check.yml' + +permissions: {} + +jobs: + check: + timeout-minutes: 15 + runs-on: ubuntu-latest + permissions: + contents: read + defaults: + run: + working-directory: misc/DimSim + steps: + - uses: actions/checkout@v6 + with: + lfs: true + + - uses: actions/setup-node@v4 + with: + node-version: 20 + + - uses: denoland/setup-deno@v2 + with: + deno-version: v2.x + + - name: Install npm deps + run: npm ci + + - name: Build frontend + run: npm run build + + - name: Type-check CLI + run: cd cli && deno check cli.ts diff --git a/.gitignore b/.gitignore index aedee04af7..efb34af7d0 100644 --- a/.gitignore +++ b/.gitignore @@ -39,10 +39,8 @@ __pycache__ # node env (used by devcontainers cli) node_modules -package.json -package-lock.json -!docs/package.json -!docs/package-lock.json +/package.json +/package-lock.json # Ignore build artifacts dist/ diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index ea8769d946..f9bb66afcb 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -39,11 +39,13 @@ repos: args: [--fix=lf] exclude: \.patch$ # keep patch files byte-identical to upstream diffs - id: check-json + exclude: ^misc/DimSim/public/sims/ # LFS-tracked - id: check-toml - id: check-yaml - id: pretty-format-json name: format json args: [ --autofix, --no-sort-keys ] + exclude: ^misc/DimSim/public/sims/ # LFS-tracked - repo: https://github.com/editorconfig-checker/editorconfig-checker.python rev: 3.4.1 diff --git a/dimos/core/global_config.py b/dimos/core/global_config.py index efba609849..28dedee746 100644 --- a/dimos/core/global_config.py +++ b/dimos/core/global_config.py @@ -65,8 +65,9 @@ class GlobalConfig(BaseSettings): obstacle_avoidance: bool = True detection_model: VlModelName = "moondream" listen_host: str = "127.0.0.1" - dimsim_scene: str = "apt" + dimsim_scene: str = "apartment" dimsim_port: int = 8090 + dimsim_headless: bool = True model_config = SettingsConfigDict( env_file=".env", diff --git a/dimos/simulation/dimsim/dimsim_process.py b/dimos/simulation/dimsim/dimsim_process.py index ead774c677..1630758145 100644 --- a/dimos/simulation/dimsim/dimsim_process.py +++ b/dimos/simulation/dimsim/dimsim_process.py @@ -19,7 +19,6 @@ import time from typing import IO -from dimos.constants import STATE_DIR from dimos.core.global_config import GlobalConfig from dimos.simulation.dimsim.deno_utils import ensure_deno, ensure_playwright_chromium from dimos.utils.logging_config import setup_logger @@ -28,8 +27,7 @@ _VIDEO_RATE = 50 _LIDAR_RATE = 1000 -_DIMSIM_REPO_URL = "https://github.com/paul-nechifor/DimSim.git" -_DIMSIM_REPO_BRANCH = "run-from-repo" +_DIMSIM_DIR = Path(__file__).resolve().parents[3] / "misc" / "DimSim" class DimSimProcess: @@ -39,13 +37,14 @@ def __init__(self, global_config: GlobalConfig) -> None: def start(self) -> None: deno_path = ensure_deno() - repo_dir = _ensure_repo() - base_cmd = _deno_cmd(deno_path, repo_dir) + base_cmd = _deno_cmd(deno_path, _resolve_dimsim_dir()) scene = self.global_config.dimsim_scene port = self.global_config.dimsim_port + headless = self.global_config.dimsim_headless - ensure_playwright_chromium(deno_path) + if headless: + ensure_playwright_chromium(deno_path) _kill_port_holder(port) render = os.environ.get("DIMSIM_RENDER", "gpu").strip() @@ -60,7 +59,7 @@ def start(self) -> None: "--port", str(port), "--no-depth", - "--headless", + *(("--headless",) if headless else ()), "--render", render, "--image-rate", @@ -69,6 +68,11 @@ def start(self) -> None: str(_LIDAR_RATE), ] + if not headless: + logger.info( + f"Open http://localhost:{port} in your browser; sensors won't publish until that tab is loaded." + ) + self.process = subprocess.Popen(cmd, stdout=subprocess.PIPE, stderr=subprocess.PIPE) self._start_log_reader() @@ -126,28 +130,30 @@ def _kill_port_holder(port: int) -> None: logger.warning(f"Failed to check/kill port {port}: {e}") -def _ensure_repo() -> Path: - repo_dir = STATE_DIR / "dimsim_repo" - if (repo_dir / ".git").exists(): - return repo_dir - STATE_DIR.mkdir(parents=True, exist_ok=True) - logger.info(f"Cloning DimSim into {repo_dir}") - subprocess.run( - [ - "git", - "clone", - "--depth", - "1", - "--branch", - _DIMSIM_REPO_BRANCH, - _DIMSIM_REPO_URL, - str(repo_dir), - ], - check=True, - ) - return repo_dir +def _resolve_dimsim_dir() -> Path: + """Pick the DimSim directory to run. DIMSIM_LOCAL env overrides the + vendored misc/DimSim/ copy — handy when iterating on DimSim itself. + + DIMSIM_LOCAL=1 → ../DimSim sibling of the dimos repo + DIMSIM_LOCAL=/some/path → that path + (unset) → vendored misc/DimSim/ + """ + local = os.environ.get("DIMSIM_LOCAL", "").strip() + if not local: + return _DIMSIM_DIR + if local == "1": + dimos_root = Path(__file__).resolve().parents[3] + path = dimos_root.parent / "DimSim" + else: + path = Path(local).expanduser().resolve() + if not (path / "cli" / "cli.ts").exists(): + raise RuntimeError( + f"DIMSIM_LOCAL={local} resolved to {path}, but {path}/cli/cli.ts does not exist" + ) + logger.info(f"Using local DimSim from {path}") + return path def _deno_cmd(deno_path: str, repo_dir: Path) -> list[str]: - cli_ts = repo_dir / "dimos-cli" / "cli.ts" + cli_ts = repo_dir / "cli" / "cli.ts" return [deno_path, "run", "--allow-all", "--unstable-net", str(cli_ts)] diff --git a/dimos/simulation/dimsim/scene_client.py b/dimos/simulation/dimsim/scene_client.py index 039091996c..c146f9532a 100644 --- a/dimos/simulation/dimsim/scene_client.py +++ b/dimos/simulation/dimsim/scene_client.py @@ -41,7 +41,7 @@ "halfHeight": 0.25, "lidarMountHeight": 0.35, "embodimentType": "quadruped", - "avatarUrl": ["/agent-model/unitree_go2.glb", "/agent-model/robot.glb"], + "avatarUrl": ["/agent-model/dimsim_unitree_stub.glb"], # Physics "maxSpeed": 3.0, "turnRate": 3.0, @@ -54,7 +54,7 @@ "halfHeight": 0.25, "lidarMountHeight": 0.35, "embodimentType": "quadruped", - "avatarUrl": ["/agent-model/unitree_go2.glb", "/agent-model/robot.glb"], + "avatarUrl": ["/agent-model/dimsim_unitree_stub.glb"], "maxSpeed": 3.0, "turnRate": 3.0, "gravity": -9.81, @@ -66,7 +66,7 @@ "halfHeight": 0.2, "lidarMountHeight": 0.35, "embodimentType": "quadruped", # ground physics - "avatarUrl": ["/agent-model/robot.glb"], + "avatarUrl": ["/agent-model/dimsim_unitree_stub.glb"], "maxSpeed": 2.0, "turnRate": 2.5, # differential drive turns by wheel speed diff "gravity": -9.81, @@ -78,7 +78,7 @@ "halfHeight": 0.4, "lidarMountHeight": 0.8, "embodimentType": "quadruped", # ground physics - "avatarUrl": ["/agent-model/robot.glb"], + "avatarUrl": ["/agent-model/dimsim_unitree_stub.glb"], "maxSpeed": 5.0, "turnRate": 1.2, # car-like: slow turn rate (limited steering angle) "gravity": -9.81, @@ -90,7 +90,7 @@ "halfHeight": 0.25, "lidarMountHeight": 0.4, "embodimentType": "quadruped", # ground physics (strafing via cmd_vel.linear.y) - "avatarUrl": ["/agent-model/robot.glb"], + "avatarUrl": ["/agent-model/dimsim_unitree_stub.glb"], "maxSpeed": 2.5, "turnRate": 4.0, # omnidirectional: fast rotation "gravity": -9.81, @@ -102,7 +102,7 @@ "halfHeight": 0.8, "lidarMountHeight": 1.6, "embodimentType": "quadruped", # ground physics - "avatarUrl": ["/agent-model/robot.glb"], + "avatarUrl": ["/agent-model/dimsim_unitree_stub.glb"], "maxSpeed": 1.5, "turnRate": 2.0, "gravity": -9.81, @@ -114,7 +114,7 @@ "halfHeight": 0.15, "lidarMountHeight": 0.25, "embodimentType": "quadruped", - "avatarUrl": ["/agent-model/robot.glb"], + "avatarUrl": ["/agent-model/dimsim_unitree_stub.glb"], "maxSpeed": 1.0, "turnRate": 3.0, "gravity": -9.81, @@ -127,7 +127,7 @@ "halfHeight": 0.1, "lidarMountHeight": 0.15, "embodimentType": "drone", - "avatarUrl": ["/agent-model/robot.glb"], + "avatarUrl": ["/agent-model/dimsim_unitree_stub.glb"], "maxSpeed": 5.0, "turnRate": 4.0, "gravity": 0, # no gravity in flight @@ -723,7 +723,7 @@ def set_embodiment( - ``"flight"`` — 6DoF, optional gravity, altitude ceiling **Avatar URL** can be: - - Built-in: ``"/agent-model/robot.glb"`` + - Built-in: ``"/agent-model/dimsim_unitree_stub.glb"`` - Local asset: ``"/local-assets/my-drone.glb"`` (see :meth:`upload_asset`) - Any URL: ``"https://example.com/robot.glb"`` diff --git a/dimos/visualization/rerun/websocket_server.py b/dimos/visualization/rerun/websocket_server.py index 3b29666fb0..a19bd79e14 100644 --- a/dimos/visualization/rerun/websocket_server.py +++ b/dimos/visualization/rerun/websocket_server.py @@ -151,13 +151,19 @@ def _dispatch(self, raw: str | bytes) -> None: msg_type = msg.get("type") + # dict.get's default is only used when the key is missing — if Rerun + # sends a 2D-panel click the "z" key is present with value None, and + # `float(None)` raises. Coerce explicitly. + def _num(v: Any) -> float: + return float(v) if v is not None else 0.0 + if msg_type == "click": self.clicked_point.publish( PointStamped( - x=float(msg.get("x", 0)), - y=float(msg.get("y", 0)), - z=float(msg.get("z", 0)), - ts=float(msg.get("timestamp_ms", 0)) / 1000.0, + x=_num(msg.get("x")), + y=_num(msg.get("y")), + z=_num(msg.get("z")), + ts=_num(msg.get("timestamp_ms")) / 1000.0, frame_id=str(msg.get("entity_path", "")), ) ) @@ -166,14 +172,14 @@ def _dispatch(self, raw: str | bytes) -> None: self.tele_cmd_vel.publish( Twist( linear=Vector3( - float(msg.get("linear_x", 0)), - float(msg.get("linear_y", 0)), - float(msg.get("linear_z", 0)), + _num(msg.get("linear_x")), + _num(msg.get("linear_y")), + _num(msg.get("linear_z")), ), angular=Vector3( - float(msg.get("angular_x", 0)), - float(msg.get("angular_y", 0)), - float(msg.get("angular_z", 0)), + _num(msg.get("angular_x")), + _num(msg.get("angular_y")), + _num(msg.get("angular_z")), ), ) ) diff --git a/misc/DimSim/.gitignore b/misc/DimSim/.gitignore new file mode 100644 index 0000000000..d5401ddc7d --- /dev/null +++ b/misc/DimSim/.gitignore @@ -0,0 +1,9 @@ +node_modules/ +*.tar.gz +dist/ +.DS_Store +**/.DS_Store +.deno/ +scenes.json +scenes/**/apt.json +scripts/ diff --git a/misc/DimSim/README.md b/misc/DimSim/README.md new file mode 100644 index 0000000000..4698d59f9a --- /dev/null +++ b/misc/DimSim/README.md @@ -0,0 +1,54 @@ +# DimSim + +Browser-based 3D simulator (Three.js + Rapier) plus a Deno bridge that talks LCM/WS to [dimos](https://github.com/dimensionalOS/dimos). Lives inside dimos as `misc/DimSim/`. + +``` +src/ — browser engine (vite-bundled) +cli/ — Deno CLI + bridge server + headless launcher + LCM vendor +evals/ — eval harness (browser) + runner (Deno) + rubrics +scenes/ — user-authored scenes (JS) + per-scene eval workflows +public/ — static assets (agent GLB, logo) +docs/ — guides +``` + +## Run + +dimsim is launched by dimos directly when you pick `--simulation dimsim`: + +```bash +cd +.venv/bin/dimos --simulation dimsim --dimsim-scene=apartment run unitree-go2-agentic +``` + +On first run, `cli/cli.ts` will build `dist/` via Vite (dimsim ships its frontend as source — Deno+Vite materializes it in ~20s). + +## Docs + +- [docs/getting-started.md](docs/getting-started.md) — 5-minute tour +- [docs/scenes.md](docs/scenes.md) — create + edit scenes +- [docs/evals.md](docs/evals.md) — write eval workflows + +## Install the CLI (optional) + +If you want `dimsim` as a global command: + +```bash +cd misc/DimSim/cli +deno install -gAf --unstable-net --name=dimsim --config=./deno.json ./cli.ts +``` + +After install: + +```bash +dimsim dev --scene apartment # standalone dev server + browser +dimsim eval list # list workflows under scenes/*/evals/ +dimsim eval go-to-couch # run one workflow against an open sim +dimsim eval --headless --scene apartment # full headless run (CI) +``` + +## Build manually + +```bash +npm install # browser deps (three, rapier, spark, vite) +npm run build # → dist/ +``` diff --git a/misc/DimSim/cli/agent.py b/misc/DimSim/cli/agent.py new file mode 100644 index 0000000000..4f9a4d10a3 --- /dev/null +++ b/misc/DimSim/cli/agent.py @@ -0,0 +1,90 @@ +#!/usr/bin/env python3 +""" +DimSim Agent — runs the dimos nav + agent stack connected to DimSim via LCM. + +DimSim acts as the robot (like simplerobot.py but richer): + - Publishes: /odom, /color_image, /lidar, /depth_image + - Subscribes: /cmd_vel + +This script runs the dimos brain that processes those sensors and sends commands. + +Usage (run with dimos venv): + ../dimos/.venv/bin/python cli/agent.py + ../dimos/.venv/bin/python cli/agent.py --nav-only # no LLM agent, just exploration +""" + +import argparse + +from dimos.core.blueprints import autoconnect +from dimos.core.transport import JpegLcmTransport, LCMTransport +from dimos.mapping.costmapper import cost_mapper +from dimos.mapping.voxels import voxel_mapper +from dimos.msgs.geometry_msgs import PoseStamped, Twist +from dimos.msgs.sensor_msgs import Image, PointCloud2 +from dimos.navigation.frontier_exploration import wavefront_frontier_explorer +from dimos.navigation.replanning_a_star.module import replanning_a_star_planner +from dimos.protocol.service.lcmservice import autoconf + +# LCM transports — same channels DimSim publishes/subscribes on. +_transports = { + ("color_image", Image): JpegLcmTransport("/color_image", Image), + ("odom", PoseStamped): LCMTransport("/odom", PoseStamped), + ("cmd_vel", Twist): LCMTransport("/cmd_vel", Twist), + ("lidar", PointCloud2): LCMTransport("/lidar", PointCloud2), +} + +# Navigation stack: LiDAR → voxels → costmap → frontier explorer → path planner +nav = ( + autoconnect( + voxel_mapper(voxel_size=0.1), + cost_mapper(algo="simple"), + replanning_a_star_planner(), + wavefront_frontier_explorer(), + ) + .transports(_transports) + .global_config(n_dask_workers=6, robot_model="dimsim") +) + + +def build_agentic(): + """Full agentic: nav + spatial memory + LLM agent + skills.""" + from dimos.agents.agent import llm_agent + from dimos.agents.cli.human import human_input + from dimos.agents.cli.web import web_input + from dimos.agents.skills.navigation import navigation_skill + from dimos.agents.skills.speak_skill import speak_skill + from dimos.perception.spatial_perception import spatial_memory + from dimos.utils.monitoring import utilization + + return autoconnect( + nav, + spatial_memory(), + utilization(), + llm_agent(), + human_input(), + navigation_skill(), + web_input(), + speak_skill(), + ).global_config(n_dask_workers=8) + + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description="DimSim dimos agent") + parser.add_argument( + "--nav-only", + action="store_true", + help="Run nav stack only (no LLM agent)", + ) + args = parser.parse_args() + + autoconf() + + blueprint = nav if args.nav_only else build_agentic() + coordinator = blueprint.build() + + print("DimSim agent running.") + print(" Subscribing: /odom, /color_image, /lidar") + print(" Publishing: /cmd_vel") + print(" Ctrl+C to exit") + + coordinator.loop() diff --git a/misc/DimSim/cli/bridge/lidar.ts b/misc/DimSim/cli/bridge/lidar.ts new file mode 100644 index 0000000000..c2e451c6cd --- /dev/null +++ b/misc/DimSim/cli/bridge/lidar.ts @@ -0,0 +1,309 @@ +/** + * Server-side LiDAR raycasting using Rapier physics world snapshot. + * + * Runs 20K Fibonacci-sphere raycasts at 5 Hz on the Deno bridge server, + * encodes PointCloud2 via @dimos/msgs, and publishes directly to LCM — + * no WebSocket hop needed. + */ + +import { + sensor_msgs, + std_msgs, +} from "@dimos/msgs"; +import type { LCM } from "../vendor/lcm/lcm.ts"; + +// -- Lidar constants (must match engine.js) ----------------------------------- +const NUM_POINTS = 15000; +const MIN_RANGE = 0.1; +const MAX_RANGE = 4; +const V_MIN_RAD = (-30 * Math.PI) / 180; +const V_MAX_RAD = (15 * Math.PI) / 180; +// 5 Hz — at 15k raycasts per scan, 10 Hz starves the physics setInterval +// (each scan takes 25-30ms on M4, ~60-80ms on weaker runners). 5 Hz halves +// the per-second blocking budget and matches typical low-end LiDAR rates +// (RPLIDAR, low-Velodyne). Module docstring already advertised 5 Hz. +const RATE_MS = 200; // 5 Hz + +const CH_LIDAR = "/lidar#sensor_msgs.PointCloud2"; + +// Agent capsule geometry → lidar mount offset (must match engine.js) +const DEFAULT_HALF_HEIGHT = 0.25; +const DEFAULT_RADIUS = 0.12; +const DEFAULT_LIDAR_MOUNT = 0.35; + +/** Subset of EmbodimentConfig relevant to lidar mount offset. */ +export interface LidarEmbodimentConfig { + radius?: number; + halfHeight?: number; + lidarMountHeight?: number; +} + +// -- _lidarToCamQuat: transforms FLU (x=forward, y=left, z=up) → Three.js camera-local -- +// Matches engine.js _lidarToCamQuat derived from rotation matrix: +// FLU x(forward) → cam -z, FLU y(left) → cam -x, FLU z(up) → cam +y +// Quaternion: (0.5, -0.5, -0.5, -0.5) +const L2C_QX = 0.5, L2C_QY = -0.5, L2C_QZ = -0.5, L2C_QW = -0.5; + +// -- Pre-compute Fibonacci sphere ray directions (pre-rotated to camera-local) - +// Directions are computed in FLU frame then rotated by _lidarToCamQuat so that +// only the agent's yaw quaternion is needed at scan time (cam-local → world). +const fibDirs = (() => { + const golden = (1 + Math.sqrt(5)) / 2; + const zMin = Math.sin(V_MIN_RAD); + const zMax = Math.sin(V_MAX_RAD); + const dirs = new Float32Array(NUM_POINTS * 3); + for (let i = 0; i < NUM_POINTS; i++) { + const z = zMin + (zMax - zMin) * (i + 0.5) / NUM_POINTS; + const r = Math.sqrt(1 - z * z); + const phi = (2 * Math.PI * i) / golden; + const fx = r * Math.cos(phi); // FLU x + const fy = r * Math.sin(phi); // FLU y + const fz = z; // FLU z + + // Rotate FLU → camera-local using _lidarToCamQuat + const tx = 2 * (L2C_QY * fz - L2C_QZ * fy); + const ty = 2 * (L2C_QZ * fx - L2C_QX * fz); + const tz = 2 * (L2C_QX * fy - L2C_QY * fx); + dirs[i * 3 + 0] = fx + L2C_QW * tx + (L2C_QY * tz - L2C_QZ * ty); + dirs[i * 3 + 1] = fy + L2C_QW * ty + (L2C_QZ * tx - L2C_QX * tz); + dirs[i * 3 + 2] = fz + L2C_QW * tz + (L2C_QX * ty - L2C_QY * tx); + } + return dirs; +})(); + +// -- Quaternion rotation helper (q * v) --------------------------------------- +function rotateByQuat( + vx: number, vy: number, vz: number, + qx: number, qy: number, qz: number, qw: number, +): [number, number, number] { + // t = 2 * cross(q.xyz, v) + const tx = 2 * (qy * vz - qz * vy); + const ty = 2 * (qz * vx - qx * vz); + const tz = 2 * (qx * vy - qy * vx); + // result = v + qw * t + cross(q.xyz, t) + return [ + vx + qw * tx + (qy * tz - qz * ty), + vy + qw * ty + (qz * tx - qx * tz), + vz + qw * tz + (qx * ty - qy * tx), + ]; +} + +// -- ServerLidar -------------------------------------------------------------- + +export class ServerLidar { + // Resolved once at module load; hot-path callers should not Deno.env.get every scan. + static readonly PROFILE = Deno.env.get("DIMSIM_PROFILE_PHYSICS") === "1"; + + private lcm: LCM; + private world: any; // RAPIER.World + private RAPIER: any; + private sentSeqs: Set; // echo filter shared with bridge server + private timer: ReturnType | null = null; + private scanCount = 0; + private logN = 0; + private publishing = false; // busy guard — skip scan if previous publish still in flight + private excludeBody: any = null; // rigid body to exclude from raycasting (agent's own colliders) + private lidarYOffset: number; + + // Current robot pose (Three.js Y-up world frame) + private px = 0; + private py = 0; + private pz = 0; + private qx = 0; + private qy = 0; + private qz = 0; + private qw = 1; + private hasPose = false; + + private ray: any; // Reusable Ray object (avoids 20k allocations per scan) + + constructor(lcm: LCM, rapierWorld: any, RAPIER: any, sentSeqs: Set, embodiment?: LidarEmbodimentConfig) { + this.lcm = lcm; + this.world = rapierWorld; + this.RAPIER = RAPIER; + this.sentSeqs = sentSeqs; + this.ray = new RAPIER.Ray({ x: 0, y: 0, z: 0 }, { x: 0, y: 0, z: 1 }); + + const halfH = embodiment?.halfHeight ?? DEFAULT_HALF_HEIGHT; + const radius = embodiment?.radius ?? DEFAULT_RADIUS; + const mount = embodiment?.lidarMountHeight ?? DEFAULT_LIDAR_MOUNT; + this.lidarYOffset = mount - (halfH + radius); + + // Step once with zero dt to initialize the query pipeline after snapshot restore. + // queryPipeline.update() crashes on restored worlds (WASM type mismatch), + // but world.step() internally updates the pipeline correctly. + this.world.step(); + } + + /** Reconfigure lidar mount offset after embodiment change. */ + reconfigure(embodiment: LidarEmbodimentConfig): void { + const halfH = embodiment.halfHeight ?? DEFAULT_HALF_HEIGHT; + const radius = embodiment.radius ?? DEFAULT_RADIUS; + const mount = embodiment.lidarMountHeight ?? DEFAULT_LIDAR_MOUNT; + this.lidarYOffset = mount - (halfH + radius); + console.log(`[lidar] reconfigured: lidarYOffset=${this.lidarYOffset.toFixed(3)}`); + } + + /** Set rigid body to exclude from raycasting (agent's own capsule). */ + setExcludeBody(body: any): void { + this.excludeBody = body; + } + + /** Update robot pose. Position is capsule center (odom); we apply lidar mount offset internally. */ + updatePose(x: number, y: number, z: number, qx: number, qy: number, qz: number, qw: number): void { + this.px = x; + this.py = y + this.lidarYOffset; // capsule center → lidar mount height + this.pz = z; + this.qx = qx; + this.qy = qy; + this.qz = qz; + this.qw = qw; + this.hasPose = true; + } + + start(): void { + if (this.timer) return; + // quiet + this.timer = setInterval(() => this._scan(), RATE_MS); + } + + stop(): void { + if (this.timer) { + clearInterval(this.timer); + this.timer = null; + } + } + + private _scan(): void { + if (!this.hasPose || this.publishing) return; + this.publishing = true; + this._doScan().catch((e) => { + console.warn("[lidar] publish error (dropped frame):", e?.message || e); + }).finally(() => { this.publishing = false; }); + } + + private async _doScan(): Promise { + const profile = ServerLidar.PROFILE; + const scanStart = profile ? performance.now() : 0; + this.scanCount++; + const jitterAngle = this.scanCount * 2.399963; // golden angle per scan + const cosJ = Math.cos(jitterAngle); + const sinJ = Math.sin(jitterAngle); + + const RAPIER = this.RAPIER; + const world = this.world; + + // Pre-allocate output buffers + const worldPts = new Float32Array(NUM_POINTS * 3); + const intensity = new Float32Array(NUM_POINTS); + let n = 0; + + const ox = this.px, oy = this.py, oz = this.pz; + const rqx = this.qx, rqy = this.qy, rqz = this.qz, rqw = this.qw; + + const raycastStart = profile ? performance.now() : 0; + + for (let i = 0; i < NUM_POINTS; i++) { + // Fibonacci direction (pre-rotated to camera-local) with per-scan golden angle jitter. + // In FLU frame, jitter rotates around Z (up). After lidarToCamQuat, FLU Z → cam Y, + // so jitter must rotate around camera-local Y axis. + const fx = fibDirs[i * 3 + 0], fy = fibDirs[i * 3 + 1], fz = fibDirs[i * 3 + 2]; + const lx = fx * cosJ + fz * sinJ; + const ly = fy; + const lz = -fx * sinJ + fz * cosJ; + + // Rotate local direction by robot quaternion → world direction + const [dx, dy, dz] = rotateByQuat(lx, ly, lz, rqx, rqy, rqz, rqw); + const len = Math.sqrt(dx * dx + dy * dy + dz * dz); + if (len < 1e-8) continue; + const nx = dx / len, ny = dy / len, nz = dz / len; + + // Reuse ray object — avoids 20k allocations per scan + this.ray.origin.x = ox; this.ray.origin.y = oy; this.ray.origin.z = oz; + this.ray.dir.x = nx; this.ray.dir.y = ny; this.ray.dir.z = nz; + // Use world.castRay (not queryPipeline.castRayAndGetNormal) — + // the pipeline API crashes on restored snapshot worlds. + // Exclude agent's own rigid body so lidar doesn't hit its own colliders. + const hit = world.castRay( + this.ray, MAX_RANGE, false, + undefined, undefined, undefined, + this.excludeBody, + ); + + if (!hit) continue; + const toi = hit.timeOfImpact ?? 0; + if (toi < MIN_RANGE || toi > MAX_RANGE) continue; + + worldPts[n * 3 + 0] = ox + nx * toi; + worldPts[n * 3 + 1] = oy + ny * toi; + worldPts[n * 3 + 2] = oz + nz * toi; + intensity[n] = 1.0 / (1.0 + 0.02 * toi * toi); + n++; + } + + const raycastEnd = profile ? performance.now() : 0; + + if (n === 0) return; + + this.logN++; + // scan logging removed — too noisy + + // Encode PointCloud2: Y-up → Z-up (ROS) cyclic permutation x→y, y→z, z→x + const pointStep = 16; + const buf = new ArrayBuffer(n * pointStep); + const view = new DataView(buf); + + for (let i = 0; i < n; i++) { + const off = i * pointStep; + const tx = worldPts[i * 3 + 0]; + const ty = worldPts[i * 3 + 1]; + const tz = worldPts[i * 3 + 2]; + view.setFloat32(off, tz, true); // ROS x = Three.js z + view.setFloat32(off + 4, tx, true); // ROS y = Three.js x + view.setFloat32(off + 8, ty, true); // ROS z = Three.js y + view.setFloat32(off + 12, intensity[i], true); + } + + const now = Date.now(); + const header = new std_msgs.Header({ + stamp: new std_msgs.Time({ sec: Math.floor(now / 1000), nsec: (now % 1000) * 1_000_000 }), + frame_id: "world", + }); + + const msg = new sensor_msgs.PointCloud2({ + header, + height: 1, + width: n, + fields_length: 4, + fields: [ + new sensor_msgs.PointField({ name: "x", offset: 0, datatype: 7, count: 1 }), + new sensor_msgs.PointField({ name: "y", offset: 4, datatype: 7, count: 1 }), + new sensor_msgs.PointField({ name: "z", offset: 8, datatype: 7, count: 1 }), + new sensor_msgs.PointField({ name: "intensity", offset: 12, datatype: 7, count: 1 }), + ], + is_bigendian: false, + point_step: pointStep, + row_step: n * pointStep, + data_length: n * pointStep, + data: new Uint8Array(buf), + is_dense: true, + }); + + // Mark seq for echo filtering (prevent server re-forwarding to browser WS) + this.sentSeqs.add(this.lcm.getNextSeq()); + // Publish directly to LCM — no WS hop (await so buffer pressure is felt) + await this.lcm.publish(CH_LIDAR, msg); + + if (profile) { + const total = performance.now() - scanStart; + const raycast = raycastEnd - raycastStart; + // Log every scan — there are only 10 per second. + if (this.scanCount % 5 === 0) { + console.log( + `[lidar-prof] scan=${this.scanCount} raycast=${raycast.toFixed(1)}ms ` + + `total=${total.toFixed(1)}ms hits=${n}/${NUM_POINTS}` + ); + } + } + } +} diff --git a/misc/DimSim/cli/bridge/physics.ts b/misc/DimSim/cli/bridge/physics.ts new file mode 100644 index 0000000000..c3e5ec30fc --- /dev/null +++ b/misc/DimSim/cli/bridge/physics.ts @@ -0,0 +1,502 @@ +/** + * Server-side agent physics (Deno/Rapier). + * + * Runs the agent's kinematic character controller at a fixed timestep on the + * server, eliminating the browser from the control loop: + * + * Python cmd_vel → LCM → Deno (physics step) → LCM odom → Python + * ↓ + * WS position → Browser (render only) + * + * The browser no longer integrates cmd_vel or steps physics — it just receives + * position updates and moves the visual avatar. + */ + +import { geometry_msgs, std_msgs } from "@dimos/msgs"; + +import type { LCM } from "../vendor/lcm/lcm.ts"; + +// -- Agent dimensions (must match AiAvatar.js / engine.js) -------------------- +const DEFAULT_AGENT_RADIUS = 0.12; +const DEFAULT_AGENT_HALF_HEIGHT = 0.25; +const CONTROLLER_OFFSET = 0.05; + +// -- Physics constants -------------------------------------------------------- +const PHYSICS_HZ = 50; +const PHYSICS_DT = 1.0 / PHYSICS_HZ; +const DEFAULT_GRAVITY_Y = -9.81; +const DEFAULT_SPEED_SCALE = 3.0; // Multiplier for cmd_vel (linear + angular) +const DEFAULT_TURN_SCALE = 3.0; +const DEFAULT_MAX_ALTITUDE = 50; + +/** Embodiment configuration passed from SceneClient / control channel. */ +export interface EmbodimentConfig { + radius?: number; + halfHeight?: number; + lidarMountHeight?: number; + embodimentType?: string; // "ground" | "drone" + maxSpeed?: number; + turnRate?: number; + gravity?: number; + maxStepHeight?: number; + groundSnapDist?: number; + maxSlopeAngle?: number; + friction?: number; + maxAltitude?: number; +} + +const CH_ODOM = "/odom#geometry_msgs.PoseStamped"; +const CH_CMD_VEL = "/cmd_vel#geometry_msgs.Twist"; +const CMD_VEL_TIMEOUT_MS = 500; + +// -- ServerPhysics ------------------------------------------------------------ + +export class ServerPhysics { + private lcm: LCM; + private world: any; // RAPIER.World + private RAPIER: any; + private sentSeqs: Set; + + private body: any; + private collider: any; + private spineCollider: any; + private controller: any; + private timer: ReturnType | null = null; + + // Embodiment params + private embodimentType: string; + private speedScale: number; + private turnScale: number; + private gravity: number; + private maxAltitude: number; + private agentRadius: number; + private agentHalfHeight: number; + private friction: number; + private maxStepHeight: number; + private groundSnapDist: number; + private maxSlopeAngle: number; + + // Agent state + private yaw = 0; + private seq = 0; + + // Profiling (DIMSIM_PROFILE_PHYSICS=1) — rolling timing per phase. + private profile = false; + private lastStepStart = 0; + private prof = { + n: 0, + sumCompute: 0, maxCompute: 0, + sumStep: 0, maxStep: 0, + sumPublish: 0, maxPublish: 0, + sumTotal: 0, maxTotal: 0, + sumInterval: 0, maxInterval: 0, + }; + + // cmd_vel (ROS frame: x=fwd, z=yaw) + private linX = 0; // forward + private linY = 0; // lateral + private linZ = 0; // vertical + private angZ = 0; // yaw rotation + private cmdVelStamp = 0; + + // Callback to send position to browser + private onPoseUpdate: ((x: number, y: number, z: number, yaw: number) => void) | null = null; + + private userColliders = new Map(); + + constructor( + lcm: LCM, + rapierWorld: any, + RAPIER: any, + sentSeqs: Set, + embodiment?: EmbodimentConfig, + ) { + this.lcm = lcm; + this.world = rapierWorld; + this.RAPIER = RAPIER; + this.sentSeqs = sentSeqs; + + // Apply embodiment config with defaults + this.embodimentType = embodiment?.embodimentType ?? "ground"; + this.speedScale = embodiment?.maxSpeed ?? DEFAULT_SPEED_SCALE; + this.turnScale = embodiment?.turnRate ?? DEFAULT_TURN_SCALE; + this.gravity = embodiment?.gravity ?? DEFAULT_GRAVITY_Y; + this.maxAltitude = embodiment?.maxAltitude ?? DEFAULT_MAX_ALTITUDE; + this.agentRadius = embodiment?.radius ?? DEFAULT_AGENT_RADIUS; + this.agentHalfHeight = embodiment?.halfHeight ?? DEFAULT_AGENT_HALF_HEIGHT; + this.friction = embodiment?.friction ?? 0.8; + this.maxStepHeight = embodiment?.maxStepHeight ?? 0.25; + this.groundSnapDist = embodiment?.groundSnapDist ?? 0.5; + this.maxSlopeAngle = embodiment?.maxSlopeAngle ?? 45; + + this._createBodyAndColliders(); + + // Count colliders to verify world integrity + let colliderCount = 0; + this.world.colliders.forEach(() => { colliderCount++; }); + // Quiet init — only log on error or reconfigure + + this.profile = Deno.env.get("DIMSIM_PROFILE_PHYSICS") === "1"; + if (this.profile) { + console.log(`[physics-prof] enabled — colliderCount=${colliderCount} target=${PHYSICS_HZ}Hz (${(1000 / PHYSICS_HZ).toFixed(1)}ms interval)`); + } + } + + private _createBodyAndColliders(): void { + const RAPIER = this.RAPIER; + + // Create agent body (kinematic position-based, like AiAvatar) + this.body = this.world.createRigidBody( + RAPIER.RigidBodyDesc.kinematicPositionBased().setTranslation(0, 3, 0), + ); + + // Main capsule collider + this.collider = this.world.createCollider( + RAPIER.ColliderDesc.capsule(this.agentHalfHeight, this.agentRadius) + .setFriction(this.friction), + this.body, + ); + + // Spine collider (horizontal, behind body center — matches AiAvatar) + const spineHalfLen = Math.max(this.agentRadius * 1.2, 0.13); + const spineRadius = Math.max(this.agentRadius * 0.62, 0.07); + const spineOffsetBack = Math.max( + this.agentRadius * 2.2, + spineHalfLen + spineRadius + 0.02, + ); + const spineOffsetY = Math.max(this.agentHalfHeight * 0.35, 0.08); + this.spineCollider = this.world.createCollider( + RAPIER.ColliderDesc.capsule(spineHalfLen, spineRadius) + .setFriction(this.friction) + .setTranslation(0, spineOffsetY, -spineOffsetBack) + .setRotation({ + x: Math.SQRT1_2, + y: 0, + z: 0, + w: Math.SQRT1_2, + }), + this.body, + ); + + // Character controller + this.controller = this.world.createCharacterController(CONTROLLER_OFFSET); + this.controller.enableAutostep(this.maxStepHeight, 0.15, true); + this.controller.enableSnapToGround(this.groundSnapDist); + this.controller.setSlideEnabled(true); + this.controller.setMaxSlopeClimbAngle((this.maxSlopeAngle * Math.PI) / 180); + this.controller.setMinSlopeSlideAngle((75 * Math.PI) / 180); + } + + /** Reconfigure physics with new embodiment params (e.g. after set_embodiment). */ + reconfigure(embodiment: EmbodimentConfig): void { + // Save current position and yaw + const pos = this.body.translation(); + const savedYaw = this.yaw; + + // Update params + this.embodimentType = embodiment.embodimentType ?? this.embodimentType; + this.speedScale = embodiment.maxSpeed ?? this.speedScale; + this.turnScale = embodiment.turnRate ?? this.turnScale; + this.gravity = embodiment.gravity ?? this.gravity; + this.maxAltitude = embodiment.maxAltitude ?? this.maxAltitude; + this.agentRadius = embodiment.radius ?? this.agentRadius; + this.agentHalfHeight = embodiment.halfHeight ?? this.agentHalfHeight; + this.friction = embodiment.friction ?? this.friction; + this.maxStepHeight = embodiment.maxStepHeight ?? this.maxStepHeight; + this.groundSnapDist = embodiment.groundSnapDist ?? this.groundSnapDist; + this.maxSlopeAngle = embodiment.maxSlopeAngle ?? this.maxSlopeAngle; + + // Remove old colliders and body + if (this.spineCollider) this.world.removeCollider(this.spineCollider, false); + if (this.collider) this.world.removeCollider(this.collider, false); + if (this.body) this.world.removeRigidBody(this.body); + + // Recreate with new params + this._createBodyAndColliders(); + + // Restore position and yaw + this.body.setNextKinematicTranslation({ x: pos.x, y: pos.y, z: pos.z }); + this.yaw = savedYaw; + this.world.step(); + + console.log(`[physics] reconfigured: type=${this.embodimentType} radius=${this.agentRadius} halfHeight=${this.agentHalfHeight} speed=${this.speedScale} gravity=${this.gravity}`); + } + + /** Set spawn position (Three.js Y-up). */ + setPosition(x: number, y: number, z: number): void { + this.body.setNextKinematicTranslation({ x, y, z }); + this.world.step(); // apply immediately + // quiet + } + + /** Add a user-authored collider to the world. The browser sends these via + * `physicsColliderAdd` when scenes are edited live (SceneClient.add_object, + * load_map, etc.). Without this the agent has no floor to stand on. */ + addCollider(uuid: string, desc: any): void { + if (!desc || this.userColliders.has(uuid)) return; + const RAPIER = this.RAPIER; + const clamp = (v: number) => Math.max(0.001, v); + let cd: any; + if (desc.shape === "sphere" && desc.radius != null) { + cd = RAPIER.ColliderDesc.ball(clamp(desc.radius)); + } else if (desc.shape === "trimesh" && desc.vertices && desc.indices) { + cd = RAPIER.ColliderDesc.trimesh( + new Float32Array(desc.vertices), + new Uint32Array(desc.indices), + ); + } else if (desc.halfExtents) { + const h = desc.halfExtents; + cd = RAPIER.ColliderDesc.cuboid(clamp(h.x), clamp(h.y), clamp(h.z)); + } else { + return; + } + cd.setFriction(0.9); + if (desc.restitution != null) cd.setRestitution(desc.restitution); + const pos = desc.position ?? { x: 0, y: 0, z: 0 }; + if (desc.dynamic) { + const body = this.world.createRigidBody( + RAPIER.RigidBodyDesc.dynamic().setTranslation(pos.x, pos.y, pos.z), + ); + if (desc.mass != null) body.setAdditionalMass(desc.mass); + const collider = this.world.createCollider(cd, body); + this.userColliders.set(uuid, { collider, body }); + } else { + cd.setTranslation(pos.x, pos.y, pos.z); + const collider = this.world.createCollider(cd); + this.userColliders.set(uuid, { collider, body: null }); + } + } + + removeCollider(uuid: string): void { + const entry = this.userColliders.get(uuid); + if (!entry) return; + if (entry.body) { + this.world.removeRigidBody(entry.body); + } else if (entry.collider) { + this.world.removeCollider(entry.collider, false); + } + this.userColliders.delete(uuid); + } + + /** Drop every user-authored collider — used when an explicit re-load + * of a level clears the existing scene content. */ + clearUserColliders(): void { + for (const uuid of [...this.userColliders.keys()]) { + this.removeCollider(uuid); + } + } + + /** Set callback for browser position sync. */ + setOnPoseUpdate( + cb: (x: number, y: number, z: number, yaw: number) => void, + ): void { + this.onPoseUpdate = cb; + } + + /** Handle incoming cmd_vel (ROS frame). */ + handleCmdVel(twist: any): void { + this.linX = twist.linear.x; // forward (ROS +x) + this.linY = twist.linear.y; // lateral + this.linZ = twist.linear.z; // vertical + this.angZ = twist.angular.z; // yaw (ROS +z = rotate left) + this.cmdVelStamp = Date.now(); + } + + /** Subscribe to cmd_vel on LCM. */ + subscribeCmdVel(): void { + this.lcm.subscribe(CH_CMD_VEL, geometry_msgs.Twist, (msg: any) => { + this.handleCmdVel(msg.data); + }); + // quiet + } + + /** Start fixed-rate physics stepping + odom publish. */ + start(): void { + if (this.timer) return; + this.subscribeCmdVel(); + this.timer = setInterval(() => this._step(), 1000 / PHYSICS_HZ); + // quiet + } + + stop(): void { + if (this.timer) { + clearInterval(this.timer); + this.timer = null; + } + } + + /** Get current position in Three.js Y-up frame. */ + getPosition(): { x: number; y: number; z: number } { + return this.body.translation(); + } + + /** Get the agent's rigid body (for lidar exclusion). */ + getBody(): any { + return this.body; + } + + getYaw(): number { + return this.yaw; + } + + private _step(): void { + const stepStart = this.profile ? performance.now() : 0; + if (this.profile && this.lastStepStart) { + const interval = stepStart - this.lastStepStart; + this.prof.sumInterval += interval; + if (interval > this.prof.maxInterval) this.prof.maxInterval = interval; + } + this.lastStepStart = stepStart; + + // Safety timeout — zero velocity if no cmd_vel received recently + const hasVel = Date.now() - this.cmdVelStamp < CMD_VEL_TIMEOUT_MS; + const linX = hasVel ? this.linX * this.speedScale : 0; + const linY = hasVel ? this.linY * this.speedScale : 0; + const linZ = hasVel ? this.linZ * this.speedScale : 0; + const angZ = hasVel ? this.angZ * this.turnScale : 0; + + // Integrate yaw (ROS angZ → Three.js Y rotation) + // ROS +z yaw = CCW from above = Three.js +Y rotation + this.yaw += angZ * PHYSICS_DT; + + const pos = this.body.translation(); + const cosY = Math.cos(this.yaw); + const sinY = Math.sin(this.yaw); + + let newPos: { x: number; y: number; z: number }; + + if (this.embodimentType === "drone") { + // Drone: 6DoF movement, no gravity, altitude clamping + const fwd = linX; + const lat = linY; + const vert = linZ; // ROS z = vertical for drone + const desired = { + x: (fwd * sinY + lat * cosY) * PHYSICS_DT, + y: vert * PHYSICS_DT, + z: (fwd * cosY - lat * sinY) * PHYSICS_DT, + }; + + this.controller.computeColliderMovement( + this.collider, + desired, + this.RAPIER.QueryFilterFlags.EXCLUDE_SENSORS, + ); + const m = this.controller.computedMovement(); + newPos = { + x: pos.x + m.x, + y: Math.min(pos.y + m.y, this.maxAltitude), + z: pos.z + m.z, + }; + } else { + // Ground robot: gravity, collision-aware + const fwd = linX; + const desired = { + x: (fwd * sinY) * PHYSICS_DT, + y: this.gravity * PHYSICS_DT * PHYSICS_DT * 0.5, // gravity + z: (fwd * cosY) * PHYSICS_DT, + }; + + this.controller.computeColliderMovement( + this.collider, + desired, + this.RAPIER.QueryFilterFlags.EXCLUDE_SENSORS, + ); + const m = this.controller.computedMovement(); + newPos = { + x: pos.x + m.x, + y: pos.y + m.y, + z: pos.z + m.z, + }; + } + + this.body.setNextKinematicTranslation(newPos); + + const computeEnd = this.profile ? performance.now() : 0; + + // Step world to apply kinematic translation (needed for next computeColliderMovement) + this.world.step(); + + const stepEnd = this.profile ? performance.now() : 0; + + // Publish odom to LCM (Three.js Y-up → ROS Z-up) + this._publishOdom(newPos); + + // Notify browser for visual sync + if (this.onPoseUpdate) { + this.onPoseUpdate(newPos.x, newPos.y, newPos.z, this.yaw); + } + + if (this.profile) { + const publishEnd = performance.now(); + const compute = computeEnd - stepStart; + const step = stepEnd - computeEnd; + const publish = publishEnd - stepEnd; + const total = publishEnd - stepStart; + const p = this.prof; + p.n++; + p.sumCompute += compute; if (compute > p.maxCompute) p.maxCompute = compute; + p.sumStep += step; if (step > p.maxStep) p.maxStep = step; + p.sumPublish += publish; if (publish > p.maxPublish) p.maxPublish = publish; + p.sumTotal += total; if (total > p.maxTotal) p.maxTotal = total; + + // Log rolling averages every 20 steps (~0.4s at 50Hz target, ~4s at 5Hz actual). + if (p.n >= 20) { + const intervalAvg = p.sumInterval / Math.max(p.n - 1, 1); + const effHz = intervalAvg > 0 ? 1000 / intervalAvg : 0; + console.log( + `[physics-prof] n=${p.n} ` + + `compute=${(p.sumCompute / p.n).toFixed(2)}/${p.maxCompute.toFixed(1)}ms ` + + `step=${(p.sumStep / p.n).toFixed(2)}/${p.maxStep.toFixed(1)}ms ` + + `pub=${(p.sumPublish / p.n).toFixed(2)}/${p.maxPublish.toFixed(1)}ms ` + + `total=${(p.sumTotal / p.n).toFixed(2)}/${p.maxTotal.toFixed(1)}ms ` + + `interval=${intervalAvg.toFixed(1)}/${p.maxInterval.toFixed(1)}ms ` + + `effHz=${effHz.toFixed(1)}` + ); + // reset rolling counters but keep maxima — useful to spot worst-case drift + p.n = 0; + p.sumCompute = p.sumStep = p.sumPublish = p.sumTotal = p.sumInterval = 0; + } + } + } + + private _publishOdom(pos: { x: number; y: number; z: number }): void { + // Three.js Y-up → ROS Z-up: (x,y,z) → (z,x,y) + const rosX = pos.z; + const rosY = pos.x; + const rosZ = pos.y; + + // Yaw quaternion (Three.js Y-axis → ROS Z-axis) + const qw = Math.cos(this.yaw / 2); + const qRosZ = Math.sin(this.yaw / 2); // rotation about ROS Z + + const now = Date.now(); + + const header = new std_msgs.Header({ + seq: this.seq++, + stamp: new std_msgs.Time({ sec: Math.floor(now / 1000), nsec: (now % 1000) * 1_000_000 }), + frame_id: "world", + }); + + const pose = new geometry_msgs.Pose(); + pose.position = new geometry_msgs.Point(); + pose.position.x = rosX; + pose.position.y = rosY; + pose.position.z = rosZ; + pose.orientation = new geometry_msgs.Quaternion(); + pose.orientation.x = 0; + pose.orientation.y = 0; + pose.orientation.z = qRosZ; + pose.orientation.w = qw; + + const odom = new geometry_msgs.PoseStamped(); + odom.header = header; + odom.pose = pose; + + try { + this.sentSeqs.add(this.lcm.getNextSeq()); + this.lcm.publishRaw(CH_ODOM, odom.encode()).catch(() => {}); + } catch (e: unknown) { + if (this.seq <= 3) console.warn("[physics] odom publish error:", e); + } + } +} diff --git a/misc/DimSim/cli/bridge/server.ts b/misc/DimSim/cli/bridge/server.ts new file mode 100644 index 0000000000..0dd359cd76 --- /dev/null +++ b/misc/DimSim/cli/bridge/server.ts @@ -0,0 +1,508 @@ +#!/usr/bin/env -S deno run --allow-net --allow-read --unstable-net + +/** + * DimSim Bridge Server + * + * - One control WebSocket plus multiple sensor WebSockets. + * Separate TCP streams so large sensor data never blocks real-time odom + * or other sensor streams. + * - LCM multicast relay (WS ↔ LCM) + * - Per-channel isolation for multi-page parallel evals + * - Static file server for the pre-built DimSim frontend (dist/) + * - Uses vendored LCM transport with joinMulticastV4 fix + */ + +import { LCM } from "../vendor/lcm/lcm.ts"; +import { decodePacket } from "../vendor/lcm/transport.ts"; +import { MAGIC_SHORT, SHORT_HEADER_SIZE } from "../vendor/lcm/types.ts"; +import { serveDir } from "@std/http/file-server"; +import { ServerLidar } from "./lidar.ts"; +import { ServerPhysics } from "./physics.ts"; +import { geometry_msgs } from "@dimos/msgs"; + +// Magic prefix for Rapier world snapshot (ASCII "DSSN") +const SNAPSHOT_MAGIC = 0x4453534E; +const DEFAULT_LCM_PORT = 7667; +const DEFAULT_LCM_HOST = "239.255.76.67"; + +const SCENE_MIME: Record = { + js: "application/javascript; charset=utf-8", + mjs: "application/javascript; charset=utf-8", + json: "application/json; charset=utf-8", + glb: "model/gltf-binary", + gltf: "model/gltf+json", + bin: "application/octet-stream", + png: "image/png", + jpg: "image/jpeg", + jpeg: "image/jpeg", + webp: "image/webp", + avif: "image/avif", + ktx2: "image/ktx2", + hdr: "image/vnd.radiance", + exr: "image/x-exr", +}; + +export interface BridgeServerOptions { + port: number; + distDir: string; + scene?: string; + evalOnly?: boolean; + headless?: boolean; + channels?: string[]; + lcmBasePort?: number; + sensorRates?: Record; + sensorEnable?: Record; + cameraFov?: number; +} + +/** Per-channel state: each channel gets its own LCM, physics, lidar, and WS client sets. */ +interface ChannelState { + name: string; + controlClients: Set; + activeControlClient: WebSocket | null; + sensorClients: Set; + lcm: LCM | null; + sentSeqs: Set; + serverLidar: ServerLidar | null; + serverPhysics: ServerPhysics | null; + embodiment: Record | null; +} + +export async function startBridgeServer(options: BridgeServerOptions) { + const { + port, distDir, scene, + evalOnly = false, headless = false, + channels, lcmBasePort = DEFAULT_LCM_PORT, + sensorRates, sensorEnable, cameraFov, + } = options; + + // Scene the engine boots into. Injected as window.__dimosScene below so + // engine.js dynamically imports /scenes//index.js. Sanitize to a + // restricted charset so the value can't escape the `; + html = html.replace("", `${inject}\n`); + return new Response(html, { headers: { "content-type": "text/html; charset=utf-8" } }); + } catch { + return new Response("index.html not found", { status: 404 }); + } + } + + // JS scene project folders. Resolution order: + // 1. DIMSIM_SCENES_DIR env (dimos points this at user-authored scenes) + // 2. dist/scenes/ (shipped built-ins, when running from a built binary) + // 3. ../scenes/ (dev built-ins, when running directly from source) + if (url.pathname.startsWith("/scenes/")) { + const rel = url.pathname.slice("/scenes/".length); + const candidates = [ + Deno.env.get("DIMSIM_SCENES_DIR"), + `${distDir}/scenes`, + `${distDir}/../scenes`, + ].filter((d): d is string => !!d && d.length > 0); + for (const dir of candidates) { + try { + const filePath = `${dir}/${rel}`; + const data = await Deno.readFile(filePath); + const ext = rel.split(".").pop()?.toLowerCase() ?? ""; + const contentType = SCENE_MIME[ext] ?? "application/octet-stream"; + return new Response(data, { headers: { "content-type": contentType } }); + } catch { /* try next */ } + } + return new Response(`Scene file not found: ${rel}`, { status: 404 }); + } + + return serveDir(req, { fsRoot: distDir, quiet: true }); + }); + + const channelInfo = channelNames.length > 1 + ? ` (${channelNames.length} channels: ${channelNames.join(", ")})` + : ""; + console.log(`[bridge] :${port}${evalOnly ? " (eval-only)" : " (LCM bridge)"}${channelInfo}`); + + // Run all LCM instances + const lcmInstances = [...channelMap.values()].map(s => s.lcm).filter(Boolean) as LCM[]; + if (lcmInstances.length > 0) { + await Promise.all(lcmInstances.map(l => l.run())); + } else { + await new Promise(() => {}); + } +} + +if (import.meta.main) { + const distDir = new URL("../../dist", import.meta.url).pathname; + const scene = Deno.args.find((_a: string, i: number, arr: string[]) => arr[i - 1] === "--scene") || "apartment"; + const port = parseInt(Deno.args.find((_a: string, i: number, arr: string[]) => arr[i - 1] === "--port") || "8090"); + await startBridgeServer({ port, distDir, scene }); +} diff --git a/misc/DimSim/cli/cli.ts b/misc/DimSim/cli/cli.ts new file mode 100644 index 0000000000..78f828176a --- /dev/null +++ b/misc/DimSim/cli/cli.ts @@ -0,0 +1,437 @@ +#!/usr/bin/env -S deno run --allow-all --unstable-net + +/** + * DimSim CLI — 3D simulation + eval runner + dev server. + * + * Usage: + * dimsim dev [--scene ] [--port ] Dev server + browser + * dimsim eval Run one workflow (auto --connect) + * dimsim eval [--headless] [--parallel N] [--render gpu] Headless CI evals + * dimsim eval list List eval workflows + * dimsim agent [--nav-only] dimos Python agent + */ + +import { resolve, dirname, fromFileUrl } from "@std/path"; +import { startBridgeServer } from "./bridge/server.ts"; +import { launchHeadless, launchMultiPage, type RenderMode } from "./headless/launcher.ts"; +import { runEvals, runEvalsMultiPage, collectWorkflows, toJunitXml, type EvalResult } from "../evals/runner.ts"; + +const CLI_DIR = dirname(fromFileUrl(import.meta.url)); +const PROJECT_DIR = resolve(CLI_DIR, ".."); +const LOCAL_DIST_DIR = resolve(PROJECT_DIR, "dist"); +const SCENES_DIR = resolve(PROJECT_DIR, "scenes"); +const DIMOS_VENV = resolve(PROJECT_DIR, "../../.venv/bin/python"); +const AGENT_PY = resolve(CLI_DIR, "agent.py"); + +/** + * Build dist/ from the repo's own sources using Deno's npm compat. + * Everything needed is already in-tree: src/ (engine), public/ (scenes, + * embodiment, logo). Vite bundles src/ and copies public/ verbatim, so + * no assets need to be downloaded from GitHub releases, and npm/Node are + * not required — Deno runs Vite directly. + * + * Important for the vendored layout (misc/DimSim/ inside dimos): dist/ is + * gitignored and never committed, so on first run we have to materialize + * it ourselves rather than asking the user to `npm run build`. + * + * --no-lock keeps the repo's deno.lock (which tracks only JSR deps for + * the CLI) from being polluted with the frontend's npm dep graph. + */ +async function tryBuildFromSource( + projectDir: string, + distDir: string, +): Promise { + let viteSpec = "npm:vite@^5"; + try { + const pkg = JSON.parse(await Deno.readTextFile(`${projectDir}/package.json`)); + const v = pkg.devDependencies?.vite ?? pkg.dependencies?.vite; + if (!v) return false; + viteSpec = `npm:vite@${v}`; + } catch { + return false; + } + + // node_modules/ — install from package.json if missing. Vite resolves + // bare imports (three, rapier, etc.) via node_modules at build time. + try { + await Deno.stat(`${projectDir}/node_modules`); + } catch { + console.log(`[dimsim] node_modules/ not found — running 'deno install' (one-time)...`); + const install = new Deno.Command(Deno.execPath(), { + args: ["install", "--no-lock"], cwd: projectDir, + stdout: "inherit", stderr: "inherit", + }).spawn(); + const s = await install.status; + if (!s.success) { + console.error(`[dimsim] deno install failed (exit ${s.code}).`); + return false; + } + } + + console.log(`[dimsim] Building frontend with Vite...`); + const build = new Deno.Command(Deno.execPath(), { + args: ["run", "-A", "--no-lock", viteSpec, "build"], + cwd: projectDir, + stdout: "inherit", stderr: "inherit", + }).spawn(); + const bs = await build.status; + if (!bs.success) { + console.error(`[dimsim] vite build failed (exit ${bs.code}).`); + return false; + } + + try { + await Deno.stat(`${distDir}/index.html`); + return true; + } catch { + console.error(`[dimsim] Build completed but ${distDir}/index.html is missing.`); + return false; + } +} + +/** Resolve distDir: use local dist/ if present, otherwise build it from source. */ +async function resolveDistDir(): Promise { + try { + await Deno.stat(`${LOCAL_DIST_DIR}/index.html`); + return LOCAL_DIST_DIR; + } catch { /* not found — fall through to build */ } + + if (await tryBuildFromSource(PROJECT_DIR, LOCAL_DIST_DIR)) { + return LOCAL_DIST_DIR; + } + + console.error(`[dimsim] No dist/ found and tryBuildFromSource() failed.`); + console.error(`[dimsim] Build manually: cd ${PROJECT_DIR} && npm run build`); + Deno.exit(1); +} + +function printUsage() { + console.log(` +DimSim CLI — 3D simulation + eval harness for dimos + +Commands: + dimsim dev [options] Dev server (open browser, optional eval) + dimsim eval list List installed eval workflows + dimsim eval Run one workflow against an already-running bridge + dimsim eval [options] Run eval workflows (headless CI) + dimsim agent [options] Launch dimos Python agent + +Dev: + --scene Scene to load (default: apartment) + --port Server port (default: 8090) + --headless Launch headless browser (no GUI) + --render gpu|cpu Render mode for headless (default: gpu) + --channels Number of parallel browser pages (multi-instance) + --eval Run eval after browser connects + --env Environment filter + --image-rate Image publish interval in ms (default: 500 = 2 Hz) + --lidar-rate LiDAR publish interval in ms (default: 200 = 5 Hz) + --odom-rate Odom publish interval in ms (default: 20 = 50 Hz) + --no-depth Disable depth image publishing + --camera-fov Camera FOV in degrees (default: 80) + +Eval: + --connect Connect to existing bridge (use with dimos) + --headless Headless Chromium (required for CI) + --parallel N parallel browser pages (default: 1) + --render gpu|cpu gpu = Metal/ANGLE, cpu = SwiftShader (default: cpu) + --env Filter to environment + --workflow Filter to workflow + --output json|junit Output format (default: json) + --port Bridge port (default: 8090) + --timeout Engine init timeout (default: auto) + +Agent: + --nav-only Nav stack only (no LLM agent) + --venv Python venv path (default: ../../.venv/bin/python relative to misc/DimSim/) +`); +} + +function parseArgs(args: string[]) { + const opts: Record = {}; + for (let i = 0; i < args.length; i++) { + const arg = args[i]; + if (arg.startsWith("--")) { + const key = arg.slice(2); + const next = args[i + 1]; + if (next && !next.startsWith("--")) { + opts[key] = next; + i++; + } else { + opts[key] = true; + } + } + } + return opts; +} + +async function main() { + const subcommand = Deno.args[0]; + const opts = parseArgs(Deno.args.slice(1)); + + if (!subcommand || subcommand === "help" || subcommand === "--help") { + printUsage(); + Deno.exit(0); + } + + if (subcommand === "--version" || subcommand === "version") { + try { + const text = await Deno.readTextFile(new URL("./deno.json", import.meta.url)); + console.log(JSON.parse(text).version); + } catch { + console.log("unknown"); + } + Deno.exit(0); + } + + const port = parseInt(opts.port as string) || 8090; + + // ── Dev ───────────────────────────────────────────────────────────── + if (subcommand === "dev") { + const distDir = await resolveDistDir(); + const scene = (opts.scene as string) || "apartment"; + const headless = opts.headless === true; + const render = ((opts.render as string) === "cpu" ? "cpu" : "gpu") as RenderMode; + const numChannels = Math.max(1, parseInt(opts.channels as string) || 1); + const evalWorkflow = opts.eval as string | undefined; + + // Sensor publish rates (ms) — overrides browser defaults + const sensorRates: Record = {}; + if (opts["image-rate"]) sensorRates.images = parseInt(opts["image-rate"] as string); + if (opts["lidar-rate"]) sensorRates.lidar = parseInt(opts["lidar-rate"] as string); + if (opts["odom-rate"]) sensorRates.odom = parseInt(opts["odom-rate"] as string); + + // Sensor enable/disable (depth only — color and lidar are essential) + const sensorEnable: Record = {}; + if (opts["no-depth"] === true) sensorEnable.depth = false; + + // Camera FOV + const cameraFov = opts["camera-fov"] ? parseInt(opts["camera-fov"] as string) : undefined; + + // Build channel list for multi-instance mode + const channels = numChannels > 1 + ? Array.from({ length: numChannels }, (_, i) => `page-${i}`) + : undefined; + + console.log(`[dimsim] Dev mode — scene: ${scene}, port: ${port}${headless ? " (headless)" : ""}${channels ? ` (${numChannels} channels)` : ""}`); + console.log(`[dimsim] Serving from: ${distDir}`); + + // LCM bridge is always active in dev mode (unlike eval --headless which disables it) + startBridgeServer({ + port, distDir, scene, headless, channels, + sensorRates: Object.keys(sensorRates).length > 0 ? sensorRates : undefined, + sensorEnable: Object.keys(sensorEnable).length > 0 ? sensorEnable : undefined, + cameraFov, + }); + + if (headless) { + if (channels) { + // Multi-page mode: open N browser pages in one Chromium instance + console.log(`[dimsim] Launching headless browser with ${numChannels} pages...`); + const url = `http://localhost:${port}`; + await launchMultiPage({ url, numPages: numChannels, render, timeout: 120_000 }); + await new Promise((r) => setTimeout(r, 3000)); + console.log(`[dimsim] ${numChannels} headless pages ready. LCM bridge active.`); + } else { + console.log("[dimsim] Launching headless browser..."); + const url = `http://localhost:${port}`; + // CPU rendering with SwiftShader is slow — scene + agent init takes + // ~27s on CI Macs. Allow 90s by default; override via env var. + const headlessTimeout = parseInt( + Deno.env.get("DIMSIM_HEADLESS_TIMEOUT") || "90000", + ); + await launchHeadless({ url, timeout: headlessTimeout, render }); + await new Promise((r) => setTimeout(r, 3000)); + console.log("[dimsim] Headless browser ready. LCM bridge active."); + } + } else { + console.log(`[dimsim] Open http://localhost:${port} in your browser`); + } + + if (evalWorkflow) { + console.log(`[dimsim] Eval workflow: ${evalWorkflow}`); + console.log("[dimsim] Waiting for browser to connect and load scene...\n"); + + const results = await runEvals({ + wsUrl: `ws://localhost:${port}`, + scenesRoot: SCENES_DIR, + filterScene: opts.env as string, + filterWorkflow: evalWorkflow, + }); + + const passed = results.filter((r) => r.passed).length; + const failed = results.length - passed; + console.log(`\n[dimsim] Eval done: ${passed} passed, ${failed} failed`); + console.log("[dimsim] Server still running. Press Ctrl+C to stop."); + } else { + console.log("[dimsim] Press Ctrl+C to stop."); + } + + // Keep alive + await new Promise(() => {}); + } + + // ── Agent ─────────────────────────────────────────────────────────── + if (subcommand === "agent") { + const pythonBin = (opts.venv as string) || DIMOS_VENV; + const navOnly = opts["nav-only"] === true; + + // Verify python exists + try { + await Deno.stat(pythonBin); + } catch { + console.error(`[dimsim] dimos venv not found at: ${pythonBin}`); + console.error(`[dimsim] Install dimos first, or pass --venv /path/to/python`); + Deno.exit(1); + } + + const cmd = [pythonBin, AGENT_PY]; + if (navOnly) cmd.push("--nav-only"); + + console.log(`[dimsim] Starting dimos agent${navOnly ? " (nav-only)" : ""}...`); + console.log(`[dimsim] Python: ${pythonBin}`); + + const proc = new Deno.Command(cmd[0], { + args: cmd.slice(1), + stdin: "inherit", + stdout: "inherit", + stderr: "inherit", + env: { ...Deno.env.toObject() }, + }).spawn(); + + const status = await proc.status; + Deno.exit(status.code); + } + + // ── Eval list ─────────────────────────────────────────────────────── + if (subcommand === "eval" && Deno.args[1] === "list") { + const found = collectWorkflows({ scenesRoot: SCENES_DIR }); + if (found.length === 0) { + console.log(`\nNo eval workflows under ${SCENES_DIR}/*/evals/\n`); + Deno.exit(0); + } + const byScene = new Map(); + for (const wf of found) { + if (!byScene.has(wf.scene)) byScene.set(wf.scene, []); + byScene.get(wf.scene)!.push(wf.workflow); + } + const sorted = [...byScene.entries()].sort((a, b) => a[0].localeCompare(b[0])); + console.log(""); + for (const [scene, workflows] of sorted) { + console.log(` \x1b[1m${scene}\x1b[0m \x1b[2m(${workflows.length})\x1b[0m`); + workflows.sort(); + for (const w of workflows) console.log(` ${w}`); + } + console.log(`\n \x1b[2m${found.length} workflow(s) across ${sorted.length} scene(s)\x1b[0m\n`); + Deno.exit(0); + } + + // ── Eval ──────────────────────────────────────────────────────────── + if (subcommand === "eval") { + // Positional workflow: `dimsim eval go-to-tv` is shorthand for + // `dimsim eval --workflow go-to-tv --connect`. Accepts either bare + // workflow name ("go-to-tv") or scene-qualified ("apartment/go-to-tv"). + const positional = Deno.args[1] && !Deno.args[1].startsWith("--") ? Deno.args[1] : null; + let posScene: string | undefined; + let posWorkflow: string | undefined; + if (positional) { + const slash = positional.indexOf("/"); + if (slash !== -1) { + posScene = positional.slice(0, slash); + posWorkflow = positional.slice(slash + 1); + } else { + posWorkflow = positional; + } + } + // If a workflow was given positionally, default to --connect. Spinning up + // a fresh headless bridge for a one-off run during dev is rarely what you + // want; the common case is "the sim is already open, run this eval in it". + const connectMode = opts.connect === true || positional !== null; + const outputFormat = (opts.output as string) === "junit" ? "junit" : "json"; + const wsUrl = `ws://localhost:${port}`; + const filterScene = posScene ?? (opts.scene as string) ?? (opts.env as string); + const filterWorkflow = posWorkflow ?? (opts.workflow as string); + + // --connect mode: just run the runner against an existing bridge + if (connectMode) { + console.log(`[dimsim] Connecting to existing bridge at ${wsUrl}…`); + const results = await runEvals({ wsUrl, scenesRoot: SCENES_DIR, filterScene, filterWorkflow }); + if (outputFormat === "junit") console.log(toJunitXml(results)); + const passed = results.filter((r) => r.passed).length; + const failed = results.length - passed; + console.log(`\n[dimsim] Done: ${passed} passed, ${failed} failed, ${results.length} total`); + Deno.exit(failed > 0 ? 1 : 0); + } + + const distDir = await resolveDistDir(); + const headless = opts.headless === true; + const scene = (opts.scene as string) || (opts.env as string) || "apartment"; + const parallel = Math.max(1, parseInt(opts.parallel as string) || 1); + const render = ((opts.render as string) === "gpu" ? "gpu" : "cpu") as RenderMode; + const defaultTimeout = render === "cpu" ? 120000 : 30000; + const timeout = parseInt(opts.timeout as string) || defaultTimeout; + + if (headless && parallel > 1) { + const allWorkflows = collectWorkflows({ + scenesRoot: SCENES_DIR, filterScene, filterWorkflow, + }); + if (allWorkflows.length === 0) { + console.log("[dimsim] No workflows match filter criteria."); + Deno.exit(0); + } + const numPages = Math.min(parallel, allWorkflows.length); + console.log(`[dimsim] Multi-page eval — ${allWorkflows.length} workflows across ${numPages} page(s)`); + + startBridgeServer({ port, distDir, scene, evalOnly: true }); + await new Promise((r) => setTimeout(r, 500)); + + const url = `http://localhost:${port}`; + const instance = await launchMultiPage({ url, numPages, timeout, render }); + await new Promise((r) => setTimeout(r, 2000)); + + const allResults = await runEvalsMultiPage({ + wsUrl, scenesRoot: SCENES_DIR, + channels: instance.channels, + filterScene, filterWorkflow, + }); + + await instance.close(); + + if (outputFormat === "junit") console.log(toJunitXml(allResults)); + else console.log(JSON.stringify(allResults, null, 2)); + + const passed = allResults.filter((r) => r.passed).length; + const failed = allResults.length - passed; + console.log(`\n[dimsim] Done: ${passed} passed, ${failed} failed, ${allResults.length} total`); + Deno.exit(failed > 0 ? 1 : 0); + } + + // -- Single worker eval (sequential) ----------------------------------- + console.log(`[dimsim] Eval mode — headless: ${headless}, port: ${port}`); + startBridgeServer({ port, distDir, scene, evalOnly: headless }); + await new Promise((r) => setTimeout(r, 500)); + + const url = `http://localhost:${port}`; + if (headless) { + console.log("[dimsim] Launching headless browser…"); + const instance = await launchHeadless({ url, timeout, render }); + await new Promise((r) => setTimeout(r, 3000)); + + const results = await runEvals({ wsUrl, scenesRoot: SCENES_DIR, filterScene, filterWorkflow }); + if (outputFormat === "junit") console.log(toJunitXml(results)); + + await instance.close(); + const failed = results.filter((r) => !r.passed).length; + Deno.exit(failed > 0 ? 1 : 0); + } else { + console.log(`[dimsim] Open ${url} in your browser to start evals`); + console.log("[dimsim] Press Ctrl+C to stop."); + await new Promise(() => {}); + } + } + + printUsage(); + Deno.exit(1); +} + +main(); diff --git a/misc/DimSim/cli/deno.json b/misc/DimSim/cli/deno.json new file mode 100644 index 0000000000..3d48a13d8c --- /dev/null +++ b/misc/DimSim/cli/deno.json @@ -0,0 +1,21 @@ +{ + "name": "@antim/dimsim", + "version": "0.3.2", + "description": "3D simulation environment for the dimos robotics stack. Browser-based Three.js + Rapier sim with LCM transport, sensor publishing, and eval harness.", + "license": "MIT", + "exports": { + ".": "./cli.ts" + }, + "tasks": { + "start": "deno run --allow-net --allow-read --unstable-net bridge/server.ts", + "eval": "deno run --allow-all cli.ts eval" + }, + "imports": { + "@dimos/lcm": "./vendor/lcm/mod.ts", + "@dimos/msgs": "jsr:@dimos/msgs@^0.1.4", + "@std/path": "jsr:@std/path@^1", + "@std/http": "jsr:@std/http@^1", + "playwright": "npm:playwright@^1.58", + "@dimforge/rapier3d-compat": "npm:@dimforge/rapier3d-compat@^0.14.0" + } +} diff --git a/misc/DimSim/cli/deno.lock b/misc/DimSim/cli/deno.lock new file mode 100644 index 0000000000..7cbc0c61ac --- /dev/null +++ b/misc/DimSim/cli/deno.lock @@ -0,0 +1,117 @@ +{ + "version": "5", + "specifiers": { + "jsr:@antim/dimsim@*": "0.1.27", + "jsr:@dimos/msgs@~0.1.4": "0.1.4", + "jsr:@std/cli@^1.0.27": "1.0.27", + "jsr:@std/encoding@^1.0.10": "1.0.10", + "jsr:@std/fmt@^1.0.9": "1.0.9", + "jsr:@std/fs@^1.0.22": "1.0.22", + "jsr:@std/html@^1.0.5": "1.0.5", + "jsr:@std/http@1": "1.0.24", + "jsr:@std/internal@^1.0.12": "1.0.12", + "jsr:@std/media-types@^1.1.0": "1.1.0", + "jsr:@std/net@^1.0.6": "1.0.6", + "jsr:@std/path@1": "1.1.4", + "jsr:@std/path@^1.1.4": "1.1.4", + "jsr:@std/streams@^1.0.17": "1.0.17", + "npm:@dimforge/rapier3d-compat@0.14": "0.14.0", + "npm:playwright@*": "1.58.2", + "npm:playwright@^1.58.0": "1.58.2" + }, + "jsr": { + "@antim/dimsim@0.1.27": { + "integrity": "fc7f8f3aaeb0e06b06aaf35e157308f656be344db434a10bb573343c43a4bbbb", + "dependencies": [ + "jsr:@dimos/msgs", + "jsr:@std/http", + "jsr:@std/path@1", + "npm:@dimforge/rapier3d-compat", + "npm:playwright@^1.58.0" + ] + }, + "@dimos/msgs@0.1.4": { + "integrity": "564bc30b4bc41a562c296c257a15055283ca0cbd66d0627991ede5295832d0c4" + }, + "@std/cli@1.0.27": { + "integrity": "eba97edd0891871a7410e835dd94b3c260c709cca5983df2689c25a71fbe04de" + }, + "@std/encoding@1.0.10": { + "integrity": "8783c6384a2d13abd5e9e87a7ae0520a30e9f56aeeaa3bdf910a3eaaf5c811a1" + }, + "@std/fmt@1.0.9": { + "integrity": "2487343e8899fb2be5d0e3d35013e54477ada198854e52dd05ed0422eddcabe0" + }, + "@std/fs@1.0.22": { + "integrity": "de0f277a58a867147a8a01bc1b181d0dfa80bfddba8c9cf2bacd6747bcec9308" + }, + "@std/html@1.0.5": { + "integrity": "4e2d693f474cae8c16a920fa5e15a3b72267b94b84667f11a50c6dd1cb18d35e" + }, + "@std/http@1.0.24": { + "integrity": "4dd59afd7cfd6e2e96e175b67a5a829b449ae55f08575721ec691e5d85d886d4", + "dependencies": [ + "jsr:@std/cli", + "jsr:@std/encoding", + "jsr:@std/fmt", + "jsr:@std/fs", + "jsr:@std/html", + "jsr:@std/media-types", + "jsr:@std/net", + "jsr:@std/path@^1.1.4", + "jsr:@std/streams" + ] + }, + "@std/internal@1.0.12": { + "integrity": "972a634fd5bc34b242024402972cd5143eac68d8dffaca5eaa4dba30ce17b027" + }, + "@std/media-types@1.1.0": { + "integrity": "c9d093f0c05c3512932b330e3cc1fe1d627b301db33a4c2c2185c02471d6eaa4" + }, + "@std/net@1.0.6": { + "integrity": "110735f93e95bb9feb95790a8b1d1bf69ec0dc74f3f97a00a76ea5efea25500c" + }, + "@std/path@1.1.4": { + "integrity": "1d2d43f39efb1b42f0b1882a25486647cb851481862dc7313390b2bb044314b5", + "dependencies": [ + "jsr:@std/internal" + ] + }, + "@std/streams@1.0.17": { + "integrity": "7859f3d9deed83cf4b41f19223d4a67661b3d3819e9fc117698f493bf5992140" + } + }, + "npm": { + "@dimforge/rapier3d-compat@0.14.0": { + "integrity": "sha512-/uHrUzS+CRQ+NQrrJCEDUkhwHlNsAAexbNXgbN9sHY+GwR+SFFAFrxRr8Llf5/AJZzqiLANdQIfJ63Cw4gJVqw==" + }, + "fsevents@2.3.2": { + "integrity": "sha512-xiqMQR4xAeHTuB9uWm+fFRcIOgKBMiOBP+eXiyT7jsgVCq1bkVygt00oASowB7EdtpOHaaPgKt812P9ab+DDKA==", + "os": ["darwin"], + "scripts": true + }, + "playwright-core@1.58.2": { + "integrity": "sha512-yZkEtftgwS8CsfYo7nm0KE8jsvm6i/PTgVtB8DL726wNf6H2IMsDuxCpJj59KDaxCtSnrWan2AeDqM7JBaultg==", + "bin": true + }, + "playwright@1.58.2": { + "integrity": "sha512-vA30H8Nvkq/cPBnNw4Q8TWz1EJyqgpuinBcHET0YVJVFldr8JDNiU9LaWAE1KqSkRYazuaBhTpB5ZzShOezQ6A==", + "dependencies": [ + "playwright-core" + ], + "optionalDependencies": [ + "fsevents" + ], + "bin": true + } + }, + "workspace": { + "dependencies": [ + "jsr:@dimos/msgs@~0.1.4", + "jsr:@std/http@1", + "jsr:@std/path@1", + "npm:@dimforge/rapier3d-compat@0.14", + "npm:playwright@^1.58.0" + ] + } +} diff --git a/misc/DimSim/cli/headless/launcher.ts b/misc/DimSim/cli/headless/launcher.ts new file mode 100644 index 0000000000..0a9a6c8875 --- /dev/null +++ b/misc/DimSim/cli/headless/launcher.ts @@ -0,0 +1,204 @@ +/** + * Headless Launcher — Playwright-based headless Chromium for CI/CD evals. + * + * Rendering modes: + * gpu — Metal/ANGLE (macOS, fast, max ~3 parallel pages) + * cpu — SwiftShader (Linux CI, no GPU needed, sequential only on <16 cores) + */ + +import { chromium, type Browser, type Page } from "playwright"; + +export type RenderMode = "gpu" | "cpu"; + +export interface LaunchOptions { + url: string; + timeout?: number; + render?: RenderMode; +} + +export interface HeadlessInstance { + browser: Browser; + page: Page; + close: () => Promise; +} + +export interface MultiPageInstance { + browser: Browser; + pages: Page[]; + channels: string[]; + close: () => Promise; +} + +export interface MultiPageOptions { + url: string; + numPages: number; + timeout?: number; + render?: RenderMode; +} + +// ── Chrome flags per render mode ────────────────────────────────────────── + +const GPU_ARGS = [ + "--headless=new", + "--no-sandbox", + "--disable-setuid-sandbox", + "--disable-features=SkiaGraphite", + "--enable-webgl", + "--enable-webgl2", + "--ignore-gpu-blocklist", + "--enable-gpu", + "--use-gl=angle", + "--use-angle=metal", + "--in-process-gpu", + "--disable-gpu-sandbox", + // Prevent Chrome from throttling timers in headless/background mode + "--disable-background-timer-throttling", + "--disable-backgrounding-occluded-windows", + "--disable-renderer-backgrounding", +]; + +const CPU_ARGS = [ + "--headless=new", + "--no-sandbox", + "--disable-setuid-sandbox", + "--disable-features=SkiaGraphite", + "--enable-webgl", + "--enable-webgl2", + "--use-gl=angle", + "--use-angle=swiftshader", + "--enable-unsafe-swiftshader", + "--disable-gpu", + // Prevent Chrome from throttling timers in headless/background mode + "--disable-background-timer-throttling", + "--disable-backgrounding-occluded-windows", + "--disable-renderer-backgrounding", +]; + +// Default: bundled Chromium (works on Linux + macOS in CPU mode with SwiftShader). +// Set DIMSIM_CHROME_CHANNEL=chrome to use system Google Chrome (needed for hardware +// WebGL on macOS — bundled Chromium ships without the full Metal/ANGLE GPU stack). +const LAUNCH_CHANNEL = Deno.env.get("DIMSIM_CHROME_CHANNEL") || undefined; + +// ── Helpers ─────────────────────────────────────────────────────────────── + +/** Filter noisy browser console output — only forward errors, warnings, and eval/bridge logs. */ +function hookPageConsole(page: Page, tag: string): void { + const verbose = Deno.env.get("DIMSIM_VERBOSE") === "1"; + page.on("console", (msg) => { + const type = msg.type(); + const text = msg.text(); + if (!verbose) { + if (text.includes("Texture marked for update") || text.includes("Failed to load resource") || + text.includes("GPU stall due to ReadPixels") || text.includes("Automatic fallback to software WebGL") || + text.includes("GroupMarkerNotSet")) return; + } + if (type === "error") console.error(`${tag} ${text}`); + else if (type === "warning") console.warn(`${tag} ${text}`); + else if (verbose || text.startsWith("[eval]") || text.startsWith("[DimosBridge]")) { + console.log(`${tag} ${text}`); + } + }); +} + +function getViewport(render: RenderMode) { + // CPU mode: tiny viewport — SwiftShader renders every pixel on CPU + return render === "cpu" + ? { width: 320, height: 240 } + : { width: 1280, height: 720 }; +} + +// ── Single-page launcher ───────────────────────────────────────────────── + +export async function launchHeadless(options: LaunchOptions): Promise { + const { url, timeout = 30000, render = "cpu" } = options; + const args = render === "gpu" ? GPU_ARGS : CPU_ARGS; + + console.log(`[headless] Launching: render=${render}`); + + const browser = await chromium.launch({ + headless: false, // --headless=new passed via args (Playwright's built-in headless uses old mode) + channel: LAUNCH_CHANNEL, + args, + }); + + const context = await browser.newContext({ viewport: getViewport(render), deviceScaleFactor: 1 }); + const page = await context.newPage(); + hookPageConsole(page, "[browser]"); + + // Set default timeout so waitForFunction picks it up (its third arg is + // options, not the second — passing {timeout} as second silently uses + // Playwright's 30s default). + context.setDefaultTimeout(timeout); + page.setDefaultTimeout(timeout); + + await page.goto(url, { waitUntil: "load", timeout }); + await page.waitForFunction( + () => typeof (window as unknown as Record).__dimosBridge !== "undefined", + undefined, + { timeout }, + ); + + console.log("[headless] Engine ready."); + + return { + browser, + page, + close: async () => { + await browser.close(); + console.log("[headless] Browser closed."); + }, + }; +} + +// ── Multi-page launcher (single browser, N tabs) ──────────────────────── + +export async function launchMultiPage(options: MultiPageOptions): Promise { + const { url, numPages, timeout = 120_000, render = "cpu" } = options; + const args = render === "gpu" ? GPU_ARGS : CPU_ARGS; + const viewport = getViewport(render); + + console.log(`[headless] Multi-page: ${numPages} pages, render=${render}, timeout=${timeout}ms`); + + const browser = await chromium.launch({ headless: false, channel: LAUNCH_CHANNEL, args }); + + const pages: Page[] = []; + const channels: string[] = []; + + for (let i = 0; i < numPages; i++) { + const channel = `page-${i}`; + channels.push(channel); + + const context = await browser.newContext({ viewport, deviceScaleFactor: 1 }); + context.setDefaultTimeout(timeout); + const page = await context.newPage(); + page.setDefaultTimeout(timeout); + hookPageConsole(page, `[page-${i}]`); + + const pageUrl = `${url}?channel=${channel}`; + console.log(`[headless] Page ${i}: loading...`); + await page.goto(pageUrl, { waitUntil: "load", timeout }); + await page.waitForFunction( + () => typeof (window as unknown as Record).__dimosBridge !== "undefined", + undefined, + { timeout }, + ); + console.log(`[headless] Page ${i}: ready`); + + pages.push(page); + + // Stagger launches to avoid GPU/CPU contention during scene load + if (i < numPages - 1) await new Promise((r) => setTimeout(r, 5000)); + } + + console.log(`[headless] All ${numPages} pages ready.`); + + return { + browser, + pages, + channels, + close: async () => { + await browser.close(); + console.log("[headless] Browser closed."); + }, + }; +} diff --git a/misc/DimSim/cli/test/dimos_integration.py b/misc/DimSim/cli/test/dimos_integration.py new file mode 100755 index 0000000000..4981dbbe33 --- /dev/null +++ b/misc/DimSim/cli/test/dimos_integration.py @@ -0,0 +1,232 @@ +#!/usr/bin/env python3 +""" +DimSim ↔ dimos Integration Test (UDP Multicast) + +Validates end-to-end connectivity between DimSim (browser sim) and dimos +(Python robotics stack) via LCM UDP multicast through the bridge server. + +Data flow: + Python ──UDP multicast──▶ Bridge Server ──WebSocket──▶ Browser (DimSim) + Python ◀──UDP multicast── Bridge Server ◀──WebSocket── Browser (DimSim) + +This script: + 1. Joins the LCM multicast group (239.255.76.67:7667) + 2. Publishes /cmd_vel Twist commands as LCM packets via UDP multicast → agent moves + 3. Listens for /odom, /camera/image, /camera/depth, /lidar/points on multicast + 4. Reports what it receives; SUCCESS when all 4 channels are live + +Prerequisites: + 1. Start DimSim bridge: + ~/.deno/bin/deno run --allow-all --unstable-net cli/cli.ts dev + 2. Open http://localhost:8090 in Chrome (scene must load) + 3. Run this script from the dimos venv: + /path/to/dimos/.venv/bin/python cli/test/dimos_integration.py + +Options: + --timeout N Timeout in seconds (default: 30) + --rate N cmd_vel publish rate in Hz (default: 10) +""" + +import argparse +import socket +import struct +import sys +import threading +import time + +# dimos message types for encoding cmd_vel +from dimos.msgs.geometry_msgs.Twist import Twist +from dimos.msgs.geometry_msgs.Vector3 import Vector3 + +# -- LCM constants ------------------------------------------------------------ +LCM_MAGIC = 0x4C433032 # "LC02" in ASCII / big-endian +MCAST_GRP = "239.255.76.67" +MCAST_PORT = 7667 +_seq = 0 + +# -- LCM packet codec (matches @dimos/msgs encodePacket / decodePacket) -------- + + +def encode_lcm_packet(channel: str, payload: bytes) -> bytes: + """Encode an LCM binary packet (same format as @dimos/msgs encodePacket).""" + global _seq + ch_bytes = channel.encode("utf-8") + buf = struct.pack(">II", LCM_MAGIC, _seq) + ch_bytes + b"\x00" + payload + _seq += 1 + return buf + + +def decode_lcm_packet(data: bytes) -> tuple[str, bytes]: + """Decode an LCM packet → (channel, payload). Raises ValueError on bad packet.""" + if len(data) < 9: + raise ValueError("Packet too short") + magic = struct.unpack_from(">I", data, 0)[0] + if magic != LCM_MAGIC: + raise ValueError(f"Bad magic: 0x{magic:08x}") + null_pos = data.index(0, 8) + channel = data[8:null_pos].decode("utf-8") + payload = data[null_pos + 1 :] + return channel, payload + + +# -- Channel names (must match DimSim's dimosBridge.ts) ------------------------ +CH_CMD_VEL = "/cmd_vel#geometry_msgs.Twist" +CH_ODOM = "/odom#geometry_msgs.PoseStamped" +CH_IMAGE = "/camera/image#sensor_msgs.Image" +CH_DEPTH = "/camera/depth#sensor_msgs.Image" +CH_LIDAR = "/lidar/points#sensor_msgs.PointCloud2" + + +def create_mcast_recv_socket() -> socket.socket: + """Create a UDP socket joined to the LCM multicast group for receiving.""" + sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM, socket.IPPROTO_UDP) + sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1) + try: + sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEPORT, 1) + except AttributeError: + pass + sock.bind(("127.0.0.1", MCAST_PORT)) + mreq = struct.pack("4s4s", socket.inet_aton(MCAST_GRP), socket.inet_aton("0.0.0.0")) + sock.setsockopt(socket.IPPROTO_IP, socket.IP_ADD_MEMBERSHIP, mreq) + sock.setsockopt(socket.IPPROTO_IP, socket.IP_MULTICAST_LOOP, 0) + sock.settimeout(1.0) + return sock + + +def create_mcast_send_socket() -> socket.socket: + """Create a UDP socket for sending to the LCM multicast group.""" + sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM, socket.IPPROTO_UDP) + sock.setsockopt(socket.IPPROTO_IP, socket.IP_MULTICAST_TTL, 1) + sock.setsockopt(socket.IPPROTO_IP, socket.IP_MULTICAST_LOOP, 0) + return sock + + +def main(): + parser = argparse.ArgumentParser(description="DimSim ↔ dimos integration test (UDP multicast)") + parser.add_argument("--timeout", type=int, default=30, help="Timeout in seconds") + parser.add_argument("--rate", type=int, default=10, help="cmd_vel publish rate (Hz)") + args = parser.parse_args() + + received = {"odom": 0, "image": 0, "depth": 0, "lidar": 0} + tick = 0 + success = False + running = True + + recv_sock = create_mcast_recv_socket() + send_sock = create_mcast_send_socket() + + print(f"[integration] LCM multicast {MCAST_GRP}:{MCAST_PORT}") + print(f"[integration] Publishing /cmd_vel at {args.rate} Hz") + print("[integration] Listening for sensor data on multicast") + print(f"[integration] Timeout: {args.timeout}s\n") + + # -- Receive thread -------------------------------------------------------- + def recv_loop(): + while running: + try: + data, addr = recv_sock.recvfrom(65536) + except TimeoutError: + continue + except OSError: + break + + try: + channel, payload = decode_lcm_packet(data) + except (ValueError, IndexError): + continue + + if "/odom" in channel: + received["odom"] += 1 + if received["odom"] <= 3 or received["odom"] % 10 == 0: + print(f"[integration] Got odom #{received['odom']} ({len(payload)}B)") + elif "/camera/image" in channel: + received["image"] += 1 + if received["image"] <= 3 or received["image"] % 10 == 0: + print(f"[integration] Got RGB #{received['image']} ({len(payload)}B)") + elif "/camera/depth" in channel: + received["depth"] += 1 + if received["depth"] <= 3 or received["depth"] % 10 == 0: + print(f"[integration] Got depth #{received['depth']} ({len(payload)}B)") + elif "/lidar/points" in channel: + received["lidar"] += 1 + if received["lidar"] <= 3 or received["lidar"] % 10 == 0: + print(f"[integration] Got LiDAR #{received['lidar']} ({len(payload)}B)") + + recv_thread = threading.Thread(target=recv_loop, daemon=True) + recv_thread.start() + + # -- Send loop ------------------------------------------------------------- + interval = 1.0 / args.rate + start_time = time.time() + + try: + while time.time() - start_time < args.timeout: + # Build Twist — Three.js identity: z=forward, y=yaw + twist = Twist( + linear=Vector3(0, 0, 0.5), + angular=Vector3(0, 0.3, 0), + ) + payload = twist.lcm_encode() + packet = encode_lcm_packet(CH_CMD_VEL, payload) + send_sock.sendto(packet, (MCAST_GRP, MCAST_PORT)) + tick += 1 + + if tick <= 3 or tick % 20 == 0: + print(f"[integration] Sent cmd_vel #{tick}") + + # Status check every 5s + elapsed = time.time() - start_time + if tick > 1 and (tick % (args.rate * 5) == 0): + print( + f"\n[integration] STATUS ({elapsed:.0f}s): " + f"cmd_sent={tick} odom={received['odom']} " + f"rgb={received['image']} depth={received['depth']} " + f"lidar={received['lidar']}" + ) + + if all(v > 0 for v in received.values()): + success = True + print("\n========================================") + print(" SUCCESS: All channels working!") + print(" DimSim ↔ dimos LCM multicast verified.") + print("========================================\n") + break + + if received["odom"] == 0 and elapsed > 10: + print("[integration] No sensor data on multicast. Check:") + print(" 1. Bridge running with vendored @dimos/lcm (joinMulticastV4)") + print(" 2. Browser open at localhost:8090 with scene loaded") + print() + + time.sleep(interval) + + if not success: + print(f"\n[integration] TIMEOUT after {args.timeout}s") + print( + f"[integration] Final: cmd_sent={tick} odom={received['odom']} " + f"rgb={received['image']} depth={received['depth']} " + f"lidar={received['lidar']}" + ) + + except KeyboardInterrupt: + print("\n[integration] Interrupted by user") + + finally: + running = False + # Send zero velocity (safety stop) + try: + stop_twist = Twist() + stop_pkt = encode_lcm_packet(CH_CMD_VEL, stop_twist.lcm_encode()) + send_sock.sendto(stop_pkt, (MCAST_GRP, MCAST_PORT)) + except Exception: + pass + + recv_sock.close() + send_sock.close() + print("[integration] Done.") + + sys.exit(0 if success else 1) + + +if __name__ == "__main__": + main() diff --git a/misc/DimSim/cli/vendor/lcm/lcm.ts b/misc/DimSim/cli/vendor/lcm/lcm.ts new file mode 100644 index 0000000000..f4aa7b2c96 --- /dev/null +++ b/misc/DimSim/cli/vendor/lcm/lcm.ts @@ -0,0 +1,236 @@ +// LCM Main Class - Pure TypeScript Implementation (vendored from @dimos/lcm@0.2.0) + +import type { + LCMOptions, + LCMMessage, + MessageClass, + ParsedUrl, + Subscription, + SubscriptionHandler, + PacketHandler, + PacketSubscription, +} from "./types.ts"; +import { MAX_SMALL_MESSAGE, SHORT_HEADER_SIZE } from "./types.ts"; +import { parseUrl } from "./url.ts"; +import { + UdpMulticastSocket, + FragmentReassembler, + encodeSmallMessage, + encodeFragmentedMessage, + decodePacket, +} from "./transport.ts"; + +const textEncoder = new TextEncoder(); + +export class LCM { + private readonly config: ParsedUrl; + private socket: UdpMulticastSocket | null = null; + private reassembler = new FragmentReassembler(); + private subscriptions: Subscription[] = []; + private packetSubscriptions: PacketSubscription[] = []; + private sequenceNumber = 0; + private running = false; + private messageQueue: LCMMessage[] = []; + + constructor(url?: string); + constructor(options?: LCMOptions); + constructor(urlOrOptions?: string | LCMOptions) { + if (typeof urlOrOptions === "string") { + this.config = parseUrl(urlOrOptions); + } else { + this.config = parseUrl(urlOrOptions?.url); + if (urlOrOptions?.ttl !== undefined) { + this.config.ttl = urlOrOptions.ttl; + } + if (urlOrOptions?.iface !== undefined) { + this.config.iface = urlOrOptions.iface; + } + } + } + + async start(): Promise { + if (this.running) return; + this.socket = new UdpMulticastSocket(this.config); + this.running = true; + await this.socket.listen((data, _addr) => { + this.handlePacket(data); + }); + } + + stop(): void { + this.running = false; + if (this.socket) { + this.socket.close(); + this.socket = null; + } + } + + subscribeRaw(channelPattern: string, handler: SubscriptionHandler): () => void { + const pattern = this.channelToRegex(channelPattern); + const subscription: Subscription = { + channel: channelPattern, + pattern, + handler: handler as SubscriptionHandler, + }; + this.subscriptions.push(subscription); + return () => { + const idx = this.subscriptions.indexOf(subscription); + if (idx !== -1) this.subscriptions.splice(idx, 1); + }; + } + + subscribePacket(handler: PacketHandler): () => void; + subscribePacket(channelPattern: string, handler: PacketHandler): () => void; + subscribePacket(patternOrHandler: string | PacketHandler, maybeHandler?: PacketHandler): () => void { + const pattern = typeof patternOrHandler === "string" + ? this.channelToRegex(patternOrHandler) + : null; + const handler = typeof patternOrHandler === "function" + ? patternOrHandler + : maybeHandler!; + const subscription: PacketSubscription = { pattern, handler }; + this.packetSubscriptions.push(subscription); + return () => { + const idx = this.packetSubscriptions.indexOf(subscription); + if (idx !== -1) this.packetSubscriptions.splice(idx, 1); + }; + } + + subscribe(channel: string, msgClass: MessageClass, handler: SubscriptionHandler): () => void { + const typeName = (msgClass as unknown as { _NAME: string })._NAME; + const fullChannel = channel.includes("#") ? channel : `${channel}#${typeName}`; + const pattern = this.channelToRegex(fullChannel); + const subscription: Subscription = { + channel: fullChannel, + pattern, + handler: handler as SubscriptionHandler, + msgClass: msgClass as MessageClass, + }; + this.subscriptions.push(subscription); + return () => { + const idx = this.subscriptions.indexOf(subscription); + if (idx !== -1) this.subscriptions.splice(idx, 1); + }; + } + + async publishRaw(channel: string, data: Uint8Array): Promise { + if (!this.socket) throw new Error("LCM not started. Call start() first."); + const channelBytes = textEncoder.encode(channel); + const totalSize = SHORT_HEADER_SIZE + channelBytes.length + 1 + data.length; + const seq = this.sequenceNumber++; + if (totalSize <= MAX_SMALL_MESSAGE) { + const packet = encodeSmallMessage(channel, data, seq); + await this.socket.send(packet); + } else { + const fragments = encodeFragmentedMessage(channel, data, seq); + for (const fragment of fragments) { + await this.socket.send(fragment); + } + } + } + + async publish(channel: string, msg: T): Promise { + const data = msg.encode(); + const typeName = (msg.constructor as unknown as { _NAME?: string })._NAME; + const fullChannel = typeName && !channel.includes("#") + ? `${channel}#${typeName}` + : channel; + await this.publishRaw(fullChannel, data); + } + + async publishPacket(packet: Uint8Array): Promise { + if (!this.socket) throw new Error("LCM not started. Call start() first."); + await this.socket.send(packet); + } + + handle(timeoutMs: number = 0): number { + const messages = this.messageQueue.splice(0); + for (const msg of messages) { + this.dispatchMessage(msg); + } + return messages.length; + } + + async handleAsync(timeoutMs: number = 100): Promise { + const startTime = Date.now(); + while (this.messageQueue.length === 0) { + if (timeoutMs >= 0 && Date.now() - startTime >= timeoutMs) break; + await new Promise((resolve) => setTimeout(resolve, 10)); + } + return this.handle(); + } + + async run(callback?: () => void | Promise): Promise { + while (this.running) { + await this.handleAsync(100); + if (callback) await callback(); + } + } + + private channelToRegex(pattern: string): RegExp { + const escaped = pattern.replace(/[.+?^${}()|[\]\\]/g, "\\$&"); + const regexStr = "^" + escaped.replace(/\*/g, ".*") + "$"; + return new RegExp(regexStr); + } + + private handlePacket(data: Uint8Array): void { + const decoded = decodePacket(data); + if (!decoded) return; + + const channel = decoded.type === "small" ? decoded.channel : decoded.channel; + + if (channel) { + for (const sub of this.packetSubscriptions) { + if (!sub.pattern || sub.pattern.test(channel)) { + try { sub.handler(data); } catch (e) { console.error(`Error in raw packet handler:`, e); } + } + } + } + + if (decoded.type === "small") { + this.queueMessage(decoded.channel, decoded.data); + } else { + const complete = this.reassembler.processFragment(decoded); + if (complete) this.queueMessage(complete.channel, complete.data); + } + } + + private queueMessage(channel: string, data: Uint8Array): void { + const msg: LCMMessage = { + channel, + data: new Uint8Array(data), + timestamp: Date.now(), + }; + this.messageQueue.push(msg); + } + + private dispatchMessage(msg: LCMMessage): void { + for (const sub of this.subscriptions) { + if (sub.pattern.test(msg.channel)) { + try { + if (sub.msgClass) { + const decoded = sub.msgClass.decode(msg.data); + sub.handler({ channel: msg.channel, data: decoded, timestamp: msg.timestamp }); + } else { + sub.handler(msg); + } + } catch (e) { + console.error(`Error in subscription handler for ${msg.channel}:`, e); + } + } + } + } + + getConfig(): ParsedUrl { + return { ...this.config }; + } + + isRunning(): boolean { + return this.running; + } + + /** Peek at the next sequence number (for echo filtering). */ + getNextSeq(): number { + return this.sequenceNumber; + } +} diff --git a/misc/DimSim/cli/vendor/lcm/mod.ts b/misc/DimSim/cli/vendor/lcm/mod.ts new file mode 100644 index 0000000000..f1ad2a5bd1 --- /dev/null +++ b/misc/DimSim/cli/vendor/lcm/mod.ts @@ -0,0 +1,6 @@ +// LCM Pure TypeScript Implementation (vendored from @dimos/lcm@0.2.0) +// FIX: Added joinMulticastV4() in transport.ts + +export { LCM } from "./lcm.ts"; +export type { LCMOptions, LCMMessage, MessageClass, ParsedUrl, PacketHandler } from "./types.ts"; +export { parseUrl, DEFAULT_MULTICAST_GROUP, DEFAULT_PORT } from "./url.ts"; diff --git a/misc/DimSim/cli/vendor/lcm/transport.ts b/misc/DimSim/cli/vendor/lcm/transport.ts new file mode 100644 index 0000000000..b98a6bc866 --- /dev/null +++ b/misc/DimSim/cli/vendor/lcm/transport.ts @@ -0,0 +1,352 @@ +// LCM UDP Multicast Transport (vendored from @dimos/lcm@0.2.0) +// FIX: Added joinMulticastV4() call in UdpMulticastSocket.listen() + +import { + MAGIC_SHORT, + MAGIC_LONG, + MAX_SMALL_MESSAGE, + SHORT_HEADER_SIZE, + FRAGMENT_HEADER_SIZE, +} from "./types.ts"; +import type { ParsedUrl } from "./types.ts"; + +const textEncoder = new TextEncoder(); +const textDecoder = new TextDecoder(); + +/** Encode a small LCM message (fits in single UDP packet) */ +export function encodeSmallMessage( + channel: string, + data: Uint8Array, + sequenceNumber: number +): Uint8Array { + const channelBytes = textEncoder.encode(channel); + const totalSize = SHORT_HEADER_SIZE + channelBytes.length + 1 + data.length; + + if (totalSize > MAX_SMALL_MESSAGE) { + throw new Error(`Message too large for small message format: ${totalSize} > ${MAX_SMALL_MESSAGE}`); + } + + const buffer = new Uint8Array(totalSize); + const view = new DataView(buffer.buffer); + + let offset = 0; + + // Magic number (big-endian) + view.setUint32(offset, MAGIC_SHORT, false); + offset += 4; + + // Sequence number (big-endian) + view.setUint32(offset, sequenceNumber, false); + offset += 4; + + // Channel name (null-terminated) + buffer.set(channelBytes, offset); + offset += channelBytes.length; + buffer[offset] = 0; // null terminator + offset += 1; + + // Payload + buffer.set(data, offset); + + return buffer; +} + +/** Encode a fragmented LCM message (requires multiple UDP packets) */ +export function encodeFragmentedMessage( + channel: string, + data: Uint8Array, + sequenceNumber: number, + maxFragmentSize: number = 65000 +): Uint8Array[] { + const channelBytes = textEncoder.encode(channel); + const payloadSize = data.length; + + const firstFragmentPayloadSpace = maxFragmentSize - FRAGMENT_HEADER_SIZE - channelBytes.length - 1; + const subsequentFragmentPayloadSpace = maxFragmentSize - FRAGMENT_HEADER_SIZE; + + let numFragments = 1; + let remainingBytes = payloadSize - Math.min(payloadSize, firstFragmentPayloadSpace); + if (remainingBytes > 0) { + numFragments += Math.ceil(remainingBytes / subsequentFragmentPayloadSpace); + } + + const fragments: Uint8Array[] = []; + let payloadOffset = 0; + + for (let fragmentNum = 0; fragmentNum < numFragments; fragmentNum++) { + const isFirst = fragmentNum === 0; + const headerSize = FRAGMENT_HEADER_SIZE; + const channelSize = isFirst ? channelBytes.length + 1 : 0; + + const maxPayloadForThisFragment = isFirst + ? firstFragmentPayloadSpace + : subsequentFragmentPayloadSpace; + + const payloadForThisFragment = Math.min( + maxPayloadForThisFragment, + payloadSize - payloadOffset + ); + + const fragmentSize = headerSize + channelSize + payloadForThisFragment; + const fragment = new Uint8Array(fragmentSize); + const view = new DataView(fragment.buffer); + + let offset = 0; + + view.setUint32(offset, MAGIC_LONG, false); + offset += 4; + view.setUint32(offset, sequenceNumber, false); + offset += 4; + view.setUint32(offset, payloadSize, false); + offset += 4; + view.setUint32(offset, payloadOffset, false); + offset += 4; + view.setUint16(offset, fragmentNum, false); + offset += 2; + view.setUint16(offset, numFragments, false); + offset += 2; + + if (isFirst) { + fragment.set(channelBytes, offset); + offset += channelBytes.length; + fragment[offset] = 0; + offset += 1; + } + + fragment.set(data.subarray(payloadOffset, payloadOffset + payloadForThisFragment), offset); + payloadOffset += payloadForThisFragment; + fragments.push(fragment); + } + + return fragments; +} + +/** Decoded small message */ +export interface DecodedSmallMessage { + type: "small"; + channel: string; + data: Uint8Array; + sequenceNumber: number; +} + +/** Decoded fragment */ +export interface DecodedFragment { + type: "fragment"; + sequenceNumber: number; + payloadSize: number; + fragmentOffset: number; + fragmentNumber: number; + numFragments: number; + channel?: string; + data: Uint8Array; +} + +/** Decode a received UDP packet */ +export function decodePacket(packet: Uint8Array): DecodedSmallMessage | DecodedFragment | null { + if (packet.length < SHORT_HEADER_SIZE) { + return null; + } + + const view = new DataView(packet.buffer, packet.byteOffset, packet.byteLength); + const magic = view.getUint32(0, false); + + if (magic === MAGIC_SHORT) { + return decodeSmallPacket(packet, view); + } else if (magic === MAGIC_LONG) { + return decodeFragmentPacket(packet, view); + } + + return null; +} + +function decodeSmallPacket(packet: Uint8Array, view: DataView): DecodedSmallMessage | null { + const sequenceNumber = view.getUint32(4, false); + + let channelEnd = SHORT_HEADER_SIZE; + while (channelEnd < packet.length && packet[channelEnd] !== 0) { + channelEnd++; + } + + if (channelEnd >= packet.length) { + return null; + } + + const channel = textDecoder.decode(packet.subarray(SHORT_HEADER_SIZE, channelEnd)); + const data = packet.subarray(channelEnd + 1); + + return { type: "small", channel, data, sequenceNumber }; +} + +function decodeFragmentPacket(packet: Uint8Array, view: DataView): DecodedFragment | null { + if (packet.length < FRAGMENT_HEADER_SIZE) { + return null; + } + + const sequenceNumber = view.getUint32(4, false); + const payloadSize = view.getUint32(8, false); + const fragmentOffset = view.getUint32(12, false); + const fragmentNumber = view.getUint16(16, false); + const numFragments = view.getUint16(18, false); + + let offset = FRAGMENT_HEADER_SIZE; + let channel: string | undefined; + + if (fragmentNumber === 0) { + let channelEnd = offset; + while (channelEnd < packet.length && packet[channelEnd] !== 0) { + channelEnd++; + } + if (channelEnd >= packet.length) { + return null; + } + channel = textDecoder.decode(packet.subarray(offset, channelEnd)); + offset = channelEnd + 1; + } + + const data = packet.subarray(offset); + + return { type: "fragment", sequenceNumber, payloadSize, fragmentOffset, fragmentNumber, numFragments, channel, data }; +} + +/** Fragment reassembler for handling large messages */ +export class FragmentReassembler { + private pending = new Map; + buffer: Uint8Array; + lastActivity: number; + }>(); + + private timeoutMs: number; + + constructor(timeoutMs: number = 5000) { + this.timeoutMs = timeoutMs; + } + + processFragment(fragment: DecodedFragment): { channel: string; data: Uint8Array } | null { + const now = Date.now(); + this.cleanup(now); + + let entry = this.pending.get(fragment.sequenceNumber); + + if (!entry) { + if (fragment.fragmentNumber !== 0 || !fragment.channel) { + return null; + } + + entry = { + channel: fragment.channel, + payloadSize: fragment.payloadSize, + numFragments: fragment.numFragments, + receivedFragments: new Set(), + buffer: new Uint8Array(fragment.payloadSize), + lastActivity: now, + }; + this.pending.set(fragment.sequenceNumber, entry); + } + + if (fragment.fragmentOffset + fragment.data.length > entry.buffer.length) { + // Fragment doesn't fit — corrupted or mismatched packet, discard. + this.pending.delete(fragment.sequenceNumber); + return null; + } + entry.buffer.set(fragment.data, fragment.fragmentOffset); + entry.receivedFragments.add(fragment.fragmentNumber); + entry.lastActivity = now; + + if (entry.receivedFragments.size === entry.numFragments) { + this.pending.delete(fragment.sequenceNumber); + return { channel: entry.channel, data: entry.buffer }; + } + + return null; + } + + private cleanup(now: number): void { + for (const [seq, entry] of this.pending) { + if (now - entry.lastActivity > this.timeoutMs) { + this.pending.delete(seq); + } + } + } +} + +/** UDP Multicast socket wrapper for Deno */ +export class UdpMulticastSocket { + private socket: Deno.DatagramConn | null = null; + private readonly config: ParsedUrl; + private running = false; + + constructor(config: ParsedUrl) { + this.config = config; + } + + /** Start listening for multicast messages */ + async listen(onMessage: (data: Uint8Array, addr: Deno.NetAddr) => void): Promise { + // reuseAddress allows multiple processes to bind to the same multicast port + this.socket = Deno.listenDatagram({ + port: this.config.port, + transport: "udp", + hostname: "0.0.0.0", + reuseAddress: true, + }); + + // FIX: Join the multicast group and enable loopback for local IPC + const membership = await this.socket.joinMulticastV4(this.config.host, this.config.iface ?? "0.0.0.0"); + membership.setLoopback(true); + if (this.config.ttl !== undefined) { + membership.setTTL(this.config.ttl); + } + + this.running = true; + + // Read loop + (async () => { + try { + while (this.running && this.socket) { + const [data, addr] = await this.socket.receive(); + if (addr.transport === "udp") { + onMessage(data, addr); + } + } + } catch (e) { + if (this.running) { + console.error("UDP receive error:", e); + } + } + })(); + } + + /** Send a UDP packet to the multicast group */ + async send(data: Uint8Array): Promise { + if (!this.socket) { + // Create a socket for sending if we don't have one + this.socket = Deno.listenDatagram({ + port: 0, // Ephemeral port for sending + transport: "udp", + hostname: "0.0.0.0", + }); + } + + await this.socket.send(data, { + transport: "udp", + hostname: this.config.host, + port: this.config.port, + }); + } + + /** Close the socket */ + close(): void { + this.running = false; + if (this.socket) { + try { + this.socket.close(); + } catch { + // Ignore close errors + } + this.socket = null; + } + } +} diff --git a/misc/DimSim/cli/vendor/lcm/types.ts b/misc/DimSim/cli/vendor/lcm/types.ts new file mode 100644 index 0000000000..2f4e1a14b3 --- /dev/null +++ b/misc/DimSim/cli/vendor/lcm/types.ts @@ -0,0 +1,62 @@ +// LCM Type Definitions (vendored from @dimos/lcm@0.2.0) + +/** LCM message as received */ +export interface LCMMessage { + channel: string; + data: T; + timestamp: number; +} + +/** Interface for LCM message classes (generated types) */ +export interface MessageClass { + readonly _HASH: bigint; + readonly _NAME: string; + decode(data: Uint8Array): T; + new (init?: Partial): T & { encode(): Uint8Array }; +} + +/** Subscription handler function */ +export type SubscriptionHandler = (msg: LCMMessage) => void; + +/** Packet handler function (for raw UDP packets) */ +export type PacketHandler = (packet: Uint8Array) => void; + +/** LCM configuration options */ +export interface LCMOptions { + /** LCM URL (e.g., "udpm://239.255.76.67:7667?ttl=1") */ + url?: string; + /** Multicast TTL (time-to-live) */ + ttl?: number; + /** Network interface to bind to */ + iface?: string; +} + +/** Parsed LCM URL */ +export interface ParsedUrl { + scheme: string; + host: string; + port: number; + ttl: number; + iface?: string; +} + +/** Internal subscription record */ +export interface Subscription { + channel: string; + pattern: RegExp; + handler: SubscriptionHandler; + msgClass?: MessageClass; +} + +/** Internal packet subscription record */ +export interface PacketSubscription { + pattern: RegExp | null; // null = match all + handler: PacketHandler; +} + +// LCM Protocol constants +export const MAGIC_SHORT = 0x4c433032; // "LC02" +export const MAGIC_LONG = 0x4c433033; // "LC03" +export const MAX_SMALL_MESSAGE = 65535; +export const SHORT_HEADER_SIZE = 8; +export const FRAGMENT_HEADER_SIZE = 20; diff --git a/misc/DimSim/cli/vendor/lcm/url.ts b/misc/DimSim/cli/vendor/lcm/url.ts new file mode 100644 index 0000000000..ecad329e02 --- /dev/null +++ b/misc/DimSim/cli/vendor/lcm/url.ts @@ -0,0 +1,61 @@ +// LCM URL Parser (vendored from @dimos/lcm@0.2.0) + +import type { ParsedUrl } from "./types.ts"; + +export const DEFAULT_MULTICAST_GROUP = "239.255.76.67"; +export const DEFAULT_PORT = 7667; +export const DEFAULT_TTL = 0; + +/** + * Parse an LCM URL into its components. + * + * Supported formats: + * - "udpm://239.255.76.67:7667?ttl=1" + * - "udpm://239.255.76.67:7667" + * - "udpm://" (uses defaults) + * - "" (uses defaults) + */ +export function parseUrl(url?: string): ParsedUrl { + if (!url || url === "" || url === "udpm://") { + return { + scheme: "udpm", + host: DEFAULT_MULTICAST_GROUP, + port: DEFAULT_PORT, + ttl: DEFAULT_TTL, + }; + } + + const match = url.match(/^(\w+):\/\/([^:/?#]+)?(?::(\d+))?(?:\?(.*))?$/); + if (!match) { + throw new Error(`Invalid LCM URL: ${url}`); + } + + const [, scheme, host, portStr, queryStr] = match; + + if (scheme !== "udpm") { + throw new Error(`Unsupported LCM scheme: ${scheme} (only "udpm" is supported)`); + } + + const port = portStr ? parseInt(portStr, 10) : DEFAULT_PORT; + + // Parse query parameters + let ttl = DEFAULT_TTL; + let iface: string | undefined; + + if (queryStr) { + const params = new URLSearchParams(queryStr); + const ttlStr = params.get("ttl"); + if (ttlStr) { + ttl = parseInt(ttlStr, 10); + } + iface = params.get("iface") ?? undefined; + } + + return { + scheme, + host: host || DEFAULT_MULTICAST_GROUP, + port, + ttl, + iface, + }; +} diff --git a/misc/DimSim/docs/evals.md b/misc/DimSim/docs/evals.md new file mode 100644 index 0000000000..43782f13e8 --- /dev/null +++ b/misc/DimSim/docs/evals.md @@ -0,0 +1,95 @@ +# Evals + +An eval workflow is one JS file at `scenes//evals/.js`. It imports `runEval` from `@dimsim/eval` and calls it. That's the whole authoring surface. + +## Create a new eval + +```js +// scenes/apartment/evals/go-to-couch.js +import { runEval } from '@dimsim/eval'; + +await runEval({ + scene: 'apartment', + task: 'Go to the couch', + timeoutSec: 30, + startPose: { x: 0, y: 0.5, z: 3, yaw: 0 }, + success: (ctx) => ctx.rubrics.objectDistance({ target: 'sectional', thresholdM: 2.0 }), +}); +``` + +Drop the file under any scene's `evals/` folder and `dimsim eval list` picks it up. + +## Run it + +```bash +dimsim eval go-to-couch # against the open sim +dimsim eval --headless --scene apartment --workflow go-to-couch # standalone / CI +deno run -A misc/DimSim/scenes/apartment/evals/go-to-couch.js # direct execution +``` + +All three end up at the same harness in the browser; pick whichever feels natural for the moment. + +## The workflow object + +| Field | Required | Description | +|---|---|---| +| `scene` | ✓ | Scene name. Must match a directory under `scenes/`. | +| `task` | ✓ | Human-readable goal. Shown in the overlay + logged. | +| `success(ctx)` | ✓ | Returns `{passed, reason?, score?}`. Polled every 250 ms until it passes or timeout. | +| `timeoutSec` | – | Default 120. Wall-clock cap. | +| `startPose` | – | `{x, y, z, yaw?}` — applied before `setup`. Yaw in degrees. | +| `setup(ctx)` | – | Async fn run once at start — spawn obstacles, set props, anything. | + +## The `ctx` object + +Both `setup(ctx)` and `success(ctx)` receive: + +| Field | What | +|---|---| +| `ctx.agent` | The live agent — `setPosition`, `getPosition`, `group`, etc. | +| `ctx.agentPos` | `{x, y, z}` — current translation, convenience copy. | +| `ctx.sceneState` | `{assets, agentPos}` — used by rubric helpers. | +| `ctx.setAgentPose({x, y, z, yaw?})` | Teleport the agent. | +| `ctx.findAsset(query)` | Case-insensitive search by title or id. | +| `ctx.dist(a, b)` | Euclidean distance. | +| `ctx.rubrics.objectDistance({target, thresholdM?})` | Pass if agent is within `thresholdM` of `target`'s bbox surface. | +| `ctx.rubrics.radiusContains({targets, radiusM?})` | Pass if agent is within `radiusM` of the centroid of `targets`. | + +## Custom scoring + +If neither built-in rubric fits, write the logic inline: + +```js +success: ({ agentPos, findAsset, dist }) => { + const tv = findAsset('television'); + const couch = findAsset('sectional'); + if (!tv || !couch) return { passed: false, reason: 'targets missing' }; + const mid = { + x: (tv.transform.x + couch.transform.x) / 2, + y: 0, + z: (tv.transform.z + couch.transform.z) / 2, + }; + const d = dist(agentPos, mid); + return { passed: d <= 1.5, score: d, reason: `${d.toFixed(2)}m from midpoint` }; +} +``` + +## Scripted setup + +`setup(ctx)` is async — do whatever you need before scoring starts: + +```js +setup: async ({ agent }) => { + agent.setPosition(-3, 0.5, 0); + await new Promise(r => setTimeout(r, 250)); // let physics settle +}, +``` + +You can spawn obstacles, change embodiments mid-eval, or set up multi-stage tests here. The harness doesn't constrain you. + +## Tips + +- **One eval at a time.** The harness is a singleton; running two evals concurrently isn't supported. Use `--parallel N` with multiple browser pages for throughput. +- **Score is yours to define.** Lower-is-better for distances, higher-is-better for coverage — CI consumers should not assume. +- **`startPose` yaw is in degrees**, not radians. +- **`setup`/`success` callbacks can use any browser API** (THREE, scene, Rapier) — they run in the browser context, not in Deno. diff --git a/misc/DimSim/docs/getting-started.md b/misc/DimSim/docs/getting-started.md new file mode 100644 index 0000000000..d9a294917d --- /dev/null +++ b/misc/DimSim/docs/getting-started.md @@ -0,0 +1,88 @@ +# Getting started + +5-minute tour. For deeper guides see [scenes.md](scenes.md) and [evals.md](evals.md). + +## The two ways DimSim runs + +```bash +# 1. dimos drives DimSim (production / agentic / CI) +.venv/bin/dimos --simulation dimsim --dimsim-scene=apartment run unitree-go2-agentic + +# 2. DimSim runs standalone (engine dev / scene authoring) +cd misc/DimSim/cli +deno run -A --unstable-net cli.ts dev --scene apartment +``` + +Both end up with a Vite-built `dist/` and a bridge on port 8090. Same scenes, same browser. Difference is just who's driving the agent. + +If you install the CLI globally, replace the `deno run` boilerplate with `dimsim`: + +```bash +cd misc/DimSim/cli +deno install -gAf --unstable-net --name=dimsim --config=./deno.json ./cli.ts +``` + +## 60-second loop: edit a scene + +1. `dimsim dev --scene warehouse` +2. Open `misc/DimSim/scenes/warehouse/index.js` in your editor. +3. Change `setSky({ brightness: 0.7 })` to `setSky({ brightness: 1.5 })`. Save. +4. The browser HMR-reloads — brighter sky. + +## 60-second loop: write an eval + +`misc/DimSim/scenes/apartment/evals/look-at-window.js`: + +```js +import { runEval } from '@dimsim/eval'; + +await runEval({ + scene: 'apartment', + task: 'Stand near a window', + timeoutSec: 20, + startPose: { x: 0, y: 0.5, z: 3, yaw: 0 }, + success: (ctx) => ctx.rubrics.objectDistance({ target: 'window', thresholdM: 1.5 }), +}); +``` + +From a separate terminal (while the sim is running): + +```bash +dimsim eval look-at-window +``` + +The browser shows a green/red overlay when it finishes, and the result echoes in your terminal. + +## Where things live + +``` +src/ engine + scene API + bridge client (browser, vite-bundled) +cli/ dimsim CLI + bridge server (Deno) +evals/ eval harness + rubrics + Deno client (both runtimes) +scenes/ YOUR scenes — author here +public/ static assets (default robot GLB) +docs/ guides +``` + +## Quick reference + +| What | How | +|---|---| +| Launch sim + open browser | `dimsim dev --scene ` | +| Launch headless | `dimsim dev --scene --headless` | +| List eval workflows | `dimsim eval list` | +| Run one eval against open sim | `dimsim eval ` | +| Run one eval headless | `dimsim eval --headless --scene --workflow ` | +| Run all evals for a scene | `dimsim eval --headless --scene ` | +| Run all evals, JUnit XML | `dimsim eval --headless --output junit > junit.xml` | +| Direct workflow execution | `deno run -A scenes//evals/.js` | +| Build the frontend manually | `cd misc/DimSim && npm run build` | +| Spin up a profiler | `bash scripts/profile-live.sh` | +| Verify cmd_vel → odom round-trip | `python cli/test/dimos_integration.py` | + +## Common gotchas + +- **Headless slow to boot on CI** — use `--render cpu` and bump `--timeout 120000`. +- **`unitree-go2-basic` hides lidar in Rerun** by override. Click the eye icon in the Rerun entity tree, or use `unitree-go2-spatial` / `unitree-go2-agentic` which leave it visible. +- **Click-to-nav** in Rerun only works on nav-enabled blueprints (`unitree-go2-agentic` and friends). `unitree-go2-basic` has no nav stack. +- **First launch is slow** — Vite builds `dist/` on first run (~20s). Subsequent runs reuse it. diff --git a/misc/DimSim/docs/scenes.md b/misc/DimSim/docs/scenes.md new file mode 100644 index 0000000000..fe97b2565c --- /dev/null +++ b/misc/DimSim/docs/scenes.md @@ -0,0 +1,186 @@ +# Scenes + +A scene is one JS file: `scenes//index.js`. It default-exports an async `build(api)` function. DimSim hot-reloads it on save. + +## Create a new scene + +```bash +mkdir -p misc/DimSim/scenes/my-room +``` + +`misc/DimSim/scenes/my-room/index.js`: + +```js +export default async function build({ scene, THREE, physics, setSky }) { + setSky({ topColor: '#3a4654', horizonColor: '#cfd6df', brightness: 0.8 }); + + // floor + const floor = new THREE.Mesh( + new THREE.BoxGeometry(20, 0.2, 20), + new THREE.MeshPhysicalMaterial({ color: 0x808080, roughness: 0.9 }), + ); + floor.position.y = -0.1; + scene.add(floor); + physics.staticCollider(floor, 'box'); + + // a wall + const wall = new THREE.Mesh( + new THREE.BoxGeometry(20, 3, 0.2), + new THREE.MeshPhysicalMaterial({ color: 0xc4c1b8, roughness: 0.8 }), + ); + wall.position.set(0, 1.5, -10); + scene.add(wall); + physics.staticCollider(wall, 'box'); + + // lighting + scene.add(new THREE.HemisphereLight(0xffffff, 0x404040, 0.6)); + const sun = new THREE.DirectionalLight(0xffffff, 1.0); + sun.position.set(10, 20, 10); + sun.castShadow = true; + scene.add(sun); + + return { spawnPoint: { x: 0, y: 0.5, z: 0 } }; +} +``` + +Run it: + +```bash +dimsim dev --scene my-room +# or via dimos: +dimos --simulation dimsim --dimsim-scene=my-room run unitree-go2-basic +``` + +## Edit a scene + +Open the file, edit, save. The browser HMR-reloads — no full refresh. + +The whole `build()` re-runs on every save, so iteration is cheap. Try changing `setSky({ brightness: 0.8 })` to `1.5` — the sky brightens within a second. + +## The `api` argument + +`build(api)` gets one argument — destructure what you need: + +| Field | What | +|---|---| +| `scene` | The `THREE.Scene`. `scene.add(mesh)` anything you want rendered. | +| `THREE` | The engine's THREE module. Use this rather than re-importing. | +| `physics.staticCollider(mesh, shape)` | Make a mesh solid (agent can't walk through, lidar hits it). `shape`: `'box'` \| `'trimesh'` \| `'sphere'`. | +| `physics.dynamicCollider(mesh, {mass, shape})` | Mesh becomes a rigid body — falls, can be pushed. Engine syncs `mesh.position` each frame. | +| `setSky({...})` | Atmosphere. Keys: `topColor`, `horizonColor`, `bottomColor`, `brightness`, `softness`, `sunStrength`, `sunHeight`. | +| `setEmbodiment({...})` | Declare the agent — avatar GLB + capsule dimensions + physics mode + control params. See "Robot embodiment" below. | +| `loadGLTF(url)` | Async GLB load — `await loadGLTF('./forklift.glb')` returns `{scene, animations, …}`. | +| `agent`, `camera`, `renderer`, `RAPIER`, `rapierWorld` | Live engine refs if you need them. | + +## Robot embodiment + +`setEmbodiment(config)` swaps the avatar mesh **and** reconfigures the bridge's server-side physics + lidar mount — so changing `embodimentType` from `'ground'` to `'drone'` instantly switches the cmd_vel → motion mapping from differential-drive (with gravity) to 6DoF flight (no gravity, altitude clamp). + +```js +// ground robot (default) +setEmbodiment({ + embodimentType: 'ground', + avatarUrl: '/agent-model/dimsim_unitree_stub.glb', + radius: 0.18, + halfHeight: 0.25, + maxSpeed: 1.5, + turnRate: 2.5, + gravity: -9.81, +}); + +// drone +setEmbodiment({ + embodimentType: 'drone', + avatarUrl: '/agent-model/dimsim_unitree_stub.glb', + radius: 0.3, + halfHeight: 0.1, + gravity: 0, + maxSpeed: 3.0, + turnRate: 2.0, + maxAltitude: 8, +}); +``` + +| Field | What | +|---|---| +| `embodimentType` | `'ground'` (differential-drive + gravity) or `'drone'` (6DoF). | +| `avatarUrl` | URL of the GLB to render. Bridge serves `/agent-model/*` from `public/`. | +| `radius`, `halfHeight` | Capsule collider dimensions. Also drive lidar mount height. | +| `maxSpeed` | Linear cmd_vel scale. | +| `turnRate` | Angular.z cmd_vel scale. | +| `gravity` | m/s². `0` for flight, `-9.81` for ground. | +| `maxAltitude` | Drone-only ceiling. | +| `lidarMountHeight`, `maxStepHeight`, `groundSnapDist`, `maxSlopeAngle`, `friction` | Optional fine-tuning. | + +Call it once at scene-build time (anywhere in `build()`), or call it again later to swap mid-scene. `scenes/warehouse/index.js` declares a drone as its first line — see it for a working example. + +## Return value + +`build()` can return `{ spawnPoint?, embodiment? }`: + +```js +return { spawnPoint: { x: 2, y: 0.5, z: -5 } }; +``` + +If omitted, the agent spawns at `(2, 0.5, 3)`. + +## Common patterns + +**Loops for repeated geometry.** The whole module re-runs on HMR, so spawning 50 crates via a loop is fine — no `_disposed` bookkeeping needed. + +```js +const crateGeo = new THREE.BoxGeometry(1, 1, 1); +const crateMat = new THREE.MeshPhysicalMaterial({ color: 0x8b5a2b, roughness: 0.75 }); +for (let i = 0; i < 8; i++) { + const c = new THREE.Mesh(crateGeo, crateMat); + c.position.set((i % 4) - 1.5, 0.5 + Math.floor(i / 4), 3); + scene.add(c); + physics.staticCollider(c, 'box'); +} +``` + +**GLB props.** Drop a GLB next to `index.js`, then: + +```js +const gltf = await loadGLTF('./forklift.glb'); +const forklift = gltf.scene; +forklift.position.set(5, 0, 0); +scene.add(forklift); +physics.staticCollider(forklift, 'trimesh'); +``` + +**Lighting** — `HemisphereLight` for ambient fill + one `DirectionalLight` with `castShadow = true` is enough for most interiors. `PointLight`s give nice volumetric pendant effects but turn off `castShadow` to keep frame rate sane. + +**Tune the shadow camera** if shadows pop: + +```js +const sun = new THREE.DirectionalLight(0xffffff, 1.0); +sun.castShadow = true; +sun.shadow.mapSize.set(2048, 2048); +sun.shadow.camera.left = -20; +sun.shadow.camera.right = 20; +sun.shadow.camera.top = 25; +sun.shadow.camera.bottom = -25; +scene.add(sun); +``` + +**Materials** — `MeshPhysicalMaterial` supports clearcoat, sheen, transmission, iridescence — use it for anything you care about visually. The engine sets the renderer up for HDR/PBR. + +## Always pair `scene.add(mesh)` with a collider + +Otherwise the agent walks through it and lidar passes straight through: + +```js +scene.add(mesh); +physics.staticCollider(mesh, 'box'); // ← don't skip this +``` + +Pure-visual meshes (decoration the agent can't bump into) — skip the collider on purpose. Just be aware. + +## Tip: start from `scenes/empty/` + +It's a one-file scene with a floor and a sky. Copy it as a template: + +```bash +cp -r misc/DimSim/scenes/empty misc/DimSim/scenes/my-room +``` diff --git a/misc/DimSim/evals/deno-client.ts b/misc/DimSim/evals/deno-client.ts new file mode 100644 index 0000000000..4bf67d1563 --- /dev/null +++ b/misc/DimSim/evals/deno-client.ts @@ -0,0 +1,108 @@ +/// +/** + * Deno-side `@dimsim/eval` runEval — dispatch a workflow file to the + * browser via the bridge instead of running it locally. + * + * A workflow file under scenes//evals/.js does: + * + * import { runEval } from '@dimsim/eval'; + * await runEval({ scene, task, success, ... }); + * + * In the browser, that import resolves (via the index.html importmap) + * to the bundled EvalHarness chunk and runs the eval in-place. + * + * In Deno, scenes/deno.json maps `@dimsim/eval` here. We don't have a + * THREE.js scene, agent, or Rapier — we just open a control WebSocket + * to a running bridge, ship `{type:'runEval', workflowUrl}`, and wait + * for `{type:'evalResult'}`. The browser imports the same workflow + * file URL and runs the success/setup callbacks for real. + * + * Net effect: `deno run -A scenes//evals/.js` is a one-liner + * shortcut for `dimsim eval /`, both end at the same + * EvalHarness in the open browser. + */ + +import { fromFileUrl } from "@std/path"; + +interface DenoEvalResult { + type: "evalResult"; + workflowUrl: string; + scene: string; + task: string; + passed: boolean; + reason?: string; + score?: number; + durationMs: number; +} + +/** Find the "/scenes/..." segment in the entry-point file path. */ +function _resolveWorkflowUrl(): string { + const main = Deno.mainModule; + if (!main.startsWith("file://")) { + throw new Error( + `@dimsim/eval: can only infer workflow URL from a 'deno run ' invocation, got ${main}`, + ); + } + const abs = fromFileUrl(main); + const i = abs.indexOf("/scenes/"); + if (i === -1) { + throw new Error( + `@dimsim/eval: workflow file must live under a 'scenes/' directory; got ${abs}`, + ); + } + return abs.slice(i); // e.g. "/scenes/apartment/evals/go-to-couch.js" +} + +/** Open the control WebSocket, race resolve / error / 5s timeout. */ +function _connect(wsUrl: string): Promise { + return new Promise((resolve, reject) => { + const ws = new WebSocket(wsUrl); + const t = setTimeout(() => reject(new Error(`@dimsim/eval: timed out connecting to ${wsUrl}`)), 5000); + ws.addEventListener("open", () => { clearTimeout(t); resolve(ws); }, { once: true }); + ws.addEventListener("error", (e) => { clearTimeout(t); reject(e); }, { once: true }); + }); +} + +/** + * Public entry — same name + same call shape as the browser export, so + * workflow files don't change between runtimes. The `workflow` object + * is forwarded only as a logging convenience here; the browser is what + * actually runs `setup` / `success` (it re-imports the file from URL). + */ +export async function runEval(workflow: { scene?: string; task?: string }): Promise { + const workflowUrl = _resolveWorkflowUrl(); + const port = parseInt(Deno.env.get("DIMSIM_PORT") || "8090"); + const wsUrl = `ws://localhost:${port}/?ch=control`; + + console.log(`[eval] dispatching ${workflowUrl} → ${wsUrl}`); + if (workflow?.task) console.log(`[eval] task: ${workflow.task}`); + + let ws: WebSocket; + try { + ws = await _connect(wsUrl); + } catch (e: any) { + console.error(`[eval] failed to connect to bridge — is dimsim running? (${e?.message ?? e})`); + Deno.exit(2); + } + + try { + const result = await new Promise((resolve) => { + ws.addEventListener("message", (event) => { + if (typeof event.data !== "string") return; + let msg: any; + try { msg = JSON.parse(event.data); } catch { return; } + if (msg.type !== "evalResult") return; + if (msg.workflowUrl && msg.workflowUrl !== workflowUrl) return; + resolve(msg as DenoEvalResult); + }); + ws.send(JSON.stringify({ type: "runEval", workflowUrl })); + }); + + const tag = result.passed ? "\x1b[32mPASS\x1b[0m" : "\x1b[31mFAIL\x1b[0m"; + console.log(`[eval] ${tag} (${result.durationMs}ms): ${result.reason ?? ""}`); + if (!result.passed) Deno.exit(1); + return result; + } finally { + try { ws.close(); } catch { /* ignore */ } + } +} diff --git a/misc/DimSim/evals/deno.json b/misc/DimSim/evals/deno.json new file mode 100644 index 0000000000..8c12c8280f --- /dev/null +++ b/misc/DimSim/evals/deno.json @@ -0,0 +1,5 @@ +{ + "imports": { + "@std/path": "jsr:@std/path@^1" + } +} diff --git a/misc/DimSim/evals/harness.ts b/misc/DimSim/evals/harness.ts new file mode 100644 index 0000000000..188f0abe0c --- /dev/null +++ b/misc/DimSim/evals/harness.ts @@ -0,0 +1,380 @@ +/** + * EvalHarness — browser-side runner for JS-native eval workflows. + * + * A workflow is a JS module under `scenes//evals/.js` whose + * default export shapes like: + * + * export default { + * scene: 'apartment', + * task: 'Go to the couch', + * timeoutSec: 30, + * startPose: { x: 0, y: 0.5, z: 3, yaw: 0 }, // optional sugar + * setup: async (ctx) => { … }, // optional + * success: (ctx) => ({ passed, reason?, score? }), + * }; + * + * The Deno runner sends one `{type:'runEval', workflowUrl, channel?}` WS + * message; this class dynamic-imports the module, runs `setup(ctx)` once, + * then polls `success(ctx)` every 250 ms until passed or timeout, and + * replies with `{type:'evalResult', …}`. No JSON criteria, no runner-side + * orchestration — the workflow file is the source of truth. + */ + +import { + type SceneState, type AssetEntry, type EvalSuccess as _EvalSuccess, + type ObjectDistanceOpts, type RadiusContainsOpts, + findAsset, dist, objectDistance, radiusContains, +} from "./rubrics.ts"; +import type { DimosBridge } from "../bridge.ts"; + +export interface AgentPose { x: number; y: number; z: number; yaw: number; pitch: number; } +export interface StartPose { x?: number; y?: number; z?: number; yaw?: number; } + +/** Shape returned by `workflow.success(ctx)`. */ +export interface EvalSuccess { + passed: boolean; + reason?: string; + score?: number; +} + +/** Context passed to `workflow.setup(ctx)` and `workflow.success(ctx)`. */ +export interface EvalContext { + agent: any; + agentPos: { x: number; y: number; z: number }; + sceneState: SceneState; + setAgentPose: (p: StartPose) => void; + findAsset: (q: string) => AssetEntry | null; + dist: (a: { x: number; y: number; z: number }, b: { x: number; y: number; z: number }) => number; + /** Pre-bound high-level rubric helpers — `ctx.rubrics.objectDistance({...})` etc. */ + rubrics: { + objectDistance: (opts: ObjectDistanceOpts) => EvalSuccess; + radiusContains: (opts: RadiusContainsOpts) => EvalSuccess; + }; +} + +/** Default-export shape of a workflow file. */ +export interface EvalWorkflow { + scene: string; + task: string; + timeoutSec?: number; + startPose?: StartPose; + setup?: (ctx: EvalContext) => void | Promise; + success: (ctx: EvalContext) => EvalSuccess; +} + +export interface EvalResultMsg { + type: "evalResult"; + workflowUrl: string; + scene: string; + task: string; + passed: boolean; + reason?: string; + score?: number; + durationMs: number; + channel?: string; +} + +export interface EvalHarnessOptions { + bridge: DimosBridge; + getSceneState: () => SceneState; + getAgentPose: () => AgentPose | null; + channel?: string; +} + +declare global { + interface Window { __dimosAgent?: any; } +} + +// ── Singleton registration ────────────────────────────────────────────────── +// +// Workflow files import `runEval` from `@dimsim/eval`. The importmap in +// index.html points that bare specifier at this very chunk's bundled +// filename (pinned by vite.config.js → `dist/assets/dimsim-eval.js`), so +// the workflow ends up importing this same module — which means it sees +// the `_instance` set below by engine.js after EvalHarness construction. + +let _instance: EvalHarness | null = null; +let _readyResolvers: Array<() => void> = []; + +/** engine.js calls this once the harness is wired up. */ +export function setEvalHarness(h: EvalHarness): void { + _instance = h; + const r = _readyResolvers; + _readyResolvers = []; + for (const fn of r) fn(); +} + +async function _waitForInstance(): Promise { + if (_instance) return _instance; + await new Promise((resolve) => _readyResolvers.push(resolve)); + return _instance!; +} + +/** + * Public entry — what workflow files call after importing from + * `@dimsim/eval`. Resolves when the workflow finishes (passed, failed, + * or timed out); also sends a `{type:'evalResult'}` WS message for the + * Deno runner along the way. + */ +export async function runEval(workflow: EvalWorkflow): Promise { + const h = await _waitForInstance(); + return h.runEval(workflow); +} + +// ──────────────────────────────────────────────────────────────────────────── + +export class EvalHarness { + bridge: DimosBridge; + getSceneState: () => SceneState; + getAgentPose: () => AgentPose | null; + channel: string; + + _activeUrl: string | null = null; + _overlay: HTMLDivElement | null = null; + + constructor({ bridge, getSceneState, getAgentPose, channel }: EvalHarnessOptions) { + this.bridge = bridge; + this.getSceneState = getSceneState; + this.getAgentPose = getAgentPose; + this.channel = channel || ""; + this._hookBridgeMessages(); + } + + // ── WS plumbing ──────────────────────────────────────────────────────────── + + _hookBridgeMessages(): void { + const origConnect = this.bridge.connect.bind(this.bridge); + this.bridge.connect = () => { + origConnect(); + setTimeout(() => { + const ws = this.bridge.ws; + if (ws) this._patchWsOnMessage(ws); + }, 100); + }; + const ws = this.bridge.ws; + if (ws) this._patchWsOnMessage(ws); + } + + _patchWsOnMessage(ws: WebSocket): void { + const origOnMessage = ws.onmessage; + const evalTypes = new Set(["runEval", "ping"]); + ws.onmessage = (event: MessageEvent) => { + if (typeof event.data === "string") { + try { + const cmd = JSON.parse(event.data); + if (cmd.type && evalTypes.has(cmd.type)) { + this._handleCommand(cmd); + return; + } + } catch { /* not JSON */ } + if (origOnMessage) (origOnMessage as (e: MessageEvent) => void).call(ws, event); + return; + } + if (origOnMessage) (origOnMessage as (e: MessageEvent) => void).call(ws, event); + }; + } + + _send(msg: Record): void { + if (this.channel) msg.channel = this.channel; + this.bridge.sendCommand(msg); + } + + async _handleCommand(cmd: { type: string; channel?: string; [k: string]: any }): Promise { + if (this.channel && cmd.channel && cmd.channel !== this.channel) return; + switch (cmd.type) { + case "runEval": + await this._loadAndRunWorkflowFile(cmd.workflowUrl); + break; + case "ping": + this._send({ type: "pong", ts: Date.now() }); + break; + } + } + + /** + * WS-driven entry: dynamic-import a workflow file. The file's top-level + * `await runEval({...})` (via the `@dimsim/eval` import map) calls + * `this.runEval(workflow)` and sends the result WS message itself. We + * just await the import — when it resolves the eval is done. + */ + async _loadAndRunWorkflowFile(workflowUrl: string): Promise { + try { + const cacheBust = `?t=${Date.now()}`; + await import(/* @vite-ignore */ workflowUrl + cacheBust); + } catch (e: any) { + console.error("[eval] failed to import %s:", workflowUrl, e); + this._send({ + type: "evalResult", workflowUrl, scene: "", task: "", + passed: false, reason: `import failed: ${e?.message ?? e}`, + durationMs: 0, + }); + } + } + + // ── Public entry point (called by workflow files via @dimsim/eval) ───────── + + /** + * Run a workflow object end-to-end. Workflow files do: + * + * import { runEval } from '@dimsim/eval'; + * await runEval({ scene, task, success, … }); + * + * That import resolves to public/_dimsim/eval-api.js which delegates to + * this method via `window.__dimsim.eval.runEval`. Result is both + * returned to the caller AND sent over WS as `{type:'evalResult'}` for + * the Deno runner. + */ + async runEval(workflow: EvalWorkflow): Promise { + if (!workflow || typeof workflow.success !== "function") { + const msg = "runEval(workflow) requires { scene, task, success() }"; + console.error(`[eval] ${msg}`); + return this._fail("", "", "", msg); + } + const tag = `${workflow.scene ?? "?"}/${workflow.task}`; + if (this._activeUrl) { + const err = `another eval is already running: ${this._activeUrl}`; + console.warn(`[eval] ${err}`); + return this._fail("", workflow.scene, workflow.task, err); + } + this._activeUrl = tag; + + console.log(`[eval] running: ${tag}`); + this._showOverlay(workflow.task, workflow.timeoutSec ?? 120); + + const start = Date.now(); + const timeoutMs = (workflow.timeoutSec ?? 120) * 1000; + const ctx = this._makeContext(); + + if (workflow.startPose) ctx.setAgentPose(workflow.startPose); + if (workflow.setup) { + try { await workflow.setup(ctx); } + catch (e: any) { + const reason = `setup() threw: ${e?.message ?? e}`; + console.error(`[eval] ${reason}`); + this._activeUrl = null; + return this._fail("", workflow.scene, workflow.task, reason, Date.now() - start); + } + } + + return new Promise((resolve) => { + const tick = () => { + const elapsed = Date.now() - start; + let result: EvalSuccess; + try { + result = workflow.success(this._makeContext()); + } catch (e: any) { + result = { passed: false, reason: `success() threw: ${e?.message ?? e}` }; + } + if (result.passed) { + this._finish(workflow, true, result, elapsed, resolve); + return; + } + if (elapsed >= timeoutMs) { + this._finish(workflow, false, { passed: false, ...result, reason: result.reason ?? "timeout" }, elapsed, resolve); + return; + } + setTimeout(tick, 250); + }; + tick(); + }); + } + + // ── Internals ────────────────────────────────────────────────────────────── + + _makeContext(): EvalContext { + const sceneState = this.getSceneState(); + const pose = this.getAgentPose(); + const agentPos = pose + ? { x: pose.x, y: pose.y, z: pose.z } + : { x: 0, y: 0, z: 0 }; + sceneState.agentPos = agentPos; + const ctxLite = { agentPos, sceneState }; + return { + agent: window.__dimosAgent, + agentPos, + sceneState, + setAgentPose: (p) => { + const a = window.__dimosAgent; + if (!a) return; + a.setPosition(p.x ?? 0, p.y ?? 0.5, p.z ?? 0); + if (p.yaw !== undefined && a.group) a.group.rotation.y = (p.yaw * Math.PI) / 180; + }, + findAsset: (q) => findAsset(q, sceneState), + dist, + rubrics: { + objectDistance: (opts) => objectDistance(ctxLite, opts), + radiusContains: (opts) => radiusContains(ctxLite, opts), + }, + }; + } + + _finish( + wf: EvalWorkflow, passed: boolean, + result: EvalSuccess, durationMs: number, + resolve: (msg: EvalResultMsg) => void, + ): void { + const msg: EvalResultMsg = { + type: "evalResult", + workflowUrl: "", + scene: wf.scene, + task: wf.task, + passed, + reason: result.reason, + score: result.score, + durationMs, + }; + console.log(`[eval] ${passed ? "PASS" : "FAIL"} (${durationMs}ms): ${result.reason ?? ""}`); + this._showResult(passed, result.reason ?? (passed ? "ok" : "fail")); + this._send(msg); + this._activeUrl = null; + resolve(msg); + } + + _fail(workflowUrl: string, scene: string, task: string, reason: string, durationMs = 0): EvalResultMsg { + const msg: EvalResultMsg = { + type: "evalResult", workflowUrl, scene, task, + passed: false, reason, durationMs, + }; + this._send(msg); + return msg; + } + + // ── UI overlay ───────────────────────────────────────────────────────────── + + _showOverlay(task: string, timeoutSec: number): void { + if (this._overlay) this._overlay.remove(); + const el = document.createElement("div"); + el.style.cssText = "position:fixed;top:16px;left:50%;transform:translateX(-50%);z-index:99999;background:rgba(0,0,0,0.85);color:#fff;font:14px/1.5 monospace;padding:12px 24px;border-radius:10px;text-align:center;pointer-events:none;"; + const taskEl = document.createElement("div"); + taskEl.style.cssText = "color:#4fc3f7;font-size:16px;font-weight:bold;margin-bottom:4px;"; + taskEl.textContent = `EVAL: ${task}`; + const timerEl = document.createElement("div"); + timerEl.style.cssText = "color:#aaa;font-size:13px;"; + el.appendChild(taskEl); el.appendChild(timerEl); + document.body.appendChild(el); + this._overlay = el; + + let remaining = timeoutSec; + timerEl.textContent = `${remaining}s remaining`; + const interval = setInterval(() => { + remaining--; + if (remaining <= 0 || !this._activeUrl) { clearInterval(interval); return; } + timerEl.textContent = `${remaining}s remaining`; + }, 1000); + } + + _showResult(pass: boolean, details: string): void { + if (this._overlay) this._overlay.remove(); + const el = document.createElement("div"); + const bg = pass ? "rgba(46,125,50,0.9)" : "rgba(198,40,40,0.9)"; + el.style.cssText = `position:fixed;top:16px;left:50%;transform:translateX(-50%);z-index:99999;background:${bg};color:#fff;font:14px/1.5 monospace;padding:12px 24px;border-radius:10px;text-align:center;pointer-events:none;`; + el.textContent = `${pass ? "PASS" : "FAIL"}: ${details}`; + document.body.appendChild(el); + this._overlay = el; + setTimeout(() => { if (this._overlay === el) { el.remove(); this._overlay = null; } }, 5000); + } + + dispose(): void { + if (this._overlay) { this._overlay.remove(); this._overlay = null; } + } +} diff --git a/misc/DimSim/evals/rubrics.ts b/misc/DimSim/evals/rubrics.ts new file mode 100644 index 0000000000..dac7aaee47 --- /dev/null +++ b/misc/DimSim/evals/rubrics.ts @@ -0,0 +1,127 @@ +/** + * Eval rubric helpers — building blocks for `workflow.success(ctx)`. + * + * Two layers of API: + * + * 1. High-level rubrics that match the common eval shapes and return an + * `EvalSuccess` ({passed, reason, score}) directly: + * - objectDistance({ target, thresholdM }) + * - radiusContains({ targets, radiusM }) + * + * 2. Low-level helpers if you want to write the scoring inline: + * - findAsset(query, sceneState) → AssetEntry | null + * - dist(a, b) → number + * - distToSurface(point, center, bbox?) → number + */ + +export interface Vec3 { x: number; y: number; z: number; } + +export interface AssetEntry { + title?: string; + id?: string; + transform?: { x?: number; y?: number; z?: number }; + _bbox?: { w: number; h: number; d: number }; +} + +export interface SceneState { + assets?: AssetEntry[]; + agentPos?: Vec3; +} + +export interface EvalSuccess { + passed: boolean; + reason?: string; + score?: number; +} + +// ── Low-level helpers ──────────────────────────────────────────────────────── + +export function dist(a: Vec3, b: Vec3): number { + const dx = a.x - b.x, dy = a.y - b.y, dz = a.z - b.z; + return Math.sqrt(dx * dx + dy * dy + dz * dz); +} + +export function distToSurface(point: Vec3, center: Vec3, bbox?: { w: number; h: number; d: number }): number { + if (!bbox) return dist(point, center); + const hw = bbox.w / 2, hh = bbox.h / 2, hd = bbox.d / 2; + const cx = Math.max(center.x - hw, Math.min(point.x, center.x + hw)); + const cy = Math.max(center.y - hh, Math.min(point.y, center.y + hh)); + const cz = Math.max(center.z - hd, Math.min(point.z, center.z + hd)); + return dist(point, { x: cx, y: cy, z: cz }); +} + +/** Find the first asset whose title or id contains `query` (case-insensitive). */ +export function findAsset(query: string, sceneState: SceneState): AssetEntry | null { + if (!sceneState.assets) return null; + const lower = query.toLowerCase(); + for (const a of sceneState.assets) { + if (a.title?.toLowerCase().includes(lower) || a.id?.toLowerCase().includes(lower)) return a; + } + return null; +} + +function assetPos(a: AssetEntry): Vec3 | null { + if (!a.transform) return null; + return { x: a.transform.x ?? 0, y: a.transform.y ?? 0, z: a.transform.z ?? 0 }; +} + +// ── High-level rubrics (return EvalSuccess directly) ───────────────────────── + +export interface ObjectDistanceOpts { + target: string; + thresholdM?: number; +} + +/** Pass when the agent is within `thresholdM` of the target's bbox surface. */ +export function objectDistance( + ctx: { agentPos: Vec3; sceneState: SceneState }, + { target, thresholdM = 0.5 }: ObjectDistanceOpts, +): EvalSuccess { + const hit = findAsset(target, ctx.sceneState); + if (!hit) return { passed: false, reason: `target "${target}" not found in scene`, score: Infinity }; + const pos = assetPos(hit); + if (!pos) return { passed: false, reason: `target "${target}" has no transform`, score: Infinity }; + const d = distToSurface(ctx.agentPos, pos, hit._bbox); + return { + passed: d <= thresholdM, + score: Math.round(d * 1000) / 1000, + reason: `${d.toFixed(3)}m to "${hit.title ?? target}" (threshold ${thresholdM}m)`, + }; +} + +export interface RadiusContainsOpts { + targets: string[]; + radiusM?: number; +} + +/** Pass when the agent is within `radiusM` of the centroid of the listed targets. */ +export function radiusContains( + ctx: { agentPos: Vec3; sceneState: SceneState }, + { targets, radiusM = 3.0 }: RadiusContainsOpts, +): EvalSuccess { + if (!targets || targets.length === 0) return { passed: false, reason: "no targets specified" }; + + const found: Vec3[] = []; + const missing: string[] = []; + for (const name of targets) { + const a = findAsset(name, ctx.sceneState); + const p = a ? assetPos(a) : null; + if (p) found.push(p); + else missing.push(name); + } + if (found.length === 0) { + return { passed: false, reason: `no targets found: ${missing.join(", ")}`, score: Infinity }; + } + + const centroid: Vec3 = { x: 0, y: 0, z: 0 }; + for (const p of found) { centroid.x += p.x; centroid.y += p.y; centroid.z += p.z; } + centroid.x /= found.length; centroid.y /= found.length; centroid.z /= found.length; + + const d = Math.round(dist(ctx.agentPos, centroid) * 1000) / 1000; + const missingNote = missing.length ? ` (missing: ${missing.join(", ")})` : ""; + return { + passed: d <= radiusM, + score: d, + reason: `${d.toFixed(3)}m to centroid of ${found.length} targets${missingNote} (radius ${radiusM}m)`, + }; +} diff --git a/misc/DimSim/evals/runner.ts b/misc/DimSim/evals/runner.ts new file mode 100644 index 0000000000..ce28c36f22 --- /dev/null +++ b/misc/DimSim/evals/runner.ts @@ -0,0 +1,251 @@ +/** + * Eval Runner — Deno-side orchestrator. + * + * Walks `scenes//evals/*.js` to discover workflows, then for each one + * opens a control WebSocket to the bridge, sends `{type:'runEval', + * workflowUrl}`, and awaits the `{type:'evalResult', ...}` reply from the + * browser-side harness. + * + * No JSON parsing. No manifest.json. The workflow file is the source of + * truth — its `setup(ctx)` runs in the browser, its `success(ctx)` is + * polled until passed or timeout, and the runner just collects results. + */ + +import { resolve } from "@std/path"; + +export interface EvalResult { + scene: string; + workflow: string; + workflowUrl: string; + task: string; + passed: boolean; + reason: string; + score: number | null; + durationMs: number; +} + +export interface WorkflowEntry { + scene: string; + workflow: string; + filePath: string; + /** URL the browser uses to dynamic-import the workflow module. */ + url: string; +} + +export interface RunEvalOptions { + /** Control WebSocket URL (no `?ch=...`). */ + wsUrl: string; + /** Absolute path to the scenes/ root. */ + scenesRoot: string; + filterScene?: string; + filterWorkflow?: string; + /** Filter to specific workflow names ("scene/workflow" or just "workflow"). */ + filterWorkflows?: string[]; +} + +/** Walk `scenes//evals/*.js` and return one entry per workflow file. */ +export function collectWorkflows(opts: { + scenesRoot: string; + filterScene?: string; + filterWorkflow?: string; + filterWorkflows?: string[]; +}): WorkflowEntry[] { + const { scenesRoot, filterScene, filterWorkflow, filterWorkflows } = opts; + const matchSet = filterWorkflows && filterWorkflows.length + ? new Set(filterWorkflows) + : null; + + const out: WorkflowEntry[] = []; + let sceneDirs: Deno.DirEntry[]; + try { + sceneDirs = [...Deno.readDirSync(scenesRoot)]; + } catch { + return out; + } + + for (const sceneEnt of sceneDirs) { + if (!sceneEnt.isDirectory) continue; + const scene = sceneEnt.name; + if (filterScene && filterScene !== scene) continue; + + const evalsDir = resolve(scenesRoot, scene, "evals"); + let workflowEnts: Deno.DirEntry[]; + try { + workflowEnts = [...Deno.readDirSync(evalsDir)]; + } catch { + continue; // no evals dir → no workflows for this scene + } + + for (const ent of workflowEnts) { + if (!ent.isFile || !ent.name.endsWith(".js")) continue; + const workflow = ent.name.slice(0, -3); + if (filterWorkflow && filterWorkflow !== workflow) continue; + if (matchSet && !matchSet.has(workflow) && !matchSet.has(`${scene}/${workflow}`)) continue; + + out.push({ + scene, + workflow, + filePath: resolve(evalsDir, ent.name), + url: `/scenes/${scene}/evals/${ent.name}`, + }); + } + } + return out; +} + +/** Run each workflow sequentially over one control WebSocket. */ +export async function runEvals(options: RunEvalOptions): Promise { + const workflows = collectWorkflows(options); + if (workflows.length === 0) { + console.log("[runner] no workflows match filter — nothing to do."); + return []; + } + console.log(`[runner] running ${workflows.length} workflow(s)…`); + + const ws = await _connect(options.wsUrl); + try { + const results: EvalResult[] = []; + for (const wf of workflows) { + console.log(`[runner] → ${wf.scene}/${wf.workflow}`); + const result = await _runOne(ws, wf); + results.push(result); + const tag = result.passed ? "PASS" : "FAIL"; + console.log(`[runner] ${tag} (${result.durationMs}ms): ${result.reason}`); + } + return results; + } finally { + try { ws.close(); } catch { /* ignore */ } + } +} + +/** Parallel variant — one control WS per channel, workflows round-robin'd across them. */ +export interface RunEvalsMultiPageOptions extends RunEvalOptions { + /** Channel names from launchMultiPage (one per browser page). */ + channels: string[]; +} + +export async function runEvalsMultiPage(options: RunEvalsMultiPageOptions): Promise { + const workflows = collectWorkflows(options); + if (workflows.length === 0 || options.channels.length === 0) return []; + + // Open one socket per channel. + // Two query params: + // channel= → routes the WS to that channel's bridge state + // ch=control → marks it as a control (not sensor) socket so text + // frames (the `runEval` JSON) are processed, not dropped + const sockets = await Promise.all( + options.channels.map((ch) => + _connect(`${options.wsUrl}/?channel=${encodeURIComponent(ch)}&ch=control`), + ), + ); + + // Round-robin workflows across sockets. + const queues: WorkflowEntry[][] = sockets.map(() => []); + workflows.forEach((wf, i) => queues[i % queues.length].push(wf)); + + try { + const all = await Promise.all( + sockets.map(async (ws, i) => { + const out: EvalResult[] = []; + for (const wf of queues[i]) { + console.log(`[runner:${options.channels[i]}] → ${wf.scene}/${wf.workflow}`); + out.push(await _runOne(ws, wf)); + } + return out; + }), + ); + return all.flat(); + } finally { + for (const ws of sockets) { + try { ws.close(); } catch { /* ignore */ } + } + } +} + +/** JUnit-style XML emitter for CI consumption. */ +export function toJunitXml(results: EvalResult[]): string { + const lines: string[] = []; + lines.push(''); + const failures = results.filter((r) => !r.passed).length; + lines.push(``); + for (const r of results) { + const name = `${r.scene}/${r.workflow}`; + const time = (r.durationMs / 1000).toFixed(3); + if (r.passed) { + lines.push(` `); + } else { + lines.push(` `); + lines.push(` `); + lines.push(` `); + } + } + lines.push(""); + return lines.join("\n"); +} + +// ── Internals ──────────────────────────────────────────────────────────────── + +function _connect(wsUrl: string): Promise { + // Force the control channel so eval text messages route correctly. + const url = wsUrl.includes("?") ? wsUrl : `${wsUrl}/?ch=control`; + const ws = new WebSocket(url); + return new Promise((resolve, reject) => { + ws.addEventListener("open", () => resolve(ws), { once: true }); + ws.addEventListener("error", (e) => reject(e), { once: true }); + }); +} + +function _runOne(ws: WebSocket, wf: WorkflowEntry): Promise { + return new Promise((resolve) => { + const cleanup = () => { + ws.removeEventListener("message", onMessage); + ws.removeEventListener("error", onFail); + ws.removeEventListener("close", onFail); + }; + const onMessage = (event: MessageEvent) => { + if (typeof event.data !== "string") return; + let msg: any; + try { msg = JSON.parse(event.data); } catch { return; } + if (msg.type !== "evalResult") return; + if (msg.workflowUrl && msg.workflowUrl !== wf.url) return; + cleanup(); + resolve({ + scene: wf.scene, + workflow: wf.workflow, + workflowUrl: wf.url, + task: msg.task ?? "", + passed: !!msg.passed, + reason: msg.reason ?? (msg.passed ? "ok" : "fail"), + score: typeof msg.score === "number" ? msg.score : null, + durationMs: msg.durationMs ?? 0, + }); + }; + // If the socket closes or errors before the result lands, fail the eval + // instead of hanging the entire runEvals call forever. + const onFail = (event: Event) => { + cleanup(); + const reason = event.type === "close" + ? "websocket closed before evalResult" + : "websocket error before evalResult"; + resolve({ + scene: wf.scene, + workflow: wf.workflow, + workflowUrl: wf.url, + task: "", + passed: false, + reason, + score: null, + durationMs: 0, + }); + }; + ws.addEventListener("message", onMessage); + ws.addEventListener("error", onFail); + ws.addEventListener("close", onFail); + ws.send(JSON.stringify({ type: "runEval", workflowUrl: wf.url })); + }); +} + +function _escape(s: string): string { + return s.replace(/&/g, "&").replace(//g, ">") + .replace(/"/g, """).replace(/'/g, "'"); +} diff --git a/misc/DimSim/index.html b/misc/DimSim/index.html new file mode 100644 index 0000000000..8df983a21a --- /dev/null +++ b/misc/DimSim/index.html @@ -0,0 +1,148 @@ + + + + + + DimSim + + + + + + + + + +
+
+ + + + + + +
+
+ DimSim + +
+ +
+
No scene loaded
+ + +
+ + + +
+
+ Sensor Debug +
+ + +
+
+ +
+
+ + +
+
+
+ Min + + 0.2m +
+
+ Max + + 12.0m +
+
+
+ +
+
+ +
+
+ + +
+
+
+ + +
+ Agent Vision +
+
RGB
+ Agent POV +
Depth
+ +
LiDAR
+ +
+
+ +
Waiting...
+
+
+
+ Request Details +
+
No request yet
+
+ Prompt +

+              
+
+ Context +

+              
+
+ Raw Output +

+              
+
+
+
+ Activity Log +
+
+
+ +
+ + + +
+ + +
+ + + +
+ + + + + +
+ WASD move + E interact + B spawn + G ghost +
+ + + + + + + diff --git a/misc/DimSim/package-lock.json b/misc/DimSim/package-lock.json new file mode 100644 index 0000000000..9bd3f917d7 --- /dev/null +++ b/misc/DimSim/package-lock.json @@ -0,0 +1,1022 @@ +{ + "name": "dimsim", + "version": "1.0.0", + "lockfileVersion": 3, + "requires": true, + "packages": { + "": { + "name": "dimsim", + "version": "1.0.0", + "dependencies": { + "@dimforge/rapier3d-compat": "^0.14.0", + "@sparkjsdev/spark": "latest", + "three": "^0.168.0" + }, + "devDependencies": { + "vite": "^5.4.10" + } + }, + "node_modules/@dimforge/rapier3d-compat": { + "version": "0.14.0", + "resolved": "https://registry.npmjs.org/@dimforge/rapier3d-compat/-/rapier3d-compat-0.14.0.tgz", + "integrity": "sha512-/uHrUzS+CRQ+NQrrJCEDUkhwHlNsAAexbNXgbN9sHY+GwR+SFFAFrxRr8Llf5/AJZzqiLANdQIfJ63Cw4gJVqw==", + "license": "Apache-2.0" + }, + "node_modules/@esbuild/aix-ppc64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/aix-ppc64/-/aix-ppc64-0.21.5.tgz", + "integrity": "sha512-1SDgH6ZSPTlggy1yI6+Dbkiz8xzpHJEVAlF/AM1tHPLsf5STom9rwtjE4hKAF20FfXXNTFqEYXyJNWh1GiZedQ==", + "cpu": [ + "ppc64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "aix" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/android-arm": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/android-arm/-/android-arm-0.21.5.tgz", + "integrity": "sha512-vCPvzSjpPHEi1siZdlvAlsPxXl7WbOVUBBAowWug4rJHb68Ox8KualB+1ocNvT5fjv6wpkX6o/iEpbDrf68zcg==", + "cpu": [ + "arm" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "android" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/android-arm64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/android-arm64/-/android-arm64-0.21.5.tgz", + "integrity": "sha512-c0uX9VAUBQ7dTDCjq+wdyGLowMdtR/GoC2U5IYk/7D1H1JYC0qseD7+11iMP2mRLN9RcCMRcjC4YMclCzGwS/A==", + "cpu": [ + "arm64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "android" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/android-x64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/android-x64/-/android-x64-0.21.5.tgz", + "integrity": "sha512-D7aPRUUNHRBwHxzxRvp856rjUHRFW1SdQATKXH2hqA0kAZb1hKmi02OpYRacl0TxIGz/ZmXWlbZgjwWYaCakTA==", + "cpu": [ + "x64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "android" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/darwin-arm64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/darwin-arm64/-/darwin-arm64-0.21.5.tgz", + "integrity": "sha512-DwqXqZyuk5AiWWf3UfLiRDJ5EDd49zg6O9wclZ7kUMv2WRFr4HKjXp/5t8JZ11QbQfUS6/cRCKGwYhtNAY88kQ==", + "cpu": [ + "arm64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "darwin" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/darwin-x64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/darwin-x64/-/darwin-x64-0.21.5.tgz", + "integrity": "sha512-se/JjF8NlmKVG4kNIuyWMV/22ZaerB+qaSi5MdrXtd6R08kvs2qCN4C09miupktDitvh8jRFflwGFBQcxZRjbw==", + "cpu": [ + "x64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "darwin" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/freebsd-arm64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/freebsd-arm64/-/freebsd-arm64-0.21.5.tgz", + "integrity": "sha512-5JcRxxRDUJLX8JXp/wcBCy3pENnCgBR9bN6JsY4OmhfUtIHe3ZW0mawA7+RDAcMLrMIZaf03NlQiX9DGyB8h4g==", + "cpu": [ + "arm64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "freebsd" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/freebsd-x64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/freebsd-x64/-/freebsd-x64-0.21.5.tgz", + "integrity": "sha512-J95kNBj1zkbMXtHVH29bBriQygMXqoVQOQYA+ISs0/2l3T9/kj42ow2mpqerRBxDJnmkUDCaQT/dfNXWX/ZZCQ==", + "cpu": [ + "x64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "freebsd" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/linux-arm": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/linux-arm/-/linux-arm-0.21.5.tgz", + "integrity": "sha512-bPb5AHZtbeNGjCKVZ9UGqGwo8EUu4cLq68E95A53KlxAPRmUyYv2D6F0uUI65XisGOL1hBP5mTronbgo+0bFcA==", + "cpu": [ + "arm" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/linux-arm64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/linux-arm64/-/linux-arm64-0.21.5.tgz", + "integrity": "sha512-ibKvmyYzKsBeX8d8I7MH/TMfWDXBF3db4qM6sy+7re0YXya+K1cem3on9XgdT2EQGMu4hQyZhan7TeQ8XkGp4Q==", + "cpu": [ + "arm64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/linux-ia32": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/linux-ia32/-/linux-ia32-0.21.5.tgz", + "integrity": "sha512-YvjXDqLRqPDl2dvRODYmmhz4rPeVKYvppfGYKSNGdyZkA01046pLWyRKKI3ax8fbJoK5QbxblURkwK/MWY18Tg==", + "cpu": [ + "ia32" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/linux-loong64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/linux-loong64/-/linux-loong64-0.21.5.tgz", + "integrity": "sha512-uHf1BmMG8qEvzdrzAqg2SIG/02+4/DHB6a9Kbya0XDvwDEKCoC8ZRWI5JJvNdUjtciBGFQ5PuBlpEOXQj+JQSg==", + "cpu": [ + "loong64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/linux-mips64el": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/linux-mips64el/-/linux-mips64el-0.21.5.tgz", + "integrity": "sha512-IajOmO+KJK23bj52dFSNCMsz1QP1DqM6cwLUv3W1QwyxkyIWecfafnI555fvSGqEKwjMXVLokcV5ygHW5b3Jbg==", + "cpu": [ + "mips64el" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/linux-ppc64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/linux-ppc64/-/linux-ppc64-0.21.5.tgz", + "integrity": "sha512-1hHV/Z4OEfMwpLO8rp7CvlhBDnjsC3CttJXIhBi+5Aj5r+MBvy4egg7wCbe//hSsT+RvDAG7s81tAvpL2XAE4w==", + "cpu": [ + "ppc64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/linux-riscv64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/linux-riscv64/-/linux-riscv64-0.21.5.tgz", + "integrity": "sha512-2HdXDMd9GMgTGrPWnJzP2ALSokE/0O5HhTUvWIbD3YdjME8JwvSCnNGBnTThKGEB91OZhzrJ4qIIxk/SBmyDDA==", + "cpu": [ + "riscv64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/linux-s390x": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/linux-s390x/-/linux-s390x-0.21.5.tgz", + "integrity": "sha512-zus5sxzqBJD3eXxwvjN1yQkRepANgxE9lgOW2qLnmr8ikMTphkjgXu1HR01K4FJg8h1kEEDAqDcZQtbrRnB41A==", + "cpu": [ + "s390x" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/linux-x64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/linux-x64/-/linux-x64-0.21.5.tgz", + "integrity": "sha512-1rYdTpyv03iycF1+BhzrzQJCdOuAOtaqHTWJZCWvijKD2N5Xu0TtVC8/+1faWqcP9iBCWOmjmhoH94dH82BxPQ==", + "cpu": [ + "x64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/netbsd-x64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/netbsd-x64/-/netbsd-x64-0.21.5.tgz", + "integrity": "sha512-Woi2MXzXjMULccIwMnLciyZH4nCIMpWQAs049KEeMvOcNADVxo0UBIQPfSmxB3CWKedngg7sWZdLvLczpe0tLg==", + "cpu": [ + "x64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "netbsd" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/openbsd-x64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/openbsd-x64/-/openbsd-x64-0.21.5.tgz", + "integrity": "sha512-HLNNw99xsvx12lFBUwoT8EVCsSvRNDVxNpjZ7bPn947b8gJPzeHWyNVhFsaerc0n3TsbOINvRP2byTZ5LKezow==", + "cpu": [ + "x64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "openbsd" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/sunos-x64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/sunos-x64/-/sunos-x64-0.21.5.tgz", + "integrity": "sha512-6+gjmFpfy0BHU5Tpptkuh8+uw3mnrvgs+dSPQXQOv3ekbordwnzTVEb4qnIvQcYXq6gzkyTnoZ9dZG+D4garKg==", + "cpu": [ + "x64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "sunos" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/win32-arm64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/win32-arm64/-/win32-arm64-0.21.5.tgz", + "integrity": "sha512-Z0gOTd75VvXqyq7nsl93zwahcTROgqvuAcYDUr+vOv8uHhNSKROyU961kgtCD1e95IqPKSQKH7tBTslnS3tA8A==", + "cpu": [ + "arm64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "win32" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/win32-ia32": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/win32-ia32/-/win32-ia32-0.21.5.tgz", + "integrity": "sha512-SWXFF1CL2RVNMaVs+BBClwtfZSvDgtL//G/smwAc5oVK/UPu2Gu9tIaRgFmYFFKrmg3SyAjSrElf0TiJ1v8fYA==", + "cpu": [ + "ia32" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "win32" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@esbuild/win32-x64": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/@esbuild/win32-x64/-/win32-x64-0.21.5.tgz", + "integrity": "sha512-tQd/1efJuzPC6rCFwEvLtci/xNFcTZknmXs98FYDfGE4wP9ClFV98nyKrzJKVPMhdDnjzLhdUyMX4PsQAPjwIw==", + "cpu": [ + "x64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "win32" + ], + "engines": { + "node": ">=12" + } + }, + "node_modules/@rollup/rollup-android-arm-eabi": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-android-arm-eabi/-/rollup-android-arm-eabi-4.60.4.tgz", + "integrity": "sha512-F5QXMSiFebS9hKZj02XhWLLnRpJ3B3AROP0tWbFBSj+6kCbg5m9j5JoHKd4mmSVy5mS/IMQloYgYxCuJC0fxEQ==", + "cpu": [ + "arm" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "android" + ] + }, + "node_modules/@rollup/rollup-android-arm64": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-android-arm64/-/rollup-android-arm64-4.60.4.tgz", + "integrity": "sha512-GxxTKApUpzRhof7poWvCJHRF51C67u1R7D6DiluBE8wKU1u5GWE8t+v81JvJYtbawoBFX1hLv5Ei4eVjkWokaw==", + "cpu": [ + "arm64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "android" + ] + }, + "node_modules/@rollup/rollup-darwin-arm64": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-darwin-arm64/-/rollup-darwin-arm64-4.60.4.tgz", + "integrity": "sha512-tua0TaJxMOB1R0V0RS1jFZ/RpURFDJIOR2A6jWwQeawuFyS4gBW+rntLRaQd0EQ4bd6Vp44Z2rXW+YYDBsj6IA==", + "cpu": [ + "arm64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "darwin" + ] + }, + "node_modules/@rollup/rollup-darwin-x64": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-darwin-x64/-/rollup-darwin-x64-4.60.4.tgz", + "integrity": "sha512-CSKq7MsP+5PFIcydhAiR1K0UhEI1A2jWXVKHPCBZ151yOutENwvnPocgVHkivu2kviURtCEB6zUQw0vs8RrhMg==", + "cpu": [ + "x64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "darwin" + ] + }, + "node_modules/@rollup/rollup-freebsd-arm64": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-freebsd-arm64/-/rollup-freebsd-arm64-4.60.4.tgz", + "integrity": "sha512-+O8OkVdyvXMtJEciu2wS/pzm1IxntEEQx3z5TAVy4l32G0etZn+RsA48ARRrFm6Ri8fvqPQfgrvNxSjKAbnd3g==", + "cpu": [ + "arm64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "freebsd" + ] + }, + "node_modules/@rollup/rollup-freebsd-x64": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-freebsd-x64/-/rollup-freebsd-x64-4.60.4.tgz", + "integrity": "sha512-Iw3oMskH3AfNuhU0MSN7vNbdi4me/NiYo2azqPz/Le16zHSa+3RRmliCMWWQmh4lcndccU40xcJuTYJZxNo/lw==", + "cpu": [ + "x64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "freebsd" + ] + }, + "node_modules/@rollup/rollup-linux-arm-gnueabihf": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-arm-gnueabihf/-/rollup-linux-arm-gnueabihf-4.60.4.tgz", + "integrity": "sha512-EIPRXTVQpHyF8WOo219AD2yEltPehLTcTMz2fn6JsatLYSzQf00hj3rulF+yauOlF9/FtM2WpkT/hJh/KJFGhA==", + "cpu": [ + "arm" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ] + }, + "node_modules/@rollup/rollup-linux-arm-musleabihf": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-arm-musleabihf/-/rollup-linux-arm-musleabihf-4.60.4.tgz", + "integrity": "sha512-J3Yh9PzzF1Ovah2At+lHiGQdsYgArxBbXv/zHfSyaiFQEqvNv7DcW98pCrmdjCZBrqBiKrKKe2V+aaSGWuBe/w==", + "cpu": [ + "arm" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ] + }, + "node_modules/@rollup/rollup-linux-arm64-gnu": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-arm64-gnu/-/rollup-linux-arm64-gnu-4.60.4.tgz", + "integrity": "sha512-BFDEZMYfUvLn37ONE1yMBojPxnMlTFsdyNoqncT0qFq1mAfllL+ATMMJd8TeuVMiX84s1KbcxcZbXInmcO2mRg==", + "cpu": [ + "arm64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ] + }, + "node_modules/@rollup/rollup-linux-arm64-musl": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-arm64-musl/-/rollup-linux-arm64-musl-4.60.4.tgz", + "integrity": "sha512-pc9EYOSlOgdQ2uPl1o9PF6/kLSgaUosia7gOuS8mB69IxJvlclko1MECXysjs5ryez1/5zjYqx3+xYU0TU6R1A==", + "cpu": [ + "arm64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ] + }, + "node_modules/@rollup/rollup-linux-loong64-gnu": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-loong64-gnu/-/rollup-linux-loong64-gnu-4.60.4.tgz", + "integrity": "sha512-NxnomyxYerDh5n4iLrNa+sH+Z+U4BMEE46V2PgQ/hoB909i8gV1M5wPojWg9fk1jWpO3IQnOs20K4wyZuFLEFQ==", + "cpu": [ + "loong64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ] + }, + "node_modules/@rollup/rollup-linux-loong64-musl": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-loong64-musl/-/rollup-linux-loong64-musl-4.60.4.tgz", + "integrity": "sha512-nbJnQ8a3z1mtmrwImCYhc6BGpThAyYVRQxw9uKSKG4wR6aAYno9sVjJ0zaZcW9BPJX1GbrDPf+SvdWjgTuDmnw==", + "cpu": [ + "loong64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ] + }, + "node_modules/@rollup/rollup-linux-ppc64-gnu": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-ppc64-gnu/-/rollup-linux-ppc64-gnu-4.60.4.tgz", + "integrity": "sha512-2EU6acNrQLd8tYvo/LXW535wupT3m6fo7HKo6lr7ktQoItxTyOL1ZCR/GfGCuXl2vR+zmfI6eRXkSemafv+iVg==", + "cpu": [ + "ppc64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ] + }, + "node_modules/@rollup/rollup-linux-ppc64-musl": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-ppc64-musl/-/rollup-linux-ppc64-musl-4.60.4.tgz", + "integrity": "sha512-WeBtoMuaMxiiIrO2IYP3xs6GMWkJP2C0EoT8beTLkUPmzV1i/UcOSVw1d5r9KBODtHKilG5yFxsGRnBbK3wJ4A==", + "cpu": [ + "ppc64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ] + }, + "node_modules/@rollup/rollup-linux-riscv64-gnu": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-riscv64-gnu/-/rollup-linux-riscv64-gnu-4.60.4.tgz", + "integrity": "sha512-FJHFfqpKUI3A10WrWKiFbBZ7yVbGT4q4B5o1qKFFojqpaYoh9LrQgqWCmmcxQzVSXYtyB5bzkXrYzlHTs21MYA==", + "cpu": [ + "riscv64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ] + }, + "node_modules/@rollup/rollup-linux-riscv64-musl": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-riscv64-musl/-/rollup-linux-riscv64-musl-4.60.4.tgz", + "integrity": "sha512-mcEl6CUT5IAUmQf1m9FYSmVqCJlpQ8r8eyftFUHG8i9OhY7BkBXSUdnLH5DOf0wCOjcP9v/QO93zpmF1SptCCw==", + "cpu": [ + "riscv64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ] + }, + "node_modules/@rollup/rollup-linux-s390x-gnu": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-s390x-gnu/-/rollup-linux-s390x-gnu-4.60.4.tgz", + "integrity": "sha512-ynt3JxVd2w2buzoKDWIyiV1pJW93xlQic1THVLXilz429oijRpSHivZAgp65KBu+cMcgf1eVVjdnTLvPxgCuoQ==", + "cpu": [ + "s390x" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ] + }, + "node_modules/@rollup/rollup-linux-x64-gnu": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-x64-gnu/-/rollup-linux-x64-gnu-4.60.4.tgz", + "integrity": "sha512-Boiz5+MsaROEWDf+GGEwF8VMHGhlUoQMtIPjOgA5fv4osupqTVnJteQNKJwUcnUog2G55jYXH7KZFFiJe0TEzQ==", + "cpu": [ + "x64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ] + }, + "node_modules/@rollup/rollup-linux-x64-musl": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-x64-musl/-/rollup-linux-x64-musl-4.60.4.tgz", + "integrity": "sha512-+qfSY27qIrFfI/Hom04KYFw3GKZSGU4lXus51wsb5EuySfFlWRwjkKWoE9emgRw/ukoT4Udsj4W/+xxG8VbPKg==", + "cpu": [ + "x64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ] + }, + "node_modules/@rollup/rollup-openbsd-x64": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-openbsd-x64/-/rollup-openbsd-x64-4.60.4.tgz", + "integrity": "sha512-VpTfOPHgVXEBeeR8hZ2O0F3aSso+JDWqTWmTmzcQKted54IAdUVbxE+j/MVxUsKa8L20HJhv3vUezVPoquqWjA==", + "cpu": [ + "x64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "openbsd" + ] + }, + "node_modules/@rollup/rollup-openharmony-arm64": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-openharmony-arm64/-/rollup-openharmony-arm64-4.60.4.tgz", + "integrity": "sha512-IPOsh5aRYuLv/nkU51X10Bf75Bsf6+gZdx1X+QP5QM6lIJFHHqbHLG0uJn/hWthzo13UAc2umiUorqZy3axoZg==", + "cpu": [ + "arm64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "openharmony" + ] + }, + "node_modules/@rollup/rollup-win32-arm64-msvc": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-win32-arm64-msvc/-/rollup-win32-arm64-msvc-4.60.4.tgz", + "integrity": "sha512-4QzE9E81OohJ/HKzHhsqU+zcYYojVOXlFMs1DdyMT6qXl/niOH7AVElmmEdUNHHS/oRkc++d5k6Vy85zFs0DEw==", + "cpu": [ + "arm64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "win32" + ] + }, + "node_modules/@rollup/rollup-win32-ia32-msvc": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-win32-ia32-msvc/-/rollup-win32-ia32-msvc-4.60.4.tgz", + "integrity": "sha512-zTPgT1YuHHcd+Tmx7h8aml0FWFVelV5N54oHow9SLj+GfoDy/huQ+UV396N/C7KpMDMiPspRktzM1/0r1usYEA==", + "cpu": [ + "ia32" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "win32" + ] + }, + "node_modules/@rollup/rollup-win32-x64-gnu": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-win32-x64-gnu/-/rollup-win32-x64-gnu-4.60.4.tgz", + "integrity": "sha512-DRS4G7mi9lJxqEDezIkKCaUIKCrLUUDCUaCsTPCi/rtqaC6D/jjwslMQyiDU50Ka0JKpeXeRBFBAXwArY52vBw==", + "cpu": [ + "x64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "win32" + ] + }, + "node_modules/@rollup/rollup-win32-x64-msvc": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/@rollup/rollup-win32-x64-msvc/-/rollup-win32-x64-msvc-4.60.4.tgz", + "integrity": "sha512-QVTUovf40zgTqlFVrKA1uXMVvU2QWEFWfAH8Wdc48IxLvrJMQVMBRjuQyUpzZCDkakImib9eVazbWlC6ksWtJw==", + "cpu": [ + "x64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "win32" + ] + }, + "node_modules/@sparkjsdev/spark": { + "version": "2.1.0", + "resolved": "https://registry.npmjs.org/@sparkjsdev/spark/-/spark-2.1.0.tgz", + "integrity": "sha512-BRw+MuMzx0B3K8fDLQygt2OHEhYUV+41RX7btq9pZ3rCVrq42o57jW34VAIvC7JO/84DJh/1AutACV9ym6BfVg==", + "license": "MIT", + "dependencies": { + "fflate": "^0.8.2" + }, + "peerDependencies": { + "three": ">=0.180.0" + } + }, + "node_modules/@types/estree": { + "version": "1.0.8", + "resolved": "https://registry.npmjs.org/@types/estree/-/estree-1.0.8.tgz", + "integrity": "sha512-dWHzHa2WqEXI/O1E9OjrocMTKJl2mSrEolh1Iomrv6U+JuNwaHXsXx9bLu5gG7BUWFIN0skIQJQ/L1rIex4X6w==", + "dev": true, + "license": "MIT" + }, + "node_modules/esbuild": { + "version": "0.21.5", + "resolved": "https://registry.npmjs.org/esbuild/-/esbuild-0.21.5.tgz", + "integrity": "sha512-mg3OPMV4hXywwpoDxu3Qda5xCKQi+vCTZq8S9J/EpkhB2HzKXq4SNFZE3+NK93JYxc8VMSep+lOUSC/RVKaBqw==", + "dev": true, + "hasInstallScript": true, + "license": "MIT", + "bin": { + "esbuild": "bin/esbuild" + }, + "engines": { + "node": ">=12" + }, + "optionalDependencies": { + "@esbuild/aix-ppc64": "0.21.5", + "@esbuild/android-arm": "0.21.5", + "@esbuild/android-arm64": "0.21.5", + "@esbuild/android-x64": "0.21.5", + "@esbuild/darwin-arm64": "0.21.5", + "@esbuild/darwin-x64": "0.21.5", + "@esbuild/freebsd-arm64": "0.21.5", + "@esbuild/freebsd-x64": "0.21.5", + "@esbuild/linux-arm": "0.21.5", + "@esbuild/linux-arm64": "0.21.5", + "@esbuild/linux-ia32": "0.21.5", + "@esbuild/linux-loong64": "0.21.5", + "@esbuild/linux-mips64el": "0.21.5", + "@esbuild/linux-ppc64": "0.21.5", + "@esbuild/linux-riscv64": "0.21.5", + "@esbuild/linux-s390x": "0.21.5", + "@esbuild/linux-x64": "0.21.5", + "@esbuild/netbsd-x64": "0.21.5", + "@esbuild/openbsd-x64": "0.21.5", + "@esbuild/sunos-x64": "0.21.5", + "@esbuild/win32-arm64": "0.21.5", + "@esbuild/win32-ia32": "0.21.5", + "@esbuild/win32-x64": "0.21.5" + } + }, + "node_modules/fflate": { + "version": "0.8.3", + "resolved": "https://registry.npmjs.org/fflate/-/fflate-0.8.3.tgz", + "integrity": "sha512-tbZNuJrLwGUp3zshBtdy4W+ORxZuIh8a5ilyIEQDC5rY1f3U20JMry0Ll3WBzU58EZKsEuJFXhb5gwv8CsPvgA==", + "license": "MIT" + }, + "node_modules/fsevents": { + "version": "2.3.3", + "resolved": "https://registry.npmjs.org/fsevents/-/fsevents-2.3.3.tgz", + "integrity": "sha512-5xoDfX+fL7faATnagmWPpbFtwh/R77WmMMqqHGS65C3vvB0YHrgF+B1YmZ3441tMj5n63k0212XNoJwzlhffQw==", + "dev": true, + "hasInstallScript": true, + "license": "MIT", + "optional": true, + "os": [ + "darwin" + ], + "engines": { + "node": "^8.16.0 || ^10.6.0 || >=11.0.0" + } + }, + "node_modules/nanoid": { + "version": "3.3.12", + "resolved": "https://registry.npmjs.org/nanoid/-/nanoid-3.3.12.tgz", + "integrity": "sha512-ZB9RH/39qpq5Vu6Y+NmUaFhQR6pp+M2Xt76XBnEwDaGcVAqhlvxrl3B2bKS5D3NH3QR76v3aSrKaF/Kiy7lEtQ==", + "dev": true, + "funding": [ + { + "type": "github", + "url": "https://github.com/sponsors/ai" + } + ], + "license": "MIT", + "bin": { + "nanoid": "bin/nanoid.cjs" + }, + "engines": { + "node": "^10 || ^12 || ^13.7 || ^14 || >=15.0.1" + } + }, + "node_modules/picocolors": { + "version": "1.1.1", + "resolved": "https://registry.npmjs.org/picocolors/-/picocolors-1.1.1.tgz", + "integrity": "sha512-xceH2snhtb5M9liqDsmEw56le376mTZkEX/jEb/RxNFyegNul7eNslCXP9FDj/Lcu0X8KEyMceP2ntpaHrDEVA==", + "dev": true, + "license": "ISC" + }, + "node_modules/postcss": { + "version": "8.5.15", + "resolved": "https://registry.npmjs.org/postcss/-/postcss-8.5.15.tgz", + "integrity": "sha512-FfR8sjd4em2T6fb3I2MwAJU7HWVMr9zba+enmQeeWFfCbm+UOC/0X4DS8XtpUTMwWMGbjKYP7xjfNekzyGmB3A==", + "dev": true, + "funding": [ + { + "type": "opencollective", + "url": "https://opencollective.com/postcss/" + }, + { + "type": "tidelift", + "url": "https://tidelift.com/funding/github/npm/postcss" + }, + { + "type": "github", + "url": "https://github.com/sponsors/ai" + } + ], + "license": "MIT", + "dependencies": { + "nanoid": "^3.3.12", + "picocolors": "^1.1.1", + "source-map-js": "^1.2.1" + }, + "engines": { + "node": "^10 || ^12 || >=14" + } + }, + "node_modules/rollup": { + "version": "4.60.4", + "resolved": "https://registry.npmjs.org/rollup/-/rollup-4.60.4.tgz", + "integrity": "sha512-WHeFSbZYsPu3+bLoNRUuAO+wavNlocOPf3wSHTP7hcFKVnJeWsYlCDbr3mTS14FCizf9ccIxXA8sGL8zKeQN3g==", + "dev": true, + "license": "MIT", + "dependencies": { + "@types/estree": "1.0.8" + }, + "bin": { + "rollup": "dist/bin/rollup" + }, + "engines": { + "node": ">=18.0.0", + "npm": ">=8.0.0" + }, + "optionalDependencies": { + "@rollup/rollup-android-arm-eabi": "4.60.4", + "@rollup/rollup-android-arm64": "4.60.4", + "@rollup/rollup-darwin-arm64": "4.60.4", + "@rollup/rollup-darwin-x64": "4.60.4", + "@rollup/rollup-freebsd-arm64": "4.60.4", + "@rollup/rollup-freebsd-x64": "4.60.4", + "@rollup/rollup-linux-arm-gnueabihf": "4.60.4", + "@rollup/rollup-linux-arm-musleabihf": "4.60.4", + "@rollup/rollup-linux-arm64-gnu": "4.60.4", + "@rollup/rollup-linux-arm64-musl": "4.60.4", + "@rollup/rollup-linux-loong64-gnu": "4.60.4", + "@rollup/rollup-linux-loong64-musl": "4.60.4", + "@rollup/rollup-linux-ppc64-gnu": "4.60.4", + "@rollup/rollup-linux-ppc64-musl": "4.60.4", + "@rollup/rollup-linux-riscv64-gnu": "4.60.4", + "@rollup/rollup-linux-riscv64-musl": "4.60.4", + "@rollup/rollup-linux-s390x-gnu": "4.60.4", + "@rollup/rollup-linux-x64-gnu": "4.60.4", + "@rollup/rollup-linux-x64-musl": "4.60.4", + "@rollup/rollup-openbsd-x64": "4.60.4", + "@rollup/rollup-openharmony-arm64": "4.60.4", + "@rollup/rollup-win32-arm64-msvc": "4.60.4", + "@rollup/rollup-win32-ia32-msvc": "4.60.4", + "@rollup/rollup-win32-x64-gnu": "4.60.4", + "@rollup/rollup-win32-x64-msvc": "4.60.4", + "fsevents": "~2.3.2" + } + }, + "node_modules/source-map-js": { + "version": "1.2.1", + "resolved": "https://registry.npmjs.org/source-map-js/-/source-map-js-1.2.1.tgz", + "integrity": "sha512-UXWMKhLOwVKb728IUtQPXxfYU+usdybtUrK/8uGE8CQMvrhOpwvzDBwj0QhSL7MQc7vIsISBG8VQ8+IDQxpfQA==", + "dev": true, + "license": "BSD-3-Clause", + "engines": { + "node": ">=0.10.0" + } + }, + "node_modules/three": { + "version": "0.168.0", + "resolved": "https://registry.npmjs.org/three/-/three-0.168.0.tgz", + "integrity": "sha512-6m6jXtDwMJEK/GGMbAOTSAmxNdzKvvBzgd7q8bE/7Tr6m7PaBh5kKLrN7faWtlglXbzj7sVba48Idwx+NRsZXw==", + "license": "MIT" + }, + "node_modules/vite": { + "version": "5.4.21", + "resolved": "https://registry.npmjs.org/vite/-/vite-5.4.21.tgz", + "integrity": "sha512-o5a9xKjbtuhY6Bi5S3+HvbRERmouabWbyUcpXXUA1u+GNUKoROi9byOJ8M0nHbHYHkYICiMlqxkg1KkYmm25Sw==", + "dev": true, + "license": "MIT", + "dependencies": { + "esbuild": "^0.21.3", + "postcss": "^8.4.43", + "rollup": "^4.20.0" + }, + "bin": { + "vite": "bin/vite.js" + }, + "engines": { + "node": "^18.0.0 || >=20.0.0" + }, + "funding": { + "url": "https://github.com/vitejs/vite?sponsor=1" + }, + "optionalDependencies": { + "fsevents": "~2.3.3" + }, + "peerDependencies": { + "@types/node": "^18.0.0 || >=20.0.0", + "less": "*", + "lightningcss": "^1.21.0", + "sass": "*", + "sass-embedded": "*", + "stylus": "*", + "sugarss": "*", + "terser": "^5.4.0" + }, + "peerDependenciesMeta": { + "@types/node": { + "optional": true + }, + "less": { + "optional": true + }, + "lightningcss": { + "optional": true + }, + "sass": { + "optional": true + }, + "sass-embedded": { + "optional": true + }, + "stylus": { + "optional": true + }, + "sugarss": { + "optional": true + }, + "terser": { + "optional": true + } + } + } + } +} diff --git a/misc/DimSim/package.json b/misc/DimSim/package.json new file mode 100644 index 0000000000..a5a99e8e1f --- /dev/null +++ b/misc/DimSim/package.json @@ -0,0 +1,20 @@ +{ + "name": "dimsim", + "private": true, + "version": "1.0.0", + "type": "module", + "description": "Browser-based 3D simulator (Three.js + Rapier) + Deno bridge — runs as the simulation backend for dimos.", + "scripts": { + "dev": "vite --force", + "build": "vite build", + "preview": "vite preview" + }, + "dependencies": { + "@dimforge/rapier3d-compat": "^0.14.0", + "@sparkjsdev/spark": "latest", + "three": "^0.168.0" + }, + "devDependencies": { + "vite": "^5.4.10" + } +} diff --git a/misc/DimSim/public/embodiment/dimsim_unitree_stub.glb b/misc/DimSim/public/embodiment/dimsim_unitree_stub.glb new file mode 100644 index 0000000000..79296152a2 --- /dev/null +++ b/misc/DimSim/public/embodiment/dimsim_unitree_stub.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:761813170c01429ab9215ad4e37b95a768437fc0c6aa1d643f5938a672263322 +size 55746312 diff --git a/misc/DimSim/public/logo.svg b/misc/DimSim/public/logo.svg new file mode 100644 index 0000000000..d64b96adfc --- /dev/null +++ b/misc/DimSim/public/logo.svg @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/misc/DimSim/scenes/apartment/evals/go-to-couch.js b/misc/DimSim/scenes/apartment/evals/go-to-couch.js new file mode 100644 index 0000000000..30b36db952 --- /dev/null +++ b/misc/DimSim/scenes/apartment/evals/go-to-couch.js @@ -0,0 +1,9 @@ +import { runEval } from '@dimsim/eval'; + +await runEval({ + scene: 'apartment', + task: 'Go to the couch', + timeoutSec: 30, + startPose: { x: 0, y: 0.5, z: 3, yaw: 0 }, + success: (ctx) => ctx.rubrics.objectDistance({ target: 'sectional', thresholdM: 2.0 }), +}); diff --git a/misc/DimSim/scenes/apartment/evals/go-to-kitchen.js b/misc/DimSim/scenes/apartment/evals/go-to-kitchen.js new file mode 100644 index 0000000000..5165406385 --- /dev/null +++ b/misc/DimSim/scenes/apartment/evals/go-to-kitchen.js @@ -0,0 +1,9 @@ +import { runEval } from '@dimsim/eval'; + +await runEval({ + scene: 'apartment', + task: 'Go to the kitchen', + timeoutSec: 30, + startPose: { x: 0, y: 0.5, z: 3, yaw: 0 }, + success: (ctx) => ctx.rubrics.objectDistance({ target: 'refrigerator', thresholdM: 3.0 }), +}); diff --git a/misc/DimSim/scenes/apartment/evals/go-to-tv.js b/misc/DimSim/scenes/apartment/evals/go-to-tv.js new file mode 100644 index 0000000000..c9800d80e5 --- /dev/null +++ b/misc/DimSim/scenes/apartment/evals/go-to-tv.js @@ -0,0 +1,9 @@ +import { runEval } from '@dimsim/eval'; + +await runEval({ + scene: 'apartment', + task: 'Go to the TV', + timeoutSec: 30, + startPose: { x: 0, y: 0.5, z: 3, yaw: 0 }, + success: (ctx) => ctx.rubrics.objectDistance({ target: 'television', thresholdM: 2.0 }), +}); diff --git a/misc/DimSim/scenes/apartment/index.js b/misc/DimSim/scenes/apartment/index.js new file mode 100644 index 0000000000..215994f64f --- /dev/null +++ b/misc/DimSim/scenes/apartment/index.js @@ -0,0 +1,120 @@ +// scenes/apartment/index.js — pure Three.js entry for the apartment. +// +// Static structure (walls, floor, ceiling, fixtures): ./structure.glb +// Interactive objects (fridge, cabinets, TV, etc.): ./objects//.glb +// keyed by ./objects/manifest.json. Sky, lights, tags inlined below. + +const SKY = { + topColor: '#0b64f4', + horizonColor: '#d9e5f7', + bottomColor: '#3b6cce', + brightness: 0.9, + softness: 0.75, + sunStrength: 0.17, + sunHeight: 0.34, +}; + +const TAGS = ['modern', 'apartment', 'interior', 'furnished']; + +export default async function build({ scene, THREE, physics, setSky, loadGLTF, loadLevel }) { + setSky(SKY); + + // ── Lights ───────────────────────────────────────────────────────────────── + const lr1 = new THREE.PointLight(new THREE.Color('#FFFAF0'), 2, 8); + lr1.position.set(2, 2.8, 2.5); + scene.add(lr1); + + const lr2 = new THREE.PointLight(new THREE.Color('#FFFAF0'), 0, 8); + lr2.position.set(4, 2.9, 1.5); + scene.add(lr2); + + const kit1 = new THREE.PointLight(new THREE.Color('#F0FFFF'), 2.5, 8); + kit1.position.set(-4, 2.8, 2.5); + scene.add(kit1); + + const kit2 = new THREE.PointLight(new THREE.Color('#F0FFFF'), 2.5, 8); + kit2.position.set(-4, 2.9, 3.5); + scene.add(kit2); + + const bed1 = new THREE.PointLight(new THREE.Color('#FFE4B5'), 2, 8); + bed1.position.set(-2.5, 2.8, -2.5); + scene.add(bed1); + + const bed2 = new THREE.PointLight(new THREE.Color('#FFE4B5'), 1.5, 8); + bed2.position.set(-2.5, 2.9, -3.5); + scene.add(bed2); + + const path1 = new THREE.PointLight(new THREE.Color('#FFD700'), 1, 3); + path1.position.set(-2, 0.25, 5.8); + scene.add(path1); + + const path2 = new THREE.PointLight(new THREE.Color('#FFD700'), 1, 3); + path2.position.set(0, 0.25, 5.8); + scene.add(path2); + + const path3 = new THREE.PointLight(new THREE.Color('#FFD700'), 1, 3); + path3.position.set(2, 0.25, 5.8); + scene.add(path3); + + const bath1 = new THREE.PointLight(new THREE.Color('#F0FFFF'), 1.5, 6); + bath1.position.set(3.5, 2.8, -2.5); + scene.add(bath1); + + const sun = new THREE.DirectionalLight(new THREE.Color('#ffffff'), 1); + sun.position.set(2.9245321131985382, 14.007232336425105, 16.10510431845022); + sun.target.position.set(2.9990998365488326, 9.488242347246995, 13.966607385475479); + sun.castShadow = true; + sun.shadow.mapSize.set(2048, 2048); + sun.shadow.camera.left = -30; + sun.shadow.camera.right = 30; + sun.shadow.camera.top = 30; + sun.shadow.camera.bottom = -30; + scene.add(sun); + scene.add(sun.target); + + // ── Static structure (walls/floor/ceiling/fixtures, baked from primitives) ── + const sg = await loadGLTF('./structure.glb'); + sg.scene.traverse((o) => { + if (o.isMesh) { + o.castShadow = true; + o.receiveShadow = true; + } + }); + scene.add(sg.scene); + physics.staticCollider(sg.scene, 'trimesh'); + + // ── Interactive objects (GLB-per-state, with actions/state machines) ─────── + const manifest = await fetch('/scenes/apartment/objects/manifest.json').then((r) => r.json()); + + const assets = manifest.map((entry) => ({ + id: entry.id, + title: entry.title, + transform: entry.transform, + currentStateId: entry.currentStateId, + _shapePivotCenter: entry._shapePivotCenter, + pickable: entry.pickable, + bumpable: entry.bumpable, + bumpResponse: entry.bumpResponse, + bumpDamping: entry.bumpDamping, + castShadow: entry.castShadow, + receiveShadow: entry.receiveShadow, + actions: entry.actions || [], + states: (entry.states || []).map((s) => ({ + id: s.id, + name: s.name, + glbUrl: `/scenes/apartment/objects/${s.file}`, + })), + })); + + await loadLevel({ + version: '2.0', + worldKey: 'default', + tags: TAGS, + assets, + }); + + return { + embodiment: null, + spawnPoint: { x: 2, y: 0.5, z: 3 }, + }; +} diff --git a/misc/DimSim/scenes/apartment/objects/arc-floor-lamp/state-default.glb b/misc/DimSim/scenes/apartment/objects/arc-floor-lamp/state-default.glb new file mode 100644 index 0000000000..ddede4e302 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/arc-floor-lamp/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c4ef00b2304b405746f09f6bd6b35c9981937366a70d64f087a19d9f9b17a5d2 +size 585968 diff --git a/misc/DimSim/scenes/apartment/objects/arc-floor-lamp/state-mlskixi4-xebf.glb b/misc/DimSim/scenes/apartment/objects/arc-floor-lamp/state-mlskixi4-xebf.glb new file mode 100644 index 0000000000..ddede4e302 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/arc-floor-lamp/state-mlskixi4-xebf.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c4ef00b2304b405746f09f6bd6b35c9981937366a70d64f087a19d9f9b17a5d2 +size 585968 diff --git a/misc/DimSim/scenes/apartment/objects/art-deco-gold-finished-bar-cart-with-two-glass-s/state-default.glb b/misc/DimSim/scenes/apartment/objects/art-deco-gold-finished-bar-cart-with-two-glass-s/state-default.glb new file mode 100644 index 0000000000..d28a610071 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/art-deco-gold-finished-bar-cart-with-two-glass-s/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:e7ac100213ae3170bd8097c0264c43e08a38724d9c5cd46311be544000df1791 +size 147548 diff --git a/misc/DimSim/scenes/apartment/objects/assorted-decorative-plants/state-default.glb b/misc/DimSim/scenes/apartment/objects/assorted-decorative-plants/state-default.glb new file mode 100644 index 0000000000..adfaa8c6dd --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/assorted-decorative-plants/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:68ea9331c2464dcb36f042e670bd7f1c3b8125ff11b4c50cae133871691327e9 +size 906376 diff --git a/misc/DimSim/scenes/apartment/objects/automatic-drip-coffee-maker-with-glass-carafe-i/state-default.glb b/misc/DimSim/scenes/apartment/objects/automatic-drip-coffee-maker-with-glass-carafe-i/state-default.glb new file mode 100644 index 0000000000..64d421304d --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/automatic-drip-coffee-maker-with-glass-carafe-i/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:f44258a94a8909d82c67dd688ce8e0366f2912b36f7c0f7871bc50bd4dde26f1 +size 223808 diff --git a/misc/DimSim/scenes/apartment/objects/bathroom-vanity-and-sink/state-default.glb b/misc/DimSim/scenes/apartment/objects/bathroom-vanity-and-sink/state-default.glb new file mode 100644 index 0000000000..c16afae496 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/bathroom-vanity-and-sink/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:aee4db9810e0e5cdb842a4b227cb6aa06b08ca63193acb6b2f060df2f0847453 +size 187992 diff --git a/misc/DimSim/scenes/apartment/objects/bedside-table/state-default.glb b/misc/DimSim/scenes/apartment/objects/bedside-table/state-default.glb new file mode 100644 index 0000000000..de7a19af09 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/bedside-table/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:ec847525d25bb8e2391c0b2eb4edf29c3a3e123af71cc1f52fd9993be0f3f31f +size 7144640 diff --git a/misc/DimSim/scenes/apartment/objects/bedside-table/state-mlsm2hfh-kpff.glb b/misc/DimSim/scenes/apartment/objects/bedside-table/state-mlsm2hfh-kpff.glb new file mode 100644 index 0000000000..0c6dc2bed4 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/bedside-table/state-mlsm2hfh-kpff.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:220267491822f796fe71cfd731c48d501428fb57389758f9423f65c0bf08d160 +size 7151960 diff --git a/misc/DimSim/scenes/apartment/objects/bohemian-style-woven-macrame/state-default.glb b/misc/DimSim/scenes/apartment/objects/bohemian-style-woven-macrame/state-default.glb new file mode 100644 index 0000000000..bf05242218 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/bohemian-style-woven-macrame/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:84be0236520a9fa691211c7a7e50c84b33429adf046d5329f49c5f6aaee23b67 +size 313152 diff --git a/misc/DimSim/scenes/apartment/objects/books/state-default.glb b/misc/DimSim/scenes/apartment/objects/books/state-default.glb new file mode 100644 index 0000000000..e03a6890cb --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/books/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:89ce9649c4c0567cebb1288a953c8c0428087c49bc75bea6af9cd6f7e28848bd +size 284300 diff --git a/misc/DimSim/scenes/apartment/objects/bookshelf-decor/state-default.glb b/misc/DimSim/scenes/apartment/objects/bookshelf-decor/state-default.glb new file mode 100644 index 0000000000..7581089def --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/bookshelf-decor/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:762b4c306db409a42ddda0e771d94f5876686529a3e16111f1346d1d5666ed33 +size 1082604 diff --git a/misc/DimSim/scenes/apartment/objects/built-in-stainless-steel-dishwasher/state-default.glb b/misc/DimSim/scenes/apartment/objects/built-in-stainless-steel-dishwasher/state-default.glb new file mode 100644 index 0000000000..b5ede05930 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/built-in-stainless-steel-dishwasher/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:82447bc193e1f8c3f6e7378e0241d9ac15b155ddf19a1371666c270a9341d49b +size 22280 diff --git a/misc/DimSim/scenes/apartment/objects/chunky-knit-wool-throw-blanket-with-visible-weav/state-default.glb b/misc/DimSim/scenes/apartment/objects/chunky-knit-wool-throw-blanket-with-visible-weav/state-default.glb new file mode 100644 index 0000000000..3f8f86822d --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/chunky-knit-wool-throw-blanket-with-visible-weav/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:4658bd699a5c33748530135b3cf64006373143400fac2a452e72d94f1de84b33 +size 463872 diff --git a/misc/DimSim/scenes/apartment/objects/classic-outdoor-garden-bench/state-default.glb b/misc/DimSim/scenes/apartment/objects/classic-outdoor-garden-bench/state-default.glb new file mode 100644 index 0000000000..0950262c0f --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/classic-outdoor-garden-bench/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:514dbc4065f956284818b30a9c280fe8f2ed19eea675d140ad058b71895ca428 +size 56032 diff --git a/misc/DimSim/scenes/apartment/objects/console-with-cabinets/state-default.glb b/misc/DimSim/scenes/apartment/objects/console-with-cabinets/state-default.glb new file mode 100644 index 0000000000..54fae734ca --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/console-with-cabinets/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:f0a0fa0fff9eb80fc2c5d1b2c8a61be3f84dd24cdbc691831da13faee3712e46 +size 7297816 diff --git a/misc/DimSim/scenes/apartment/objects/console-with-cabinets/state-mlsncwfv-pq43.glb b/misc/DimSim/scenes/apartment/objects/console-with-cabinets/state-mlsncwfv-pq43.glb new file mode 100644 index 0000000000..1fd4c259a4 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/console-with-cabinets/state-mlsncwfv-pq43.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5894a964cec58a60cfb89deaa12426816271d8aef1e73208f6b52df81d4d9a80 +size 7300400 diff --git a/misc/DimSim/scenes/apartment/objects/contemporary-white-ceramic-toilet-with-sleek-lin/state-default.glb b/misc/DimSim/scenes/apartment/objects/contemporary-white-ceramic-toilet-with-sleek-lin/state-default.glb new file mode 100644 index 0000000000..37add0d8fb --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/contemporary-white-ceramic-toilet-with-sleek-lin/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:a63bd446c2343599d7576cf40718966fb67135ba5227b98e7bfb57b2967fd3b0 +size 387040 diff --git a/misc/DimSim/scenes/apartment/objects/detailed-porcelain-dinner-plate-with-gold-rim-an/state-default.glb b/misc/DimSim/scenes/apartment/objects/detailed-porcelain-dinner-plate-with-gold-rim-an/state-default.glb new file mode 100644 index 0000000000..52a3183344 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/detailed-porcelain-dinner-plate-with-gold-rim-an/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:e2981caa6d6c2ad8ceb54b7a625103065a16d5a9cbfec4b1eb59eb9d04b994bd +size 328560 diff --git a/misc/DimSim/scenes/apartment/objects/dining-chair/state-default.glb b/misc/DimSim/scenes/apartment/objects/dining-chair/state-default.glb new file mode 100644 index 0000000000..6470be2f51 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/dining-chair/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:332fd1cf6db3b245f2fa29d3d853a0afb8a007826e63a56e4500829a6b25e816 +size 8170956 diff --git a/misc/DimSim/scenes/apartment/objects/framed-abstract-oil-painting/state-default.glb b/misc/DimSim/scenes/apartment/objects/framed-abstract-oil-painting/state-default.glb new file mode 100644 index 0000000000..cfeb6ebe5b --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/framed-abstract-oil-painting/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c03169172ec1d9384b911cf3ebf7c289af0b0e3038062ca0440e098b4463fc6c +size 1426496 diff --git a/misc/DimSim/scenes/apartment/objects/framed-landscape-oil-painting/state-default.glb b/misc/DimSim/scenes/apartment/objects/framed-landscape-oil-painting/state-default.glb new file mode 100644 index 0000000000..5aa644ddeb --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/framed-landscape-oil-painting/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:becc877432db5a547ad6875b2d996203d83a2fb58b4ec0c6bbdd0b93bde8e65d +size 7961960 diff --git a/misc/DimSim/scenes/apartment/objects/freestanding-oval-soaking-bathtub-with-chrome-fl/state-default.glb b/misc/DimSim/scenes/apartment/objects/freestanding-oval-soaking-bathtub-with-chrome-fl/state-default.glb new file mode 100644 index 0000000000..753d1637ac --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/freestanding-oval-soaking-bathtub-with-chrome-fl/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:87b3275bf150a91549829458a45fb566c4012a012916d5e16e6b71628940b273 +size 87080 diff --git a/misc/DimSim/scenes/apartment/objects/freestanding-oval-soaking-bathtub-with-chrome-fl/state-mlsiig1y-6e45.glb b/misc/DimSim/scenes/apartment/objects/freestanding-oval-soaking-bathtub-with-chrome-fl/state-mlsiig1y-6e45.glb new file mode 100644 index 0000000000..daf7654b62 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/freestanding-oval-soaking-bathtub-with-chrome-fl/state-mlsiig1y-6e45.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:00164bacaaeb97a03fb1350783fc9bd94d84d3e346ba3d97bd9782bcd5e52e32 +size 87132 diff --git a/misc/DimSim/scenes/apartment/objects/galvanized-steel-watering-can-with-a-long-spout/state-default.glb b/misc/DimSim/scenes/apartment/objects/galvanized-steel-watering-can-with-a-long-spout/state-default.glb new file mode 100644 index 0000000000..fa9b213a93 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/galvanized-steel-watering-can-with-a-long-spout/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:dd5c886eb576b8d06b330558e7f4f1d9ccee7f1f8b93cae4aee477b230a9ac38 +size 340556 diff --git a/misc/DimSim/scenes/apartment/objects/hardcover-book-lying-open-with-paper-pages-and-p/state-default.glb b/misc/DimSim/scenes/apartment/objects/hardcover-book-lying-open-with-paper-pages-and-p/state-default.glb new file mode 100644 index 0000000000..d531ec01e0 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/hardcover-book-lying-open-with-paper-pages-and-p/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:d3c3ff196eb5b512e22dd42951f05c9d1de304dab8842a67f5fe87e1fec5ea0d +size 290324 diff --git a/misc/DimSim/scenes/apartment/objects/hardcover-books-1/state-default.glb b/misc/DimSim/scenes/apartment/objects/hardcover-books-1/state-default.glb new file mode 100644 index 0000000000..0e72ededc7 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/hardcover-books-1/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:809728c182a237caf91b109b77f82c0475c74f31dcb35925feaceb830c58dbe9 +size 743840 diff --git a/misc/DimSim/scenes/apartment/objects/hardcover-books/state-default.glb b/misc/DimSim/scenes/apartment/objects/hardcover-books/state-default.glb new file mode 100644 index 0000000000..54d130472c --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/hardcover-books/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:1f1324e5e42bb08edf674d1e0451c231bec5ab531528f481bcae291f628c8a9c +size 562212 diff --git a/misc/DimSim/scenes/apartment/objects/high-speed-kitchen-blender-with-glass-jar-and-me/state-default.glb b/misc/DimSim/scenes/apartment/objects/high-speed-kitchen-blender-with-glass-jar-and-me/state-default.glb new file mode 100644 index 0000000000..5ae7065c52 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/high-speed-kitchen-blender-with-glass-jar-and-me/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:3b8a948b157b1c561c6cedd96a007030a2d619b92a5b0f3ebf9f65ddbb481bf4 +size 434196 diff --git a/misc/DimSim/scenes/apartment/objects/kitchen-base-cabinet/state-default.glb b/misc/DimSim/scenes/apartment/objects/kitchen-base-cabinet/state-default.glb new file mode 100644 index 0000000000..6ce0437657 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/kitchen-base-cabinet/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:19ee47ea1a85533b4a93e56d2a7002ce1520bc6f9847aa13c95beb89bc5e72e5 +size 29416 diff --git a/misc/DimSim/scenes/apartment/objects/kitchen-base-cabinet/state-mlsr95pw-kpf4.glb b/misc/DimSim/scenes/apartment/objects/kitchen-base-cabinet/state-mlsr95pw-kpf4.glb new file mode 100644 index 0000000000..4e558c405c --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/kitchen-base-cabinet/state-mlsr95pw-kpf4.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c7c1bcd453cd17747720552688f390ffd6fb3000c0eee9ec1e1cd6e18c0aaf19 +size 36348 diff --git a/misc/DimSim/scenes/apartment/objects/kitchen-wall-cabinet/state-default.glb b/misc/DimSim/scenes/apartment/objects/kitchen-wall-cabinet/state-default.glb new file mode 100644 index 0000000000..1d1e246fdc --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/kitchen-wall-cabinet/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:b0a21a9216f29dd005250b020ba188f82e886b3862957d5f73a5859c18ca2c9c +size 28620 diff --git a/misc/DimSim/scenes/apartment/objects/laptop-open/state-default.glb b/misc/DimSim/scenes/apartment/objects/laptop-open/state-default.glb new file mode 100644 index 0000000000..5787b0980c --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/laptop-open/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:72c2c85e8b32fb9fa91c4ca28b4424ae21ac46fb6b3989c65ccc5e0948cd04c1 +size 840568 diff --git a/misc/DimSim/scenes/apartment/objects/large-detailed-oak-tree-with-textured-bark-and-l/state-default.glb b/misc/DimSim/scenes/apartment/objects/large-detailed-oak-tree-with-textured-bark-and-l/state-default.glb new file mode 100644 index 0000000000..26cbae5a6d --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/large-detailed-oak-tree-with-textured-bark-and-l/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:9201662dead3d7925f6ef0d1fe383842233590e8d5c36f735ffea0ba4b390d0d +size 29917356 diff --git a/misc/DimSim/scenes/apartment/objects/large-ornate-mahogany-dining-table/state-default.glb b/misc/DimSim/scenes/apartment/objects/large-ornate-mahogany-dining-table/state-default.glb new file mode 100644 index 0000000000..c8f5cfdf9f --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/large-ornate-mahogany-dining-table/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:7ad521d7b40fe9dd786256da2ef132c879af08d2223c71d41830b590aaf264af +size 7381876 diff --git a/misc/DimSim/scenes/apartment/objects/large-terracotta-garden-pots-with-intricate-flor/state-default.glb b/misc/DimSim/scenes/apartment/objects/large-terracotta-garden-pots-with-intricate-flor/state-default.glb new file mode 100644 index 0000000000..ff744b7cc1 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/large-terracotta-garden-pots-with-intricate-flor/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:fada31452d0b3d5c833df43ba78345d132e5df4b082a50f0d75440ea104f6b0e +size 316788 diff --git a/misc/DimSim/scenes/apartment/objects/large-wardrobe/state-default.glb b/misc/DimSim/scenes/apartment/objects/large-wardrobe/state-default.glb new file mode 100644 index 0000000000..33ae45f5b6 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/large-wardrobe/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c20a8a18501baaf1a0cd8f6061eb5505ef1cb149a4fa37d522dd43eb4f0462a7 +size 7173296 diff --git a/misc/DimSim/scenes/apartment/objects/large-wardrobe/state-mlsmklqi-mykf.glb b/misc/DimSim/scenes/apartment/objects/large-wardrobe/state-mlsmklqi-mykf.glb new file mode 100644 index 0000000000..0fc5826004 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/large-wardrobe/state-mlsmklqi-mykf.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:eca7d7650015f635e34cc38e692088dc5724372f7fda3cf98a3b0d857a5e7772 +size 7189268 diff --git a/misc/DimSim/scenes/apartment/objects/light-oak-wooden-bed-tray-with-handles-and-short/state-default.glb b/misc/DimSim/scenes/apartment/objects/light-oak-wooden-bed-tray-with-handles-and-short/state-default.glb new file mode 100644 index 0000000000..35a03d0a08 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/light-oak-wooden-bed-tray-with-handles-and-short/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:3c3bf58548ec8ab5fd698a3fd73104ae64dbeac124cd1806b72dc9e9493474be +size 292404 diff --git a/misc/DimSim/scenes/apartment/objects/luxury-rainfall-shower-head-and-wall-mounted-mix/state-default.glb b/misc/DimSim/scenes/apartment/objects/luxury-rainfall-shower-head-and-wall-mounted-mix/state-default.glb new file mode 100644 index 0000000000..876872f3c4 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/luxury-rainfall-shower-head-and-wall-mounted-mix/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:f004531170d3176448ad56a98f7d376e32669557fb4f4366c5bb6316aec45201 +size 392756 diff --git a/misc/DimSim/scenes/apartment/objects/manifest.json b/misc/DimSim/scenes/apartment/objects/manifest.json new file mode 100644 index 0000000000..039a80bdde --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/manifest.json @@ -0,0 +1,3855 @@ +[ + { + "id": "59a525468c75d8-19c73105016", + "title": "Modern L-shaped sectional", + "transform": { + "position": { + "x": 4.3815894523994166, + "y": 0.49017637093479277, + "z": 1.0556627709770972 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1.1238777028003708, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.004147224596688148, + "y": 0.3749999998137355, + "z": 0.44999999254941947 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "modern-l-shaped-sectional/state-default.glb" + } + ] + }, + { + "id": "95e67f414e06f8-19c73110d54", + "title": "Wooden coffee table with glass top", + "transform": { + "position": { + "x": 3.953765809257721, + "y": 0.315281337994577, + "z": 1.7067945710626398 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": -0.0024741389971831285, + "y": 0.23709522248274384, + "z": 0.001997171270521708 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 1.25, + "bumpDamping": 0.78, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "wooden-coffee-table-with-glass-top/state-default.glb" + } + ] + }, + { + "id": "2f1b51866fa368-19c731443ef", + "title": "Console with cabinets", + "transform": { + "position": { + "x": 4.516290373580539, + "y": 0.3523583672864196, + "z": 4.64489994581474 + }, + "rotation": { + "x": 0, + "y": 3.141592653589793, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.24142332983411488, + "z": 0.027500016428739227 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [ + { + "id": "cycle-state-default-to-state-mlsncwfv-pq43", + "label": "to Open", + "from": "state-default", + "to": "state-mlsncwfv-pq43" + }, + { + "id": "cycle-state-mlsncwfv-pq43-to-state-default", + "label": "to closed", + "from": "state-mlsncwfv-pq43", + "to": "state-default" + } + ], + "states": [ + { + "id": "state-default", + "name": "closed", + "file": "console-with-cabinets/state-default.glb" + }, + { + "id": "state-mlsncwfv-pq43", + "name": "Open", + "file": "console-with-cabinets/state-mlsncwfv-pq43.glb" + } + ] + }, + { + "id": "c7899f757219b-19c731bc6ff", + "title": "Television", + "transform": { + "position": { + "x": 4.500068482229571, + "y": 1.6470746382091632, + "z": 4.880000008134797 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-mlr4bgf0-u7gv", + "_shapePivotCenter": { + "x": 3.862724577460491, + "y": 0.5565298706483899, + "z": 1.7678768512278153 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [ + { + "id": "cycle-state-mlr4bgf0-u7gv-to-state-mlr4dvjl-fyw3", + "label": "to ON", + "from": "state-mlr4bgf0-u7gv", + "to": "state-mlr4dvjl-fyw3" + }, + { + "id": "cycle-state-mlr4dvjl-fyw3-to-state-mlr4bgf0-u7gv", + "label": "to OFF", + "from": "state-mlr4dvjl-fyw3", + "to": "state-mlr4bgf0-u7gv" + } + ], + "states": [ + { + "id": "state-mlr4bgf0-u7gv", + "name": "OFF", + "file": "television/state-mlr4bgf0-u7gv.glb" + }, + { + "id": "state-mlr4dvjl-fyw3", + "name": "ON", + "file": "television/state-mlr4dvjl-fyw3.glb" + } + ] + }, + { + "id": "227cb298980678-19c731c8141", + "title": "Modern tripod floor lamp", + "transform": { + "position": { + "x": 2.567363667122909, + "y": 0.9266403965704086, + "z": 0.7462406515396548 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.021859171998984822, + "y": 0.8218468760394194, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [ + { + "id": "cycle-state-default-to-state-mlrpcv6c-bdvt", + "label": "to OFF", + "from": "state-default", + "to": "state-mlrpcv6c-bdvt" + }, + { + "id": "cycle-state-mlrpcv6c-bdvt-to-state-default", + "label": "to ON", + "from": "state-mlrpcv6c-bdvt", + "to": "state-default" + } + ], + "states": [ + { + "id": "state-default", + "name": "ON", + "file": "modern-tripod-floor-lamp/state-default.glb" + }, + { + "id": "state-mlrpcv6c-bdvt", + "name": "OFF", + "file": "modern-tripod-floor-lamp/state-mlrpcv6c-bdvt.glb" + } + ] + }, + { + "id": "3b515be13388f-19c73217ec3", + "title": "Wooden bookcase", + "transform": { + "position": { + "x": -1.2346250672621193, + "y": 1.0120243146713455, + "z": 0.21597170828388723 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1.2804687702858426, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.8999999999999999, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "wooden-bookcase/state-default.glb" + } + ] + }, + { + "id": "0d3779109193e-19c73221b10", + "title": "bookshelf decor", + "transform": { + "position": { + "x": -1.2161971652872015, + "y": 0.7367178620425292, + "z": 0.21783707347967085 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.08705190594401346, + "y": 0.10999999791383742, + "z": -0.0016066725690125835 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "bookshelf-decor/state-default.glb" + } + ] + }, + { + "id": "d76362662545e-19c73234c4d", + "title": "Books", + "transform": { + "position": { + "x": -1.4493133008996957, + "y": 1.4775923795984425, + "z": 0.2510956471722847 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.0012008581219888764, + "y": 0.04850000034272671, + "z": -0.0021056519411290844 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "books/state-default.glb" + } + ] + }, + { + "id": "578967ee4707-19c73238f45", + "title": "Hardcover books 1", + "transform": { + "position": { + "x": -0.8614216537918351, + "y": 1.14, + "z": 0.26 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 1.5707963267948966 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": -0.006083928007335378, + "y": 0.09999999932944774, + "z": 0.0030000000000000027 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "hardcover-books-1/state-default.glb" + } + ] + }, + { + "id": "1a72e35e19a66-19c73244ffc", + "title": "Small potted plant", + "transform": { + "position": { + "x": -1.4087380833018583, + "y": 1.184871881798844, + "z": 0.25297856262312113 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.14893394079338146, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "small-potted-plant/state-default.glb" + } + ] + }, + { + "id": "22db76c93c7648-19c7324b0a5", + "title": "Hardcover books", + "transform": { + "position": { + "x": -1.552216185656096, + "y": 0.29590875727765287, + "z": 0.24483101995851997 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": -0.004628634243017425, + "y": 0.048, + "z": 0.003862298942239717 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "hardcover-books/state-default.glb" + } + ] + }, + { + "id": "28f8380d2b909-19c7325a1fe", + "title": "Queen size bed", + "transform": { + "position": { + "x": -4.893117299804146, + "y": 0.68, + "z": -2.45 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.6000000000000001, + "z": -0.07500001341104512 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "queen-size-bed/state-default.glb" + } + ] + }, + { + "id": "c73ce00cad78a8-19c732af8bf", + "title": "Bedside table", + "transform": { + "position": { + "x": -5.64, + "y": 0.39, + "z": -1.2651768042674925 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1.5019873160601556, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.275, + "z": 0.01249999839812517 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [ + { + "id": "cycle-state-default-to-state-mlsm2hfh-kpff", + "label": "to Open", + "from": "state-default", + "to": "state-mlsm2hfh-kpff" + }, + { + "id": "cycle-state-mlsm2hfh-kpff-to-state-default", + "label": "to Closed", + "from": "state-mlsm2hfh-kpff", + "to": "state-default" + } + ], + "states": [ + { + "id": "state-default", + "name": "Closed", + "file": "bedside-table/state-default.glb" + }, + { + "id": "state-mlsm2hfh-kpff", + "name": "Open", + "file": "bedside-table/state-mlsm2hfh-kpff.glb" + } + ] + }, + { + "id": "392a951bb6f11-19c732bcfa3", + "title": "Bedside table", + "transform": { + "position": { + "x": -5.628831317188218, + "y": 0.372181049562469, + "z": -3.622031341394607 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1.5, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.275, + "z": 0.01249999839812517 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [ + { + "id": "cycle-state-default-to-state-mlsm2hfh-kpff", + "label": "to Open", + "from": "state-default", + "to": "state-mlsm2hfh-kpff" + }, + { + "id": "cycle-state-mlsm2hfh-kpff-to-state-default", + "label": "to Closed", + "from": "state-mlsm2hfh-kpff", + "to": "state-default" + } + ], + "states": [ + { + "id": "state-default", + "name": "Closed", + "file": "bedside-table/state-default.glb" + }, + { + "id": "state-mlsm2hfh-kpff", + "name": "Open", + "file": "bedside-table/state-mlsm2hfh-kpff.glb" + } + ] + }, + { + "id": "d1b8634521f5b-19c732c7954", + "title": "Hardcover books", + "transform": { + "position": { + "x": -5.536708061318499, + "y": 0.45461773108196735, + "z": -3.702951078012202 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": -0.004628634243017425, + "y": 0.048, + "z": 0.003862298942239717 + }, + "pickable": true, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "hardcover-books/state-default.glb" + } + ] + }, + { + "id": "cffc759645ff18-19c732db260", + "title": "Books", + "transform": { + "position": { + "x": -5.580755687496764, + "y": 0.4376603227117231, + "z": -1.2697435441517564 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1.0849412180967812, + "y": 0.77, + "z": 0.77 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.0012008581219888764, + "y": 0.04850000034272671, + "z": -0.0021056519411290844 + }, + "pickable": true, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "books/state-default.glb" + } + ] + }, + { + "id": "bc6db6f4cbd0a-19c732ef8c8", + "title": "Modern Office Work Desk", + "transform": { + "position": { + "x": -1.7301176406514844, + "y": 0.4654592368201924, + "z": -0.43338758405308886 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.37499999267980455, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "modern-office-work-desk/state-default.glb" + } + ] + }, + { + "id": "5028f5326c4f1-19c73300d7f", + "title": "Work Chair", + "transform": { + "position": { + "x": -1.6718826945870606, + "y": 0.6166519299880042, + "z": -1.539229575343378 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 0.6439314083963319, + "y": 0.6439314083963319, + "z": 0.6439314083963319 + } + }, + "currentStateId": "state-mlrqdudw-h1ax", + "_shapePivotCenter": { + "x": -0.21270116532945352, + "y": -0.3700314207695614, + "z": -0.9905300125758202 + }, + "pickable": false, + "bumpable": true, + "bumpResponse": 0.65, + "bumpDamping": 0.77, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-mlrqdudw-h1ax", + "name": "default", + "file": "work-chair/state-mlrqdudw-h1ax.glb" + } + ] + }, + { + "id": "ac7a816a60265-19c73317f64", + "title": "Arc floor lamp", + "transform": { + "position": { + "x": -2.333111809397252, + "y": 0.8985525485842618, + "z": -0.4373821778992827 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 0.7651227023559565, + "y": 0.7651227023559565, + "z": 0.7651227023559565 + } + }, + "currentStateId": "state-mlskixi4-xebf", + "_shapePivotCenter": { + "x": 0.7149999964237214, + "y": 1.055747293351406, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [ + { + "id": "cycle-state-default-to-state-mlskixi4-xebf", + "label": "to OFF", + "from": "state-default", + "to": "state-mlskixi4-xebf" + }, + { + "id": "cycle-state-mlskixi4-xebf-to-state-default", + "label": "to ON", + "from": "state-mlskixi4-xebf", + "to": "state-default" + } + ], + "states": [ + { + "id": "state-default", + "name": "ON", + "file": "arc-floor-lamp/state-default.glb" + }, + { + "id": "state-mlskixi4-xebf", + "name": "OFF", + "file": "arc-floor-lamp/state-mlskixi4-xebf.glb" + } + ] + }, + { + "id": "1765e77823bda8-19c7334745f", + "title": "Large wardrobe", + "transform": { + "position": { + "x": -0.31533036247765267, + "y": 1.1536078665542793, + "z": -4.546448663974232 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1.3917312529711456, + "y": 1, + "z": 1.091767035307015 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 1.0499999996274711, + "z": 0.02000000406056643 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [ + { + "id": "cycle-state-default-to-state-mlsmklqi-mykf", + "label": "to Open", + "from": "state-default", + "to": "state-mlsmklqi-mykf" + }, + { + "id": "cycle-state-mlsmklqi-mykf-to-state-default", + "label": "to closed", + "from": "state-mlsmklqi-mykf", + "to": "state-default" + } + ], + "states": [ + { + "id": "state-default", + "name": "closed", + "file": "large-wardrobe/state-default.glb" + }, + { + "id": "state-mlsmklqi-mykf", + "name": "Open", + "file": "large-wardrobe/state-mlsmklqi-mykf.glb" + } + ] + }, + { + "id": "6eaff768b565c-19c7335c107", + "title": "Freestanding oval soaking bathtub with chrome fl...", + "transform": { + "position": { + "x": 4.522408021754294, + "y": 0.3904049244978556, + "z": -0.896791648070859 + }, + "rotation": { + "x": 0, + "y": 3.141592653589793, + "z": 0 + }, + "scale": { + "x": 1.7873490005753465, + "y": 1, + "z": 1.3568453847354858 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.08813499016471649, + "y": 0.6175507578992459, + "z": 4.231659860618338 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [ + { + "id": "cycle-state-default-to-state-mlsiig1y-6e45", + "label": "to Full", + "from": "state-default", + "to": "state-mlsiig1y-6e45" + }, + { + "id": "cycle-state-mlsiig1y-6e45-to-state-default", + "label": "to Empty", + "from": "state-mlsiig1y-6e45", + "to": "state-default" + } + ], + "states": [ + { + "id": "state-default", + "name": "Empty", + "file": "freestanding-oval-soaking-bathtub-with-chrome-fl/state-default.glb" + }, + { + "id": "state-mlsiig1y-6e45", + "name": "Full", + "file": "freestanding-oval-soaking-bathtub-with-chrome-fl/state-mlsiig1y-6e45.glb" + } + ] + }, + { + "id": "b500b00d33e638-19c735e91d7", + "title": "refrigerator", + "transform": { + "position": { + "x": -2.6390041499833767, + "y": 0.9876455923302134, + "z": 0.5193998030296436 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": -0.0032454665083127, + "y": 0.9003749143341613, + "z": -0.003915878407667384 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [ + { + "id": "cycle-state-default-to-state-mlsqs928-jonu", + "label": "to Open", + "from": "state-default", + "to": "state-mlsqs928-jonu" + }, + { + "id": "cycle-state-mlsqs928-jonu-to-state-default", + "label": "to closed", + "from": "state-mlsqs928-jonu", + "to": "state-default" + } + ], + "states": [ + { + "id": "state-default", + "name": "closed", + "file": "refrigerator/state-default.glb" + }, + { + "id": "state-mlsqs928-jonu", + "name": "Open", + "file": "refrigerator/state-mlsqs928-jonu.glb" + } + ] + }, + { + "id": "669fe9f9f97588-19c736a9260", + "title": "kitchen base cabinet", + "transform": { + "position": { + "x": -3.6717847955793625, + "y": 0.529275586728742, + "z": 0.4720761398832385 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1.8098083678676107, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": -0.0004609774656834098, + "y": 0.4399999994598329, + "z": 0.01919808945853102 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [ + { + "id": "cycle-state-default-to-state-mlsr95pw-kpf4", + "label": "to open", + "from": "state-default", + "to": "state-mlsr95pw-kpf4" + }, + { + "id": "cycle-state-mlsr95pw-kpf4-to-state-default", + "label": "to closed", + "from": "state-mlsr95pw-kpf4", + "to": "state-default" + } + ], + "states": [ + { + "id": "state-default", + "name": "closed", + "file": "kitchen-base-cabinet/state-default.glb" + }, + { + "id": "state-mlsr95pw-kpf4", + "name": "open", + "file": "kitchen-base-cabinet/state-mlsr95pw-kpf4.glb" + } + ] + }, + { + "id": "a4013b97f887b8-19c736d15ce", + "title": "kitchen base cabinet", + "transform": { + "position": { + "x": -5.578769058377267, + "y": 0.5351143306110472, + "z": 4.341854069829404 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1.7788682026204685, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": -0.0004609774656834098, + "y": 0.4399999994598329, + "z": 0.01919808945853102 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [ + { + "id": "cycle-state-default-to-state-mlsr95pw-kpf4", + "label": "to open", + "from": "state-default", + "to": "state-mlsr95pw-kpf4" + }, + { + "id": "cycle-state-mlsr95pw-kpf4-to-state-default", + "label": "to closed", + "from": "state-mlsr95pw-kpf4", + "to": "state-default" + } + ], + "states": [ + { + "id": "state-default", + "name": "closed", + "file": "kitchen-base-cabinet/state-default.glb" + }, + { + "id": "state-mlsr95pw-kpf4", + "name": "open", + "file": "kitchen-base-cabinet/state-mlsr95pw-kpf4.glb" + } + ] + }, + { + "id": "414821fb84733-19c736ec63b", + "title": "kitchen base cabinet", + "transform": { + "position": { + "x": -5.581997975509333, + "y": 0.5282067101293415, + "z": 1.7664241653590549 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1.4227205704111852, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": -0.0004609774656834098, + "y": 0.4399999994598329, + "z": 0.01919808945853102 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [ + { + "id": "cycle-state-default-to-state-mlsr95pw-kpf4", + "label": "to open", + "from": "state-default", + "to": "state-mlsr95pw-kpf4" + }, + { + "id": "cycle-state-mlsr95pw-kpf4-to-state-default", + "label": "to closed", + "from": "state-mlsr95pw-kpf4", + "to": "state-default" + } + ], + "states": [ + { + "id": "state-default", + "name": "closed", + "file": "kitchen-base-cabinet/state-default.glb" + }, + { + "id": "state-mlsr95pw-kpf4", + "name": "open", + "file": "kitchen-base-cabinet/state-mlsr95pw-kpf4.glb" + } + ] + }, + { + "id": "80182e12bc169-19c73a10d27", + "title": "Professional Gas Range", + "transform": { + "position": { + "x": -4.746920983597513, + "y": 0.5687589957482349, + "z": 0.3873462875499325 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1.1219595276194203, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.4899999935925007, + "z": 0.030999994091689576 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [ + { + "id": "cycle-state-default-to-state-mlssjm1p-xotl", + "label": "turn on front right", + "from": "state-default", + "to": "state-mlssjm1p-xotl" + }, + { + "id": "it-mlsszajl-asw9", + "label": "turn on back right", + "from": "state-default", + "to": "state-mlsskac7-ywao" + }, + { + "id": "it-mlsszdl0-9396", + "label": "turn on front left", + "from": "state-default", + "to": "state-mlssl1do-1yyl" + }, + { + "id": "cycle-state-mlssjm1p-xotl-to-state-mlsskac7-ywao", + "label": "turn off", + "from": "state-mlssjm1p-xotl", + "to": "state-default" + }, + { + "id": "cycle-state-mlsskac7-ywao-to-state-mlssl1do-1yyl", + "label": "turn off", + "from": "state-mlsskac7-ywao", + "to": "state-default" + }, + { + "id": "cycle-state-mlssl1do-1yyl-to-state-default", + "label": "turn off", + "from": "state-mlssl1do-1yyl", + "to": "state-default" + } + ], + "states": [ + { + "id": "state-default", + "name": "off", + "file": "professional-gas-range/state-default.glb" + }, + { + "id": "state-mlssjm1p-xotl", + "name": "front-right-on", + "file": "professional-gas-range/state-mlssjm1p-xotl.glb" + }, + { + "id": "state-mlsskac7-ywao", + "name": "back-right-on", + "file": "professional-gas-range/state-mlsskac7-ywao.glb" + }, + { + "id": "state-mlssl1do-1yyl", + "name": "front-left-on", + "file": "professional-gas-range/state-mlssl1do-1yyl.glb" + } + ] + }, + { + "id": "5aca293afb4bc8-19c73a60e13", + "title": "Built-in stainless steel dishwasher", + "transform": { + "position": { + "x": -5.62, + "y": 0.52, + "z": 3.5 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.42500000000000004, + "z": 0.016000004224479197 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "built-in-stainless-steel-dishwasher/state-default.glb" + } + ] + }, + { + "id": "62797796e9767-19c73af66a5", + "title": "Sink", + "transform": { + "position": { + "x": -5.59988395161818, + "y": 0.9535132879737271, + "z": 2.6793443991438437 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 0.7160886522166464, + "y": 0.40892918087790386, + "z": 0.8280100914128449 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": -0.2733975025605969, + "y": 1.2202618787565602, + "z": 1.8803600531622169 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "sink/state-default.glb" + } + ] + }, + { + "id": "80c4a613fb7268-19c73c9ac7a", + "title": "Dining chair", + "transform": { + "position": { + "x": -1.0087908140402728, + "y": 0.5434133631727004, + "z": 4.26 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.42500000000000004, + "z": 0.00026035857325493184 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "dining-chair/state-default.glb" + } + ] + }, + { + "id": "9a67b23a28cf8-19c73cb7fe7", + "title": "Large ornate mahogany dining table", + "transform": { + "position": { + "x": -0.3670123249376638, + "y": 0.47636876395355976, + "z": 3.809280713021919 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.37499999936670064, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "large-ornate-mahogany-dining-table/state-default.glb" + } + ] + }, + { + "id": "b521e3d18de31-19c73cc4ab7", + "title": "Dining chair", + "transform": { + "position": { + "x": -1.021304087860674, + "y": 0.5331213412094118, + "z": 3.31 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.42455268602766005, + "z": 0.00026035857325493184 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "dining-chair/state-default.glb" + } + ] + }, + { + "id": "c4896d1ee8f58-19c73cca1c3", + "title": "Dining chair", + "transform": { + "position": { + "x": 0.0258311295758461, + "y": 0.5434518887030261, + "z": 4.257087223482772 + }, + "rotation": { + "x": 0, + "y": 4.71238898038469, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.42455268602766005, + "z": 0.00026035857325493184 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "dining-chair/state-default.glb" + } + ] + }, + { + "id": "5870c87d73e6e-19c73cd1041", + "title": "Dining chair", + "transform": { + "position": { + "x": 0.4759727625914219, + "y": 0.5487097275235999, + "z": 3.6356960320731617 + }, + "rotation": { + "x": 0, + "y": 4.71238898038469, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.42455268602766005, + "z": 0.00026035857325493184 + }, + "pickable": false, + "bumpable": true, + "bumpResponse": 1.25, + "bumpDamping": 0.86, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "dining-chair/state-default.glb" + } + ] + }, + { + "id": "86897b7437ec4-19c73d08c40", + "title": "kitchen wall cabinet", + "transform": { + "position": { + "x": -5.7339840704817675, + "y": 2.1862344570288634, + "z": 4.379152567928243 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1.2867158952939255, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.44999999999999996, + "z": 0.01999999690800905 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "kitchen-wall-cabinet/state-default.glb" + } + ] + }, + { + "id": "d4e7cf45e14168-19c73d2c59e", + "title": "kitchen wall cabinet", + "transform": { + "position": { + "x": -5.734054470140882, + "y": 2.185881752908841, + "z": 3.4550831669585023 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.44999999999999996, + "z": 0.01999999690800905 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "kitchen-wall-cabinet/state-default.glb" + } + ] + }, + { + "id": "53ffa35fcc3b3-19c73d3c12b", + "title": "Wall-mounted stainless steel chimney range hood\n...", + "transform": { + "position": { + "x": -4.740618632346517, + "y": 2.4462029494015645, + "z": 0.3129874596416138 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1.3048132595239712, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.49499999426305297, + "z": 0.004999999888241291 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "wall-mounted-stainless-steel-chimney-range-hood/state-default.glb" + } + ] + }, + { + "id": "16b55c06139a58-19c73d4f998", + "title": "kitchen wall cabinet", + "transform": { + "position": { + "x": -5.7404835482395695, + "y": 2.183006970153812, + "z": 1.6857432491479991 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1.5347140343971224, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.44999999999999996, + "z": 0.01999999690800905 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "kitchen-wall-cabinet/state-default.glb" + } + ] + }, + { + "id": "2841a95215e2b-19c73d6a74f", + "title": "Two-slice chrome toaster with browning control d...", + "transform": { + "position": { + "x": -5.53024050161023, + "y": 1.0784581482665967, + "z": 1.5159435448934113 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.02000000216066837, + "y": 0.0950000018440187, + "z": 0.006250037542275558 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "two-slice-chrome-toaster-with-browning-control-d/state-default.glb" + } + ] + }, + { + "id": "d146e81adcfb6-19c73d6f1d1", + "title": "Automatic drip coffee maker with glass carafe\n\nI...", + "transform": { + "position": { + "x": -5.528265138870446, + "y": 1.1498788004517702, + "z": 4.666337898166567 + }, + "rotation": { + "x": -3.141592653589793, + "y": 1.2353040676263245, + "z": -3.141592653589793 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.17499999983236195, + "z": 0.017000000141561028 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "automatic-drip-coffee-maker-with-glass-carafe-i/state-default.glb" + } + ] + }, + { + "id": "b9d431e7a8db-19c73d7935a", + "title": "Modern cordless electric kettle with brushed met...", + "transform": { + "position": { + "x": -4.737252095959948, + "y": 1.1082720912950728, + "z": 0.3542968078051474 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.125, + "z": -0.004422579425060177 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "modern-cordless-electric-kettle-with-brushed-met/state-default.glb" + } + ] + }, + { + "id": "d27de72b5e0e88-19c73d801ac", + "title": "High-speed kitchen blender with glass jar and me...", + "transform": { + "position": { + "x": -5.598440540578837, + "y": 1.1821618341549747, + "z": 0.39175803651442287 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.03320012858728233, + "y": 0.21249999860301613, + "z": 0.003750044043080797 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "high-speed-kitchen-blender-with-glass-jar-and-me/state-default.glb" + } + ] + }, + { + "id": "e9ad475608341-19c73d95aaf", + "title": "Art deco gold-finished bar cart with two glass s...", + "transform": { + "position": { + "x": 1.1617934539333223, + "y": 0.5389120073767927, + "z": 0.3863584703065891 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.43250041351490937, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "art-deco-gold-finished-bar-cart-with-two-glass-s/state-default.glb" + } + ] + }, + { + "id": "2366af35eadcf8-19c73da0dcc", + "title": "Detailed porcelain dinner plate with gold rim an...", + "transform": { + "position": { + "x": 1.2032666946891117, + "y": 0.35538681201078215, + "z": 0.457809393418966 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.015000253395232687, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "detailed-porcelain-dinner-plate-with-gold-rim-an/state-default.glb" + } + ] + }, + { + "id": "9614072b45308-19c73da284e", + "title": "Detailed porcelain dinner plate with gold rim an...", + "transform": { + "position": { + "x": 1.1965681617029897, + "y": 0.42327413092342614, + "z": 0.5170610864361298 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.015000253395232687, + "z": 0 + }, + "pickable": true, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "detailed-porcelain-dinner-plate-with-gold-rim-an/state-default.glb" + } + ] + }, + { + "id": "b56a8224e0b41-19c73da6a7c", + "title": "Detailed porcelain dinner plate with gold rim an...", + "transform": { + "position": { + "x": 1.2651117557232083, + "y": 0.8539772864259029, + "z": 0.40488177152786675 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.015000253395232687, + "z": 0 + }, + "pickable": true, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "detailed-porcelain-dinner-plate-with-gold-rim-an/state-default.glb" + } + ] + }, + { + "id": "35b2a660f6f678-19c73db81a7", + "title": "Detailed porcelain dinner plate with gold rim an...", + "transform": { + "position": { + "x": 1.264493009384819, + "y": 0.8980005677819676, + "z": 0.4371962543984047 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.015000253395232687, + "z": 0 + }, + "pickable": true, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "detailed-porcelain-dinner-plate-with-gold-rim-an/state-default.glb" + } + ] + }, + { + "id": "995aeff211eac-19c73dc9250", + "title": "Wine glass", + "transform": { + "position": { + "x": 1.0177538809809166, + "y": 0.9429782021892605, + "z": 0.4498776100590399 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-mlrogc5m-n4t3", + "_shapePivotCenter": { + "x": 0, + "y": 0.11125000042840838, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [ + { + "id": "cycle-state-default-to-state-mlrogc5m-n4t3", + "label": "to full", + "from": "state-default", + "to": "state-mlrogc5m-n4t3" + }, + { + "id": "cycle-state-mlrogc5m-n4t3-to-state-default", + "label": "to empty", + "from": "state-mlrogc5m-n4t3", + "to": "state-default" + } + ], + "states": [ + { + "id": "state-default", + "name": "empty", + "file": "wine-glass/state-default.glb" + }, + { + "id": "state-mlrogc5m-n4t3", + "name": "full", + "file": "wine-glass/state-mlrogc5m-n4t3.glb" + } + ] + }, + { + "id": "0695d8eaecdef-19c73dd202d", + "title": "Salt and pepper Shakers", + "transform": { + "position": { + "x": -3.9803931457097406, + "y": 1.0048145678774343, + "z": 0.5215084811167934 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.03500000027939677, + "z": 0 + }, + "pickable": true, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "salt-and-pepper-shakers/state-default.glb" + } + ] + }, + { + "id": "3501961e59bfd-19c73dd7348", + "title": "Woven rattan placemat", + "transform": { + "position": { + "x": -0.6918154969521217, + "y": 0.8540616060927329, + "z": 3.2486867503780283 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.006163739011521584, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "woven-rattan-placemat/state-default.glb" + } + ] + }, + { + "id": "106836e6061308-19c73ddca05", + "title": "Woven rattan placemat", + "transform": { + "position": { + "x": -0.03199168640492356, + "y": 0.8639676887097529, + "z": 3.2080873974631094 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.006163739011521584, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "woven-rattan-placemat/state-default.glb" + } + ] + }, + { + "id": "a4d9f0c23dd5b-19c73ddea29", + "title": "Woven rattan placemat", + "transform": { + "position": { + "x": -0.6857401667092435, + "y": 0.859627743601119, + "z": 4.289689745315966 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.006163739011521584, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "woven-rattan-placemat/state-default.glb" + } + ] + }, + { + "id": "86bf2f5237ec6-19c73de0fe1", + "title": "Woven rattan placemat", + "transform": { + "position": { + "x": -0.04934858727521346, + "y": 0.8540464700703785, + "z": 4.288064914106616 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.006163739011521584, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "woven-rattan-placemat/state-default.glb" + } + ] + }, + { + "id": "bd9f45e625fdc-19c73de49ea", + "title": "Stainless steel cutlery set", + "transform": { + "position": { + "x": -0.696829349219807, + "y": 0.8586490872300028, + "z": 3.32 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 0.5, + "y": 0.5, + "z": 0.5 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.0025628975396361324, + "y": 0.0027103629905995495, + "z": 0.014999998435378074 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "stainless-steel-cutlery-set/state-default.glb" + } + ] + }, + { + "id": "0a096032464cd8-19c73df0150", + "title": "Stainless steel cutlery set", + "transform": { + "position": { + "x": -3.9286632656874647, + "y": 0.5386453681978114, + "z": 0.6449646063146555 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.0025628975396361324, + "y": 0.0027103629905995495, + "z": 0.014999998435378074 + }, + "pickable": true, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "stainless-steel-cutlery-set/state-default.glb" + } + ] + }, + { + "id": "0202ee297f2a88-19c73df2eb8", + "title": "Stainless steel cutlery set", + "transform": { + "position": { + "x": -3.7662372755085376, + "y": 0.5388803818702548, + "z": 0.6515124115358037 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.0025628975396361324, + "y": 0.0027103629905995495, + "z": 0.014999998435378074 + }, + "pickable": true, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "stainless-steel-cutlery-set/state-default.glb" + } + ] + }, + { + "id": "94ecfd5ada2578-19c73dfac8d", + "title": "Stainless steel cutlery set", + "transform": { + "position": { + "x": -3.4404169853090836, + "y": 0.5413681306400779, + "z": 0.6380915974649233 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.0025628975396361324, + "y": 0.0027103629905995495, + "z": 0.014999998435378074 + }, + "pickable": true, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "stainless-steel-cutlery-set/state-default.glb" + } + ] + }, + { + "id": "e504c978d237c-19c73e648dc", + "title": "Sleek countertop microwave oven with digital dis...", + "transform": { + "position": { + "x": -5.59, + "y": 1.1109554476439747, + "z": 4.160795697533484 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.16000000309199097, + "z": 0.019999998398125177 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "sleek-countertop-microwave-oven-with-digital-dis/state-default.glb" + } + ] + }, + { + "id": "7c166d4a7b1fa-19c73e6b7ae", + "title": "Classic outdoor garden bench", + "transform": { + "position": { + "x": 3.6298746749997752, + "y": 0.46974768857104965, + "z": 7.2158786326308135 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.4101636643918064, + "z": -0.009999999776482582 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "classic-outdoor-garden-bench/state-default.glb" + } + ] + }, + { + "id": "30e5d8717fd2e8-19c7406b70c", + "title": "Bathroom vanity and sink", + "transform": { + "position": { + "x": 2.031272123883404, + "y": 0.6635385096694033, + "z": -4.330352147122318 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 1.456095909396544, + "y": 0.4909199642562849, + "z": 0.26005917572635695 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "bathroom-vanity-and-sink/state-default.glb" + } + ] + }, + { + "id": "3e3ea9b2cc2e58-19c74073206", + "title": "Contemporary white ceramic toilet with sleek lin...", + "transform": { + "position": { + "x": 4.454104862841407, + "y": 0.42316131113123934, + "z": -4.505567046787334 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1.3957356681124615, + "y": 1.3957356681124615, + "z": 1.3957356681124615 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.37999999845400456, + "z": 0.0024999931454658397 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "contemporary-white-ceramic-toilet-with-sleek-lin/state-default.glb" + } + ] + }, + { + "id": "94e9a636240718-19c7407bbee", + "title": "Luxury rainfall shower head and wall-mounted mix...", + "transform": { + "position": { + "x": 1.9425969244634211, + "y": 1.3148567749089612, + "z": -0.36640908300765984 + }, + "rotation": { + "x": 0, + "y": 3.141592653589793, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 1.25, + "z": 0.26500000309199095 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "luxury-rainfall-shower-head-and-wall-mounted-mix/state-default.glb" + } + ] + }, + { + "id": "a2b85a007ca9d-19c7408763c", + "title": "Woven wicker laundry hamper with a fabric liner ...", + "transform": { + "position": { + "x": 3.25028196420934, + "y": 0.3302800075837711, + "z": -4.503918870307929 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 0.8583300892907466, + "y": 0.8583300892907466, + "z": 0.8583300892907466 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.29749999690800905, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "woven-wicker-laundry-hamper-with-a-fabric-liner/state-default.glb" + } + ] + }, + { + "id": "99c77c594d079-19c7408ea1d", + "title": "Polished chrome wall-mounted towel rack with fol...", + "transform": { + "position": { + "x": 1.2000208284940208, + "y": 1.53, + "z": -1.1057607374920708 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1.4494794852373833, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.26249999122687057, + "z": 0.01807261087466902 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "polished-chrome-wall-mounted-towel-rack-with-fol/state-default.glb" + } + ] + }, + { + "id": "7e1f8523afa01-19c74098514", + "title": "Minimalist floating wooden wall shelves for bath...", + "transform": { + "position": { + "x": 4.491771043106426, + "y": 1.2101214572034933, + "z": -0.15247527825167362 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1.1833166424840937, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 1.4399999997206032, + "z": 0.07500000000000001 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "minimalist-floating-wooden-wall-shelves-for-bath/state-default.glb" + } + ] + }, + { + "id": "ba520c65d11258-19c7409f996", + "title": "Matching ceramic soap dispenser, toothbrush hold...", + "transform": { + "position": { + "x": 1.3341187797982013, + "y": 1.1268225562070888, + "z": -4.449625881687194 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.019999999552965164, + "y": 0.08499999845400452, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "matching-ceramic-soap-dispenser-toothbrush-hold/state-default.glb" + } + ] + }, + { + "id": "9ea7f64c32fb7-19c740b89fc", + "title": "Wall-mounted medicine cabinet with a large mirro...", + "transform": { + "position": { + "x": 2.017737545060936, + "y": 1.9269932324049326, + "z": -4.810104392332999 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1.303586220666433, + "y": 1.1705937734630785, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": -0.03941424555273487, + "y": 0.4, + "z": 0.022500016540531666 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "wall-mounted-medicine-cabinet-with-a-large-mirro/state-default.glb" + } + ] + }, + { + "id": "b45b699007c72-19c74300203", + "title": "Framed abstract oil painting", + "transform": { + "position": { + "x": 4.424584573788344, + "y": 1.9470570099444073, + "z": 0.08375157009131762 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1.3643420085814393, + "y": 1.2248492171872085, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 1.5, + "z": 0.0017383729780349189 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "framed-abstract-oil-painting/state-default.glb" + } + ] + }, + { + "id": "0d071b9d15a778-19c74323057", + "title": "Framed landscape oil painting", + "transform": { + "position": { + "x": -3.608992492739797, + "y": 1.7361845431468765, + "z": -4.879999937970252 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 2.321890853006333, + "y": 2.518815242069379, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.30000000000000004, + "z": 0.002609475582382474 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "framed-landscape-oil-painting/state-default.glb" + } + ] + }, + { + "id": "8f61d882176858-19c743358f5", + "title": "Vintage poster", + "transform": { + "position": { + "x": -4.4079772102754955, + "y": 1.8962601991548873, + "z": -0.06366045843035233 + }, + "rotation": { + "x": 0, + "y": 3.141592653589793, + "z": 0 + }, + "scale": { + "x": 2.0446682506880354, + "y": 2.1001934576595302, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.32499999999999996, + "z": 0.004999999944120646 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "vintage-poster/state-default.glb" + } + ] + }, + { + "id": "46aa48c4bb14d-19c74347b30", + "title": "wall clock", + "transform": { + "position": { + "x": 5.862637492866764, + "y": 2.36, + "z": 2.88 + }, + "rotation": { + "x": 0, + "y": 4.71238898038469, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.4, + "z": 0.005000036787878975 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "wall-clock/state-default.glb" + } + ] + }, + { + "id": "ba2c0f11cedef-19c743507ed", + "title": "Wall mirror", + "transform": { + "position": { + "x": -1.8721821641931122, + "y": 1.8546174723983981, + "z": 3.9556118892043464 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.75, + "z": 0.027505963917087026 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "wall-mirror/state-default.glb" + } + ] + }, + { + "id": "39e52be49c9ec8-19c74363fc3", + "title": "Assorted decorative plants", + "transform": { + "position": { + "x": -2.9044516167844154, + "y": 0.6125478909283358, + "z": 5.464666979023578 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": -0.06828595502296761, + "y": 0.4995002142584293, + "z": 0.05005857882475222 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "assorted-decorative-plants/state-default.glb" + } + ] + }, + { + "id": "412ff4ad131ff-19c74372469", + "title": "Set of three canvas prints featuring detailed bo...", + "transform": { + "position": { + "x": -5.890814574323871, + "y": 2.1254741150774024, + "z": -2.4937709011301235 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1.7741064961903168, + "y": 1.3607416183002867, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.30000000000000004, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "set-of-three-canvas-prints-featuring-detailed-bo/state-default.glb" + } + ] + }, + { + "id": "048418404b31-19c7437cce5", + "title": "Neon light wall art", + "transform": { + "position": { + "x": 0.9, + "y": 1.65, + "z": -0.94 + }, + "rotation": { + "x": 0, + "y": 4.71238898038469, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.0455026046119541, + "y": 0.31117674360714764, + "z": -0.009999999944120645 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "neon-light-wall-art/state-default.glb" + } + ] + }, + { + "id": "eedf6074a66ce-19c7438a204", + "title": "Bohemian style woven macrame", + "transform": { + "position": { + "x": 5.856553202676937, + "y": 1.79, + "z": -2.44 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.5152472768993592, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "bohemian-style-woven-macrame/state-default.glb" + } + ] + }, + { + "id": "998aaee1750c98-19c7441f967", + "title": "Chunky knit wool throw blanket with visible weav...", + "transform": { + "position": { + "x": -4.722957697499421, + "y": 0.5995631183491226, + "z": -2.443810500735502 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1.319078993031496, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.04748437812509175, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "chunky-knit-wool-throw-blanket-with-visible-weav/state-default.glb" + } + ] + }, + { + "id": "94d820b5be849-19c7442b3c5", + "title": "Pair of plush white bed pillows with cotton text...", + "transform": { + "position": { + "x": -5.649719211474874, + "y": 0.7187351739850696, + "z": -2.4659646636791352 + }, + "rotation": { + "x": 1.5707963267948963, + "y": 1.050976584154359, + "z": -1.5707963267948963 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.11000000000000001, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "pair-of-plush-white-bed-pillows-with-cotton-text/state-default.glb" + } + ] + }, + { + "id": "2668d614a5e848-19c7443bb04", + "title": "Soft fuzzy stuffed teddy bear with button eyes a...", + "transform": { + "position": { + "x": -0.8510426342848817, + "y": 1.0184118900507562, + "z": -4.745109333958126 + }, + "rotation": { + "x": 0, + "y": -0.35751964509038986, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.1524781208620488, + "z": 0.022493639105132107 + }, + "pickable": true, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "soft-fuzzy-stuffed-teddy-bear-with-button-eyes-a/state-default.glb" + } + ] + }, + { + "id": "72878a8f5ffb28-19c74452ecd", + "title": "laptop open", + "transform": { + "position": { + "x": -1.7, + "y": 0.96, + "z": -0.41 + }, + "rotation": { + "x": 0, + "y": 3.141592653589793, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.11673651631330051, + "z": -0.04432948718632643 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "laptop-open/state-default.glb" + } + ] + }, + { + "id": "be0c1bf4a1e43-19c74455b1e", + "title": "Matte ceramic coffee mug with steam and realisti...", + "transform": { + "position": { + "x": -2.084297221134241, + "y": 0.9317528639491932, + "z": -0.46062232996302266 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.01750006346140766, + "y": 0.09077258996382548, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "matte-ceramic-coffee-mug-with-steam-and-realisti/state-default.glb" + } + ] + }, + { + "id": "e891daddeb566-19c7445a6c2", + "title": "Hardcover book lying open with paper pages and p...", + "transform": { + "position": { + "x": 5.107398196850658, + "y": 0.5789292014696342, + "z": 1.379850337825023 + }, + "rotation": { + "x": 0, + "y": -0.7614917198077298, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.010374427221847459, + "z": 0 + }, + "pickable": true, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "hardcover-book-lying-open-with-paper-pages-and-p/state-default.glb" + } + ] + }, + { + "id": "466b5c32d8ffc8-19c7445fe6d", + "title": "Thin glass and metal smartphone with reflective ...", + "transform": { + "position": { + "x": -5.620367368438998, + "y": 0.6507814526590434, + "z": -3.5722425565895612 + }, + "rotation": { + "x": 0, + "y": 0.5836908321898583, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.00625, + "z": -7.82310966007671e-10 + }, + "pickable": true, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "thin-glass-and-metal-smartphone-with-reflective/state-default.glb" + } + ] + }, + { + "id": "bfeb41524c65f8-19c74468aea", + "title": "Light oak wooden bed tray with handles and short...", + "transform": { + "position": { + "x": -4.810490635848853, + "y": 0.696442809417525, + "z": -2.773194360540799 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.12499999903142453, + "z": 0 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "light-oak-wooden-bed-tray-with-handles-and-short/state-default.glb" + } + ] + }, + { + "id": "bf9beb5fb79a8-19c744766ad", + "title": "Thick quilted duvet neatly folded with soft fabr...", + "transform": { + "position": { + "x": -1.0909513930543349, + "y": 0.2944852328458841, + "z": -4.680966959464118 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 0.43288237437984695, + "y": 1, + "z": 0.6923437151644042 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 0.11199358191488266, + "z": 0.055000002682209004 + }, + "pickable": true, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "thick-quilted-duvet-neatly-folded-with-soft-fabr/state-default.glb" + } + ] + }, + { + "id": "dbefaeda89b1d-19c744ed429", + "title": "Large detailed oak tree with textured bark and l...", + "transform": { + "position": { + "x": -1.5512307374727492, + "y": 2.5134853929878243, + "z": 8.016079845065434 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 0.6996114045873896, + "y": 0.6996114045873896, + "z": 0.6996114045873896 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0, + "y": 3.649999976158142, + "z": 0.25000003576278695 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "large-detailed-oak-tree-with-textured-bark-and-l/state-default.glb" + } + ] + }, + { + "id": "60e08e06242f38-19c74564e1e", + "title": "Galvanized steel watering can with a long spout ...", + "transform": { + "position": { + "x": 5.241405996940184, + "y": 0.21187023344930833, + "z": 5.203786043018361 + }, + "rotation": { + "x": 0, + "y": 0, + "z": 0 + }, + "scale": { + "x": 1, + "y": 1, + "z": 1 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.09620328438469122, + "y": 0.16122611763747985, + "z": 0 + }, + "pickable": true, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "galvanized-steel-watering-can-with-a-long-spout/state-default.glb" + } + ] + }, + { + "id": "843c6307ab323-19c7456cda8", + "title": "Large terracotta garden pots with intricate flor...", + "transform": { + "position": { + "x": 5.795020447146578, + "y": 0.22466053141207248, + "z": 8.532342244184631 + }, + "rotation": { + "x": 0, + "y": 1.5707963267948966, + "z": 0 + }, + "scale": { + "x": 0.5624222520343933, + "y": 0.5624222520343933, + "z": 0.5624222520343933 + } + }, + "currentStateId": "state-default", + "_shapePivotCenter": { + "x": 0.32500000298023224, + "y": 0.31999999359250064, + "z": -2.980232227667301e-9 + }, + "pickable": false, + "bumpable": false, + "bumpResponse": 0.9, + "bumpDamping": 0.9, + "castShadow": false, + "receiveShadow": false, + "actions": [], + "states": [ + { + "id": "state-default", + "name": "default", + "file": "large-terracotta-garden-pots-with-intricate-flor/state-default.glb" + } + ] + } +] \ No newline at end of file diff --git a/misc/DimSim/scenes/apartment/objects/matching-ceramic-soap-dispenser-toothbrush-hold/state-default.glb b/misc/DimSim/scenes/apartment/objects/matching-ceramic-soap-dispenser-toothbrush-hold/state-default.glb new file mode 100644 index 0000000000..fa1f3f5958 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/matching-ceramic-soap-dispenser-toothbrush-hold/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:6d535dabf534509fe3e28452975aaa5ac01c6c7e06c7f65686a9f8b483166cde +size 390684 diff --git a/misc/DimSim/scenes/apartment/objects/matte-ceramic-coffee-mug-with-steam-and-realisti/state-default.glb b/misc/DimSim/scenes/apartment/objects/matte-ceramic-coffee-mug-with-steam-and-realisti/state-default.glb new file mode 100644 index 0000000000..4a12d24d2c --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/matte-ceramic-coffee-mug-with-steam-and-realisti/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:1f8198ef23fc9c4e2b8eee2ca7dfef585eba254db817ccc124b51e14a97d7cb9 +size 67604 diff --git a/misc/DimSim/scenes/apartment/objects/minimalist-floating-wooden-wall-shelves-for-bath/state-default.glb b/misc/DimSim/scenes/apartment/objects/minimalist-floating-wooden-wall-shelves-for-bath/state-default.glb new file mode 100644 index 0000000000..172c033078 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/minimalist-floating-wooden-wall-shelves-for-bath/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:3c372327111290d8e3039ae7214469fa7ca608fa82fa25014d2739bc6964e5dd +size 338516 diff --git a/misc/DimSim/scenes/apartment/objects/modern-cordless-electric-kettle-with-brushed-met/state-default.glb b/misc/DimSim/scenes/apartment/objects/modern-cordless-electric-kettle-with-brushed-met/state-default.glb new file mode 100644 index 0000000000..e0797a7ae9 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/modern-cordless-electric-kettle-with-brushed-met/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:b6978435381bfb06cb50f5240e3826e7654ddd3d4ae5798224fb8bb35773a58d +size 402256 diff --git a/misc/DimSim/scenes/apartment/objects/modern-l-shaped-sectional/state-default.glb b/misc/DimSim/scenes/apartment/objects/modern-l-shaped-sectional/state-default.glb new file mode 100644 index 0000000000..aa78105c80 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/modern-l-shaped-sectional/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c90d01cd485a76c111f479f0adf98edafb94ed9de8412e1a1648366d398f6cb7 +size 1237140 diff --git a/misc/DimSim/scenes/apartment/objects/modern-office-work-desk/state-default.glb b/misc/DimSim/scenes/apartment/objects/modern-office-work-desk/state-default.glb new file mode 100644 index 0000000000..3a78d2d0fd --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/modern-office-work-desk/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:e8a0531a082830ed5ae7944298a08d06522ae16e5be4fc4d2297672dcda6580d +size 7261060 diff --git a/misc/DimSim/scenes/apartment/objects/modern-tripod-floor-lamp/state-default.glb b/misc/DimSim/scenes/apartment/objects/modern-tripod-floor-lamp/state-default.glb new file mode 100644 index 0000000000..49cc13911e --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/modern-tripod-floor-lamp/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5120ee40ab6e16d691bec8df9a1706c342667de183b14eb39d9194c2f9ce5a10 +size 587672 diff --git a/misc/DimSim/scenes/apartment/objects/modern-tripod-floor-lamp/state-mlrpcv6c-bdvt.glb b/misc/DimSim/scenes/apartment/objects/modern-tripod-floor-lamp/state-mlrpcv6c-bdvt.glb new file mode 100644 index 0000000000..f84aa514c5 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/modern-tripod-floor-lamp/state-mlrpcv6c-bdvt.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:9c87c9326473786effe27a9c42a3bbe3ac91b495a38de05b2936c907fbc11f50 +size 587716 diff --git a/misc/DimSim/scenes/apartment/objects/neon-light-wall-art/state-default.glb b/misc/DimSim/scenes/apartment/objects/neon-light-wall-art/state-default.glb new file mode 100644 index 0000000000..c09176be7b --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/neon-light-wall-art/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:d7e5c1efd9d82139f895d0f45138d04b112750b9769e609aa1380c573905dd12 +size 30864 diff --git a/misc/DimSim/scenes/apartment/objects/pair-of-plush-white-bed-pillows-with-cotton-text/state-default.glb b/misc/DimSim/scenes/apartment/objects/pair-of-plush-white-bed-pillows-with-cotton-text/state-default.glb new file mode 100644 index 0000000000..dba8028cd2 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/pair-of-plush-white-bed-pillows-with-cotton-text/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:7cabb071524c75b9f5127e72b2eb0734a25c99c3b6abe2fb5715a40027b87715 +size 471560 diff --git a/misc/DimSim/scenes/apartment/objects/polished-chrome-wall-mounted-towel-rack-with-fol/state-default.glb b/misc/DimSim/scenes/apartment/objects/polished-chrome-wall-mounted-towel-rack-with-fol/state-default.glb new file mode 100644 index 0000000000..85b1763dfb --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/polished-chrome-wall-mounted-towel-rack-with-fol/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:eecd13ed1d667181967fef1e0c5d91acfc0915d76bc7e0404b1bf2b30e849439 +size 514304 diff --git a/misc/DimSim/scenes/apartment/objects/professional-gas-range/state-default.glb b/misc/DimSim/scenes/apartment/objects/professional-gas-range/state-default.glb new file mode 100644 index 0000000000..c15cb087a0 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/professional-gas-range/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:d8109e458f1d0a27e9d393ae4977a64b6feba9cac916a610310232ec1e18b2c9 +size 121688 diff --git a/misc/DimSim/scenes/apartment/objects/professional-gas-range/state-mlssjm1p-xotl.glb b/misc/DimSim/scenes/apartment/objects/professional-gas-range/state-mlssjm1p-xotl.glb new file mode 100644 index 0000000000..67522886d2 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/professional-gas-range/state-mlssjm1p-xotl.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:dfebe1e8414475946e88dc2beeb162259b0a546582a9788fb897e7161ef13094 +size 130176 diff --git a/misc/DimSim/scenes/apartment/objects/professional-gas-range/state-mlsskac7-ywao.glb b/misc/DimSim/scenes/apartment/objects/professional-gas-range/state-mlsskac7-ywao.glb new file mode 100644 index 0000000000..77e45f5b9e --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/professional-gas-range/state-mlsskac7-ywao.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:03040168b854d3a5daaa057f3d0ff616a0258b133365594ab77dcfdfb82d2cd3 +size 121688 diff --git a/misc/DimSim/scenes/apartment/objects/professional-gas-range/state-mlssl1do-1yyl.glb b/misc/DimSim/scenes/apartment/objects/professional-gas-range/state-mlssl1do-1yyl.glb new file mode 100644 index 0000000000..4de8b27e9a --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/professional-gas-range/state-mlssl1do-1yyl.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:15cfb6492ed1b20d6d3db50c83c17cca3a8cacf91eaf10220b9bd890100f589c +size 121736 diff --git a/misc/DimSim/scenes/apartment/objects/queen-size-bed/state-default.glb b/misc/DimSim/scenes/apartment/objects/queen-size-bed/state-default.glb new file mode 100644 index 0000000000..a6d7c7e1dc --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/queen-size-bed/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:b4d911f624cded8e69086cedfbeedff25e92eaf8532bee7e69acc05e50973b5d +size 9431752 diff --git a/misc/DimSim/scenes/apartment/objects/refrigerator/state-default.glb b/misc/DimSim/scenes/apartment/objects/refrigerator/state-default.glb new file mode 100644 index 0000000000..295ca7d29a --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/refrigerator/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:e48c5600a1aa5cf3ac9878135051cf9f14ae4cb73d48281964c2a30c40f8fa5d +size 49068 diff --git a/misc/DimSim/scenes/apartment/objects/refrigerator/state-mlsqs928-jonu.glb b/misc/DimSim/scenes/apartment/objects/refrigerator/state-mlsqs928-jonu.glb new file mode 100644 index 0000000000..1762ee4b5f --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/refrigerator/state-mlsqs928-jonu.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:2a7aba2a1d9b35334833240e84c88960bbb81e4f99dd9b114c2ca7dacce82101 +size 70212 diff --git a/misc/DimSim/scenes/apartment/objects/salt-and-pepper-shakers/state-default.glb b/misc/DimSim/scenes/apartment/objects/salt-and-pepper-shakers/state-default.glb new file mode 100644 index 0000000000..8538d93604 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/salt-and-pepper-shakers/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:80d34c58c3291423efd924ac68e106fcb1f1065243f3ac1f3e670b01a6855a69 +size 612636 diff --git a/misc/DimSim/scenes/apartment/objects/set-of-three-canvas-prints-featuring-detailed-bo/state-default.glb b/misc/DimSim/scenes/apartment/objects/set-of-three-canvas-prints-featuring-detailed-bo/state-default.glb new file mode 100644 index 0000000000..f2cad36004 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/set-of-three-canvas-prints-featuring-detailed-bo/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:89f68d3fb22840bac269f57bee966a1b1d0e846befa4f2cc6a1ed966e1606d51 +size 818456 diff --git a/misc/DimSim/scenes/apartment/objects/sink/state-default.glb b/misc/DimSim/scenes/apartment/objects/sink/state-default.glb new file mode 100644 index 0000000000..544388128b --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/sink/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:2d8f9552fc6c3f80aa7552b0e04d44541dedef1ce2ef60ccc5579bafd8fdb156 +size 83804 diff --git a/misc/DimSim/scenes/apartment/objects/sleek-countertop-microwave-oven-with-digital-dis/state-default.glb b/misc/DimSim/scenes/apartment/objects/sleek-countertop-microwave-oven-with-digital-dis/state-default.glb new file mode 100644 index 0000000000..a9dc6cc425 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/sleek-countertop-microwave-oven-with-digital-dis/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:9cc288a2c972526327ec8e7b0bc6562415ecc848b925d86c69b9cc13200dcbbb +size 420836 diff --git a/misc/DimSim/scenes/apartment/objects/small-potted-plant/state-default.glb b/misc/DimSim/scenes/apartment/objects/small-potted-plant/state-default.glb new file mode 100644 index 0000000000..48087debc4 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/small-potted-plant/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:24fd6882ffcaae0f165c01fd64d95ee3937c0e93fd819af98aefaf0f8a0c5268 +size 303104 diff --git a/misc/DimSim/scenes/apartment/objects/soft-fuzzy-stuffed-teddy-bear-with-button-eyes-a/state-default.glb b/misc/DimSim/scenes/apartment/objects/soft-fuzzy-stuffed-teddy-bear-with-button-eyes-a/state-default.glb new file mode 100644 index 0000000000..57f9601a50 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/soft-fuzzy-stuffed-teddy-bear-with-button-eyes-a/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:000e1d838c92196895931bcee3f01bf6543abdb90e31c6339c069765fb0d48bb +size 522336 diff --git a/misc/DimSim/scenes/apartment/objects/stainless-steel-cutlery-set/state-default.glb b/misc/DimSim/scenes/apartment/objects/stainless-steel-cutlery-set/state-default.glb new file mode 100644 index 0000000000..04f263073c --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/stainless-steel-cutlery-set/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:1bd120f6e539d9b8abafb49944da66eedf09bb48acefc9d0d3101030fcbd5407 +size 877620 diff --git a/misc/DimSim/scenes/apartment/objects/television/state-mlr4bgf0-u7gv.glb b/misc/DimSim/scenes/apartment/objects/television/state-mlr4bgf0-u7gv.glb new file mode 100644 index 0000000000..e9279f3b0b --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/television/state-mlr4bgf0-u7gv.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:613f4a3ad1cf067e613b8117e4ce1388ab1e5f7ecb829cd29195010a07479fb1 +size 12224 diff --git a/misc/DimSim/scenes/apartment/objects/television/state-mlr4dvjl-fyw3.glb b/misc/DimSim/scenes/apartment/objects/television/state-mlr4dvjl-fyw3.glb new file mode 100644 index 0000000000..72fe4dc167 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/television/state-mlr4dvjl-fyw3.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:046becfcfc027861349c1ffc356cd3eaf83bf3726f05453f90b1b9b5d28ab871 +size 660476 diff --git a/misc/DimSim/scenes/apartment/objects/thick-quilted-duvet-neatly-folded-with-soft-fabr/state-default.glb b/misc/DimSim/scenes/apartment/objects/thick-quilted-duvet-neatly-folded-with-soft-fabr/state-default.glb new file mode 100644 index 0000000000..b1edf306f4 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/thick-quilted-duvet-neatly-folded-with-soft-fabr/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:b312be7201ac8833e1bd5d85679dd4cd420703293ce4d6895640a54b71ffe2cc +size 464536 diff --git a/misc/DimSim/scenes/apartment/objects/thin-glass-and-metal-smartphone-with-reflective/state-default.glb b/misc/DimSim/scenes/apartment/objects/thin-glass-and-metal-smartphone-with-reflective/state-default.glb new file mode 100644 index 0000000000..2bffca99a7 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/thin-glass-and-metal-smartphone-with-reflective/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:9bad5b56ef44fc955ff40c968a0a6f094557ae0ab2f8373696c44a63c22eb21a +size 466028 diff --git a/misc/DimSim/scenes/apartment/objects/two-slice-chrome-toaster-with-browning-control-d/state-default.glb b/misc/DimSim/scenes/apartment/objects/two-slice-chrome-toaster-with-browning-control-d/state-default.glb new file mode 100644 index 0000000000..ade7ec72c9 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/two-slice-chrome-toaster-with-browning-control-d/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:a56148c04372525971900d49f8d182193d2656427fda6da240f450e9e9ca9fed +size 141696 diff --git a/misc/DimSim/scenes/apartment/objects/vintage-poster/state-default.glb b/misc/DimSim/scenes/apartment/objects/vintage-poster/state-default.glb new file mode 100644 index 0000000000..b66d675704 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/vintage-poster/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:084c6f0c20440e05a5b8812faaac3b899bdb6cb8ee1b7820f49d850f02cd6f09 +size 151300 diff --git a/misc/DimSim/scenes/apartment/objects/wall-clock/state-default.glb b/misc/DimSim/scenes/apartment/objects/wall-clock/state-default.glb new file mode 100644 index 0000000000..09e0c05efc --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/wall-clock/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5477e7fae01230e75880560cf89c197859739403b7740f9d4eb5c810beee49ff +size 59196 diff --git a/misc/DimSim/scenes/apartment/objects/wall-mirror/state-default.glb b/misc/DimSim/scenes/apartment/objects/wall-mirror/state-default.glb new file mode 100644 index 0000000000..37763e3567 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/wall-mirror/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:903c82b9c38f1855eda06867f4002e0db9aacfc715a0d27ab8f22baf2b8ee4ba +size 154116 diff --git a/misc/DimSim/scenes/apartment/objects/wall-mounted-medicine-cabinet-with-a-large-mirro/state-default.glb b/misc/DimSim/scenes/apartment/objects/wall-mounted-medicine-cabinet-with-a-large-mirro/state-default.glb new file mode 100644 index 0000000000..883bea2886 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/wall-mounted-medicine-cabinet-with-a-large-mirro/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:ca773d8aa40e2d11f105401140ec7c8a7a62e7efde70abeb85ff394d31f40734 +size 18044 diff --git a/misc/DimSim/scenes/apartment/objects/wall-mounted-stainless-steel-chimney-range-hood/state-default.glb b/misc/DimSim/scenes/apartment/objects/wall-mounted-stainless-steel-chimney-range-hood/state-default.glb new file mode 100644 index 0000000000..e144c4e813 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/wall-mounted-stainless-steel-chimney-range-hood/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:49f50c5fa351fc3eb37f75ccbc0def6503b87c6d9de193307d98afc8e8f8494c +size 155312 diff --git a/misc/DimSim/scenes/apartment/objects/wine-glass/state-default.glb b/misc/DimSim/scenes/apartment/objects/wine-glass/state-default.glb new file mode 100644 index 0000000000..2cd5e484e5 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/wine-glass/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:6fe7aa25d676188b282aebaf26bb83c80847681229023b8c3f86387f64bb5332 +size 26092 diff --git a/misc/DimSim/scenes/apartment/objects/wine-glass/state-mlrogc5m-n4t3.glb b/misc/DimSim/scenes/apartment/objects/wine-glass/state-mlrogc5m-n4t3.glb new file mode 100644 index 0000000000..b8209dd163 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/wine-glass/state-mlrogc5m-n4t3.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:762815672b79d4db9364d5d0c65e47f2062606131cf50a8e944231f99bc6c40f +size 34824 diff --git a/misc/DimSim/scenes/apartment/objects/wooden-bookcase/state-default.glb b/misc/DimSim/scenes/apartment/objects/wooden-bookcase/state-default.glb new file mode 100644 index 0000000000..89ab7cf09d --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/wooden-bookcase/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:23d924aefb491eb99f8e307b3c019dbd014a3c2afe8e20bbf1c3801a92598bee +size 7149216 diff --git a/misc/DimSim/scenes/apartment/objects/wooden-coffee-table-with-glass-top/state-default.glb b/misc/DimSim/scenes/apartment/objects/wooden-coffee-table-with-glass-top/state-default.glb new file mode 100644 index 0000000000..0fc7514dfb --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/wooden-coffee-table-with-glass-top/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:e94ca898907df260f15dfa16e06a74b171de86d4d2b35562305714f95a2a023c +size 8081160 diff --git a/misc/DimSim/scenes/apartment/objects/work-chair/state-mlrqdudw-h1ax.glb b/misc/DimSim/scenes/apartment/objects/work-chair/state-mlrqdudw-h1ax.glb new file mode 100644 index 0000000000..5db9b1dbaa --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/work-chair/state-mlrqdudw-h1ax.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c412550dbdca13a9156bb80c7ad84aa38053518c50c69f4d91a1c387b3883a81 +size 1462112 diff --git a/misc/DimSim/scenes/apartment/objects/woven-rattan-placemat/state-default.glb b/misc/DimSim/scenes/apartment/objects/woven-rattan-placemat/state-default.glb new file mode 100644 index 0000000000..aedfef0f45 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/woven-rattan-placemat/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5d06b94922c52ff1bcc4de4c62c9a48558e4a26af147ad7e59157cac1d7d2b25 +size 285780 diff --git a/misc/DimSim/scenes/apartment/objects/woven-wicker-laundry-hamper-with-a-fabric-liner/state-default.glb b/misc/DimSim/scenes/apartment/objects/woven-wicker-laundry-hamper-with-a-fabric-liner/state-default.glb new file mode 100644 index 0000000000..f22b66f7a7 --- /dev/null +++ b/misc/DimSim/scenes/apartment/objects/woven-wicker-laundry-hamper-with-a-fabric-liner/state-default.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:652a0d297f197925de9cd3861e94185c03ae2f317033b5da01b59a85cc3c6c93 +size 563716 diff --git a/misc/DimSim/scenes/apartment/structure.glb b/misc/DimSim/scenes/apartment/structure.glb new file mode 100644 index 0000000000..8394981f5b --- /dev/null +++ b/misc/DimSim/scenes/apartment/structure.glb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5d1d4ae848c8d6378e1f6a03aba55dfeeb47a6b42010be065ed93c76a6ba3736 +size 5800704 diff --git a/misc/DimSim/scenes/deno.json b/misc/DimSim/scenes/deno.json new file mode 100644 index 0000000000..8f291d84e2 --- /dev/null +++ b/misc/DimSim/scenes/deno.json @@ -0,0 +1,6 @@ +{ + "imports": { + "@dimsim/eval": "../evals/deno-client.ts", + "@std/path": "jsr:@std/path@^1" + } +} diff --git a/misc/DimSim/scenes/deno.lock b/misc/DimSim/scenes/deno.lock new file mode 100644 index 0000000000..29ad14327a --- /dev/null +++ b/misc/DimSim/scenes/deno.lock @@ -0,0 +1,23 @@ +{ + "version": "5", + "specifiers": { + "jsr:@std/internal@^1.0.12": "1.0.12", + "jsr:@std/path@1": "1.1.4" + }, + "jsr": { + "@std/internal@1.0.12": { + "integrity": "972a634fd5bc34b242024402972cd5143eac68d8dffaca5eaa4dba30ce17b027" + }, + "@std/path@1.1.4": { + "integrity": "1d2d43f39efb1b42f0b1882a25486647cb851481862dc7313390b2bb044314b5", + "dependencies": [ + "jsr:@std/internal" + ] + } + }, + "workspace": { + "dependencies": [ + "jsr:@std/path@1" + ] + } +} diff --git a/misc/DimSim/scenes/empty/index.js b/misc/DimSim/scenes/empty/index.js new file mode 100644 index 0000000000..6f1d83f8f2 --- /dev/null +++ b/misc/DimSim/scenes/empty/index.js @@ -0,0 +1,19 @@ +// scenes/empty/index.js — empty starter scene. +// Sky + ambient lighting, no geometry, no embodiment. Use this as a canvas +// to author from scratch via the SceneClient SDK or by editing this file. + +export default async function build({ scene, THREE }) { + scene.add(new THREE.AmbientLight(0xffffff, 0.6)); + + const sun = new THREE.DirectionalLight(0xfff5e6, 1.5); + sun.position.set(10, 20, 10); + sun.castShadow = true; + scene.add(sun); + + scene.add(new THREE.HemisphereLight(0x87ceeb, 0x4a7a4a, 0.4)); + + return { + embodiment: null, + spawnPoint: { x: 0, y: 0.5, z: 0 }, + }; +} diff --git a/misc/DimSim/scenes/warehouse/index.js b/misc/DimSim/scenes/warehouse/index.js new file mode 100644 index 0000000000..2083ab0d92 --- /dev/null +++ b/misc/DimSim/scenes/warehouse/index.js @@ -0,0 +1,210 @@ +// scenes/warehouse/index.js — pure JS dev cycle. +// +// Everything is built directly from Three.js primitives (no JSON, no +// loadLevel). Edit the constants at the top, save, and the engine +// re-imports this file on hot-reload. +// +// NOTE: meshes added with `scene.add` are NOT registered in the engine's +// interaction registry (assets[]), so E-key pickup / state toggles won't +// see them. That gap is the "registerAsset API" item on the roadmap. +// For warehouse-style scenes (move around, look at stuff) this is fine. + +const FLOOR = { width: 30, depth: 40 }; +const WALL_H = 6; +const SKY = { + topColor: '#3a4654', + horizonColor:'#b8c0c8', + bottomColor: '#586470', + brightness: 0.7, + softness: 0.9, + sunStrength: 0.25, + sunHeight: 0.6, +}; + +export default async function build({ scene, THREE, physics, setSky, setEmbodiment, loadGLTF }) { + setSky(SKY); + + setEmbodiment({ + embodimentType: 'ground', + radius: 0.3, + halfHeight: 0.85, + lidarMountHeight: 1.6, + gravity: -9.81, + maxSpeed: 1.4, + turnRate: 2.5, + }); + + // ── Floor ──────────────────────────────────────────────────────────────── + const floor = new THREE.Mesh( + new THREE.BoxGeometry(FLOOR.width, 0.2, FLOOR.depth), + new THREE.MeshPhysicalMaterial({ color: 0x6b6f74, roughness: 0.95, metalness: 0.05 }), + ); + floor.position.y = -0.1; + floor.receiveShadow = true; + scene.add(floor); + physics.staticCollider(floor, 'box'); + + // ── Walls (north, south, east, west) ──────────────────────────────────── + const wallMat = new THREE.MeshPhysicalMaterial({ color: 0xc4c1b8, roughness: 0.8 }); + const wallSpecs = [ + // [w, h, d, x, y, z] + [FLOOR.width, WALL_H, 0.3, 0, WALL_H / 2, FLOOR.depth / 2], + [FLOOR.width, WALL_H, 0.3, 0, WALL_H / 2, -FLOOR.depth / 2], + [0.3, WALL_H, FLOOR.depth, FLOOR.width / 2, WALL_H / 2, 0], + [0.3, WALL_H, FLOOR.depth, -FLOOR.width / 2, WALL_H / 2, 0], + ]; + for (const [w, h, d, x, y, z] of wallSpecs) { + const wall = new THREE.Mesh(new THREE.BoxGeometry(w, h, d), wallMat); + wall.position.set(x, y, z); + wall.castShadow = wall.receiveShadow = true; + scene.add(wall); + physics.staticCollider(wall, 'box'); + } + + // ── Pallet racks: 3 rows of vertical posts + shelves ───────────────────── + // A rack = two side posts, 3 horizontal beams, optional crates on shelves. + const rackMat = new THREE.MeshPhysicalMaterial({ color: 0xd4823a, roughness: 0.5, metalness: 0.4 }); + const crateMat = new THREE.MeshPhysicalMaterial({ color: 0x8b5a2b, roughness: 0.75 }); + const palletMat = new THREE.MeshPhysicalMaterial({ color: 0x6b4423, roughness: 0.9 }); + + const rackBays = 4; + const bayWidth = 2.4; + const rackDepth = 1.2; + const rackHeight = 5.0; + const shelfYs = [1.5, 3.0, 4.5]; + + function addRack(originX, originZ) { + // Vertical posts at each bay edge + const postGeo = new THREE.BoxGeometry(0.1, rackHeight, 0.1); + for (let i = 0; i <= rackBays; i++) { + for (const dz of [-rackDepth / 2, rackDepth / 2]) { + const post = new THREE.Mesh(postGeo, rackMat); + post.position.set(originX + i * bayWidth, rackHeight / 2, originZ + dz); + post.castShadow = true; + scene.add(post); + physics.staticCollider(post, 'box'); + } + } + // Horizontal beams per shelf level + const beamGeo = new THREE.BoxGeometry(rackBays * bayWidth, 0.08, 0.08); + for (const y of shelfYs) { + for (const dz of [-rackDepth / 2, rackDepth / 2]) { + const beam = new THREE.Mesh(beamGeo, rackMat); + beam.position.set(originX + (rackBays * bayWidth) / 2, y, originZ + dz); + beam.castShadow = true; + scene.add(beam); + physics.staticCollider(beam, 'box'); + } + } + // Shelf decks + const deckGeo = new THREE.BoxGeometry(rackBays * bayWidth, 0.04, rackDepth); + for (const y of shelfYs) { + const deck = new THREE.Mesh(deckGeo, palletMat); + deck.position.set(originX + (rackBays * bayWidth) / 2, y - 0.05, originZ); + deck.castShadow = deck.receiveShadow = true; + scene.add(deck); + physics.staticCollider(deck, 'box'); + } + // Crates on a few of the shelves (skip some bays for variety) + const occupied = [ + [0, 0], [0, 1], [0, 3], + [1, 0], [1, 2], + [2, 1], [2, 2], [2, 3], + ]; + const crateGeo = new THREE.BoxGeometry(bayWidth * 0.85, 0.7, rackDepth * 0.85); + for (const [shelfIdx, bayIdx] of occupied) { + const crate = new THREE.Mesh(crateGeo, crateMat); + crate.position.set( + originX + bayIdx * bayWidth + bayWidth / 2, + shelfYs[shelfIdx] + 0.35, + originZ, + ); + crate.castShadow = crate.receiveShadow = true; + scene.add(crate); + physics.staticCollider(crate, 'box'); + } + } + + addRack(-FLOOR.width / 2 + 3, -10); + addRack(-FLOOR.width / 2 + 3, 0); + addRack(-FLOOR.width / 2 + 3, 10); + + // ── Loose pallet stacks near the dock ──────────────────────────────────── + for (let i = 0; i < 4; i++) { + const stackX = 8 + (i % 2) * 1.6; + const stackZ = -14 + Math.floor(i / 2) * 1.6; + for (let h = 0; h < 3; h++) { + const c = new THREE.Mesh( + new THREE.BoxGeometry(1.2, 0.4, 1.2), + crateMat, + ); + c.position.set(stackX, 0.2 + h * 0.42, stackZ); + c.castShadow = c.receiveShadow = true; + scene.add(c); + physics.staticCollider(c, 'box'); + } + } + + // ── Loading-dock door (visual only — flat panel on east wall) ─────────── + const dockDoor = new THREE.Mesh( + new THREE.BoxGeometry(0.05, 3.6, 3.6), + new THREE.MeshPhysicalMaterial({ color: 0x3a3f47, roughness: 0.4, metalness: 0.6 }), + ); + dockDoor.position.set(FLOOR.width / 2 - 0.1, 1.8, 12); + scene.add(dockDoor); + + const ball = new THREE.Mesh( + new THREE.SphereGeometry(0.4, 32, 32), + new THREE.MeshPhysicalMaterial({ color: 0x2196f3, roughness: 0.35, metalness: 0.1 }), + ); + ball.position.set(0, 3.0, -10); + ball.castShadow = ball.receiveShadow = true; + scene.add(ball); + physics.dynamicCollider(ball, { shape: 'sphere', mass: 1.0, restitution: 0.6 }); + + // ── Cross-scene GLB import test: pull the sectional out of apartment ───── + // The dedup'd GLB references textures via `../_textures/.png` which + // resolves relative to the GLB's URL — so loading it from any other scene + // still resolves correctly into /scenes/apartment/objects/_textures/. + const sectional = await loadGLTF('../apartment/objects/modern-l-shaped-sectional/state-default.glb'); + sectional.scene.traverse((o) => { + if (o.isMesh) { o.castShadow = true; o.receiveShadow = true; } + }); + sectional.scene.position.set(0, 0.5, -8); + scene.add(sectional.scene); + physics.staticCollider(sectional.scene, 'trimesh'); + + // ── Lights ─────────────────────────────────────────────────────────────── + scene.add(new THREE.HemisphereLight(0xc8d4e0, 0x303030, 0.45)); + + const sun = new THREE.DirectionalLight(0xffffff, 0.9); + sun.position.set(15, 25, 10); + sun.castShadow = true; + sun.shadow.mapSize.set(2048, 2048); + sun.shadow.camera.left = -20; + sun.shadow.camera.right = 20; + sun.shadow.camera.top = 25; + sun.shadow.camera.bottom = -25; + scene.add(sun); + + // Pendant lights down the centerline + for (let i = 0; i < 4; i++) { + const z = -15 + i * 10; + const housing = new THREE.Mesh( + new THREE.CylinderGeometry(0.3, 0.45, 0.25, 16), + new THREE.MeshPhysicalMaterial({ color: 0x202428, roughness: 0.5 }), + ); + housing.position.set(0, WALL_H - 0.5, z); + scene.add(housing); + + const bulb = new THREE.PointLight(0xfff2cf, 12, 14, 1.4); + bulb.position.set(0, WALL_H - 0.8, z); + bulb.castShadow = false; + scene.add(bulb); + } + + return { + embodiment: null, + spawnPoint: { x: 0, y: 1.0, z: -15 }, + }; +} diff --git a/misc/DimSim/src/AiAvatar.js b/misc/DimSim/src/AiAvatar.js new file mode 100644 index 0000000000..de90a0c3c5 --- /dev/null +++ b/misc/DimSim/src/AiAvatar.js @@ -0,0 +1,243 @@ +import * as THREE from "three"; +import { GLTFLoader } from "three/examples/jsm/loaders/GLTFLoader.js"; + +/** + * AiAvatar — visual + physics container for a single agent. + * + * In dimos mode the agent's pose is driven externally over LCM (cmd_vel in → + * server physics → /odom out, then engine.js calls `setPosition`). This + * class therefore only owns: + * - the THREE.Group visual (fallback capsule + facing cone + optional GLB) + * - the Rapier rigid body + capsule colliders + * - GLB load with auto-scale and box-collider resize + * - setPosition / getPosition for external drive + * - per-frame `update` that ticks the animation mixer and syncs the visual + * + * The autonomous wander / VLM behavior that lived here previously is gone — + * dimos drives the agent, and engine.js even overrides `update` on the dimos + * agent to skip everything except the visual sync. + */ +export class AiAvatar { + constructor({ + id = null, + scene, + rapierWorld, + RAPIER, + avatarUrl = "/avatars/kai.glb", + headless = false, + }) { + this.id = id || `ai-${Math.random().toString(36).slice(2, 8)}`; + this.scene = scene; + this.rapierWorld = rapierWorld; + this.RAPIER = RAPIER; + this.avatarUrl = avatarUrl; + this.headless = headless; + + // Match the smaller player capsule so the agent fits the same gaps. + this.radius = 0.12; + this.halfHeight = 0.25; + + // Look pitch — engine.js reads this when capturing the agent's POV. + this.pitch = 0; + + this.group = new THREE.Group(); + this.group.name = `AiAvatar:${this.id}`; + this.scene.add(this.group); + + // Fallback capsule visual. Replaced by the GLB once loaded. + this.fallback = new THREE.Mesh( + new THREE.CapsuleGeometry(this.radius * 0.9, this.halfHeight * 2.0, 6, 10), + new THREE.MeshStandardMaterial({ color: 0x8cffc1, roughness: 0.65 }), + ); + this.fallback.castShadow = false; + this.fallback.receiveShadow = false; + this.group.add(this.fallback); + + // Direction indicator (visible until GLB hides it in _applyGLB). + this._facing = new THREE.Mesh( + new THREE.ConeGeometry(this.radius * 0.45, this.radius * 1.35, 14), + new THREE.MeshStandardMaterial({ color: 0xffc36a, roughness: 0.45, metalness: 0.05 }), + ); + this._facing.rotation.x = Math.PI / 2; + this._facing.position.set(0, this.halfHeight * 0.15, this.radius * 1.1); + this._facing.renderOrder = 10; + this.group.add(this._facing); + + // Rapier body + capsule collider (kinematic — pose is set, not simulated). + this.body = this.rapierWorld.createRigidBody( + this.RAPIER.RigidBodyDesc.kinematicPositionBased().setTranslation(0, 3, 0), + ); + this.collider = this.rapierWorld.createCollider( + this.RAPIER.ColliderDesc.capsule(this.halfHeight, this.radius).setFriction(0.8), + this.body, + ); + + // Horizontal "spine" capsule trailing behind the vertical capsule so the + // physics body roughly matches a quadruped silhouette. Used by lidar and + // collision; movement controller still uses the vertical capsule. + this._spineHalfLen = Math.max(this.radius * 1.2, 0.13); + this._spineRadius = Math.max(this.radius * 0.62, 0.07); + this._spineOffsetBack = Math.max( + this.radius * 2.2, + this._spineHalfLen + this._spineRadius + 0.02, + ); + this._spineOffsetY = Math.max(this.halfHeight * 0.35, 0.08); + this.spineCollider = this.rapierWorld.createCollider( + this.RAPIER.ColliderDesc.capsule(this._spineHalfLen, this._spineRadius) + .setFriction(0.8) + .setTranslation(0, this._spineOffsetY, -this._spineOffsetBack) + // Rotate the capsule's local +Y axis to +Z (along the spine). + .setRotation({ x: Math.SQRT1_2, y: 0, z: 0, w: Math.SQRT1_2 }), + this.body, + ); + this.boxCollider = null; // Replaced when GLB loads (matches model bbox). + + // Best-effort: load the requested GLB. Falls through avatarUrl array if a + // load fails, ultimately leaving the capsule fallback in place. + this._loadGLB(); + } + + dispose() { + try { this.scene.remove(this.group); } catch { /* already gone */ } + try { + if (this.boxCollider) this.rapierWorld.removeCollider(this.boxCollider, true); + if (this.spineCollider) this.rapierWorld.removeCollider(this.spineCollider, true); + this.rapierWorld.removeCollider(this.collider, true); + this.rapierWorld.removeRigidBody(this.body); + } catch { /* world torn down already */ } + } + + setPosition(x, y, z) { + this.body.setTranslation({ x, y, z }, true); + this.body.setLinvel({ x: 0, y: 0, z: 0 }, true); + } + + getPosition() { + const p = this.body.translation(); + return [p.x, p.y, p.z]; + } + + update(dt) { + if (this.mixer) this.mixer.update(dt); + this._syncVisual(); + } + + _syncVisual() { + if (!this.body) return; + const p = this.body.translation(); + this.group.position.set(p.x, p.y, p.z); + this._syncSpineCollider(); + } + + _syncSpineCollider() { + if (!this.spineCollider || !this.body) return; + const p = this.body.translation(); + const yaw = this.group.rotation.y ?? 0; + const xOff = -Math.sin(yaw) * this._spineOffsetBack; + const zOff = -Math.cos(yaw) * this._spineOffsetBack; + const q = new THREE.Quaternion().setFromEuler( + new THREE.Euler(Math.PI / 2, yaw, 0, "YXZ"), + ); + try { + if (typeof this.spineCollider.setTranslationWrtParent === "function") { + this.spineCollider.setTranslationWrtParent({ x: xOff, y: this._spineOffsetY, z: zOff }); + } else { + this.spineCollider.setTranslation({ + x: p.x + xOff, y: p.y + this._spineOffsetY, z: p.z + zOff, + }); + } + if (typeof this.spineCollider.setRotationWrtParent === "function") { + this.spineCollider.setRotationWrtParent({ x: q.x, y: q.y, z: q.z, w: q.w }); + } else { + this.spineCollider.setRotation({ x: q.x, y: q.y, z: q.z, w: q.w }); + } + } catch { /* collider torn down */ } + } + + _loadGLB() { + if (!this.avatarUrl) return; + const loader = new GLTFLoader(); + const urls = Array.isArray(this.avatarUrl) ? this.avatarUrl : [this.avatarUrl]; + const tryLoad = (index) => { + if (index >= urls.length) { + console.log(`[AiAvatar] No avatar model found, using capsule fallback.`); + return; + } + loader.load( + urls[index], + (gltf) => { this._applyGLB(gltf); }, + undefined, + () => { tryLoad(index + 1); }, + ); + }; + tryLoad(0); + } + + _applyGLB(gltf) { + try { this.group.remove(this.fallback); } catch { /* already gone */ } + try { this._facing.visible = false; } catch { /* gone */ } + + this.model = gltf.scene; + + // Auto-fit: scale the model to roughly the capsule height, then offset down + // so its feet are on the floor (group origin sits at body center). + const bbox = new THREE.Box3().setFromObject(this.model); + const size = bbox.getSize(new THREE.Vector3()); + const targetHeight = this.halfHeight * 2 + this.radius * 2; + const scaleFactor = targetHeight / (size.y || 1); + // Y-squash so the unrigged GLB reads as a low-slung quadruped instead of an + // upright biped. Camera POV (GO2_CAMERA_HEIGHT in engine.js) is the real + // signal; this is purely visual. + this.model.scale.set(scaleFactor, scaleFactor * 0.6, scaleFactor); + + bbox.setFromObject(this.model); + const newCenter = bbox.getCenter(new THREE.Vector3()); + const newMin = bbox.min; + this.model.position.x -= newCenter.x; + this.model.position.z -= newCenter.z; + this.model.position.y = -newMin.y - (this.halfHeight + this.radius); + + // Replace the placeholder box collider with one that matches the GLB bbox. + bbox.setFromObject(this.model); + const finalSize = bbox.getSize(new THREE.Vector3()); + const finalCenter = bbox.getCenter(new THREE.Vector3()); + if (this.boxCollider) { + this.rapierWorld.removeCollider(this.boxCollider, true); + this.boxCollider = null; + } + this.boxCollider = this.rapierWorld.createCollider( + this.RAPIER.ColliderDesc + .cuboid(finalSize.x / 2, finalSize.y / 2, finalSize.z / 2) + .setFriction(0.8) + .setTranslation(finalCenter.x, finalCenter.y, finalCenter.z), + this.body, + ); + + // Headless: keep the collider, drop the visual — saves GPU memory. Used + // by dimos when no embodiment is requested (the agent moves invisibly). + if (this.headless) { + this.model = null; + return; + } + + this.model.traverse((m) => { + if (m.isMesh) { + m.castShadow = false; + m.receiveShadow = true; + } + }); + this.group.add(this.model); + + if (gltf.animations?.length) { + this.mixer = new THREE.AnimationMixer(this.model); + this._actions = {}; + for (const clip of gltf.animations) { + this._actions[clip.name] = this.mixer.clipAction(clip); + } + const idle = + this._actions["idle"] || this._actions["Idle"] || this._actions["Idle_A"]; + if (idle) idle.play(); + else this.mixer.clipAction(gltf.animations[0]).play(); + } + } +} diff --git a/misc/DimSim/src/bridge.ts b/misc/DimSim/src/bridge.ts new file mode 100644 index 0000000000..8c83f33a94 --- /dev/null +++ b/misc/DimSim/src/bridge.ts @@ -0,0 +1,577 @@ +/** + * DimosBridge — Browser-side WebSocket client for dimos integration. + * + * Uses separate WebSocket connections so large sensor streams do not block + * each other or real-time odom/cmd_vel: + * wsControl → /odom, /cmd_vel (tiny packets, real-time) + * wsSensors → /lidar + snapshots + * wsRgb → /color_image + * wsDepth → /depth_image + * + * All messages are LCM-encoded binary packets using @dimos/msgs, sent over + * WebSocket to the bridge server which relays them to/from dimos via LCM/UDP. + */ + +// @ts-ignore — CDN import (runs in browser, no Deno/Node type resolution) +import { + encodePacket, + decodePacket, + geometry_msgs, + sensor_msgs, + std_msgs, +} from "https://esm.sh/jsr/@dimos/msgs@0.1.4"; + +// -- Channels ---------------------------------------------------------------- +const CH_CMD_VEL = "/cmd_vel#geometry_msgs.Twist"; +const CH_ODOM = "/odom#geometry_msgs.PoseStamped"; +const CH_IMAGE = "/color_image#sensor_msgs.Image"; +const CH_DEPTH = "/depth_image#sensor_msgs.Image"; +const CH_LIDAR = "/lidar#sensor_msgs.PointCloud2"; + +// -- Default publish rates (ms) ---------------------------------------------- +const DEFAULT_RATES: PublishRates = { odom: 20, lidar: 200, images: 200 }; // 50 Hz odom, 5 Hz lidar, 5 Hz images +const CMD_VEL_TIMEOUT_MS = 500; +const BRIDGE_DEBUG = false; +const LIDAR_POINT_STEP = 16; + +// -- Types -------------------------------------------------------------------- + +export interface PublishRates { odom: number; lidar: number; images: number; } +export interface SensorEnable { depth: boolean; } + +export interface RgbFrame { + data: Uint8Array; + width: number; + height: number; +} + +export interface DepthFrame { + data: Float32Array; + width: number; + height: number; +} + +export interface LidarFrame { + numPoints: number; + points: Float32Array; // N*3 interleaved XYZ + intensity?: Float32Array; // N +} + +export interface OdomPose { + x: number; y: number; z: number; + qx: number; qy: number; qz: number; qw: number; +} + +export interface SensorSources { + captureRgb: () => RgbFrame | null; + captureDepth: () => DepthFrame | null; + captureLidar: () => LidarFrame | null; + getOdomPose: () => OdomPose | null; +} + +export type FrameTransform = "identity" | "ros"; + +export interface DimosBridgeOptions { + wsUrl?: string; + agent: any; + sensorSources: SensorSources; + rates?: Partial; + sensorEnable?: Partial; + frameTransform?: FrameTransform; +} + +export class DimosBridge { + wsUrl: string; + agent: any; + sensors: SensorSources; + rates: PublishRates; + sensorEnable: SensorEnable; + frameTransform: FrameTransform; + + // Separate sockets so depth backlog does not starve RGB. + wsControl: WebSocket | null; // odom + cmd_vel (tiny, real-time) + wsSensors: WebSocket | null; // lidar + snapshots + wsRgb: WebSocket | null; // color image + wsDepth: WebSocket | null; // depth image + + // Keep legacy .ws alias pointing to control for compatibility + get ws(): WebSocket | null { return this.wsControl; } + + _timers: Record>; + _dirty: { odom: boolean; lidar: boolean; images: boolean }; + _rafId: number | null; + _connected: boolean; + + _cmdVel: { linX: number; linY: number; linZ: number; angX: number; angY: number; angZ: number } | null; + _cmdVelStamp: number; + _serverLidar: boolean; + _lidarBuf: ArrayBuffer; + _lidarView: DataView; + _lidarCapacityPoints: number; + _pc2Fields: any[]; + + constructor({ wsUrl, agent, sensorSources, rates, sensorEnable, frameTransform }: DimosBridgeOptions) { + const protocol = location.protocol === "https:" ? "wss:" : "ws:"; + this.wsUrl = wsUrl || `${protocol}//${location.host}`; + this.agent = agent; + this.sensors = sensorSources; + this.rates = { ...DEFAULT_RATES, ...rates }; + this.sensorEnable = { depth: true, ...sensorEnable }; + this.frameTransform = frameTransform || "ros"; + this.wsControl = null; + this.wsSensors = null; + this.wsRgb = null; + this.wsDepth = null; + this._timers = {}; + this._dirty = { odom: false, lidar: false, images: false }; + this._rafId = null; + this._connected = false; + this._cmdVel = null; + this._cmdVelStamp = 0; + this._serverLidar = false; + this._lidarBuf = new ArrayBuffer(0); + this._lidarView = new DataView(this._lidarBuf); + this._lidarCapacityPoints = 0; + this._pc2Fields = [ + new sensor_msgs.PointField({ name: "x", offset: 0, datatype: 7, count: 1 }), + new sensor_msgs.PointField({ name: "y", offset: 4, datatype: 7, count: 1 }), + new sensor_msgs.PointField({ name: "z", offset: 8, datatype: 7, count: 1 }), + new sensor_msgs.PointField({ name: "intensity", offset: 12, datatype: 7, count: 1 }), + ]; + } + + connect(): void { + // Read channel from URL param (for multi-page parallel evals) + const channel = new URLSearchParams(location.search).get("channel") || ""; + const channelSuffix = channel ? `&channel=${channel}` : ""; + + // Control socket: odom out, cmd_vel in + this.wsControl = new WebSocket(this.wsUrl + "?ch=control" + channelSuffix); + this.wsControl.binaryType = "arraybuffer"; + + this.wsControl.onopen = () => { + console.log("[DimosBridge] control WS connected"); + this._connected = true; + this._startPublishing(); + this._flushPendingCommands(); + }; + + this.wsControl.onmessage = (event: MessageEvent) => { + // Text messages: server-side physics pose updates + embodiment config + if (typeof event.data === "string") { + try { + const msg = JSON.parse(event.data); + if (msg.type === "pose") { + this._handleServerPose(msg.x, msg.y, msg.z, msg.yaw); + } else if (msg.type === "embodimentConfig") { + this._handleEmbodimentConfig(msg); + } + } catch {} + return; + } + // Binary messages: LCM packets (cmd_vel relay) + if (!(event.data instanceof ArrayBuffer)) return; + try { + const raw = new Uint8Array(event.data); + const { channel, data } = decodePacket(raw); + this._handlePacket(channel, data); + } catch {} + }; + + this.wsControl.onclose = () => { + console.log("[DimosBridge] control WS disconnected, reconnecting in 2s..."); + this._connected = false; + this._stopPublishing(); + setTimeout(() => this.connect(), 2000); + }; + + this.wsControl.onerror = () => {}; + + // Sensor socket: lidar + snapshots out (no incoming expected) + this.wsSensors = new WebSocket(this.wsUrl + "?ch=sensors" + channelSuffix); + this.wsSensors.binaryType = "arraybuffer"; + + this.wsSensors.onopen = () => { + console.log("[DimosBridge] sensor WS connected"); + }; + + this.wsSensors.onclose = () => { + console.log("[DimosBridge] sensor WS disconnected"); + }; + + this.wsSensors.onerror = () => {}; + + this.wsRgb = new WebSocket(this.wsUrl + "?ch=rgb" + channelSuffix); + this.wsRgb.binaryType = "arraybuffer"; + this.wsRgb.onclose = () => { + console.log("[DimosBridge] RGB WS disconnected"); + }; + this.wsRgb.onerror = () => {}; + + this.wsDepth = new WebSocket(this.wsUrl + "?ch=depth" + channelSuffix); + this.wsDepth.binaryType = "arraybuffer"; + this.wsDepth.onclose = () => { + console.log("[DimosBridge] depth WS disconnected"); + }; + this.wsDepth.onerror = () => {}; + } + + // -- Incoming packets ------------------------------------------------------- + + _handlePacket(channel: string, data: any): void { + if (channel === CH_CMD_VEL) { + this._handleCmdVel(data); + } + } + + _handleCmdVel(twist: any): void { + const lin = twist.linear; + const ang = twist.angular; + + let linX: number, linY: number, linZ: number; + let angX: number, angY: number, angZ: number; + + if (this.frameTransform === "ros") { + // ROS → Three.js: inverse of the cyclic permutation (x→y, y→z, z→x) + linX = lin.y; + linY = lin.z; + linZ = lin.x; + angX = ang.y; + angY = ang.z; + angZ = ang.x; + } else { + linX = lin.x; linY = lin.y; linZ = lin.z; + angX = ang.x; angY = ang.y; angZ = ang.z; + } + + this._cmdVel = { linX, linY, linZ, angX, angY, angZ }; + this._cmdVelStamp = Date.now(); + } + + /** Get current velocity, auto-zeroing after CMD_VEL_TIMEOUT_MS (safety stop). */ + getCmdVel(): { linX: number; linY: number; linZ: number; angX: number; angY: number; angZ: number } { + if (!this._cmdVel || Date.now() - this._cmdVelStamp > CMD_VEL_TIMEOUT_MS) { + return { linX: 0, linY: 0, linZ: 0, angX: 0, angY: 0, angZ: 0 }; + } + return this._cmdVel; + } + + /** Handle server-side physics pose update (Three.js Y-up frame). */ + _handleServerPose(x: number, y: number, z: number, yaw: number): void { + if (!this.agent) return; + // Move the agent body to the server-authoritative position + if (this.agent.body) { + this.agent.body.setNextKinematicTranslation({ x, y, z }); + } + if (this.agent.group) { + this.agent.group.rotation.y = yaw; + } + // Update engine's _dimosYaw for sensor capture / odom pose reading + if ((window as any).__dimosSetYaw) { + (window as any).__dimosSetYaw(yaw); + } + // Store for odom/sensor capture + this._serverPose = { x, y, z, yaw }; + } + + _serverPose: { x: number; y: number; z: number; yaw: number } | null = null; + + _handleEmbodimentConfig(msg: any): void { + console.log("[DimosBridge] embodiment config received:", msg.embodimentType || "quadruped"); + // Apply config to engine globals (dimensions, speed, type) + if ((window as any).applyEmbodiment) { + (window as any).applyEmbodiment(msg); + } + // Swap the agent's avatar model if avatarUrl changed + if (this.agent && msg.avatarUrl) { + const urls = Array.isArray(msg.avatarUrl) ? msg.avatarUrl : [msg.avatarUrl]; + this.agent.avatarUrl = urls; + // Update dimensions on the agent so _applyGLB auto-fits correctly + if (msg.radius != null) this.agent.radius = msg.radius; + if (msg.halfHeight != null) this.agent.halfHeight = msg.halfHeight; + // Remove current model and reload + if (this.agent.model) { + this.agent.group.remove(this.agent.model); + this.agent.model = null; + } + this.agent._loadGLB(); + // Scenes that return `embodiment: null` ship with the agent's group + // hidden (engine.js sets `group.visible = false`). Dimos sending an + // embodimentConfig is the signal that an external agent is now + // driving — re-enable visibility so the model actually renders. + if (this.agent.group) this.agent.group.visible = true; + } + } + + // -- Outgoing sensor data --------------------------------------------------- + + sceneReady = false; + + _startPublishing(): void { + // No lidar timer — server-side lidar handles it via LCM directly. + // Images default 5 Hz (configurable via rates.images) + if (this.rates.images > 0) { + this._timers["images"] = setInterval(() => this._publishImages(), this.rates.images); + } + } + + _makeHeader(frameId: string): any { + const now = Date.now(); + return new std_msgs.Header({ + stamp: new std_msgs.Time({ sec: Math.floor(now / 1000), nsec: (now % 1000) * 1_000_000 }), + frame_id: frameId, + }); + } + + _publishOdom(): void { + if (!this._isControlSocketOpen()) return; + this._publishOdomSync(this._makeHeader("world")); + } + + _publishLidar(): void { + if (!this._isSocketOpen(this.wsSensors)) return; + this._publishLidarSync(this._makeHeader("world")); + } + + _publishImages(): void { + if (!this._isSocketOpen(this.wsRgb) && !this._isSocketOpen(this.wsDepth)) return; + const camHeader = this._makeHeader("camera_optical"); + if (this._isSocketOpen(this.wsRgb)) this._publishRgbSync(camHeader); + if (this.sensorEnable.depth && this._isSocketOpen(this.wsDepth)) this._publishDepthSync(camHeader); + } + + // -- Odom ------------------------------------------------------------------- + + _odomDbgN = 0; + + _publishOdomSync(header: any): void { + try { + const pose = this.sensors.getOdomPose(); + if (!pose) return; + + this._odomDbgN++; + + // Three.js (Y-up) → ROS (Z-up) cyclic permutation: x→y, y→z, z→x + const rosQx = pose.qz; + const rosQy = pose.qx; + const rosQz = pose.qy; + const rosQw = pose.qw; + + const q = new geometry_msgs.Quaternion(); + q.x = rosQx; q.y = rosQy; q.z = rosQz; q.w = rosQw; + const pt = new geometry_msgs.Point(); + pt.x = pose.z; pt.y = pose.x; pt.z = pose.y; + const p = new geometry_msgs.Pose(); + p.position = pt; + p.orientation = q; + + header.seq = this._odomDbgN; + const odomMsg = new geometry_msgs.PoseStamped(); + odomMsg.header = header; + odomMsg.pose = p; + + if (BRIDGE_DEBUG && (this._odomDbgN <= 3 || this._odomDbgN % 100 === 0)) { + console.log(`[odom TX seq=${this._odomDbgN}] qz=${rosQz.toFixed(4)} qw=${rosQw.toFixed(4)}`); + } + + // Send on CONTROL socket (not sensor socket) + this._sendControl(CH_ODOM, odomMsg); + } catch (e) { + console.warn("[DimosBridge] odom publish error:", e); + } + } + + _stopPublishing(): void { + for (const k of Object.keys(this._timers)) clearInterval(this._timers[k]); + this._timers = {}; + if (this._rafId) cancelAnimationFrame(this._rafId); + this._rafId = null; + } + + /** Send on the control WebSocket (odom, small real-time data) */ + _sendControl(channel: string, msg: any): void { + const ws = this.wsControl; + if (!ws || ws.readyState !== WebSocket.OPEN) return; + ws.send(encodePacket(channel, msg)); + } + + /** Send on a sensor WebSocket (images, lidar — large data). */ + _sendSensor(ws: WebSocket | null, channel: string, msg: any): void { + if (!ws || ws.readyState !== WebSocket.OPEN) return; + ws.send(encodePacket(channel, msg)); + } + + /** Legacy _send — routes to appropriate socket based on channel */ + _send(channel: string, msg: any): void { + if (channel === CH_ODOM) { + this._sendControl(channel, msg); + } else if (channel === CH_IMAGE) { + this._sendSensor(this.wsRgb, channel, msg); + } else if (channel === CH_DEPTH) { + this._sendSensor(this.wsDepth, channel, msg); + } else { + this._sendSensor(this.wsSensors, channel, msg); + } + } + + // -- RGB -------------------------------------------------------------------- + + _publishRgbSync(header: any): void { + try { + if (!this._isSocketOpen(this.wsRgb)) return; + const frame = this.sensors.captureRgb(); + if (!frame) return; + + this._sendSensor(this.wsRgb, CH_IMAGE, new sensor_msgs.Image({ + header, + height: frame.height, + width: frame.width, + encoding: "jpeg", + is_bigendian: 0, + step: 0, // not applicable for compressed format + data_length: frame.data.length, + data: frame.data, + })); + } catch (e) { + console.warn("[DimosBridge] RGB publish error:", e); + } + } + + // -- Depth ------------------------------------------------------------------ + + _depthU16: Uint16Array | null = null; + + _publishDepthSync(header: any): void { + try { + if (!this._isSocketOpen(this.wsDepth)) return; + const frame = this.sensors.captureDepth(); + if (!frame) return; + + // Quantize float32 meters → uint16 millimeters (0–65.535m range, 1mm precision) + const n = frame.data.length; + if (!this._depthU16 || this._depthU16.length !== n) { + this._depthU16 = new Uint16Array(n); + } + const f32 = frame.data; + const u16 = this._depthU16; + for (let i = 0; i < n; i++) { + const mm = f32[i] * 1000; + u16[i] = mm > 65535 ? 65535 : mm < 0 ? 0 : mm; + } + const depthBytes = new Uint8Array(u16.buffer, u16.byteOffset, u16.byteLength); + + this._sendSensor(this.wsDepth, CH_DEPTH, new sensor_msgs.Image({ + header, + height: frame.height, + width: frame.width, + encoding: "16UC1", + is_bigendian: 0, + step: frame.width * 2, + data_length: depthBytes.length, + data: depthBytes, + })); + } catch (e) { + console.warn("[DimosBridge] depth publish error:", e); + } + } + + // -- LiDAR ------------------------------------------------------------------ + + _lidarDbgN = 0; + _publishLidarSync(header: any): void { + try { + if (!this._isSocketOpen(this.wsSensors)) return; + const frame = this.sensors.captureLidar(); + this._lidarDbgN++; + if (BRIDGE_DEBUG && (this._lidarDbgN <= 3 || this._lidarDbgN % 100 === 0)) { + console.log(`[DimosBridge] lidar #${this._lidarDbgN}: ${frame ? frame.numPoints : 'null'} pts, sensorWS=${this.wsSensors?.readyState}`); + } + if (!frame) return; + + const numPoints = frame.numPoints || 0; + if (numPoints === 0) return; + + this._ensureLidarCapacity(numPoints); + const pointStep = LIDAR_POINT_STEP; + const view = this._lidarView; + const pts = frame.points; + const intensity = frame.intensity; + + // Points are Three.js world-frame (Y-up). + // Convert to ROS world-frame (Z-up): cyclic permutation x→y, y→z, z→x + for (let i = 0; i < numPoints; i++) { + const off = i * pointStep; + const tx = pts[i * 3 + 0], ty = pts[i * 3 + 1], tz = pts[i * 3 + 2]; + view.setFloat32(off, tz, true); // ROS x = Three.js z + view.setFloat32(off + 4, tx, true); // ROS y = Three.js x + view.setFloat32(off + 8, ty, true); // ROS z = Three.js y + view.setFloat32(off + 12, intensity ? intensity[i] : 1.0, true); + } + + this._sendSensor(this.wsSensors, CH_LIDAR, new sensor_msgs.PointCloud2({ + header, + height: 1, + width: numPoints, + fields_length: this._pc2Fields.length, + fields: this._pc2Fields, + is_bigendian: 0, + point_step: pointStep, + row_step: numPoints * pointStep, + data_length: numPoints * pointStep, + data: new Uint8Array(this._lidarBuf, 0, numPoints * pointStep), + is_dense: 1, + })); + } catch (e) { + console.warn("[DimosBridge] LiDAR publish error:", e); + } + } + + _pendingCommands: Record[] = []; + + /** Send a JSON command on the control WebSocket. Queues if the socket + * isn't OPEN yet — _flushPendingCommands() drains on onopen. */ + sendCommand(cmd: Record): void { + const ws = this.wsControl; + if (ws && ws.readyState === WebSocket.OPEN) { + ws.send(JSON.stringify(cmd)); + } else { + this._pendingCommands.push(cmd); + } + } + + _flushPendingCommands(): void { + const ws = this.wsControl; + if (!ws || ws.readyState !== WebSocket.OPEN) return; + const pending = this._pendingCommands; + this._pendingCommands = []; + if (pending.length) console.log(`[DimosBridge] flushing ${pending.length} queued command(s)`); + for (const cmd of pending) ws.send(JSON.stringify(cmd)); + } + + dispose(): void { + this._stopPublishing(); + if (this.wsControl) { this.wsControl.onclose = null; this.wsControl.close(); } + if (this.wsSensors) { this.wsSensors.onclose = null; this.wsSensors.close(); } + if (this.wsRgb) { this.wsRgb.onclose = null; this.wsRgb.close(); } + if (this.wsDepth) { this.wsDepth.onclose = null; this.wsDepth.close(); } + this.wsControl = null; + this.wsSensors = null; + this.wsRgb = null; + this.wsDepth = null; + } + + _isControlSocketOpen(): boolean { + return !!this.wsControl && this.wsControl.readyState === WebSocket.OPEN; + } + + _isSocketOpen(ws: WebSocket | null): boolean { + return !!ws && ws.readyState === WebSocket.OPEN; + } + + _ensureLidarCapacity(numPoints: number): void { + if (numPoints <= this._lidarCapacityPoints) return; + this._lidarCapacityPoints = numPoints; + this._lidarBuf = new ArrayBuffer(numPoints * LIDAR_POINT_STEP); + this._lidarView = new DataView(this._lidarBuf); + } +} diff --git a/misc/DimSim/src/engine.js b/misc/DimSim/src/engine.js new file mode 100644 index 0000000000..97508bdbd7 --- /dev/null +++ b/misc/DimSim/src/engine.js @@ -0,0 +1,7684 @@ +import "./style.css"; + +import * as THREE from "three"; +import { PointerLockControls } from "three/examples/jsm/controls/PointerLockControls.js"; +import { AiAvatar } from "./AiAvatar.js"; +import { GLTFLoader } from "three/examples/jsm/loaders/GLTFLoader.js"; +import { RoomEnvironment } from "three/examples/jsm/environments/RoomEnvironment.js"; +import { RoundedBoxGeometry } from "three/examples/jsm/geometries/RoundedBoxGeometry.js"; + +let threeRendererRef = null; +let threeSceneRef = null; +let RAPIER = null; +let _rapierInitPromise = null; +let rapierWorld = null; +let worldBody = null; +let playerBody = null; +let playerCollider = null; +let flyMode = true; +let ghostMode = true; +let characterController = null; +let _rapierStepFaultCount = 0; +let walkVerticalVel = 0; +let aiAgents = []; + +// Track asset collider handles for cleanup +const _assetColliderHandles = new Map(); + +// Player dimensions (tuned smaller so you can fit inside tighter splat/glb interiors). +const PLAYER_RADIUS = 0.12; +const PLAYER_HALF_HEIGHT = 0.25; +const PLAYER_EYE_HEIGHT = PLAYER_HALF_HEIGHT + PLAYER_RADIUS + 0.2; // camera above body origin +const LIDAR_MOUNT_HEIGHT = 0.35; // Go2 lidar mount height above ground +// Real Go2 front camera height above ground in its home/operating crouch pose. +// Used for agent-POV captures so the rendered view matches what the hardware +// camera would see (low, not eye-level). ~0.30 m matches the MuJoCo go2.xml +// home keyframe (thigh 0.9, calf -1.8) which the Go2 actually stands in. +const GO2_CAMERA_HEIGHT = 0.30; +// Go2 front RGB-D camera is mounted on the front of the head, forward of the +// body center. Offsetting places the camera origin outside the robot mesh so +// POV captures don't render the inside of the body. +const GO2_CAMERA_FORWARD = 0.18; + +const canvas = document.getElementById("c"); +const statusEl = document.getElementById("status"); +const resetBtn = document.getElementById("reset"); +const assetsListEl = document.getElementById("assets-list"); // null in sim-only +const overlayEl = document.getElementById("overlay"); +const simPanelCollapseBtn = document.getElementById("sim-panel-collapse"); +const simPanelOpenBtn = document.getElementById("sim-panel-open"); +const statusSimEl = document.getElementById("status-sim"); +const spawnAiBtn = document.getElementById("spawn-ai"); +const agentPanelEl = document.getElementById("agent-panel"); +const agentLastEl = document.getElementById("agent-last"); +const agentObservationEl = document.getElementById("agent-observation"); +const agentShotImgEl = document.getElementById("agent-shot-img"); +const agentReqMetaEl = document.getElementById("agent-req-meta"); +const agentReqPromptEl = document.getElementById("agent-req-prompt"); +const agentReqContextEl = document.getElementById("agent-req-context"); +const agentRespRawEl = document.getElementById("agent-resp-raw"); +const agentLogEl = document.getElementById("agent-log"); +const agentTaskStatusEl = document.getElementById("agent-task-status"); +const agentTaskInputEl = document.getElementById("agent-task-input"); +const agentTaskStartBtn = document.getElementById("agent-task-start"); +const agentTaskEndBtn = document.getElementById("agent-task-end"); +const simCameraModeToggleBtn = document.getElementById("sim-camera-toggle"); +const simViewRgbdBtn = document.getElementById("sim-view-rgbd"); +const simViewLidarBtn = document.getElementById("sim-view-lidar"); +const simViewCompareBtn = document.getElementById("sim-view-compare"); +const simRgbdGrayBtn = document.getElementById("sim-rgbd-gray"); +const simRgbdColormapBtn = document.getElementById("sim-rgbd-colormap"); +const simRgbdAutoRangeBtn = document.getElementById("sim-rgbd-auto-range"); +const simRgbdNoiseBtn = document.getElementById("sim-rgbd-noise"); +const simRgbdSpeckleBtn = document.getElementById("sim-rgbd-speckle"); +const simRgbdMinEl = document.getElementById("sim-rgbd-min"); +const simRgbdMaxEl = document.getElementById("sim-rgbd-max"); +const simRgbdMinValEl = document.getElementById("sim-rgbd-min-val"); +const simRgbdMaxValEl = document.getElementById("sim-rgbd-max-val"); +const simRgbdPcOverlayBtn = document.getElementById("sim-rgbd-pc-overlay"); +const simLidarColorRangeBtn = document.getElementById("sim-lidar-color-range"); +const simLidarOrderedDebugBtn = document.getElementById("sim-lidar-ordered-debug"); +const simLidarNoiseBtn = document.getElementById("sim-lidar-noise"); +const simLidarMultiReturnBtn = document.getElementById("sim-lidar-multireturn"); + +// ── dimos integration mode ────────────────────────────────────────────────── +// Activated via ?dimos=1 URL param or window.__dimosMode (injected by Deno bridge server). +// When active: internal VLM loop disabled, agent pose driven by external /odom, +// sensor data (RGB, depth, LiDAR) published as LCM packets via WebSocket bridge. +const _dimosParams = new URLSearchParams(window.location.search); +const dimosMode = _dimosParams.get("dimos") === "1" || window.__dimosMode === true; +if (dimosMode) document.body.classList.add("dimos-mode"); +const dimosScene = _dimosParams.get("scene") || window.__dimosScene || null; +let simSensorViewMode = "rgb"; // "rgb" | "rgbd" | "lidar" +let simCompareView = false; // show RGB + RGB-D + LiDAR side-by-side +let simPanelCollapsed = false; +let simUserCameraMode = localStorage.getItem("sparkWorldSimCameraMode") === "agent" ? "agent" : "user"; +let rgbdVizMode = "colormap"; // "colormap" | "gray" +let rgbdAutoRange = true; +let rgbdRangeMinM = 0.2; +let rgbdRangeMaxM = 12.0; +let rgbdNoiseEnabled = false; +let rgbdSpeckleEnabled = false; +let rgbdPcOverlayOnLidar = false; +let lidarColorByRange = false; // false = intensity grayscale (realistic default) +let lidarOrderedDebugView = false; // false=unordered 3D cloud, true=ordered rings debug +let lidarNoiseEnabled = false; // deterministic range noise + dropouts +let lidarMultiReturnMode = "strongest"; // "strongest" | "last" +let worldKey = localStorage.getItem("sparkWorldLastWorldKey") ?? "default"; + +function clampNum(v, min, max) { + const n = Number(v); + if (!Number.isFinite(n)) return min; + return Math.min(max, Math.max(min, n)); +} + +function normalizeHexColor(value, fallback) { + try { + return `#${new THREE.Color(value).getHexString()}`; + } catch { + return fallback; + } +} + +function createDefaultSceneSettings() { + return { + sky: { + enabled: false, + topColor: "#7aa9ff", + horizonColor: "#cfe5ff", + bottomColor: "#f4f8ff", + brightness: 1.0, + softness: 1.35, + sunStrength: 0.18, + sunHeight: 0.45, + }, + }; +} + +function normalizeSceneSettings(raw) { + const defaults = createDefaultSceneSettings(); + const src = raw && typeof raw === "object" ? raw : {}; + const srcSky = src.sky && typeof src.sky === "object" ? src.sky : {}; + return { + sky: { + enabled: !!srcSky.enabled, + topColor: normalizeHexColor(srcSky.topColor, defaults.sky.topColor), + horizonColor: normalizeHexColor(srcSky.horizonColor, defaults.sky.horizonColor), + bottomColor: normalizeHexColor(srcSky.bottomColor, defaults.sky.bottomColor), + brightness: clampNum(srcSky.brightness, 0.2, 2.0), + softness: clampNum(srcSky.softness, 0.2, 3.0), + sunStrength: clampNum(srcSky.sunStrength, 0.0, 1.0), + sunHeight: clampNum(srcSky.sunHeight, -0.2, 1.0), + }, + }; +} + +function serializeSceneSettings() { + return normalizeSceneSettings(sceneSettings); +} + +let sceneSettings = createDefaultSceneSettings(); +let tags = []; +let selectedTagId = null; +let draftTag = null; // tag being edited/created +const tagsGroup = new THREE.Group(); +tagsGroup.name = "tagsGroup"; + +// Assets (Edit mode) +let assets = []; // [{id,title,notes,states:[{id,name,glbName,dataBase64,interactions:[{id,label,to}]}],currentStateId,actions:[{id,label,from,to}],transform:{...}, _colliderHandle?}] +let selectedAssetId = null; +const assetsGroup = new THREE.Group(); +assetsGroup.name = "assetsGroup"; +const gltfLoader = new GLTFLoader(); + +// ============================================================================= +// BLOB SHADOW – lightweight planar shadow for GLB assets (no shadow maps needed) +// ============================================================================= +// Procedural radial-gradient texture (created once, shared by all blob shadows) +let _blobShadowTexture = null; +let _blobShadowGeometry = null; + +function getBlobShadowTexture() { + if (_blobShadowTexture) return _blobShadowTexture; + const size = 128; + const canvas = document.createElement("canvas"); + canvas.width = size; + canvas.height = size; + // Use a GRAYSCALE gradient: white = opaque shadow, black = transparent. + // This texture will be used as an alphaMap (only the luminance/R channel matters). + const ctx = canvas.getContext("2d"); + const gradient = ctx.createRadialGradient(size / 2, size / 2, 0, size / 2, size / 2, size / 2); + gradient.addColorStop(0, "#ffffff"); // center: fully opaque + gradient.addColorStop(0.35, "#cccccc"); + gradient.addColorStop(0.65, "#444444"); + gradient.addColorStop(1, "#000000"); // edge: fully transparent + ctx.fillStyle = gradient; + ctx.fillRect(0, 0, size, size); + _blobShadowTexture = new THREE.CanvasTexture(canvas); + _blobShadowTexture.needsUpdate = true; + return _blobShadowTexture; +} + +function getBlobShadowGeometry() { + if (_blobShadowGeometry) return _blobShadowGeometry; + _blobShadowGeometry = new THREE.PlaneGeometry(1, 1); + // Rotate so the plane lies flat on the XZ ground plane (face up) + _blobShadowGeometry.rotateX(-Math.PI / 2); + return _blobShadowGeometry; +} + +// Create a blob shadow mesh sized to an asset's footprint. +// Returns a Mesh that should be added as a child of the asset root. +// `opts` = { opacity, scale, stretch, rotationDeg, offsetX, offsetY, offsetZ } +function createBlobShadow(assetId, footprintX, footprintZ, localGroundY, opts) { + const o = opts || {}; + const userScale = o.scale ?? 1.0; + const userOpacity = o.opacity ?? 0.5; + const stretch = o.stretch ?? 1.0; // >1 elongates X, <1 elongates Z + const rotDeg = o.rotationDeg ?? 0; // rotation around Y in degrees + const offsetX = o.offsetX ?? 0; + const offsetY = o.offsetY ?? 0; + const offsetZ = o.offsetZ ?? 0; + + // Base diameter from asset footprint, then apply user scale + const baseDiameter = Math.max(footprintX, footprintZ) * 1.1; + const d = baseDiameter * userScale; + if (d < 0.04) return null; + + const mat = new THREE.MeshBasicMaterial({ + color: 0x000000, + alphaMap: getBlobShadowTexture(), + transparent: true, + depthWrite: false, + depthTest: true, + opacity: userOpacity, + side: THREE.DoubleSide, + // Use ONLY constant depth bias. Slope-based factor causes the blob to + // appear to slide as the camera angle changes while moving. + polygonOffset: true, + polygonOffsetFactor: 0, + polygonOffsetUnits: -300, + }); + const mesh = new THREE.Mesh(getBlobShadowGeometry(), mat); + // stretch > 1 makes the X axis wider; Z axis is inversely narrower to + // keep the overall area roughly constant. + const sx = d * stretch; + const sz = d / stretch; + mesh.scale.set(sx, 1, sz); + // Raise slightly so it stays on/just above floor. + mesh.position.set(offsetX, localGroundY + 0.08 + offsetY, offsetZ); + // The shared geometry is already rotated to lie on XZ. An additional Y + // rotation spins the ellipse around the vertical axis. + mesh.rotation.y = (rotDeg * Math.PI) / 180; + mesh.renderOrder = 1000; + mesh.castShadow = false; + mesh.receiveShadow = false; + mesh.name = `blobShadow:${assetId}`; + mesh.userData.isBlobShadow = true; + mesh.userData._baseDiameter = baseDiameter; + mesh.userData._baseLocalY = localGroundY + 0.08; + return mesh; +} + +// ============================================================================= +// PRIMITIVES (Level Editor) – lightweight parametric shapes +// ============================================================================= +let primitives = []; // [{id, type, name, dimensions:{...}, transform:{position,rotation,scale}, material:{color,roughness,metalness,textureDataUrl}, physics:bool, _colliderHandle?}] +let selectedPrimitiveId = null; +const _assetBumpVelocities = new Map(); // assetId -> THREE.Vector3 +const _playerPosPrevForBump = new THREE.Vector3(); +let _playerPosPrevForBumpValid = false; +const _agentPosPrevForBump = new Map(); // agentId -> THREE.Vector3 +let _lastBumpSaveAt = 0; +let _lastBumpColliderSyncAt = 0; +const primitivesGroup = new THREE.Group(); +primitivesGroup.name = "primitivesGroup"; + +const PRIMITIVE_DEFAULTS = { + box: { + width: 1, + height: 1, + depth: 1, + edgeRadius: 0, + edgeSegments: 4, + widthSegments: 1, + heightSegments: 1, + depthSegments: 1, + }, + sphere: { + radius: 0.5, + widthSegments: 32, + heightSegments: 16, + phiStartDeg: 0, + phiLengthDeg: 360, + thetaStartDeg: 0, + thetaLengthDeg: 180, + }, + cylinder: { radiusTop: 0.5, radiusBottom: 0.5, height: 1, radialSegments: 32, heightSegments: 1, openEnded: 0 }, + cone: { radius: 0.5, height: 1, radialSegments: 32, heightSegments: 1, openEnded: 0 }, + torus: { radius: 0.5, tube: 0.15, radialSegments: 16, tubularSegments: 48, arcDeg: 360 }, + plane: { width: 2, height: 2, widthSegments: 1, heightSegments: 1 }, +}; + +const PRIMITIVE_DIM_CONFIG = { + width: { min: 0.05, max: 50, step: 0.05 }, + height: { min: 0.05, max: 50, step: 0.05 }, + depth: { min: 0.05, max: 50, step: 0.05 }, + radius: { min: 0.01, max: 20, step: 0.01 }, + radiusTop: { min: 0.01, max: 20, step: 0.01 }, + radiusBottom: { min: 0.01, max: 20, step: 0.01 }, + tube: { min: 0.01, max: 10, step: 0.01 }, + edgeRadius: { min: 0, max: 2.5, step: 0.01 }, + edgeSegments: { min: 1, max: 12, step: 1, integer: true }, + widthSegments: { min: 1, max: 128, step: 1, integer: true }, + heightSegments: { min: 1, max: 128, step: 1, integer: true }, + depthSegments: { min: 1, max: 128, step: 1, integer: true }, + radialSegments: { min: 3, max: 128, step: 1, integer: true }, + tubularSegments: { min: 3, max: 256, step: 1, integer: true }, + phiStartDeg: { min: 0, max: 360, step: 1 }, + phiLengthDeg: { min: 1, max: 360, step: 1 }, + thetaStartDeg: { min: 0, max: 180, step: 1 }, + thetaLengthDeg: { min: 1, max: 180, step: 1 }, + arcDeg: { min: 1, max: 360, step: 1 }, + openEnded: { min: 0, max: 1, step: 1, integer: true }, +}; + +function formatPrimitiveDimValue(key, value) { + if (PRIMITIVE_DIM_CONFIG[key]?.integer) return String(Math.round(value)); + if (key.endsWith("Deg")) return `${Math.round(value)}°`; + if (key === "openEnded") return value >= 0.5 ? "Yes" : "No"; + return Number(value).toFixed(2); +} + +const PRIMITIVE_DIM_LABELS = { + edgeRadius: "Roundness", + edgeSegments: "Round Detail", + widthSegments: "Detail X", + heightSegments: "Detail Y", + depthSegments: "Detail Z", + radialSegments: "Circle Detail", + tubularSegments: "Ring Detail", + phiStartDeg: "Horizontal Cut Start", + phiLengthDeg: "Horizontal Fill", + thetaStartDeg: "Vertical Cut Start", + thetaLengthDeg: "Vertical Fill", + arcDeg: "Ring Opening", + openEnded: "Open Ends", + radiusTop: "Top Radius", + radiusBottom: "Bottom Radius", +}; + +function getPrimitiveDimLabel(key) { + return PRIMITIVE_DIM_LABELS[key] || key.replace(/([A-Z])/g, " $1").replace(/^./, (s) => s.toUpperCase()); +} + +// ============================================================================= +// EDITOR LIGHTS – user-placed lights with full control +// ============================================================================= +let editorLights = []; // [{id, type, name, color, intensity, position:{x,y,z}, target:{x,y,z}, distance, angle, penumbra, castShadow, _lightObj?, _helperObj?}] +let groups = []; // [{id, name, children:[primId,...], pickable?}] +const lightsGroup = new THREE.Group(); +lightsGroup.name = "lightsGroup"; +const _assetRaycaster = new THREE.Raycaster(); +const _agentAssetRaycaster = new THREE.Raycaster(); +const _tmpV1 = new THREE.Vector3(); +const _tmpV2 = new THREE.Vector3(); +const _tmpV3 = new THREE.Vector3(); + +// Agent camera follow mode (first-person POV) +let agentCameraFollow = false; +let _agentFollowInitialized = false; + +// Agent task state — per-agent tasks for parallel execution. +let agentTask = { + active: false, + instruction: "", + startedAt: 0, + finishedAt: 0, + finishedReason: "", + lastSummary: "", +}; +const _agentTasks = new Map(); // agentId -> { active, instruction, startedAt, finishedAt, finishedReason, lastSummary } + +function _getAgentTask(agentId) { + return _agentTasks.get(agentId) || agentTask; +} + +function _setAgentTask(agentId, task) { + _agentTasks.set(agentId, task); + // Keep global agentTask in sync with the most recent active task (for UI compat) + if (task.active) { + agentTask = { ...task }; + } +} +let selectedAgentInspectorId = null; +const agentInspectorStateById = new Map(); // id -> { shot, request, response } +let agentCameraFollowId = null; +let agentUiSelectedLabelEl = null; +let agentUiSpawnBtn = null; +let agentUiFollowBtn = null; +let agentUiStopBtn = null; +let agentUiRemoveBtn = null; +let agentUiTaskInputEl = null; +let agentUiTaskRunBtn = null; +let agentTaskTargetId = null; +let agentBadgeLayerEl = null; +const agentBadgeElsById = new Map(); +const MAX_AGENT_COUNT = 4; + +// ============================================================================= +// WORLD MANIFEST & LOADING +// ============================================================================= + +// Helper to normalize asset schema (backward compat) +// This function ensures all asset properties are properly loaded including states, interactions, and actions +function normalizeAssetSchema(raw) { + // Ensure states exist + if (!raw.states || raw.states.length === 0) { + raw.states = [{ + id: crypto.randomUUID(), + name: "default", + glbName: raw.glbName || "", + dataBase64: raw.dataBase64 || "", + interactions: [], + }]; + raw.currentStateId = raw.states[0].id; + } + + // Ensure each state has interactions array + for (const state of raw.states) { + if (!Array.isArray(state.interactions)) { + state.interactions = []; + } + } + + // Build the normalized asset object + const normalized = { + id: raw.id ?? crypto.randomUUID(), + title: raw.title ?? "", + notes: raw.notes ?? "", + states: raw.states, + currentStateId: raw.currentStateId ?? raw.states[0]?.id, + actions: [], // Will be populated below + transform: raw.transform ?? { position: { x: 0, y: 0, z: 0 }, rotation: { x: 0, y: 0, z: 0 }, scale: { x: 1, y: 1, z: 1 } }, + pickable: raw.pickable ?? false, // Can be picked up and moved + castShadow: raw.castShadow ?? false, + receiveShadow: raw.receiveShadow ?? false, + blobShadow: raw.blobShadow ?? null, // { opacity, scale, stretch, rotationDeg, offsetX, offsetY, offsetZ } + }; + + // Copy actions if they exist in raw data + if (Array.isArray(raw.actions) && raw.actions.length > 0) { + normalized.actions = raw.actions.map(act => ({ + id: act.id, + label: act.label || "toggle", + from: act.from, + to: act.to, + })); + } else { + // Backfill actions from state interactions if no actions array exists + for (const state of normalized.states) { + for (const interaction of state.interactions || []) { + if (interaction.to && interaction.to !== state.id) { + normalized.actions.push({ + id: interaction.id || `act_${state.id}_${interaction.to}`, + label: interaction.label || "toggle", + from: state.id, + to: interaction.to, + }); + } + } + } + } + + // Also backfill interactions from actions if any state is missing them + if (normalized.actions.length > 0) { + const actionsByFrom = new Map(); + for (const act of normalized.actions) { + if (!actionsByFrom.has(act.from)) actionsByFrom.set(act.from, []); + actionsByFrom.get(act.from).push({ id: act.id, label: act.label, to: act.to }); + } + for (const state of normalized.states) { + if (!state.interactions || state.interactions.length === 0) { + state.interactions = actionsByFrom.get(state.id) || []; + } + } + } + + return normalized; +} + +const renderer = new THREE.WebGLRenderer({ + canvas, + // SparkRenderer docs recommend antialias:false for splats (MSAA doesn't help splats and can hurt) + antialias: false, + powerPreference: "high-performance", + // Required for reading pixels from the canvas (agent POV capture) + preserveDrawingBuffer: true, +}); +renderer.setPixelRatio(Math.min(window.devicePixelRatio || 1, 2)); +renderer.setSize(window.innerWidth, window.innerHeight, false); +renderer.outputColorSpace = THREE.SRGBColorSpace; +renderer.toneMapping = THREE.ACESFilmicToneMapping; +renderer.toneMappingExposure = 1.1; + +// Shadows: OFF by default. Enabled dynamically only when a light actually casts shadows. +// BasicShadowMap is fully deterministic (no PCF/stochastic filtering). +renderer.shadowMap.enabled = false; +renderer.shadowMap.type = THREE.BasicShadowMap; +renderer.shadowMap.autoUpdate = false; // we control when shadow maps update + +const clock = new THREE.Clock(); +const scene = new THREE.Scene(); +scene.background = new THREE.Color(0x06070a); + +// Image-based lighting for PBR GLBs. This dramatically improves "too dark" assets. +try { + const pmrem = new THREE.PMREMGenerator(renderer); + scene.environment = pmrem.fromScene(new RoomEnvironment(), 0.04).texture; + pmrem.dispose(); +} catch { + // ignore +} + +// Make renderer/scene available to SparkRenderer initialization after dynamic import. +threeRendererRef = renderer; +threeSceneRef = scene; + +const camera = new THREE.PerspectiveCamera( + 65, + window.innerWidth / window.innerHeight, + 0.05, + 2000 +); +camera.position.set(0, 1.7, 4); + +// Lighting for non-splat geometry (assets/avatars). +// Splats are mostly self-lit visually; GLB assets need strong, stable fill to avoid looking black. +const ambientLight = new THREE.AmbientLight(0xffffff, 0.65); +scene.add(ambientLight); + +const hemi = new THREE.HemisphereLight(0xffffff, 0x223344, 0.85); +hemi.position.set(0, 10, 0); +scene.add(hemi); + +const dir = new THREE.DirectionalLight(0xffffff, 1.6); +dir.position.set(8, 14, 6); +dir.castShadow = false; // off by default; user enables via Scene Lighting panel +dir.shadow.mapSize.width = 512; +dir.shadow.mapSize.height = 512; +dir.shadow.camera.near = 0.5; +dir.shadow.camera.far = 40; +dir.shadow.camera.left = -15; +dir.shadow.camera.right = 15; +dir.shadow.camera.top = 15; +dir.shadow.camera.bottom = -15; +dir.shadow.bias = -0.003; +scene.add(dir); + +// Headlamp-style light attached to the camera so assets are visible wherever they are placed. +const headLamp = new THREE.PointLight(0xffffff, 1.4, 26, 1.5); +headLamp.position.set(0, 1.0, 0.6); +camera.add(headLamp); + +// Lightweight procedural sky dome (single draw call). This is intentionally +// simple so it remains cheap for scale/headless workloads. +const skyUniforms = { + uTop: { value: new THREE.Color("#7aa9ff") }, + uHorizon: { value: new THREE.Color("#cfe5ff") }, + uBottom: { value: new THREE.Color("#f4f8ff") }, + uBrightness: { value: 1.0 }, + uSoftness: { value: 1.35 }, + uSunStrength: { value: 0.18 }, + uSunDir: { value: new THREE.Vector3(0, 0.45, -1).normalize() }, +}; +const skyDome = new THREE.Mesh( + new THREE.SphereGeometry(220, 24, 16), + new THREE.ShaderMaterial({ + uniforms: skyUniforms, + side: THREE.BackSide, + depthWrite: false, + vertexShader: ` + varying vec3 vWorldDir; + void main() { + vec4 worldPos = modelMatrix * vec4(position, 1.0); + vWorldDir = normalize(worldPos.xyz - cameraPosition); + gl_Position = projectionMatrix * viewMatrix * worldPos; + } + `, + fragmentShader: ` + varying vec3 vWorldDir; + uniform vec3 uTop; + uniform vec3 uHorizon; + uniform vec3 uBottom; + uniform float uBrightness; + uniform float uSoftness; + uniform float uSunStrength; + uniform vec3 uSunDir; + void main() { + float h = clamp(vWorldDir.y * 0.5 + 0.5, 0.0, 1.0); + float shaped = pow(h, max(0.15, uSoftness)); + vec3 col = mix(uBottom, uHorizon, smoothstep(0.0, 0.55, shaped)); + col = mix(col, uTop, smoothstep(0.45, 1.0, shaped)); + float sun = pow(max(dot(normalize(vWorldDir), normalize(uSunDir)), 0.0), 220.0); + col += vec3(1.0, 0.92, 0.78) * sun * uSunStrength; + gl_FragColor = vec4(col * uBrightness, 1.0); + } + `, + }) +); +skyDome.frustumCulled = false; +skyDome.renderOrder = -1000; +skyDome.visible = false; +skyDome.userData.engineInternal = true; +scene.add(skyDome); + + +// Registry of built-in scene lights so the editor can expose them +const sceneLights = [ + { id: "_ambient", label: "Ambient", obj: ambientLight, type: "ambient" }, + { id: "_hemi", label: "Hemisphere", obj: hemi, type: "hemisphere" }, + { id: "_dir", label: "Directional", obj: dir, type: "directional" }, + { id: "_headlamp", label: "Head Lamp", obj: headLamp, type: "point" }, + { id: "_sky", label: "Sky", obj: skyDome, type: "sky" }, +]; +scene.add(camera); + +// Avatar: simple capsule that follows the first-person camera. +const avatar = new THREE.Mesh( + new THREE.CapsuleGeometry(PLAYER_RADIUS * 0.8, PLAYER_HALF_HEIGHT * 2.0, 6, 12), + new THREE.MeshStandardMaterial({ color: 0x7cc4ff, roughness: 0.5 }) +); +avatar.castShadow = false; +avatar.receiveShadow = false; +avatar.visible = false; // always hidden; physics capsule handles collision +avatar.userData.engineInternal = true; +tagsGroup.userData.engineInternal = true; +assetsGroup.userData.engineInternal = true; +primitivesGroup.userData.engineInternal = true; +lightsGroup.userData.engineInternal = true; +scene.add(avatar); +scene.add(tagsGroup); +scene.add(assetsGroup); +scene.add(primitivesGroup); +scene.add(lightsGroup); + + +// ----------------------------------------------------------------------------- +// Sim sensor view modes (deterministic + lightweight) +// ----------------------------------------------------------------------------- +const DEFAULT_SCENE_BG = new THREE.Color(0x06070a); +const RGBD_BG = new THREE.Color(0x000000); +function applySceneSkySettings() { + const s = normalizeSceneSettings(sceneSettings).sky; + sceneSettings.sky = s; + skyUniforms.uTop.value.set(s.topColor); + skyUniforms.uHorizon.value.set(s.horizonColor); + skyUniforms.uBottom.value.set(s.bottomColor); + skyUniforms.uBrightness.value = s.brightness; + skyUniforms.uSoftness.value = s.softness; + skyUniforms.uSunStrength.value = s.sunStrength; + skyUniforms.uSunDir.value.set(0, s.sunHeight, -1).normalize(); +} +function applySceneRgbBackground() { + if (sceneSettings.sky.enabled) { + skyDome.visible = true; + scene.background = null; + } else { + skyDome.visible = false; + scene.background = DEFAULT_SCENE_BG; + } +} +applySceneSkySettings(); +// RGB-D visualization range tuned for indoor robotics scenes (meters). +const RGBD_MIN_DEPTH_M = 0.2; +const RGBD_MAX_DEPTH_M = 12.0; +const RGBD_AUTO_PERCENTILE_LOW = 0.05; +const RGBD_AUTO_PERCENTILE_HIGH = 0.95; +const RGBD_AUTO_RANGE_UPDATE_MS = 250; +const RGBD_AUTO_RANGE_SMOOTH = 0.2; +const RGBD_CLEAR_ALPHA = 1.0; +rgbdRangeMinM = RGBD_MIN_DEPTH_M; +rgbdRangeMaxM = RGBD_MAX_DEPTH_M; +const _rgbdSize = new THREE.Vector2( + Math.max(1, Math.floor(window.innerWidth * renderer.getPixelRatio())), + Math.max(1, Math.floor(window.innerHeight * renderer.getPixelRatio())) +); +const rgbdDepthTarget = new THREE.WebGLRenderTarget(_rgbdSize.x, _rgbdSize.y, { + minFilter: THREE.NearestFilter, + magFilter: THREE.NearestFilter, + format: THREE.RGBAFormat, + type: THREE.UnsignedByteType, + depthBuffer: true, + stencilBuffer: false, +}); +rgbdDepthTarget.texture.generateMipmaps = false; +rgbdDepthTarget.depthTexture = new THREE.DepthTexture(_rgbdSize.x, _rgbdSize.y, THREE.UnsignedIntType); +rgbdDepthTarget.depthTexture.minFilter = THREE.NearestFilter; +rgbdDepthTarget.depthTexture.magFilter = THREE.NearestFilter; +rgbdDepthTarget.depthTexture.generateMipmaps = false; +const RGBD_PC_OVERLAY_RT_W = 192; +const RGBD_PC_OVERLAY_RT_H = 108; +const rgbdOverlayDepthTarget = new THREE.WebGLRenderTarget(RGBD_PC_OVERLAY_RT_W, RGBD_PC_OVERLAY_RT_H, { + minFilter: THREE.NearestFilter, + magFilter: THREE.NearestFilter, + format: THREE.RGBAFormat, + type: THREE.UnsignedByteType, + depthBuffer: true, + stencilBuffer: false, +}); +rgbdOverlayDepthTarget.texture.generateMipmaps = false; +rgbdOverlayDepthTarget.depthTexture = new THREE.DepthTexture(RGBD_PC_OVERLAY_RT_W, RGBD_PC_OVERLAY_RT_H, THREE.UnsignedIntType); +rgbdOverlayDepthTarget.depthTexture.minFilter = THREE.NearestFilter; +rgbdOverlayDepthTarget.depthTexture.magFilter = THREE.NearestFilter; +rgbdOverlayDepthTarget.depthTexture.generateMipmaps = false; + +// RGB-D debug material (planar forward-axis depth from view-space z). +// Kept only for debugging and no longer used as default RGB-D output. +const rgbdPlanarDepthDebugMaterial = new THREE.ShaderMaterial({ + uniforms: { + uMinDepth: { value: RGBD_MIN_DEPTH_M }, + uMaxDepth: { value: RGBD_MAX_DEPTH_M }, + }, + vertexShader: ` + varying float vLinearDepth; + void main() { + vec4 mv = modelViewMatrix * vec4(position, 1.0); + vLinearDepth = -mv.z; + gl_Position = projectionMatrix * mv; + } + `, + fragmentShader: ` + varying float vLinearDepth; + uniform float uMinDepth; + uniform float uMaxDepth; + void main() { + // Blend linear + inverse depth for strong near-range sensitivity while + // preserving metric ordering (deterministic, no auto-exposure). + float d = clamp(vLinearDepth, uMinDepth, uMaxDepth); + float lin = (d - uMinDepth) / max(0.0001, (uMaxDepth - uMinDepth)); // 0 near, 1 far + float inv = (1.0 / d - 1.0 / uMaxDepth) / max(0.0001, (1.0 / uMinDepth - 1.0 / uMaxDepth)); // 1 near, 0 far + float t = clamp(0.35 * (1.0 - lin) + 0.65 * inv, 0.0, 1.0); // near -> 1, far -> 0 + + // High-contrast pseudo-color ramp (near cyan/green, far orange/red) + vec3 nearC = vec3(0.05, 0.98, 0.98); + vec3 midC = vec3(0.40, 0.95, 0.10); + vec3 farC = vec3(0.98, 0.15, 0.05); + vec3 c = (t > 0.5) ? mix(midC, nearC, (t - 0.5) * 2.0) : mix(farC, midC, t * 2.0); + gl_FragColor = vec4(c, 1.0); + } + `, +}); +rgbdPlanarDepthDebugMaterial.toneMapped = false; + +// Fullscreen passes: +// 1) reconstruct metric camera-space Z into a float render target +// 2) visualize that metric depth for display +const rgbdPostCamera = new THREE.OrthographicCamera(-1, 1, 1, -1, 0, 1); +const rgbdMetricUsesR32F = renderer.capabilities.isWebGL2 && !!renderer.extensions.get("EXT_color_buffer_float"); +const rgbdMetricTargetType = rgbdMetricUsesR32F ? THREE.FloatType : THREE.HalfFloatType; +const rgbdMetricTarget = new THREE.WebGLRenderTarget(_rgbdSize.x, _rgbdSize.y, { + minFilter: THREE.NearestFilter, + magFilter: THREE.NearestFilter, + format: rgbdMetricUsesR32F ? THREE.RedFormat : THREE.RGBAFormat, + type: rgbdMetricTargetType, + depthBuffer: false, + stencilBuffer: false, +}); +if (rgbdMetricUsesR32F) rgbdMetricTarget.texture.internalFormat = "R32F"; +rgbdMetricTarget.texture.generateMipmaps = false; +const rgbdOverlayMetricTarget = new THREE.WebGLRenderTarget(RGBD_PC_OVERLAY_RT_W, RGBD_PC_OVERLAY_RT_H, { + minFilter: THREE.NearestFilter, + magFilter: THREE.NearestFilter, + format: rgbdMetricUsesR32F ? THREE.RedFormat : THREE.RGBAFormat, + type: rgbdMetricTargetType, + depthBuffer: false, + stencilBuffer: false, +}); +if (rgbdMetricUsesR32F) rgbdOverlayMetricTarget.texture.internalFormat = "R32F"; +rgbdOverlayMetricTarget.texture.generateMipmaps = false; + +const rgbdMetricScene = new THREE.Scene(); +const rgbdMetricMaterial = new THREE.ShaderMaterial({ + uniforms: { + uDepthTex: { value: rgbdDepthTarget.depthTexture }, + uNear: { value: camera.near }, + uFar: { value: camera.far }, + uMinDepth: { value: rgbdRangeMinM }, + uMaxDepth: { value: rgbdRangeMaxM }, + uNoiseEnabled: { value: 0.0 }, + uSpeckleEnabled: { value: 0.0 }, + }, + vertexShader: ` + varying vec2 vUv; + void main() { + vUv = uv; + gl_Position = vec4(position.xy, 0.0, 1.0); + } + `, + fragmentShader: ` + varying vec2 vUv; + uniform sampler2D uDepthTex; + uniform float uNear; + uniform float uFar; + uniform float uMinDepth; + uniform float uMaxDepth; + uniform float uNoiseEnabled; + uniform float uSpeckleEnabled; + + // Perspective depth [0,1] -> view-space z (negative in front of camera). + float perspectiveDepthToViewZ(const in float depth, const in float near, const in float far) { + return (near * far) / ((far - near) * depth - far); + } + + float hash12(vec2 p) { + vec3 p3 = fract(vec3(p.xyx) * 0.1031); + p3 += dot(p3, p3.yzx + 33.33); + return fract((p3.x + p3.y) * p3.z); + } + + void main() { + float depth01 = texture2D(uDepthTex, vUv).x; + // No geometry hit: treat as max range. + if (depth01 >= 0.999999) { + gl_FragColor = vec4(uMaxDepth, uMaxDepth, uMaxDepth, 1.0); + return; + } + + float viewZ = perspectiveDepthToViewZ(depth01, uNear, uFar); + float zMetric = -viewZ; // camera-space Z in meters (robotics back-projection convention) + float d = clamp(zMetric, uMinDepth, uMaxDepth); + + if (uNoiseEnabled > 0.5) { + float span = max(0.0001, uMaxDepth - uMinDepth); + float t = clamp((d - uMinDepth) / span, 0.0, 1.0); + // Quantization: ~1mm near, up to ~8mm far (indoors). + float q = mix(0.001, 0.008, t * t); + d = floor(d / q + 0.5) * q; + + // Dropouts: more likely on edges and farther range. + float edge = clamp(length(vec2(dFdx(depth01), dFdy(depth01))) * 250.0, 0.0, 1.0); + float pDrop = 0.01 + 0.08 * t * t + 0.18 * edge; + float u = hash12(vUv * vec2(4096.0, 4096.0)); + if (u < pDrop) { + gl_FragColor = vec4(uMaxDepth, uMaxDepth, uMaxDepth, 1.0); + return; + } + + // Optional speckle noise (small multiplicative perturbation). + if (uSpeckleEnabled > 0.5) { + float n = hash12(vUv * vec2(8192.0, 8192.0) + vec2(17.3, 9.1)) - 0.5; + float amp = 0.002 + 0.01 * t; // 2mm near -> 12mm far + d = clamp(d + n * amp, uMinDepth, uMaxDepth); + } + } + + gl_FragColor = vec4(d, d, d, 1.0); + } + `, + depthTest: false, + depthWrite: false, +}); +rgbdMetricMaterial.toneMapped = false; +const rgbdMetricQuad = new THREE.Mesh(new THREE.PlaneGeometry(2, 2), rgbdMetricMaterial); +rgbdMetricScene.add(rgbdMetricQuad); + +const rgbdVizScene = new THREE.Scene(); +const rgbdVizMaterial = new THREE.ShaderMaterial({ + uniforms: { + uMetricDepthTex: { value: rgbdMetricTarget.texture }, + uMinDepth: { value: rgbdRangeMinM }, + uMaxDepth: { value: rgbdRangeMaxM }, + uGrayMode: { value: 0.0 }, + }, + vertexShader: ` + varying vec2 vUv; + void main() { + vUv = uv; + gl_Position = vec4(position.xy, 0.0, 1.0); + } + `, + fragmentShader: ` + varying vec2 vUv; + uniform sampler2D uMetricDepthTex; + uniform float uMinDepth; + uniform float uMaxDepth; + uniform float uGrayMode; + void main() { + float d = texture2D(uMetricDepthTex, vUv).r; + d = clamp(d, uMinDepth, uMaxDepth); + float lin = (d - uMinDepth) / max(0.0001, (uMaxDepth - uMinDepth)); // 0 near, 1 far + if (uGrayMode > 0.5) { + float g = 1.0 - lin; + gl_FragColor = vec4(g, g, g, 1.0); + return; + } + float inv = (1.0 / d - 1.0 / uMaxDepth) / max(0.0001, (1.0 / uMinDepth - 1.0 / uMaxDepth)); // 1 near, 0 far + float t = clamp(0.35 * (1.0 - lin) + 0.65 * inv, 0.0, 1.0); // near -> 1, far -> 0 + vec3 nearC = vec3(0.05, 0.98, 0.98); + vec3 midC = vec3(0.40, 0.95, 0.10); + vec3 farC = vec3(0.98, 0.15, 0.05); + vec3 c = (t > 0.5) ? mix(midC, nearC, (t - 0.5) * 2.0) : mix(farC, midC, t * 2.0); + gl_FragColor = vec4(c, 1.0); + } + `, + depthTest: false, + depthWrite: false, +}); +rgbdVizMaterial.toneMapped = false; +const rgbdVizQuad = new THREE.Mesh(new THREE.PlaneGeometry(2, 2), rgbdVizMaterial); +rgbdVizScene.add(rgbdVizQuad); +let _savedOverrideMaterial = null; + +function resizeRgbdTargets() { + const w = Math.max(1, Math.floor(window.innerWidth * renderer.getPixelRatio())); + const h = Math.max(1, Math.floor(window.innerHeight * renderer.getPixelRatio())); + rgbdDepthTarget.setSize(w, h); + rgbdMetricTarget.setSize(w, h); + if (rgbdDepthTarget.depthTexture) { + rgbdDepthTarget.depthTexture.image.width = w; + rgbdDepthTarget.depthTexture.image.height = h; + rgbdDepthTarget.depthTexture.needsUpdate = true; + } +} + +let _rgbdNearFarAsserted = false; +let _rgbdLastAutoRangeMs = 0; + +function updateRgbdRangeLabels() { + if (simRgbdMinValEl) simRgbdMinValEl.textContent = `${rgbdRangeMinM.toFixed(1)}m`; + if (simRgbdMaxValEl) simRgbdMaxValEl.textContent = `${rgbdRangeMaxM.toFixed(1)}m`; +} + +function setRgbdRange(minD, maxD) { + const lo = Math.max(0.05, Math.min(minD, maxD - 0.05)); + const hi = Math.max(lo + 0.05, maxD); + rgbdRangeMinM = lo; + rgbdRangeMaxM = hi; + rgbdMetricMaterial.uniforms.uMinDepth.value = lo; + rgbdMetricMaterial.uniforms.uMaxDepth.value = hi; + rgbdVizMaterial.uniforms.uMinDepth.value = lo; + rgbdVizMaterial.uniforms.uMaxDepth.value = hi; + if (simRgbdMinEl) simRgbdMinEl.value = lo.toFixed(1); + if (simRgbdMaxEl) simRgbdMaxEl.value = hi.toFixed(1); + updateRgbdRangeLabels(); +} + +setRgbdRange(RGBD_MIN_DEPTH_M, RGBD_MAX_DEPTH_M); + +function percentileFromSorted(sorted, p) { + if (!sorted.length) return 0; + const idx = Math.min(sorted.length - 1, Math.max(0, Math.floor(p * (sorted.length - 1)))); + return sorted[idx]; +} + +function updateRgbdAutoRangeFromMetricTarget() { + const now = performance.now(); + if (now - _rgbdLastAutoRangeMs < RGBD_AUTO_RANGE_UPDATE_MS) return; + _rgbdLastAutoRangeMs = now; + const depth = readRgbdMetricDepthFrameMeters(); + if (!depth || depth.length === 0) return; + const samples = []; + const stride = Math.max(1, Math.floor(depth.length / 5000)); + for (let i = 0; i < depth.length; i += stride) { + const d = depth[i]; + if (!Number.isFinite(d)) continue; + if (d <= RGBD_MIN_DEPTH_M || d >= RGBD_MAX_DEPTH_M) continue; + samples.push(d); + } + if (samples.length < 32) return; + samples.sort((a, b) => a - b); + const p05 = percentileFromSorted(samples, RGBD_AUTO_PERCENTILE_LOW); + const p95 = percentileFromSorted(samples, RGBD_AUTO_PERCENTILE_HIGH); + const targetMin = Math.max(RGBD_MIN_DEPTH_M, Math.min(p05, p95 - 0.1)); + const targetMax = Math.min(RGBD_MAX_DEPTH_M, Math.max(p95, targetMin + 0.1)); + const smoothMin = rgbdRangeMinM + (targetMin - rgbdRangeMinM) * RGBD_AUTO_RANGE_SMOOTH; + const smoothMax = rgbdRangeMaxM + (targetMax - rgbdRangeMaxM) * RGBD_AUTO_RANGE_SMOOTH; + setRgbdRange(smoothMin, smoothMax); +} + +function renderRgbdView(enableAutoRange = true) { + renderRgbdMetricPassOffscreen(); + + if (enableAutoRange && rgbdAutoRange) updateRgbdAutoRangeFromMetricTarget(); + rgbdVizMaterial.uniforms.uGrayMode.value = rgbdVizMode === "gray" ? 1.0 : 0.0; + + // Pass 3: visualize metric depth target. + renderer.setRenderTarget(null); + renderer.setClearColor(RGBD_BG, RGBD_CLEAR_ALPHA); + renderer.clear(true, true, true); + renderer.render(rgbdVizScene, rgbdPostCamera); +} + +function renderRgbdMetricPassOffscreen(overrideCamera) { + const cam = overrideCamera || camera; + rgbdMetricMaterial.uniforms.uNear.value = cam.near; + rgbdMetricMaterial.uniforms.uFar.value = cam.far; + rgbdMetricMaterial.uniforms.uNoiseEnabled.value = rgbdNoiseEnabled ? 1.0 : 0.0; + rgbdMetricMaterial.uniforms.uSpeckleEnabled.value = rgbdSpeckleEnabled ? 1.0 : 0.0; + if (!_rgbdNearFarAsserted && !overrideCamera) { + console.assert( + Math.abs(rgbdMetricMaterial.uniforms.uNear.value - camera.near) < 1e-9 && + Math.abs(rgbdMetricMaterial.uniforms.uFar.value - camera.far) < 1e-9, + "[RGB-D] Reconstruction near/far must match active camera near/far." + ); + _rgbdNearFarAsserted = true; + } + + // Ensure depth pass sees scene geometry, not lidar/overlay debug points. + const savedOverride = scene.overrideMaterial; + const savedAssets = assetsGroup.visible; + const savedPrims = primitivesGroup.visible; + const savedLights = lightsGroup.visible; + const savedTags = tagsGroup.visible; + const savedLidarViz = lidarVizGroup.visible; + const savedRgbdPc = rgbdPcOverlayGroup.visible; + + scene.overrideMaterial = null; + assetsGroup.visible = true; + primitivesGroup.visible = true; + lightsGroup.visible = true; + tagsGroup.visible = false; + lidarVizGroup.visible = false; + rgbdPcOverlayGroup.visible = false; + + renderer.setRenderTarget(rgbdDepthTarget); + renderer.setClearColor(0x000000, RGBD_CLEAR_ALPHA); + renderer.clear(true, true, true); + renderer.render(scene, cam); + + renderer.setRenderTarget(rgbdMetricTarget); + renderer.setClearColor(0x000000, RGBD_CLEAR_ALPHA); + renderer.clear(true, true, true); + renderer.render(rgbdMetricScene, rgbdPostCamera); + + scene.overrideMaterial = savedOverride; + assetsGroup.visible = savedAssets; + primitivesGroup.visible = savedPrims; + lightsGroup.visible = savedLights; + tagsGroup.visible = savedTags; + lidarVizGroup.visible = savedLidarViz; + rgbdPcOverlayGroup.visible = savedRgbdPc; +} + +function halfToFloat(h) { + const s = (h & 0x8000) >> 15; + const e = (h & 0x7c00) >> 10; + const f = h & 0x03ff; + if (e === 0) return (s ? -1 : 1) * Math.pow(2, -14) * (f / 1024); + if (e === 31) return f ? NaN : ((s ? -1 : 1) * Infinity); + return (s ? -1 : 1) * Math.pow(2, e - 15) * (1 + f / 1024); +} + +function readRgbdMetricDepthFrameMeters() { + const w = rgbdMetricTarget.width; + const h = rgbdMetricTarget.height; + if (!w || !h) return null; + + if (rgbdMetricUsesR32F) { + const depth = new Float32Array(w * h); + renderer.readRenderTargetPixels(rgbdMetricTarget, 0, 0, w, h, depth); + return depth; + } + + if (rgbdMetricTarget.texture.type === THREE.FloatType) { + const raw = new Float32Array(w * h * 4); + renderer.readRenderTargetPixels(rgbdMetricTarget, 0, 0, w, h, raw); + const depth = new Float32Array(w * h); + for (let i = 0; i < w * h; i++) depth[i] = raw[i * 4 + 0]; + return depth; + } + + // Half-float fallback (WebGL1 / constrained platforms) + const raw = new Uint16Array(w * h * 4); + renderer.readRenderTargetPixels(rgbdMetricTarget, 0, 0, w, h, raw); + const depth = new Float32Array(w * h); + for (let i = 0; i < w * h; i++) depth[i] = halfToFloat(raw[i * 4 + 0]); + return depth; +} + +function readRgbdOverlayMetricDepthFrameMeters() { + const w = rgbdOverlayMetricTarget.width; + const h = rgbdOverlayMetricTarget.height; + if (!w || !h) return null; + if (rgbdMetricUsesR32F) { + const depth = new Float32Array(w * h); + renderer.readRenderTargetPixels(rgbdOverlayMetricTarget, 0, 0, w, h, depth); + return depth; + } + if (rgbdOverlayMetricTarget.texture.type === THREE.FloatType) { + const raw = new Float32Array(w * h * 4); + renderer.readRenderTargetPixels(rgbdOverlayMetricTarget, 0, 0, w, h, raw); + const depth = new Float32Array(w * h); + for (let i = 0; i < w * h; i++) depth[i] = raw[i * 4 + 0]; + return depth; + } + const raw = new Uint16Array(w * h * 4); + renderer.readRenderTargetPixels(rgbdOverlayMetricTarget, 0, 0, w, h, raw); + const depth = new Float32Array(w * h); + for (let i = 0; i < w * h; i++) depth[i] = halfToFloat(raw[i * 4 + 0]); + return depth; +} + +function updateRgbdPcOverlayCloud(force = false) { + if (!rgbdPcOverlayOnLidar || simSensorViewMode !== "lidar" || lidarOrderedDebugView) { + _rgbdPcGeom.setDrawRange(0, 0); + _rgbdPcGeom.attributes.position.needsUpdate = true; + _rgbdPcGeom.attributes.color.needsUpdate = true; + _rgbdPcOverlayLastCount = 0; + _rgbdPcOverlayLastPose = null; + _rgbdPcOverlayDirty = false; + rgbdPcOverlayGroup.visible = false; + return; + } + if (!force && !_rgbdPcOverlayDirty) return; + const now = performance.now(); + const curPos = camera.getWorldPosition(new THREE.Vector3()); + const curQuat = camera.getWorldQuaternion(new THREE.Quaternion()); + if (_rgbdPcOverlayLastPose) { + const dp = curPos.distanceTo(_rgbdPcOverlayLastPose.pos); + const da = THREE.MathUtils.radToDeg(curQuat.angleTo(_rgbdPcOverlayLastPose.quat)); + if (!force && dp < RGBD_PC_OVERLAY_MIN_TRANSLATION_M && da < RGBD_PC_OVERLAY_MIN_ROT_DEG) return; + } + _rgbdPcOverlayLastUpdateMs = now; + _rgbdPcOverlayLastPose = { pos: curPos.clone(), quat: curQuat.clone() }; + + const savedDepthTex = rgbdMetricMaterial.uniforms.uDepthTex.value; + + // Low-res depth+metric pass for overlay to avoid expensive full-res readback stalls. + const savedOverride = scene.overrideMaterial; + const savedAssets = assetsGroup.visible; + const savedPrims = primitivesGroup.visible; + const savedLights = lightsGroup.visible; + const savedTags = tagsGroup.visible; + const savedLidarViz = lidarVizGroup.visible; + const savedRgbdPc = rgbdPcOverlayGroup.visible; + scene.overrideMaterial = null; + assetsGroup.visible = true; + primitivesGroup.visible = true; + lightsGroup.visible = true; + tagsGroup.visible = false; + lidarVizGroup.visible = false; + rgbdPcOverlayGroup.visible = false; + + renderer.setRenderTarget(rgbdOverlayDepthTarget); + renderer.setClearColor(0x000000, RGBD_CLEAR_ALPHA); + renderer.clear(true, true, true); + renderer.render(scene, camera); + rgbdMetricMaterial.uniforms.uDepthTex.value = rgbdOverlayDepthTarget.depthTexture; + renderer.setRenderTarget(rgbdOverlayMetricTarget); + renderer.setClearColor(0x000000, RGBD_CLEAR_ALPHA); + renderer.clear(true, true, true); + renderer.render(rgbdMetricScene, rgbdPostCamera); + rgbdMetricMaterial.uniforms.uDepthTex.value = savedDepthTex; + + scene.overrideMaterial = savedOverride; + assetsGroup.visible = savedAssets; + primitivesGroup.visible = savedPrims; + lightsGroup.visible = savedLights; + tagsGroup.visible = savedTags; + lidarVizGroup.visible = savedLidarViz; + rgbdPcOverlayGroup.visible = savedRgbdPc; + + const depth = readRgbdOverlayMetricDepthFrameMeters(); + if (!depth) { + rgbdPcOverlayGroup.visible = false; + return; + } + const w = rgbdOverlayMetricTarget.width; + const h = rgbdOverlayMetricTarget.height; + if (!w || !h) return; + + const tanHalfY = Math.tan(THREE.MathUtils.degToRad(camera.fov * 0.5)); + const fy = 0.5 * h / Math.max(1e-6, tanHalfY); + const fx = fy * camera.aspect; + const cx = (w - 1) * 0.5; + const cy = (h - 1) * 0.5; + const targetCount = Math.min(RGBD_PC_OVERLAY_MAX_POINTS, Math.floor(w * h)); + const stride = Math.max(1, Math.floor(Math.sqrt((w * h) / Math.max(1, targetCount)))); + const pCam = new THREE.Vector3(); + const pWorld = new THREE.Vector3(); + + let n = 0; + for (let py = 0; py < h; py += stride) { + const v = h - 1 - py; // flip Y because render-target readback is bottom-up + for (let px = 0; px < w; px += stride) { + if (n >= RGBD_PC_OVERLAY_MAX_POINTS) break; + const d = depth[py * w + px]; + if (!Number.isFinite(d) || d <= RGBD_MIN_DEPTH_M || d >= RGBD_MAX_DEPTH_M) continue; + const x = ((px - cx) / fx) * d; + const y = -((v - cy) / fy) * d; + const z = -d; // camera forward is -Z in three.js camera coordinates + pCam.set(x, y, z); + pWorld.copy(pCam).applyMatrix4(camera.matrixWorld); + + _rgbdPcPosArray[n * 3 + 0] = pWorld.x; + _rgbdPcPosArray[n * 3 + 1] = pWorld.y; + _rgbdPcPosArray[n * 3 + 2] = pWorld.z; + + _rgbdPcColArray[n * 3 + 0] = 0.10; + _rgbdPcColArray[n * 3 + 1] = 1.00; + _rgbdPcColArray[n * 3 + 2] = 0.25; + n++; + } + if (n >= RGBD_PC_OVERLAY_MAX_POINTS) break; + } + + _rgbdPcGeom.setDrawRange(0, n); + _rgbdPcGeom.attributes.position.needsUpdate = true; + _rgbdPcGeom.attributes.color.needsUpdate = true; + _rgbdPcOverlayLastCount = n; + _rgbdPcOverlayDirty = false; + rgbdPcOverlayGroup.visible = rgbdPcOverlayOnLidar && simSensorViewMode === "lidar" && !lidarOrderedDebugView && n > 0; +} + +// ----------------------------------------------------------------------------- +// RoboVal standardized LiDAR schema + sensor model +// ----------------------------------------------------------------------------- +// We use lidar->world pose convention for pose_T_world_lidar (T_w_l). +// i.e. p_world = T_w_l * p_lidar +// Livox Mid-360 sensor model (non-repetitive Fibonacci scan pattern) +const LIDAR_SCAN_DURATION_S = 0.1; // 10 Hz scan rate +const LIDAR_NUM_POINTS = 10000; // points per scan +const LIDAR_MAX_POINTS = LIDAR_NUM_POINTS; +const LIDAR_MIN_RANGE_M = 0.1; // Mid-360: 0.1m min +const LIDAR_MAX_RANGE_M = 5; +const LIDAR_V_MIN_RAD = THREE.MathUtils.degToRad(-30); // sees ground ~0.6m from robot +const LIDAR_V_MAX_RAD = THREE.MathUtils.degToRad(15); // 15° up avoids ceiling, focuses rays on walls/ground +// Legacy constants kept for browser UI range image (not used by dimos path) +const LIDAR_NUM_RINGS = 1; +const LIDAR_RANGE_IMAGE_W = 1; +let _lidarScanCount = 0; + +// Pre-compute Fibonacci sphere ray directions (uniform sampling on spherical cap) +const _fibLidarDirs = (() => { + const golden = (1 + Math.sqrt(5)) / 2; + const zMin = Math.sin(LIDAR_V_MIN_RAD); // sin(-7°) ≈ -0.122 + const zMax = Math.sin(LIDAR_V_MAX_RAD); // sin(52°) ≈ 0.788 + const dirs = new Float32Array(LIDAR_NUM_POINTS * 3); + for (let i = 0; i < LIDAR_NUM_POINTS; i++) { + const z = zMin + (zMax - zMin) * (i + 0.5) / LIDAR_NUM_POINTS; + const r = Math.sqrt(1 - z * z); + const phi = 2 * Math.PI * i / golden; + dirs[i * 3 + 0] = r * Math.cos(phi); // x (forward in FLU) + dirs[i * 3 + 1] = r * Math.sin(phi); // y (left in FLU) + dirs[i * 3 + 2] = z; // z (up in FLU) + } + return dirs; +})(); +const LIDAR_ACCUM_FRAMES = 50; +const LIDAR_STATS_INTERVAL_MS = 1500; +const LIDAR_ACCUM_MIN_TRANSLATION_M = 0.08; +const LIDAR_ACCUM_MIN_ROT_DEG = 1.5; +const LIDAR_ACCUM_REFRESH_S = 2.0; + +// Lidar frame uses FLU convention: +// x=forward, y=left, z=up (right-handed). Camera local is x=right, y=up, z=back. +const _lidarToCamQuat = (() => { + const m = new THREE.Matrix4().set( + 0, -1, 0, 0, + 0, 0, 1, 0, + -1, 0, 0, 0, + 0, 0, 0, 1 + ); + return new THREE.Quaternion().setFromRotationMatrix(m); +})(); + +// Pose history for deskew (camera used as lidar pose proxy) +const _lidarPoseHistory = []; // [{stampNs, pos:Vector3, quat:Quaternion}] +const LIDAR_POSE_HISTORY_NS = 2_000_000_000; // keep ~2s history +let _lidarLastStatsMs = 0; +let _lidarUseKnownGoodDebugCloud = false; + +function nowNs() { + // Use unix epoch in ns consistently (browser clock based). + return Math.floor(performance.timeOrigin * 1e6 + performance.now() * 1e6); +} + +function pushLidarPoseSample(stampNs = nowNs()) { + let pos, quat; + const dimosAgent = dimosMode && window.__dimosAgent; + if (dimosAgent) { + // In dimos mode, sample from the agent's body position + orientation. + // getPosition() returns capsule center (~0.37m above ground), so subtract + // capsule half-extent to get ground level, then add mount height. + const [ax, ay, az] = dimosAgent.getPosition?.() || [0, 0, 0]; + const groundY = ay - (PLAYER_HALF_HEIGHT + PLAYER_RADIUS); + const lidarY = groundY + LIDAR_MOUNT_HEIGHT; + pos = new THREE.Vector3(ax, lidarY, az); + const yaw = window.__dimosYaw ?? dimosAgent.group?.rotation?.y ?? 0; + const agentQuat = new THREE.Quaternion().setFromAxisAngle(new THREE.Vector3(0, 1, 0), yaw); + quat = agentQuat.multiply(_lidarToCamQuat); + } else { + pos = camera.getWorldPosition(new THREE.Vector3()); + const camQuat = camera.getWorldQuaternion(new THREE.Quaternion()); + quat = camQuat.clone().multiply(_lidarToCamQuat); + } + _lidarPoseHistory.push({ stampNs, pos, quat }); + const minNs = stampNs - LIDAR_POSE_HISTORY_NS; + while (_lidarPoseHistory.length > 2 && _lidarPoseHistory[0].stampNs < minNs) { + _lidarPoseHistory.shift(); + } +} + +function getLidarPoseAtNs(stampNs) { + if (_lidarPoseHistory.length === 0) { + const camQuat = camera.getWorldQuaternion(new THREE.Quaternion()); + return { + pos: camera.getWorldPosition(new THREE.Vector3()), + quat: camQuat.multiply(_lidarToCamQuat), + }; + } + if (_lidarPoseHistory.length === 1) { + return { + pos: _lidarPoseHistory[0].pos.clone(), + quat: _lidarPoseHistory[0].quat.clone(), + }; + } + // Find bounding samples + let i1 = 0; + while (i1 < _lidarPoseHistory.length && _lidarPoseHistory[i1].stampNs < stampNs) i1++; + if (i1 <= 0) { + return { + pos: _lidarPoseHistory[0].pos.clone(), + quat: _lidarPoseHistory[0].quat.clone(), + }; + } + if (i1 >= _lidarPoseHistory.length) { + const last = _lidarPoseHistory[_lidarPoseHistory.length - 1]; + return { pos: last.pos.clone(), quat: last.quat.clone() }; + } + const a = _lidarPoseHistory[i1 - 1]; + const b = _lidarPoseHistory[i1]; + const alpha = (stampNs - a.stampNs) / Math.max(1, b.stampNs - a.stampNs); + const pos = a.pos.clone().lerp(b.pos, alpha); + const quat = a.quat.clone().slerp(b.quat, alpha); + return { pos, quat }; +} + +function composeTwlFlat64(pos, quat) { + const m = new THREE.Matrix4().compose(pos, quat, new THREE.Vector3(1, 1, 1)); + const e = m.elements; + // Return row-major 4x4 flattened float64 (explicitly for stable downstream use) + return new Float64Array([ + e[0], e[4], e[8], e[12], + e[1], e[5], e[9], e[13], + e[2], e[6], e[10], e[14], + e[3], e[7], e[11], e[15], + ]); +} + +function twlInverseMatrix(pos, quat) { + const twl = new THREE.Matrix4().compose(pos, quat, new THREE.Vector3(1, 1, 1)); + return twl.clone().invert(); +} + +function lidarVerticalAngleForRing(ring) { + if (LIDAR_NUM_RINGS === 1) return 0; + const t = ring / (LIDAR_NUM_RINGS - 1); + return LIDAR_V_MIN_RAD + (LIDAR_V_MAX_RAD - LIDAR_V_MIN_RAD) * t; +} + +function makeRoboValLidarFrame({ + frameId, + stampNs, + points, + intensity, + ring, + t, + hasRing, + hasPerPointTime, + scanDurationS, + poseTWorldLidar, +}) { + // RoboValLidarFrame schema (used across sim/export/eval) + return { + frame_id: frameId, + stamp_ns: stampNs, + points, // Float32Array length N*3 (xyz meters, lidar frame) + intensity, // Float32Array length N + ring, // Uint16Array length N + t, // Float32Array length N (seconds from start of scan) + has_ring: hasRing, + has_per_point_time: hasPerPointTime, + scan_duration_s: scanDurationS, + pose_T_world_lidar: poseTWorldLidar, // Float64Array length 16, row-major + }; +} + +// ROS2 PointField datatype constants: +// INT8=1, UINT8=2, INT16=3, UINT16=4, INT32=5, UINT32=6, FLOAT32=7, FLOAT64=8 +function to_pointcloud2(frame) { + const n = Math.floor((frame.points?.length || 0) / 3); + const pointStep = 22; // x,y,z,float32(12) + intensity,float32(4) + ring,uint16(2) + t,float32(4) + const data = new Uint8Array(n * pointStep); + const dv = new DataView(data.buffer); + for (let i = 0; i < n; i++) { + const o = i * pointStep; + dv.setFloat32(o + 0, frame.points[i * 3 + 0], true); + dv.setFloat32(o + 4, frame.points[i * 3 + 1], true); + dv.setFloat32(o + 8, frame.points[i * 3 + 2], true); + dv.setFloat32(o + 12, frame.intensity[i] ?? 0, true); + dv.setUint16(o + 16, frame.ring[i] ?? 0, true); + dv.setFloat32(o + 18, frame.t[i] ?? 0, true); + } + return { + header: { + frame_id: frame.frame_id, + stamp: { + sec: Math.floor(frame.stamp_ns / 1e9), + nanosec: Math.floor(frame.stamp_ns % 1e9), + }, + }, + height: 1, + width: n, + fields: [ + { name: "x", offset: 0, datatype: 7, count: 1 }, + { name: "y", offset: 4, datatype: 7, count: 1 }, + { name: "z", offset: 8, datatype: 7, count: 1 }, + { name: "intensity", offset: 12, datatype: 7, count: 1 }, + { name: "ring", offset: 16, datatype: 4, count: 1 }, + { name: "t", offset: 18, datatype: 7, count: 1 }, + ], + is_bigendian: false, + point_step: pointStep, + row_step: pointStep * n, + data, + is_dense: true, + }; +} + +function toNpyBytes(typedArray, shape, descr) { + // NPY v1.0 + const magic = new Uint8Array([0x93, 0x4e, 0x55, 0x4d, 0x50, 0x59, 0x01, 0x00]); + const shapeStr = `(${shape.join(", ")}${shape.length === 1 ? "," : ""})`; + let header = `{'descr': '${descr}', 'fortran_order': False, 'shape': ${shapeStr}, }`; + // Pad so (magic+2-byte-len+header+\n) % 16 == 0 + const preamble = 10; + const base = preamble + header.length + 1; + const pad = (16 - (base % 16)) % 16; + header = header + " ".repeat(pad) + "\n"; + const headerBytes = new TextEncoder().encode(header); + const out = new Uint8Array(magic.length + 2 + headerBytes.length + typedArray.byteLength); + out.set(magic, 0); + const dv = new DataView(out.buffer); + dv.setUint16(magic.length, headerBytes.length, true); + out.set(headerBytes, magic.length + 2); + out.set(new Uint8Array(typedArray.buffer, typedArray.byteOffset, typedArray.byteLength), magic.length + 2 + headerBytes.length); + return out; +} + +function makeZipStore(entries) { + // Uncompressed ZIP (store) writer for deterministic byte output ordering. + const enc = new TextEncoder(); + const localParts = []; + const centralParts = []; + let offset = 0; + const files = []; + const crcTable = (() => { + const t = new Uint32Array(256); + for (let i = 0; i < 256; i++) { + let c = i; + for (let k = 0; k < 8; k++) c = (c & 1) ? (0xedb88320 ^ (c >>> 1)) : (c >>> 1); + t[i] = c >>> 0; + } + return t; + })(); + const crc32 = (u8) => { + let c = 0xffffffff; + for (let i = 0; i < u8.length; i++) c = crcTable[(c ^ u8[i]) & 0xff] ^ (c >>> 8); + return (c ^ 0xffffffff) >>> 0; + }; + + for (const e of entries) { + const nameBytes = enc.encode(e.name); + const data = e.data; + const crc = crc32(data); + const lfh = new Uint8Array(30 + nameBytes.length); + const dv = new DataView(lfh.buffer); + dv.setUint32(0, 0x04034b50, true); + dv.setUint16(4, 20, true); + dv.setUint16(6, 0, true); + dv.setUint16(8, 0, true); // store + dv.setUint16(10, 0, true); + dv.setUint16(12, 0, true); + dv.setUint32(14, crc, true); + dv.setUint32(18, data.length, true); + dv.setUint32(22, data.length, true); + dv.setUint16(26, nameBytes.length, true); + dv.setUint16(28, 0, true); + lfh.set(nameBytes, 30); + localParts.push(lfh, data); + files.push({ nameBytes, crc, size: data.length, offset }); + offset += lfh.length + data.length; + } + + let centralSize = 0; + for (const f of files) { + const cfh = new Uint8Array(46 + f.nameBytes.length); + const dv = new DataView(cfh.buffer); + dv.setUint32(0, 0x02014b50, true); + dv.setUint16(4, 20, true); + dv.setUint16(6, 20, true); + dv.setUint16(8, 0, true); + dv.setUint16(10, 0, true); + dv.setUint16(12, 0, true); + dv.setUint16(14, 0, true); + dv.setUint32(16, f.crc, true); + dv.setUint32(20, f.size, true); + dv.setUint32(24, f.size, true); + dv.setUint16(28, f.nameBytes.length, true); + dv.setUint16(30, 0, true); + dv.setUint16(32, 0, true); + dv.setUint16(34, 0, true); + dv.setUint16(36, 0, true); + dv.setUint32(38, 0, true); + dv.setUint32(42, f.offset, true); + cfh.set(f.nameBytes, 46); + centralParts.push(cfh); + centralSize += cfh.length; + } + + const eocd = new Uint8Array(22); + const dvE = new DataView(eocd.buffer); + dvE.setUint32(0, 0x06054b50, true); + dvE.setUint16(4, 0, true); + dvE.setUint16(6, 0, true); + dvE.setUint16(8, files.length, true); + dvE.setUint16(10, files.length, true); + dvE.setUint32(12, centralSize, true); + dvE.setUint32(16, offset, true); + dvE.setUint16(20, 0, true); + + return new Blob([...localParts, ...centralParts, eocd], { type: "application/zip" }); +} + +function frameToNpzBlob(frame, rangeImage = null) { + const n = Math.floor((frame.points?.length || 0) / 3); + const xyz = toNpyBytes(frame.points, [n, 3], " URL.revokeObjectURL(a1.href), 500); + + const a2 = document.createElement("a"); + a2.href = URL.createObjectURL(deskBlob); + a2.download = `${base}_lidar_deskewed.npz`; + document.body.appendChild(a2); + a2.click(); + a2.remove(); + setTimeout(() => URL.revokeObjectURL(a2.href), 500); + + if (rangeImage) { + const rBlob = makeZipStore([ + { name: "range.npy", data: toNpyBytes(rangeImage.range, [rangeImage.H, rangeImage.W], " URL.revokeObjectURL(a3.href), 500); + } +} + +const lidarVizGroup = new THREE.Group(); +lidarVizGroup.name = "lidarVizGroup"; +lidarVizGroup.visible = false; +const LIDAR_VIZ_MAX_POINTS = LIDAR_MAX_POINTS * LIDAR_ACCUM_FRAMES; +const _lidarPosArray = new Float32Array(LIDAR_VIZ_MAX_POINTS * 3); +const _lidarColArray = new Float32Array(LIDAR_VIZ_MAX_POINTS * 3); +const _lidarAccumFrames = []; // [{pos: Float32Array, col: Float32Array}] +let _lidarLastAccumPose = null; // {pos:Vector3, quat:Quaternion, stampNs:number} +const _lidarGeom = new THREE.BufferGeometry(); +_lidarGeom.setAttribute("position", new THREE.BufferAttribute(_lidarPosArray, 3)); +_lidarGeom.setAttribute("color", new THREE.BufferAttribute(_lidarColArray, 3)); +_lidarGeom.setDrawRange(0, 0); +const _lidarMat = new THREE.PointsMaterial({ + color: 0xffffff, + vertexColors: true, + size: 0.03, + sizeAttenuation: true, + depthTest: true, + transparent: false, +}); +const _lidarPoints = new THREE.Points(_lidarGeom, _lidarMat); +_lidarPoints.frustumCulled = false; // point cloud covers entire scene; never cull +console.assert(_lidarPoints.isPoints === true, "[LiDAR] Visualization must use THREE.Points"); +lidarVizGroup.add(_lidarPoints); +scene.add(lidarVizGroup); +let _lidarLastNonZeroDrawCount = 0; +const rgbdPcOverlayGroup = new THREE.Group(); +rgbdPcOverlayGroup.name = "rgbdPcOverlayGroup"; +rgbdPcOverlayGroup.visible = false; +const RGBD_PC_OVERLAY_MAX_POINTS = 12000; +const RGBD_PC_OVERLAY_MIN_TRANSLATION_M = 0.15; +const RGBD_PC_OVERLAY_MIN_ROT_DEG = 4.0; +const _rgbdPcPosArray = new Float32Array(RGBD_PC_OVERLAY_MAX_POINTS * 3); +const _rgbdPcColArray = new Float32Array(RGBD_PC_OVERLAY_MAX_POINTS * 3); +const _rgbdPcGeom = new THREE.BufferGeometry(); +_rgbdPcGeom.setAttribute("position", new THREE.BufferAttribute(_rgbdPcPosArray, 3)); +_rgbdPcGeom.setAttribute("color", new THREE.BufferAttribute(_rgbdPcColArray, 3)); +_rgbdPcGeom.setDrawRange(0, 0); +const _rgbdPcMat = new THREE.PointsMaterial({ + color: 0x00ff4f, + vertexColors: true, + size: 3.0, + sizeAttenuation: false, + depthTest: false, + depthWrite: false, + blending: THREE.AdditiveBlending, + transparent: true, + opacity: 1.0, +}); +const _rgbdPcPoints = new THREE.Points(_rgbdPcGeom, _rgbdPcMat); +_rgbdPcPoints.frustumCulled = false; // overlay covers entire scene; never cull +console.assert(_rgbdPcPoints.isPoints === true, "[RGB-D overlay] Visualization must use THREE.Points"); +_rgbdPcPoints.renderOrder = 2000; +rgbdPcOverlayGroup.add(_rgbdPcPoints); +scene.add(rgbdPcOverlayGroup); +let _rgbdPcOverlayLastUpdateMs = 0; +let _rgbdPcOverlayLastPose = null; +let _rgbdPcOverlayLastCount = 0; +let _rgbdPcOverlayDirty = false; + +let _lidarScanState = null; // incremental scan state (processed across frames) + +function updateSimSensorButtons() { + if (simViewCompareBtn) simViewCompareBtn.classList.toggle("active", simCompareView); + if (simViewRgbdBtn) simViewRgbdBtn.classList.toggle("active", simSensorViewMode === "rgbd" && !simCompareView); + if (simRgbdGrayBtn) simRgbdGrayBtn.classList.toggle("active", rgbdVizMode === "gray"); + if (simRgbdColormapBtn) simRgbdColormapBtn.classList.toggle("active", rgbdVizMode === "colormap"); + if (simRgbdAutoRangeBtn) simRgbdAutoRangeBtn.classList.toggle("active", rgbdAutoRange); + if (simRgbdNoiseBtn) simRgbdNoiseBtn.classList.toggle("active", rgbdNoiseEnabled); + if (simRgbdSpeckleBtn) simRgbdSpeckleBtn.classList.toggle("active", rgbdSpeckleEnabled); + if (simRgbdPcOverlayBtn) simRgbdPcOverlayBtn.classList.toggle("active", rgbdPcOverlayOnLidar); + if (simRgbdMinEl) simRgbdMinEl.disabled = rgbdAutoRange; + if (simRgbdMaxEl) simRgbdMaxEl.disabled = rgbdAutoRange; + if (simViewLidarBtn) simViewLidarBtn.classList.toggle("active", simSensorViewMode === "lidar" && !lidarOrderedDebugView && !simCompareView); + if (simLidarColorRangeBtn) simLidarColorRangeBtn.classList.toggle("active", lidarColorByRange); + if (simLidarOrderedDebugBtn) simLidarOrderedDebugBtn.classList.toggle("active", lidarOrderedDebugView); + if (simLidarNoiseBtn) simLidarNoiseBtn.classList.toggle("active", lidarNoiseEnabled); + if (simLidarMultiReturnBtn) { + simLidarMultiReturnBtn.classList.toggle("active", lidarMultiReturnMode === "last"); + simLidarMultiReturnBtn.textContent = lidarMultiReturnMode === "last" ? "LiDAR: Last Return" : "LiDAR: Strongest"; + } + updateRgbdRangeLabels(); +} + +function applySimPanelCollapsedState() { + if (!overlayEl || !agentPanelEl) return; + const shouldCollapse = simPanelCollapsed; + overlayEl.classList.toggle("sim-panel-collapsed", shouldCollapse); + agentPanelEl.classList.toggle("hidden", shouldCollapse); + simPanelOpenBtn?.classList.toggle("hidden", !shouldCollapse); +} + +function lidarRangeColor01(t) { + // Deterministic near->far gradient: cyan -> green -> yellow -> red + const x = Math.min(1, Math.max(0, t)); + if (x < 0.33) { + const u = x / 0.33; + return [0.05 + 0.35 * u, 0.98, 0.98 - 0.88 * u]; + } + if (x < 0.66) { + const u = (x - 0.33) / 0.33; + return [0.40 + 0.58 * u, 0.95 - 0.15 * u, 0.10 * (1.0 - u)]; + } + const u = (x - 0.66) / 0.34; + return [0.98, 0.80 - 0.65 * u, 0.02 + 0.03 * (1.0 - u)]; +} + +function lidarHash01(seed) { + let x = seed | 0; + x ^= x >>> 16; + x = Math.imul(x, 0x7feb352d); + x ^= x >>> 15; + x = Math.imul(x, 0x846ca68b); + x ^= x >>> 16; + return (x >>> 0) / 4294967296; +} + +function lidarGaussianNoise(seedBase) { + // Deterministic approx N(0,1) from 6 uniforms (CLT). + let s = 0; + for (let i = 0; i < 6; i++) { + s += lidarHash01(seedBase + i * 2654435761); + } + return s - 3.0; +} + +function applyLidarRealityModel(toi, incidence, scanSeed, vi, hi) { + let outRange = toi; + let dropped = false; + + if (lidarNoiseEnabled) { + // Indoor-friendly deterministic noise profile (meters). + const sigma = 0.004 + 0.0015 * Math.max(0, toi); // ~4mm near, grows with range + const n = lidarGaussianNoise(scanSeed ^ (vi * 73856093) ^ (hi * 19349663)); + outRange = Math.max(LIDAR_MIN_RANGE_M, Math.min(LIDAR_MAX_RANGE_M, outRange + sigma * n)); + + const tr = Math.min(1, Math.max(0, toi / LIDAR_MAX_RANGE_M)); + const dropoutP = 0.005 + 0.04 * tr * tr; // deterministic, stronger at longer range + const u = lidarHash01(scanSeed ^ (vi * 83492791) ^ (hi * 2654435761)); + if (u < dropoutP) dropped = true; + } + + // Multi-return knob for future lidar profiles. + // With a single physics hit, "last" is approximated as a slight farther-biased return. + if (!dropped && lidarMultiReturnMode === "last") { + const weakSurface = 1.0 - Math.max(0, Math.min(1, incidence)); + const tail = 0.015 * weakSurface; // up to 1.5 cm + outRange = Math.min(LIDAR_MAX_RANGE_M, outRange + tail); + } + + return { range: outRange, dropped }; +} + +function buildKnownGoodDebugCloud() { + // Deterministic 1m cube grid centered 2m in front of camera. + const center = new THREE.Vector3(0, 0, -2).applyMatrix4(camera.matrixWorld); + const step = 0.1; // 11^3 ~= 1331 points + const points = []; + const colors = []; + for (let x = -0.5; x <= 0.5001; x += step) { + for (let y = -0.5; y <= 0.5001; y += step) { + for (let z = -0.5; z <= 0.5001; z += step) { + points.push(center.x + x, center.y + y, center.z + z); + colors.push(0.15 + (x + 0.5) * 0.7, 0.25 + (y + 0.5) * 0.6, 0.95 - (z + 0.5) * 0.5); + } + } + } + return { + pos: new Float32Array(points), + col: new Float32Array(colors), + }; +} + +function logLidarFrameStats(points, n, ring) { + const now = performance.now(); + if (now - _lidarLastStatsMs < LIDAR_STATS_INTERVAL_MS) return; + _lidarLastStatsMs = now; + if (!n) { + console.info("[LiDAR stats]", { n_points: 0, nan_inf_pct: 0 }); + return; + } + let minX = Infinity, minY = Infinity, minZ = Infinity; + let maxX = -Infinity, maxY = -Infinity, maxZ = -Infinity; + let ringMin = Infinity; + let ringMax = -Infinity; + let bad = 0; + const yQuant = new Set(); + for (let i = 0; i < n; i++) { + const x = points[i * 3 + 0]; + const y = points[i * 3 + 1]; + const z = points[i * 3 + 2]; + if (!Number.isFinite(x) || !Number.isFinite(y) || !Number.isFinite(z)) { + bad++; + continue; + } + if (x < minX) minX = x; + if (x > maxX) maxX = x; + if (y < minY) minY = y; + if (y > maxY) maxY = y; + if (z < minZ) minZ = z; + if (z > maxZ) maxZ = z; + yQuant.add(Math.round(y * 1000)); + const rr = ring[i]; + if (rr < ringMin) ringMin = rr; + if (rr > ringMax) ringMax = rr; + } + console.info("[LiDAR stats]", { + n_points: n, + min: { x: minX, y: minY, z: minZ }, + max: { x: maxX, y: maxY, z: maxZ }, + nan_inf_pct: (100 * bad) / n, + unique_y_mm: yQuant.size, + rings_configured: LIDAR_NUM_RINGS, + ring_min: Number.isFinite(ringMin) ? ringMin : 0, + ring_max: Number.isFinite(ringMax) ? ringMax : 0, + }); +} + +function shouldAppendAccumFrame(refPose, stampNs) { + if (!_lidarLastAccumPose) return true; + const dtS = (stampNs - _lidarLastAccumPose.stampNs) / 1e9; + if (dtS >= LIDAR_ACCUM_REFRESH_S) return true; + const dp = refPose.pos.distanceTo(_lidarLastAccumPose.pos); + if (dp >= LIDAR_ACCUM_MIN_TRANSLATION_M) return true; + const ang = THREE.MathUtils.radToDeg(refPose.quat.angleTo(_lidarLastAccumPose.quat)); + if (ang >= LIDAR_ACCUM_MIN_ROT_DEG) return true; + return false; +} + +function resetLidarScanState() { + _lidarScanState = null; +} + +function updateLidarPointCloud() { + if (!rapierWorld || !RAPIER || (simSensorViewMode !== "lidar" && !dimosMode)) return; + + if (_lidarUseKnownGoodDebugCloud) { + resetLidarScanState(); + const dbg = buildKnownGoodDebugCloud(); + const nDbg = Math.min(LIDAR_VIZ_MAX_POINTS, Math.floor(dbg.pos.length / 3)); + _lidarPosArray.set(dbg.pos.subarray(0, nDbg * 3), 0); + _lidarColArray.set(dbg.col.subarray(0, nDbg * 3), 0); + _lidarGeom.setDrawRange(0, nDbg); + _lidarGeom.attributes.position.needsUpdate = true; + _lidarGeom.attributes.color.needsUpdate = true; + lidarVizGroup.position.set(0, 0, 0); + lidarVizGroup.quaternion.identity(); + lidarVizGroup.scale.set(1, 1, 1); + return; + } + + // Build set of collider handles to exclude from lidar raycasts. + // Excludes player collider and ALL AI agent colliders (lidar origin is inside them). + // In dimos mode, also explicitly exclude the active dimos agent body/colliders. + const _lidarExcludeHandles = new Set(); + const _lidarHostAgent = dimosMode ? window.__dimosAgent : null; + const _lidarExcludeRigidBodyHandle = _lidarHostAgent?.body?.handle; + if (playerCollider) _lidarExcludeHandles.add(playerCollider.handle); + if (_lidarHostAgent?.collider?.handle != null) _lidarExcludeHandles.add(_lidarHostAgent.collider.handle); + if (_lidarHostAgent?.spineCollider?.handle != null) _lidarExcludeHandles.add(_lidarHostAgent.spineCollider.handle); + for (const a of aiAgents) { + if (a?.collider) _lidarExcludeHandles.add(a.collider.handle); + if (a?.spineCollider) _lidarExcludeHandles.add(a.spineCollider.handle); + } + + // Livox Mid-360 style: Fibonacci sphere sampling, incremental over ~0.1s wall-clock. + const N = LIDAR_NUM_POINTS; + const scanDurationS = LIDAR_SCAN_DURATION_S; + const scanDurationNs = Math.floor(scanDurationS * 1e9); + if (!_lidarScanState) { + const scanStartNs = nowNs(); + _lidarScanCount++; + const jitterAngle = _lidarScanCount * 2.399963; // golden angle rotation per scan + const rangeImg = new Float32Array(LIDAR_NUM_RINGS * LIDAR_RANGE_IMAGE_W); + const intenImg = new Float32Array(LIDAR_NUM_RINGS * LIDAR_RANGE_IMAGE_W); + const ringIdxImg = new Uint16Array(LIDAR_NUM_RINGS * LIDAR_RANGE_IMAGE_W); + _lidarScanState = { + scanStartNs, + scanDurationS, + scanDurationNs, + scanSeed: (scanStartNs / 1e6) | 0, + cosJitter: Math.cos(jitterAngle), + sinJitter: Math.sin(jitterAngle), + nextIdx: 0, + n: 0, + rawPts: new Float32Array(LIDAR_MAX_POINTS * 3), + deskPts: new Float32Array(LIDAR_MAX_POINTS * 3), + intensity: new Float32Array(LIDAR_MAX_POINTS), + ring: new Uint16Array(LIDAR_MAX_POINTS), + tArr: new Float32Array(LIDAR_MAX_POINTS), + worldPts: new Float32Array(LIDAR_MAX_POINTS * 3), + colArray: new Float32Array(LIDAR_MAX_POINTS * 3), + rangeImg, + intenImg, + ringIdxImg, + }; + } + const st = _lidarScanState; + const dirLocal = new THREE.Vector3(); + const dirWorld = new THREE.Vector3(); + const pWorld = new THREE.Vector3(); + const pRawLocal = new THREE.Vector3(); + const elapsedNs = Math.max(0, nowNs() - st.scanStartNs); + const progress = Math.min(1, elapsedNs / Math.max(1, st.scanDurationNs)); + let targetIdx = Math.floor(progress * N); + targetIdx = Math.max(targetIdx, Math.min(N, st.nextIdx + 1)); + if (elapsedNs >= st.scanDurationNs) targetIdx = N; + + const cosJ = st.cosJitter, sinJ = st.sinJitter; + + for (let i = st.nextIdx; i < targetIdx; i++) { + { + if (st.n >= LIDAR_MAX_POINTS) break; + // Fibonacci direction with per-scan golden-angle rotation around Z (non-repetitive) + const fx = _fibLidarDirs[i * 3 + 0], fy = _fibLidarDirs[i * 3 + 1], fz = _fibLidarDirs[i * 3 + 2]; + const tSec = (i / Math.max(1, N - 1)) * scanDurationS; + const stampNs = st.scanStartNs + Math.floor(tSec * 1e9); + const pose = getLidarPoseAtNs(stampNs); + const w2lNow = twlInverseMatrix(pose.pos, pose.quat); + const origin = pose.pos; + + // Fibonacci direction rotated by per-scan golden angle (FLU frame) + dirLocal.set(fx * cosJ - fy * sinJ, fx * sinJ + fy * cosJ, fz); + dirWorld.copy(dirLocal).applyQuaternion(pose.quat).normalize(); + const ray = new RAPIER.Ray( + { x: origin.x, y: origin.y, z: origin.z }, + { x: dirWorld.x, y: dirWorld.y, z: dirWorld.z } + ); + let hit = null; + let singleExcludeHandle = undefined; + // Defensive retry: if a self-collider slips through, recast while excluding it. + // Keeps scans alive even if exclusion bookkeeping is briefly stale. + for (let castAttempt = 0; castAttempt < 4; castAttempt++) { + hit = rapierWorld.queryPipeline.castRayAndGetNormal( + rapierWorld.bodies, + rapierWorld.colliders, + ray, + LIDAR_MAX_RANGE_M, + false, + RAPIER.QueryFilterFlags.EXCLUDE_SENSORS, + undefined, + singleExcludeHandle, + _lidarExcludeRigidBodyHandle, + (h) => !_lidarExcludeHandles.has(h) + ); + const hitHandle = hit?.colliderHandle; + if (!hit || hitHandle == null || !_lidarExcludeHandles.has(hitHandle)) break; + singleExcludeHandle = hitHandle; + } + let toi = hit ? (hit.toi ?? hit.timeOfImpact ?? 0) : Infinity; + const hitNormal = hit?.normal || null; + + // Ground-truth-style lidar: no-return beams are omitted. + if (!Number.isFinite(toi) || toi > LIDAR_MAX_RANGE_M || toi < LIDAR_MIN_RANGE_M) continue; + + const nx = hitNormal?.x ?? 0; + const ny = hitNormal?.y ?? 0; + const nz = hitNormal?.z ?? 1; + const incidence = hitNormal ? Math.max(0, -(dirWorld.x * nx + dirWorld.y * ny + dirWorld.z * nz)) : 0.7; + const reality = applyLidarRealityModel(toi, incidence, st.scanSeed, i & 0xff, i >> 8); + if (reality.dropped) continue; + toi = reality.range; + + pWorld.set( + origin.x + dirWorld.x * toi, + origin.y + dirWorld.y * toi, + origin.z + dirWorld.z * toi + ); + pRawLocal.copy(pWorld).applyMatrix4(w2lNow); + + st.rawPts[st.n * 3 + 0] = pRawLocal.x; + st.rawPts[st.n * 3 + 1] = pRawLocal.y; + st.rawPts[st.n * 3 + 2] = pRawLocal.z; + st.worldPts[st.n * 3 + 0] = pWorld.x; + st.worldPts[st.n * 3 + 1] = pWorld.y; + st.worldPts[st.n * 3 + 2] = pWorld.z; + + st.ring[st.n] = 0; + st.tArr[st.n] = tSec; + + const atten = 1.0 / (1.0 + 0.02 * toi * toi); + const I = Math.max(0.06, Math.min(1.0, incidence * atten)); + st.intensity[st.n] = I; + const tr = Math.min(1, Math.max(0, toi / LIDAR_MAX_RANGE_M)); + const depthShade = 1.0 - 0.35 * tr; // cheap EDL-like darkening by depth/range + + if (lidarColorByRange) { + const [r, g, b] = lidarRangeColor01(tr); + st.colArray[st.n * 3 + 0] = r * depthShade; + st.colArray[st.n * 3 + 1] = g * depthShade; + st.colArray[st.n * 3 + 2] = b * depthShade; + } else { + // Intensity-like grayscale (closer to raw LiDAR semantics) + const g = I * depthShade; + st.colArray[st.n * 3 + 0] = g; + st.colArray[st.n * 3 + 1] = g; + st.colArray[st.n * 3 + 2] = g; + } + st.n++; + } + } + st.nextIdx = targetIdx; + if (st.nextIdx < N) { + // Keep LiDAR visible while a scan is still being built. + // If we don't have accumulated frames yet, show the partial current scan. + if (!lidarOrderedDebugView && _lidarAccumFrames.length === 0 && st.n > 0) { + _lidarPosArray.set(st.worldPts.subarray(0, st.n * 3), 0); + _lidarColArray.set(st.colArray.subarray(0, st.n * 3), 0); + _lidarGeom.setDrawRange(0, st.n); + if (st.n > 0) _lidarLastNonZeroDrawCount = st.n; + _lidarGeom.attributes.position.needsUpdate = true; + _lidarGeom.attributes.color.needsUpdate = true; + lidarVizGroup.position.set(0, 0, 0); + lidarVizGroup.quaternion.identity(); + lidarVizGroup.scale.set(1, 1, 1); + } + return; // scan still in progress + } + + const scanEndNs = st.scanStartNs + st.scanDurationNs; + const refPose = getLidarPoseAtNs(scanEndNs); + const refTwlFlat = composeTwlFlat64(refPose.pos, refPose.quat); + const refW2L = twlInverseMatrix(refPose.pos, refPose.quat); + const pDeskLocal = new THREE.Vector3(); + for (let i = 0; i < st.n; i++) { + pDeskLocal.set( + st.worldPts[i * 3 + 0], + st.worldPts[i * 3 + 1], + st.worldPts[i * 3 + 2] + ).applyMatrix4(refW2L); + st.deskPts[i * 3 + 0] = pDeskLocal.x; + st.deskPts[i * 3 + 1] = pDeskLocal.y; + st.deskPts[i * 3 + 2] = pDeskLocal.z; + } + + logLidarFrameStats(st.worldPts, st.n, st.ring); + + const rawFrame = makeRoboValLidarFrame({ + frameId: "lidar", + stampNs: scanEndNs, + points: st.rawPts.subarray(0, st.n * 3), + intensity: st.intensity.subarray(0, st.n), + ring: st.ring.subarray(0, st.n), + t: st.tArr.subarray(0, st.n), + hasRing: true, + hasPerPointTime: true, + scanDurationS, + poseTWorldLidar: refTwlFlat, + }); + const deskewedFrame = makeRoboValLidarFrame({ + frameId: "lidar", + stampNs: scanEndNs, + points: st.deskPts.subarray(0, st.n * 3), + intensity: st.intensity.subarray(0, st.n), + ring: st.ring.subarray(0, st.n), + t: st.tArr.subarray(0, st.n), + hasRing: true, + hasPerPointTime: true, + scanDurationS, + poseTWorldLidar: refTwlFlat, + }); + const sensorModelMeta = { + range_min_m: LIDAR_MIN_RANGE_M, + range_max_m: LIDAR_MAX_RANGE_M, + noise_enabled: lidarNoiseEnabled, + multi_return_mode: lidarMultiReturnMode, + ordered_render_debug: lidarOrderedDebugView, + deskewed: true, + }; + rawFrame.sensor_model = sensorModelMeta; + deskewedFrame.sensor_model = sensorModelMeta; + const rangeImage = { + H: LIDAR_NUM_RINGS, + W: LIDAR_RANGE_IMAGE_W, + range: st.rangeImg, + intensity: st.intenImg, + ring_index: st.ringIdxImg, + metadata: { + azimuth_convention: "col increases with azimuth in lidar FLU frame", + binning: "uniform azimuth bins", + num_rings: LIDAR_NUM_RINGS, + num_azimuth_bins: LIDAR_RANGE_IMAGE_W, + sensor_model: sensorModelMeta, + visualization_mode: lidarOrderedDebugView ? "single_sweep_ordered" : "accumulated_unordered", + accumulation: { + max_frames: LIDAR_ACCUM_FRAMES, + min_translation_m: LIDAR_ACCUM_MIN_TRANSLATION_M, + min_rotation_deg: LIDAR_ACCUM_MIN_ROT_DEG, + refresh_s: LIDAR_ACCUM_REFRESH_S, + }, + }, + }; + _lidarLatestRawFrame = rawFrame; + _lidarLatestDeskewedFrame = deskewedFrame; + _lidarLatestRangeImage = rangeImage; + // Save world-frame points for dimos bridge (Three.js Y-up coords). + // The bridge's cyclic permutation correctly converts these to ROS Z-up. + _lidarLatestWorldPts = st.worldPts.slice(0, st.n * 3); + _lidarLatestLocalPts = st.deskPts.slice(0, st.n * 3); + _lidarLatestWorldIntensity = st.intensity.slice(0, st.n); + + // Default visualization: accumulated world-space point cloud (depth-tested). + if (!lidarOrderedDebugView) { + if (shouldAppendAccumFrame(refPose, scanEndNs)) { + const framePos = new Float32Array(st.n * 3); + const frameCol = new Float32Array(st.n * 3); + framePos.set(st.worldPts.subarray(0, st.n * 3)); + frameCol.set(st.colArray.subarray(0, st.n * 3)); + _lidarAccumFrames.push({ pos: framePos, col: frameCol }); + while (_lidarAccumFrames.length > LIDAR_ACCUM_FRAMES) _lidarAccumFrames.shift(); + _lidarLastAccumPose = { + pos: refPose.pos.clone(), + quat: refPose.quat.clone(), + stampNs: scanEndNs, + }; + } + + let out = 0; + const len = _lidarAccumFrames.length; + for (let fi = 0; fi < len && out < LIDAR_VIZ_MAX_POINTS; fi++) { + const f = _lidarAccumFrames[fi]; + const age01 = len <= 1 ? 0 : (len - 1 - fi) / (len - 1); // 1 old -> 0 newest + const fade = 1.0 - 0.7 * age01; + const fn = Math.floor(f.pos.length / 3); + for (let i = 0; i < fn && out < LIDAR_VIZ_MAX_POINTS; i++, out++) { + _lidarPosArray[out * 3 + 0] = f.pos[i * 3 + 0]; + _lidarPosArray[out * 3 + 1] = f.pos[i * 3 + 1]; + _lidarPosArray[out * 3 + 2] = f.pos[i * 3 + 2]; + _lidarColArray[out * 3 + 0] = Math.max(0, Math.min(1, f.col[i * 3 + 0] * fade)); + _lidarColArray[out * 3 + 1] = Math.max(0, Math.min(1, f.col[i * 3 + 1] * fade)); + _lidarColArray[out * 3 + 2] = Math.max(0, Math.min(1, f.col[i * 3 + 2] * fade)); + } + } + if (out > 0) { + _lidarGeom.setDrawRange(0, out); + _lidarLastNonZeroDrawCount = out; + } + lidarVizGroup.position.set(0, 0, 0); + lidarVizGroup.quaternion.identity(); + lidarVizGroup.scale.set(1, 1, 1); + } else { + // Debug visualization: ordered current-frame cloud in deskewed lidar frame. + _lidarAccumFrames.length = 0; + _lidarPosArray.set(st.deskPts.subarray(0, st.n * 3), 0); + _lidarGeom.setDrawRange(0, st.n); + if (st.n > 0) _lidarLastNonZeroDrawCount = st.n; + lidarVizGroup.position.copy(refPose.pos); + lidarVizGroup.quaternion.copy(refPose.quat); + lidarVizGroup.scale.set(1, 1, 1); + } + _lidarGeom.attributes.position.needsUpdate = true; + _lidarGeom.attributes.color.needsUpdate = true; + // Guard against intermittent empty frames causing visible flicker. + if (_lidarGeom.drawRange.count <= 0 && _lidarLastNonZeroDrawCount > 0) { + _lidarGeom.setDrawRange(0, _lidarLastNonZeroDrawCount); + } + if (_lidarAutoExport) { + writeLidarFrameFiles(rawFrame, deskewedFrame, rangeImage); + } + resetLidarScanState(); +} + +function applySimSensorViewMode() { + if (simSensorViewMode === "rgb") { + // Restore default rendering. + scene.overrideMaterial = _savedOverrideMaterial; + assetsGroup.visible = true; + primitivesGroup.visible = true; + lightsGroup.visible = true; + tagsGroup.visible = false; + lidarVizGroup.visible = false; + rgbdPcOverlayGroup.visible = false; + _rgbdPcGeom.setDrawRange(0, 0); + _lidarAccumFrames.length = 0; + _lidarLastAccumPose = null; + resetLidarScanState(); + applySceneRgbBackground(); + } else if (simSensorViewMode === "rgbd") { + // RGB-D mode: render scene depth to offscreen target, then post-process to + // metric camera-space Z visualization. Do not override scene materials. + _savedOverrideMaterial = null; + scene.overrideMaterial = null; + assetsGroup.visible = true; + primitivesGroup.visible = true; + lightsGroup.visible = true; + tagsGroup.visible = false; + lidarVizGroup.visible = false; + rgbdPcOverlayGroup.visible = false; + _rgbdPcGeom.setDrawRange(0, 0); + _lidarAccumFrames.length = 0; + _lidarLastAccumPose = null; + resetLidarScanState(); + skyDome.visible = false; + scene.background = RGBD_BG; + } else { + // LiDAR mode: hide scene visuals and render deterministic point cloud only. + _savedOverrideMaterial = null; + scene.overrideMaterial = null; + assetsGroup.visible = false; + primitivesGroup.visible = false; + lightsGroup.visible = false; + tagsGroup.visible = false; + lidarVizGroup.visible = true; + rgbdPcOverlayGroup.visible = rgbdPcOverlayOnLidar && _rgbdPcOverlayLastCount > 0; + skyDome.visible = false; + scene.background = RGBD_BG; + } + updateSimSensorButtons(); +} + +function setSimSensorViewMode(mode) { + const next = mode === "rgbd" || mode === "lidar" ? mode : "rgb"; + // Toggle behavior: clicking an already-active sensor mode returns to RGB. + simSensorViewMode = (simSensorViewMode === next && next !== "rgb") ? "rgb" : next; + applySimSensorViewMode(); + if (simSensorViewMode === "rgb") { + setStatus("RGB view"); + } else if (simSensorViewMode === "rgbd") { + setStatus(`RGB-D ${rgbdVizMode === "gray" ? "grayscale" : "colormap"} (${rgbdRangeMinM.toFixed(1)}-${rgbdRangeMaxM.toFixed(1)}m)`); + } else { + setStatus(lidarOrderedDebugView ? "LiDAR single sweep view" : "LiDAR accumulated 3D point cloud"); + } +} + +// Controls: pointer-lock look + WASD move. +const controls = new PointerLockControls(camera, document.body); +scene.add(controls.object); + + +const keys = { + forward: false, + backward: false, + left: false, + right: false, + up: false, + down: false, +}; + +function setStatus(msg) { + if (statusEl) statusEl.textContent = msg || ""; + if (statusSimEl) statusSimEl.textContent = msg || ""; +} + +function randId() { + return Math.random().toString(16).slice(2) + "-" + Date.now().toString(16); +} + +function escapeHtml(s) { + return String(s) + .replaceAll("&", "&") + .replaceAll("<", "<") + .replaceAll(">", ">") + .replaceAll('"', """) + .replaceAll("'", "'"); +} + +function loadTagsForWorld() { + // Clean up old primitive colliders BEFORE replacing the arrays + for (const p of primitives) { + removePrimitiveCollider(p); + } + + try { + const rawState = localStorage.getItem("sparkWorldStateByWorld"); + const byWorld = rawState ? JSON.parse(rawState) : {}; + const state = byWorld[worldKey] || null; + if (state && typeof state === "object") { + tags = Array.isArray(state.tags) ? state.tags : []; + assets = Array.isArray(state.assets) ? state.assets.map(normalizeAsset).filter(Boolean) : []; + primitives = Array.isArray(state.primitives) ? state.primitives : []; + editorLights = Array.isArray(state.lights) ? state.lights : []; + groups = Array.isArray(state.groups) ? state.groups : []; + sceneSettings = normalizeSceneSettings(state.sceneSettings); + } else { + // Backwards compat: tags-only storage + const raw = localStorage.getItem("sparkWorldTagsByWorld"); + const byWorldOld = raw ? JSON.parse(raw) : {}; + tags = Array.isArray(byWorldOld[worldKey]) ? byWorldOld[worldKey] : []; + assets = []; + primitives = []; + editorLights = []; + groups = []; + sceneSettings = createDefaultSceneSettings(); + } + } catch { + tags = []; + assets = []; + primitives = []; + editorLights = []; + groups = []; + sceneSettings = createDefaultSceneSettings(); + } + selectedTagId = null; + draftTag = null; + selectedAssetId = null; + selectedPrimitiveId = null; + rebuildTagMarkers(); + renderTagsList(); + renderTagPanel(); + rebuildAssets(); + renderAssetsList(); + rebuildAllPrimitives(); + renderPrimitivesList(); + rebuildAllEditorLights(); + applySceneSkySettings(); + applySceneRgbBackground(); +} + +function saveTagsForWorld() { + try { + let rawState = localStorage.getItem("sparkWorldStateByWorld"); + let byWorld = {}; + + try { + byWorld = rawState ? JSON.parse(rawState) : {}; + } catch { + // Corrupted data, start fresh + console.warn("[SAVE] Corrupted localStorage data, clearing..."); + byWorld = {}; + } + + console.log(`[SAVE] Saving ${assets.length} assets for world: ${worldKey}`); + + // Only save lightweight metadata - NOT the full dataBase64 model data + // Only save state changes (currentStateId, transform) + const lightweightAssets = assets.map(a => { + // Regular assets: only save delta/metadata, not model data + return { + id: a.id, + currentStateId: a.currentStateId || a.currentState, + transform: a.transform, + pickable: a.pickable, + castShadow: a.castShadow ?? false, + receiveShadow: a.receiveShadow ?? false, + blobShadow: a.blobShadow || null, + _deltaOnly: true, + }; + }); + + // Save primitives — strip collider handles and large texture data URLs + // (textures are preserved in Export but too big for localStorage) + const savePrimitives = primitives.map((p) => { + const { _colliderHandle, ...rest } = p; + if (rest.material?.textureDataUrl) { + rest.material = { ...rest.material, textureDataUrl: null }; + } + return rest; + }); + + // Save lights (strip runtime objects) + const saveLights = editorLights.map((l) => { + const { _lightObj, _helperObj, _proxyObj, ...rest } = l; + return rest; + }); + + byWorld[worldKey] = { + tags, + assets: lightweightAssets, + primitives: savePrimitives, + lights: saveLights, + groups, + sceneSettings: serializeSceneSettings(), + }; + const dataStr = JSON.stringify(byWorld); + + // Check size before saving (localStorage limit is typically 5MB) + const sizeKB = (dataStr.length * 2) / 1024; // Rough estimate (UTF-16) + console.log(`[SAVE] Data size: ${sizeKB.toFixed(1)}KB`); + + localStorage.setItem("sparkWorldStateByWorld", dataStr); + localStorage.setItem("sparkWorldLastWorldKey", worldKey); + } catch (e) { + console.error("[SAVE] Failed to save world state:", e); + + // If quota exceeded, try clearing old data and retry + if (e.name === "QuotaExceededError") { + console.warn("[SAVE] Quota exceeded, clearing old world data..."); + try { + localStorage.removeItem("sparkWorldStateByWorld"); + // Retry with just current world and minimal data + const freshData = {}; + freshData[worldKey] = { + tags, + assets: [], + sceneSettings: serializeSceneSettings() + }; + localStorage.setItem("sparkWorldStateByWorld", JSON.stringify(freshData)); + console.log("[SAVE] Saved minimal data after clearing old data"); + } catch (e2) { + console.error("[SAVE] Still failed after clearing:", e2); + } + } + } +} + +// Clear all localStorage data for this app (useful for debugging) +function clearWorldStorage() { + localStorage.removeItem("sparkWorldStateByWorld"); + localStorage.removeItem("sparkWorldLastWorldKey"); + console.log("[STORAGE] Cleared all world storage"); +} +// Expose for debugging: window.clearWorldStorage = clearWorldStorage; + +function setWorldKey(key) { + worldKey = key || "default"; + localStorage.setItem("sparkWorldLastWorldKey", worldKey); + loadTagsForWorld(); +} + + +function getSelectedTag() { + return tags.find((t) => t.id === selectedTagId) ?? null; +} + +function renderTagPanel() { + // No-op in sim-only mode (editor tag panel not present) +} + +function renderTagsList() { + // No-op in sim-only mode (editor tags list not present) +} + +const markerGeom = new THREE.SphereGeometry(0.08, 12, 12); +const markerMat = new THREE.MeshBasicMaterial({ color: 0x7cc4ff }); +const markerMatActive = new THREE.MeshBasicMaterial({ color: 0xffd36e }); +const radiusGeom = new THREE.SphereGeometry(1, 20, 14); +const radiusMat = new THREE.MeshBasicMaterial({ + color: 0x7cc4ff, + transparent: true, + opacity: 0.08, + depthWrite: false, +}); + +function agentUiPush(event) { + const logs = [ + agentLogEl, + document.getElementById("edit-agent-log"), + ].filter(Boolean); + for (const log of logs) { + const el = document.createElement("div"); + el.className = "agent-log-item"; + el.textContent = event; + log.prepend(el); + // cap + while (log.children.length > 10) log.removeChild(log.lastChild); + } +} + +function agentUiSetLast(text) { + const value = text || ""; + if (agentLastEl) agentLastEl.textContent = value; + const editLast = document.getElementById("edit-agent-last"); + if (editLast) editLast.textContent = value; +} + +function agentUiSetShot(base64) { + if (!base64) return; + const src = `data:image/jpeg;base64,${base64}`; + if (agentShotImgEl) agentShotImgEl.src = src; + const editShot = document.getElementById("edit-agent-shot-img"); + if (editShot) editShot.src = src; +} + +function extractObservationText(parsed, raw) { + const p = parsed && typeof parsed === "object" ? parsed : {}; + const observation = + (typeof p.observation === "string" && p.observation) || + (typeof p.obs === "string" && p.obs) || + (typeof p.perception === "string" && p.perception) || + (typeof p.sceneObservation === "string" && p.sceneObservation) || + (typeof p.visualObservation === "string" && p.visualObservation) || + (typeof p.params?.observation === "string" && p.params.observation) || + ""; + if (observation.trim()) return observation.trim(); + + if (typeof raw === "string" && raw.trim()) { + const m = raw.match(/"observation"\s*:\s*"([^"]+)"/i); + if (m?.[1]) return m[1]; + } + return ""; +} + +function agentUiSetObservation(text) { + const value = String(text || "").trim(); + if (!agentObservationEl) return; + agentObservationEl.textContent = value || "No observation in latest response."; +} + +function agentUiSetRequest({ endpoint, model, prompt, context, imageBytes, messages }) { + const metaText = `endpoint: ${endpoint}\nmodel: ${model}\nimageBytes: ${imageBytes ?? "?"}\nworld: ${worldKey}`; + if (agentReqMetaEl) agentReqMetaEl.textContent = metaText; + const editMeta = document.getElementById("edit-agent-req-meta"); + if (editMeta) editMeta.textContent = metaText; + if (agentReqPromptEl) agentReqPromptEl.textContent = prompt || ""; + const editPrompt = document.getElementById("edit-agent-req-prompt"); + if (editPrompt) editPrompt.textContent = prompt || ""; + + // Format messages for display (only assistant and user messages, not system) + let contextText = ""; + if (messages && messages.length > 0) { + // Filter out system messages - only show assistant and user + const conversationMessages = messages.filter(msg => msg.role !== "system"); + if (conversationMessages.length > 0) { + contextText = conversationMessages.map((msg) => { + const role = msg.role.toUpperCase(); + let content = ""; + if (typeof msg.content === "string") { + content = msg.content; + } else if (Array.isArray(msg.content)) { + // Handle multimodal content (text + image) + content = msg.content.map(part => { + if (part.type === "text") return part.text; + if (part.type === "image_url") return "[IMAGE]"; + return JSON.stringify(part); + }).join("\n"); + } else { + content = JSON.stringify(msg.content, null, 2); + } + return `═══ ${role} ═══\n${content}`; + }).join("\n\n"); + } else { + contextText = "(No conversation history yet)"; + } + } else { + contextText = JSON.stringify(context ?? {}, null, 2); + } + if (agentReqContextEl) agentReqContextEl.textContent = contextText; + const editContext = document.getElementById("edit-agent-req-context"); + if (editContext) editContext.textContent = contextText; +} + +function agentUiSetResponse({ raw, parsed }) { + if (agentRespRawEl) agentRespRawEl.textContent = raw || ""; + const editRaw = document.getElementById("edit-agent-resp-raw"); + if (editRaw) editRaw.textContent = raw || ""; + if (agentLastEl) agentLastEl.textContent = JSON.stringify(parsed ?? {}, null, 2); + agentUiSetObservation(extractObservationText(parsed, raw)); + const editLast = document.getElementById("edit-agent-last"); + if (editLast) editLast.textContent = JSON.stringify(parsed ?? {}, null, 2); +} + +function clearAgentInspectorViews() { + if (agentShotImgEl) agentShotImgEl.removeAttribute("src"); + if (agentReqMetaEl) agentReqMetaEl.textContent = "No request yet"; + if (agentReqPromptEl) agentReqPromptEl.textContent = ""; + if (agentReqContextEl) agentReqContextEl.textContent = ""; + if (agentRespRawEl) agentRespRawEl.textContent = ""; + if (agentLastEl) agentLastEl.textContent = "Waiting..."; + if (agentObservationEl) agentObservationEl.textContent = "Waiting for first observation..."; + + const editShot = document.getElementById("edit-agent-shot-img"); + const editReqMeta = document.getElementById("edit-agent-req-meta"); + const editReqPrompt = document.getElementById("edit-agent-req-prompt"); + const editReqContext = document.getElementById("edit-agent-req-context"); + const editRespRaw = document.getElementById("edit-agent-resp-raw"); + const editLast = document.getElementById("edit-agent-last"); + if (editShot) editShot.removeAttribute("src"); + if (editReqMeta) editReqMeta.textContent = "No request yet"; + if (editReqPrompt) editReqPrompt.textContent = ""; + if (editReqContext) editReqContext.textContent = ""; + if (editRespRaw) editRespRaw.textContent = ""; + if (editLast) editLast.textContent = "Waiting..."; +} + +function showEditSpawnedAgentsTab() { + const btn = document.getElementById("vibe-tab-agents"); + btn?.click?.(); +} + +function getAgentById(id) { + const key = String(id || ""); + if (!key) return null; + return aiAgents.find((a) => a?.id === key) || null; +} + +function ensureAgentControlStrip() { + // Restrict spawned-agent controls to the right-panel "Spawned Agents" tab only. + const panelContent = document.getElementById("vibe-tab-agents-pane"); + if (!panelContent) return; + + let strip = document.getElementById("agent-control-strip"); + + // Re-parent strip if it ended up in the wrong panel after mode switch. + if (strip && strip.parentElement !== panelContent) { + strip.remove(); + strip = null; + agentUiSelectedLabelEl = null; + agentUiSpawnBtn = null; + agentUiFollowBtn = null; + agentUiStopBtn = null; + agentUiRemoveBtn = null; + agentUiTaskInputEl = null; + agentUiTaskRunBtn = null; + } + + if (agentUiSelectedLabelEl && agentUiFollowBtn && agentUiStopBtn && agentUiRemoveBtn) return; + + if (!strip) { + strip = document.createElement("div"); + strip.id = "agent-control-strip"; + strip.className = "agent-control-strip"; + strip.innerHTML = ` +
Selected: none
+
+ + + + +
+
+ + +
+ `; + panelContent.insertBefore(strip, panelContent.firstChild || null); + } + + agentUiSelectedLabelEl = document.getElementById("agent-selected-label"); + agentUiSpawnBtn = document.getElementById("agent-selected-spawn"); + agentUiFollowBtn = document.getElementById("agent-selected-follow"); + agentUiStopBtn = document.getElementById("agent-selected-stop"); + agentUiRemoveBtn = document.getElementById("agent-selected-remove"); + agentUiTaskInputEl = document.getElementById("agent-selected-task-input"); + agentUiTaskRunBtn = document.getElementById("agent-selected-task-run"); + + agentUiSpawnBtn?.addEventListener("click", () => { + void spawnOrMoveAiAtAim({ createNew: true, silent: false, ephemeral: false }).then(() => { + const newest = aiAgents[aiAgents.length - 1]; + if (newest?.id) selectAgentInspector(newest.id); + renderSelectedAgentControls(); + }); + showEditSpawnedAgentsTab(); + }); + agentUiFollowBtn?.addEventListener("click", () => { + const a = getAgentById(selectedAgentInspectorId); + if (!a) return; + if (agentCameraFollow && agentCameraFollowId === a.id) { + disableAgentCameraFollow(); + } else { + enableAgentCameraFollow(a.id); + } + renderSelectedAgentControls(); + }); + agentUiStopBtn?.addEventListener("click", () => { + const a = getAgentById(selectedAgentInspectorId); + if (!a) return; + stopAiAgent(a, "ui-stop"); + setStatus(`Stopped ${a.id}.`); + renderSelectedAgentControls(); + }); + agentUiRemoveBtn?.addEventListener("click", () => { + const a = getAgentById(selectedAgentInspectorId); + if (!a) return; + removeAiAgent(a, "ui-remove"); + setStatus(`Removed ${a.id}.`); + if (agentTask.active && aiAgents.length === 0) endAgentTask("all-agents-removed"); + renderSelectedAgentControls(); + }); + const runSelectedTask = () => { + const a = getAgentById(selectedAgentInspectorId); + if (!a) return; + const text = String(agentUiTaskInputEl?.value || "").trim(); + if (!text) return; + if (agentTask.active) endAgentTask("replace-task"); + void startAgentTask(text, { autoPool: false, targetAgentId: a.id }); + if (agentUiTaskInputEl) agentUiTaskInputEl.value = ""; + setStatus(`Running task on ${a.id}.`); + showEditSpawnedAgentsTab(); + }; + agentUiTaskRunBtn?.addEventListener("click", runSelectedTask); + agentUiTaskInputEl?.addEventListener("keydown", (e) => { + e.stopPropagation(); + if (e.key === "Enter") runSelectedTask(); + }); +} + +function renderSelectedAgentControls() { + ensureAgentControlStrip(); + if (!agentUiSelectedLabelEl || !agentUiFollowBtn || !agentUiStopBtn || !agentUiRemoveBtn) return; + const a = getAgentById(selectedAgentInspectorId); + const has = !!a; + agentUiSelectedLabelEl.textContent = has ? `Selected: ${a.id}` : "Selected: none"; + agentUiFollowBtn.disabled = !has; + agentUiStopBtn.disabled = !has; + agentUiRemoveBtn.disabled = !has; + agentUiFollowBtn.textContent = has && agentCameraFollow && agentCameraFollowId === a.id ? "Unfollow POV" : "Follow POV"; +} + +function getOrCreateAgentInspectorState(agentId) { + const id = String(agentId || ""); + if (!id) return { shot: "", request: null, response: null }; + if (!agentInspectorStateById.has(id)) { + agentInspectorStateById.set(id, { shot: "", request: null, response: null }); + } + return agentInspectorStateById.get(id); +} + +function renderAgentInspector(agentId = selectedAgentInspectorId) { + const id = String(agentId || ""); + if (!id) return; + const s = getOrCreateAgentInspectorState(id); + if (agentReqMetaEl) { + const base = s.request || { endpoint: "-", model: "-", prompt: "", context: {}, imageBytes: null, messages: [] }; + agentUiSetRequest(base); + agentReqMetaEl.textContent = `${agentReqMetaEl.textContent}\nagent: ${id}`; + const editMeta = document.getElementById("edit-agent-req-meta"); + if (editMeta) editMeta.textContent = `${editMeta.textContent}\nagent: ${id}`; + } + if (s.shot) agentUiSetShot(s.shot); + if (s.response) agentUiSetResponse(s.response); +} + +function selectAgentInspector(agentId) { + const id = String(agentId || ""); + if (!id) return; + selectedAgentInspectorId = id; + showEditSpawnedAgentsTab(); + // Force strip into correct panel on selection. + ensureAgentControlStrip(); + renderAgentInspector(id); + renderSelectedAgentControls(); + // Visual flash feedback. + const strip = document.getElementById("agent-control-strip"); + if (strip) { + strip.style.outline = "2px solid var(--accent-primary)"; + setTimeout(() => { strip.style.outline = ""; }, 600); + } +} + +function renderAgentTaskUi() { + ensureAgentControlStrip(); + const bar = document.getElementById("agent-command-bar"); + const hasAgent = aiAgents.length > 0; + + if (bar) bar.style.display = ""; + if (spawnAiBtn) spawnAiBtn.style.display = hasAgent ? "none" : ""; + + if (!agentTaskStatusEl || !agentTaskInputEl || !agentTaskStartBtn || !agentTaskEndBtn) return; + + if (!agentTask.active) { + agentTaskStatusEl.textContent = ""; + agentTaskInputEl.disabled = false; + agentTaskStartBtn.disabled = !hasAgent; + agentTaskEndBtn.disabled = true; + if (bar) bar.classList.remove("active"); + } else { + agentTaskStatusEl.textContent = "Running"; + agentTaskInputEl.disabled = true; + agentTaskStartBtn.disabled = true; + agentTaskEndBtn.disabled = false; + if (bar) bar.classList.add("active"); + } + updateSimCameraModeToggleUi(); + renderSelectedAgentControls(); +} + +function updateSimCameraModeToggleUi() { + if (!simCameraModeToggleBtn) return; + const isUserCam = simUserCameraMode === "user"; + simCameraModeToggleBtn.textContent = isUserCam ? "Camera: User" : "Camera: Agent"; + simCameraModeToggleBtn.classList.toggle("active", isUserCam); + simCameraModeToggleBtn.classList.toggle("tb-muted", !isUserCam); + simCameraModeToggleBtn.title = isUserCam + ? "Keep your user camera while the agent runs" + : "Follow the active agent while the task runs"; +} + +function enableAgentCameraFollow(agentId = selectedAgentInspectorId) { + if (aiAgents.length === 0) return; + const target = getAgentById(agentId) || aiAgents[0]; + if (!target) return; + agentCameraFollow = true; + agentCameraFollowId = target.id; + _agentFollowInitialized = false; + + // Unlock player controls so camera isn't fighting with pointer lock + controls?.unlock?.(); + + // Hide the player avatar + avatar.visible = false; + + // Hide crosshair and interaction hints during follow mode + const crosshair = document.getElementById("crosshair"); + if (crosshair) crosshair.style.display = "none"; + const hint = document.getElementById("interaction-hint"); + if (hint) hint.style.display = "none"; + + console.log("[AGENT CAM] Following agent"); + renderSelectedAgentControls(); +} + +function disableAgentCameraFollow() { + agentCameraFollow = false; + agentCameraFollowId = null; + + // Show all agent meshes again + for (const a of aiAgents) { + if (a?.group) a.group.visible = true; + } + + // Avatar mesh stays hidden (physics capsule still active) + + // Restore crosshair and interaction hints + const crosshair = document.getElementById("crosshair"); + if (crosshair) crosshair.style.display = ""; + const hint = document.getElementById("interaction-hint"); + if (hint) hint.style.display = ""; + + console.log("[AGENT CAM] Returning to player"); + renderSelectedAgentControls(); +} + +function updateAgentCameraFollow(dt) { + if (!agentCameraFollow || aiAgents.length === 0) return; + + const agent = getAgentById(agentCameraFollowId) || aiAgents[0]; + if (!agent) return; + const [ax, ay, az] = agent.getPosition?.() || [0, 0, 0]; + const yaw = agent.group?.rotation?.y ?? 0; + const pitch = typeof agent.pitch === "number" ? agent.pitch : 0; + + // Place camera at the real Go2 front-camera mount: GO2_CAMERA_HEIGHT above + // the ground and GO2_CAMERA_FORWARD along the agent's heading so the origin + // sits outside the body mesh (Go2's head-mounted RGB-D, not body-center). + const feetY = ay - ((agent.halfHeight || 0.25) + (agent.radius || 0.12)); + const eyeY = feetY + GO2_CAMERA_HEIGHT; + const eyeX = ax + Math.sin(yaw) * GO2_CAMERA_FORWARD; + const eyeZ = az + Math.cos(yaw) * GO2_CAMERA_FORWARD; + camera.position.set(eyeX, eyeY, eyeZ); + + // Compute forward direction exactly like visionCapture.js does + const cp = Math.cos(pitch); + const sp = Math.sin(pitch); + const fx = Math.sin(yaw) * cp; + const fy = sp; + const fz = Math.cos(yaw) * cp; + + // Use lookAt to match the VLM capture camera + camera.lookAt(eyeX + fx, eyeY + fy, eyeZ + fz); + + // Hide the agent's own mesh so it doesn't block the view + if (agent.group) agent.group.visible = false; +} + +async function startAgentTask(instruction, { autoPool = true, targetAgentId = null } = {}) { + const text = String(instruction || "").trim(); + if (!text) return; + + const now = Date.now(); + const taskState = { + active: true, + instruction: text, + startedAt: now, + finishedAt: 0, + finishedReason: "", + lastSummary: "", + }; + + // Determine which agents get this task + const target = targetAgentId ? getAgentById(targetAgentId) : null; + agentTaskTargetId = target?.id || null; + const targets = target ? [target] : aiAgents; + + for (const a of targets) { + _setAgentTask(a.id, { ...taskState }); + a._taskStartedAt = now; + } + + agentUiPush(`${new Date().toLocaleTimeString()}\nTASK START\n${text}${target ? ` [${target.id}]` : ` [${targets.length} agents]`}`); + renderAgentTaskUi(); + + if (simUserCameraMode === "agent") enableAgentCameraFollow(); +} + +function endAgentTask(reason = "manual", agentId = null) { + if (agentId) { + // End task for a specific agent + const task = _agentTasks.get(agentId); + if (task?.active) { + task.active = false; + task.finishedAt = Date.now(); + task.finishedReason = reason; + _agentTasks.set(agentId, task); + } + agentUiPush(`${new Date().toLocaleTimeString()}\nTASK END (${reason}) [${agentId}]`); + } else { + // End all tasks + for (const [id, task] of _agentTasks) { + if (task.active) { + task.active = false; + task.finishedAt = Date.now(); + task.finishedReason = reason; + } + } + agentTask.active = false; + agentTask.finishedAt = Date.now(); + agentTask.finishedReason = reason; + agentUiPush(`${new Date().toLocaleTimeString()}\nTASK END ALL (${reason})`); + } + agentTaskTargetId = null; + + // Check if any agent still has an active task + const anyActive = [..._agentTasks.values()].some((t) => t.active); + if (!anyActive) { + agentTask.active = false; + disableAgentCameraFollow(); + } + + renderAgentTaskUi(); + +} + +function rebuildTagMarkers() { + while (tagsGroup.children.length) tagsGroup.remove(tagsGroup.children[0]); + + for (const t of tags) { + if (!t.position) continue; + const m = new THREE.Mesh(markerGeom, t.id === selectedTagId ? markerMatActive : markerMat); + m.position.set(t.position.x, t.position.y, t.position.z); + m.userData.tagId = t.id; + m.renderOrder = 1000; + tagsGroup.add(m); + + const r = Number(t.radius ?? 1.5); + const shell = new THREE.Mesh(radiusGeom, radiusMat); + shell.position.copy(m.position); + shell.scale.setScalar(Math.max(0.01, r)); + shell.userData.tagId = t.id; + shell.userData.isRadius = true; + tagsGroup.add(shell); + } + + updateMarkerMaterials(); +} + +function updateMarkerMaterials() { + for (const child of tagsGroup.children) { + if (!child.isMesh) continue; + if (child.userData?.isRadius) continue; + child.material = child.userData.tagId === selectedTagId ? markerMatActive : markerMat; + } +} + +function renderAssetModal() { + // No-op in sim-only mode (asset upload modal not present) +} + +function base64FromArrayBuffer(buf) { + const bytes = new Uint8Array(buf); + let binary = ""; + const chunk = 0x8000; + for (let i = 0; i < bytes.length; i += chunk) { + binary += String.fromCharCode.apply(null, bytes.subarray(i, i + chunk)); + } + return btoa(binary); +} + +function arrayBufferFromBase64(base64) { + const bin = atob(base64); + const len = bin.length; + const bytes = new Uint8Array(len); + for (let i = 0; i < len; i++) bytes[i] = bin.charCodeAt(i); + return bytes.buffer; +} + +function normalizeAsset(a) { + if (!a || typeof a !== "object") return null; + // Ensure pickable property exists + if (typeof a.pickable !== "boolean") a.pickable = false; + if (typeof a.bumpable !== "boolean") a.bumpable = false; + if (!Number.isFinite(a.bumpResponse)) a.bumpResponse = 0.9; + if (!Number.isFinite(a.bumpDamping)) a.bumpDamping = 0.9; + // New schema: states is array + if (Array.isArray(a.states)) { + if (!a.currentStateId && a.states[0]?.id) a.currentStateId = a.states[0].id; + // Ensure interactions exist per state. + for (const s of a.states) { + if (!Array.isArray(s.interactions)) s.interactions = []; + } + // Backfill actions from interactions if missing. + if (!Array.isArray(a.actions) || a.actions.length === 0) { + a.actions = []; + for (const s of a.states) { + for (const it of s.interactions) { + a.actions.push({ id: it.id || `act_${s.id}_${it.to}`, label: it.label || "toggle", from: s.id, to: it.to }); + } + } + } else { + // Backfill interactions from actions if missing. + const byFrom = new Map(); + for (const act of a.actions) { + if (!byFrom.has(act.from)) byFrom.set(act.from, []); + byFrom.get(act.from).push({ id: act.id, label: act.label, to: act.to }); + } + for (const s of a.states) { + if (!s.interactions || s.interactions.length === 0) s.interactions = byFrom.get(s.id) || []; + } + } + return a; + } + // Old schema: states is {A,B} + if (a.states && typeof a.states === "object") { + const out = { + id: a.id, + title: a.title || "", + notes: a.notes || "", + states: [], + currentStateId: a.currentState || "A", + actions: Array.isArray(a.actions) ? a.actions : [], + transform: a.transform || null, + bumpable: a.bumpable === true, + bumpResponse: Number.isFinite(a.bumpResponse) ? a.bumpResponse : 0.9, + bumpDamping: Number.isFinite(a.bumpDamping) ? a.bumpDamping : 0.9, + }; + const A = a.states.A; + const B = a.states.B; + if (A) out.states.push({ id: "A", name: A.name || "stateA", glbName: A.glbName || "", dataBase64: A.dataBase64 || "", interactions: [] }); + if (B) out.states.push({ id: "B", name: B.name || "stateB", glbName: B.glbName || "", dataBase64: B.dataBase64 || "", interactions: [] }); + if (!out.currentStateId) out.currentStateId = out.states[0]?.id || "A"; + out.actions = Array.isArray(out.actions) ? out.actions : []; + // Backfill interactions from actions. + const byFrom = new Map(); + for (const act of out.actions) { + if (!byFrom.has(act.from)) byFrom.set(act.from, []); + byFrom.get(act.from).push({ id: act.id, label: act.label, to: act.to }); + } + for (const s of out.states) s.interactions = byFrom.get(s.id) || []; + return out; + } + return a; +} + +function getSelectedAsset() { + return assets.find((a) => a.id === selectedAssetId) || null; +} + +function renderAssetsList() { + if (!assetsListEl) return; + assetsListEl.innerHTML = ""; + for (const a of assets) { + const el = document.createElement("div"); + el.className = "tag-item" + (a.id === selectedAssetId ? " active" : ""); + const sId = a.currentStateId || a.currentState || "A"; + const stateObj = Array.isArray(a.states) ? a.states.find((s) => s.id === sId) : a.states?.[sId]; + const label = a.title || stateObj?.glbName || "(asset)"; + const kind = stateObj?.scene || stateObj?.shapeScene ? "shape" : "glb"; + el.innerHTML = `${escapeHtml(label)}${kind}`; + el.addEventListener("click", () => selectAsset(a.id)); + assetsListEl.appendChild(el); + } +} + +function selectAsset(id) { + selectedAssetId = id; + if (id) { + selectedPrimitiveId = null; + } + renderAssetsList(); +} + +function persistSelectedAssetTransform() { + const a = getSelectedAsset(); + if (!a) return; + const obj = assetsGroup.getObjectByName(`asset:${a.id}`); + if (!obj) return; + a.transform = { + position: { x: obj.position.x, y: obj.position.y, z: obj.position.z }, + rotation: { x: obj.rotation.x, y: obj.rotation.y, z: obj.rotation.z }, + scale: { x: obj.scale.x, y: obj.scale.y, z: obj.scale.z }, + }; + saveTagsForWorld(); + if (!a.bumpable) rebuildAssetCollider(a.id); +} + +function normalizeShapeStateScene(sceneLike) { + const raw = sceneLike || { tags: [], primitives: [], lights: [], groups: [] }; + return { + tags: Array.isArray(raw.tags) ? raw.tags : [], + primitives: Array.isArray(raw.primitives) ? raw.primitives : [], + lights: Array.isArray(raw.lights) ? raw.lights : [], + groups: Array.isArray(raw.groups) ? raw.groups : [], + }; +} + +function buildShapeStateRoot(state, assetId, fixedPivotCenter = null) { + const sceneState = normalizeShapeStateScene(state?.scene || state?.shapeScene); + const root = new THREE.Group(); + const primMap = new Map(); + for (const p of sceneState.primitives) { + const geom = createPrimitiveGeometry(p.type, p.dimensions || {}); + const mat = createPrimitiveMaterial(p.material || {}); + const mesh = new THREE.Mesh(geom, mat); + applyPrimitiveCutoutShader(mesh, p); + mesh.name = `assetPrim:${assetId}:${p.id || randId()}`; + mesh.userData.assetId = assetId; + mesh.userData.isAssetPrimitive = true; + mesh.castShadow = p.castShadow !== false; + mesh.receiveShadow = p.receiveShadow !== false; + const tr = p.transform || {}; + if (tr.position) mesh.position.set(tr.position.x || 0, tr.position.y || 0, tr.position.z || 0); + if (tr.rotation) mesh.rotation.set(tr.rotation.x || 0, tr.rotation.y || 0, tr.rotation.z || 0); + if (tr.scale) mesh.scale.set(tr.scale.x ?? 1, tr.scale.y ?? 1, tr.scale.z ?? 1); + root.add(mesh); + if (p.id) primMap.set(p.id, mesh); + } + for (const g of sceneState.groups || []) { + if (!Array.isArray(g.children) || g.children.length === 0) continue; + const subgroup = new THREE.Group(); + subgroup.name = `assetGroup:${assetId}:${g.id || randId()}`; + root.add(subgroup); + for (const cid of g.children) { + const child = primMap.get(cid); + if (!child) continue; + subgroup.add(child); + } + } + + // Re-center: move the pivot to the bounding-box center so the transform + // gizmo appears on the asset rather than at an arbitrary offset. + root.updateMatrixWorld(true); + const bbox = new THREE.Box3().setFromObject(root); + if (!bbox.isEmpty()) { + const autoCenter = bbox.getCenter(new THREE.Vector3()); + const center = fixedPivotCenter ? fixedPivotCenter.clone() : autoCenter; + for (const child of root.children) { + child.position.sub(center); + } + root.position.copy(center); + root.userData._pivotCenter = center.clone(); + } + + return root; +} + +function disposeShapeStateRoot(root) { + if (!root) return; + root.traverse((obj) => { + if (!obj?.isMesh) return; + obj.geometry?.dispose?.(); + disposePrimitiveMaterial(obj.material); + }); +} + +async function instantiateAsset(a) { + if (!a?.states) return; + const sId = a.currentStateId || a.currentState || (Array.isArray(a.states) ? a.states[0]?.id : "A"); + const state = Array.isArray(a.states) + ? a.states.find((s) => s.id === sId) || a.states[0] + : a.states[sId] || a.states.A; + let root = null; + if (state?.scene || state?.shapeScene) { + let fixedPivotCenter = null; + if (a._shapePivotCenter + && Number.isFinite(a._shapePivotCenter.x) + && Number.isFinite(a._shapePivotCenter.y) + && Number.isFinite(a._shapePivotCenter.z)) { + fixedPivotCenter = new THREE.Vector3(a._shapePivotCenter.x, a._shapePivotCenter.y, a._shapePivotCenter.z); + } else if (Array.isArray(a.states) && a.states.length > 0) { + const anchorState = a.states[0]; + const anchorRoot = buildShapeStateRoot(anchorState, `${a.id}:anchor`); + const anchorCenter = anchorRoot.userData?._pivotCenter; + if (anchorCenter) { + fixedPivotCenter = anchorCenter.clone(); + a._shapePivotCenter = { x: anchorCenter.x, y: anchorCenter.y, z: anchorCenter.z }; + } + disposeShapeStateRoot(anchorRoot); + } + root = buildShapeStateRoot(state, a.id, fixedPivotCenter); + const rootCenter = root.userData?._pivotCenter; + if (rootCenter && !a._shapePivotCenter) { + a._shapePivotCenter = { x: rootCenter.x, y: rootCenter.y, z: rootCenter.z }; + } + } else if (state?.dataBase64) { + const buf = arrayBufferFromBase64(state.dataBase64); + const url = URL.createObjectURL(new Blob([buf], { type: "model/gltf-binary" })); + const gltf = await new Promise((resolve, reject) => { + gltfLoader.load(url, (g) => resolve(g), undefined, (e) => reject(e)); + }); + URL.revokeObjectURL(url); + root = gltf.scene; + } else if (state?.glbUrl) { + // Cache by URL so library assets shared across N placed instances (e.g. + // 4 dining chairs pointing to the same file) parse once and share + // geometry+materials in memory. clone(true) deep-copies the node tree but + // reuses BufferGeometry/Material — standard Three.js instancing pattern. + let cached = _glbResultCache.get(state.glbUrl); + if (!cached) { + cached = await new Promise((resolve, reject) => { + gltfLoader.load(state.glbUrl, (g) => resolve(g), undefined, (e) => reject(e)); + }); + _glbResultCache.set(state.glbUrl, cached); + } + root = cached.scene.clone(true); + } else { + return; + } + root.name = `asset:${a.id}`; + const wantShadow = a.castShadow === true; // opt-in, default OFF + const wantReceive = a.receiveShadow === true; // opt-in, default OFF + + root.traverse((m) => { + if (m.isMesh) { + if (!m.userData?.isAssetPrimitive) m.castShadow = false; // GLB assets keep cheap shadow behavior + m.receiveShadow = wantReceive; + m.userData.assetId = a.id; + } + }); + + // Pre-compute local bounding sphere ONCE (cached — never call setFromObject again) + const bbox = new THREE.Box3().setFromObject(root); + const localSphere = new THREE.Sphere(); + bbox.getBoundingSphere(localSphere); + const localCenter = localSphere.center.clone(); + root.worldToLocal(localCenter); + root.userData._localSphereCenter = localCenter; + root.userData._localSphereRadius = Math.max(localSphere.radius, 0.2); + + // Blob shadow: a cheap flat gradient circle beneath the asset. + // Uses zero shadow-map resources — just a textured plane with transparency. + if (wantShadow) { + const bboxSize = bbox.getSize(new THREE.Vector3()); + const localGroundY = bbox.min.y + 0.005; + const blob = createBlobShadow(a.id, bboxSize.x, bboxSize.z, localGroundY, { + opacity: a.blobShadow?.opacity ?? 0.5, + scale: a.blobShadow?.scale ?? 1.0, + stretch: a.blobShadow?.stretch ?? 1.0, + rotationDeg: a.blobShadow?.rotationDeg ?? 0, + offsetX: a.blobShadow?.offsetX ?? 0, + offsetY: a.blobShadow?.offsetY ?? 0, + offsetZ: a.blobShadow?.offsetZ ?? 0, + }); + if (blob) root.add(blob); + } + + const tr = a.transform || {}; + if (tr.position) root.position.set(tr.position.x, tr.position.y, tr.position.z); + if (tr.rotation) root.rotation.set(tr.rotation.x, tr.rotation.y, tr.rotation.z); + if (tr.scale) root.scale.set(tr.scale.x, tr.scale.y, tr.scale.z); + assetsGroup.add(root); + await rebuildAssetCollider(a.id); +} + +async function setAssetState(assetId, nextState) { + const a = assets.find((x) => x.id === assetId); + if (!a) return; + const exists = Array.isArray(a.states) ? a.states.some((s) => s.id === nextState) : !!a.states?.[nextState]; + if (!exists) return; + a.currentStateId = nextState; + saveTagsForWorld(); + // Replace visual + const existing = assetsGroup.getObjectByName(`asset:${a.id}`); + if (existing?.parent) existing.parent.remove(existing); + await instantiateAsset(a); + renderAssetsList(); + selectAsset(a.id); +} + +async function applyAssetAction(assetId, actionId) { + const a = assets.find((x) => x.id === assetId); + if (!a) return false; + + const act = (a.actions || []).find((x) => x.id === actionId) || null; + if (!act) return false; + const cur = a.currentStateId || a.currentState || "A"; + if (cur !== act.from) return false; + await setAssetState(assetId, act.to); + return true; +} + +function getNearbyAssetsForAgent(agent, maxDist = 1.0) { + const [ax, ay, az] = agent.getPosition?.() || [0, 0, 0]; + const yaw = agent.group?.rotation?.y ?? 0; + const pitch = typeof agent.pitch === "number" ? agent.pitch : 0; + const cp = Math.cos(pitch); + const sp = Math.sin(pitch); + + // Full 3D forward direction (with pitch) - used for raycasting + const forward3D = _tmpV1.set(Math.sin(yaw) * cp, sp, Math.cos(yaw) * cp).normalize(); + + // Horizontal-only forward direction (yaw only, no pitch) - used for "in front" check + // BUG FIX: Previously used forward3D which includes pitch, causing dot product to be + // artificially reduced when looking up/down (cos(pitch) scaling factor) + const forwardHoriz = new THREE.Vector3(Math.sin(yaw), 0, Math.cos(yaw)).normalize(); + + const eye = _tmpV2.set(ax, ay + PLAYER_EYE_HEIGHT * 0.9, az); + + const results = []; + for (const a of assets) { + const obj = assetsGroup.getObjectByName(`asset:${a.id}`); + if (!obj) continue; + + // Use cached sphere center (O(1) — no vertex traversal) + const _agentSphere = new THREE.Sphere(); + if (!getAssetWorldSphere(obj, _agentSphere)) continue; + const center = _agentSphere.center; + + const dx = center.x - ax; + const dy = center.y - ay; + const dz = center.z - az; + const dist = Math.sqrt(dx * dx + dy * dy + dz * dz); + if (dist > maxDist) continue; + + // Horizontal direction to object (for "in front" check) + const toHoriz = _tmpV3.set(dx, 0, dz); + const horizLen = toHoriz.length() || 1; + toHoriz.multiplyScalar(1 / horizLen); + + // BUG FIX: Use horizontal forward for horizontal "in front" check + // Threshold relaxed from 0.92 (~23°) to 0.7 (~45°) for better usability + const inFrontHoriz = forwardHoriz.dot(toHoriz) > 0.7; + + let isLookedAt = false; + + // Debug: log for specific asset checks + const debugThis = a.title?.toLowerCase().includes('bathtub') || a.title?.toLowerCase().includes('tub'); + + if (debugThis) { + console.log(`[RAYCAST DEBUG] Checking "${a.title}" (${a.id})`); + console.log(` Eye position:`, eye.toArray().map(v => v.toFixed(2))); + console.log(` Object center:`, [center.x.toFixed(2), center.y.toFixed(2), center.z.toFixed(2)]); + console.log(` Forward3D:`, forward3D.toArray().map(v => v.toFixed(2))); + console.log(` ForwardHoriz:`, [forwardHoriz.x.toFixed(2), forwardHoriz.y.toFixed(2), forwardHoriz.z.toFixed(2)]); + console.log(` ToHoriz:`, [toHoriz.x.toFixed(2), toHoriz.y.toFixed(2), toHoriz.z.toFixed(2)]); + const dotVal = forwardHoriz.dot(toHoriz); + console.log(` Horiz dot product:`, dotVal.toFixed(3), `(need > 0.7 for inFront, > 0.3 for proximity)`); + console.log(` inFrontHoriz (>0.7):`, inFrontHoriz); + console.log(` roughlyInFront (>0.3):`, dotVal > 0.3); + } + + // For interaction purposes, we use a very lenient "roughly in front" check + // The bounding box center can be off to the side for wide objects + const roughlyInFront = forwardHoriz.dot(toHoriz) > 0.3; // ~72° cone + + if (inFrontHoriz || roughlyInFront) { + // Cheap bounding-sphere ray test instead of expensive recursive mesh raycast + const objNode = assetsGroup.getObjectByName(`asset:${a.id}`); + if (objNode) { + const _tmpSphere = new THREE.Sphere(); + if (!getAssetWorldSphere(objNode, _tmpSphere)) { /* skip */ } + _tmpSphere.radius = Math.max(_tmpSphere.radius, 0.3); + + // Test look direction against bounding sphere + const lookRay = new THREE.Ray(eye, forward3D); + if (lookRay.intersectsSphere(_tmpSphere)) { + isLookedAt = true; + } + + // Also test toward center direction (catches pitch misalignment) + if (!isLookedAt) { + const toCenter = new THREE.Vector3( + center.x - eye.x, center.y - eye.y, center.z - eye.z + ).normalize(); + const lookAlignment = forward3D.dot(toCenter); + if (lookAlignment > 0.5) { + const centerRay = new THREE.Ray(eye, toCenter); + if (centerRay.intersectsSphere(_tmpSphere)) { + isLookedAt = true; + } + } + } + } + } + + // Method 3: If close enough and roughly in front, allow interaction even if raycast fails + // This handles cases where: + // - Mesh geometry doesn't raycast well + // - Wide objects have their center off to the side + if (!isLookedAt && dist < 1.5 && roughlyInFront) { + if (debugThis) { + console.log(` Method 3 (proximity fallback): dist=${dist.toFixed(2)}, roughlyInFront=${roughlyInFront}`); + } + isLookedAt = true; + } + + if (debugThis) { + console.log(` Final isLookedAt:`, isLookedAt); + } + + const stateKey = a.currentStateId || a.currentState || "A"; + const stateObj = Array.isArray(a.states) + ? a.states.find((s) => s.id === stateKey) + : a.states?.[stateKey]; + const stateName = stateObj?.name || stateKey; + const holdStatus = isAssetHeld(a.id); + results.push({ + id: a.id, + title: a.title || "", + notes: a.notes || "", + dist, + isLookedAt, + currentState: stateKey, + currentStateName: stateName, + actions: (a.actions || []).filter((x) => x.from === stateKey).map((x) => ({ id: x.id, label: x.label, from: x.from, to: x.to })), + pickable: a.pickable || false, + isHeld: holdStatus.held, + heldBy: holdStatus.by || null, + }); + } + + results.sort((a, b) => a.dist - b.dist); + return results.slice(0, 20); +} + +function getNearbyPrimitivesForAgent(agent, maxDist = 2.5) { + const [ax, ay, az] = agent.getPosition?.() || [0, 0, 0]; + const yaw = agent.group?.rotation?.y ?? 0; + const pitch = typeof agent.pitch === "number" ? agent.pitch : 0; + const cp = Math.cos(pitch); + const sp = Math.sin(pitch); + const forward3D = _tmpV1.set(Math.sin(yaw) * cp, sp, Math.cos(yaw) * cp).normalize(); + const forwardHoriz = _tmpV2.set(Math.sin(yaw), 0, Math.cos(yaw)).normalize(); + const eye = _tmpV3.set(ax, ay + PLAYER_EYE_HEIGHT * 0.9, az); + + const out = []; + for (const p of primitives) { + const obj = primitivesGroup.getObjectByName(`prim:${p.id}`); + if (!obj) continue; + const center = obj.getWorldPosition(new THREE.Vector3()); + const dx = center.x - ax; + const dy = center.y - ay; + const dz = center.z - az; + const dist = Math.hypot(dx, dy, dz); + if (dist > maxDist) continue; + + const toObj = new THREE.Vector3(center.x - eye.x, center.y - eye.y, center.z - eye.z).normalize(); + const toHoriz = new THREE.Vector3(dx, 0, dz); + const horizLen = toHoriz.length() || 1; + toHoriz.multiplyScalar(1 / horizLen); + const lookAlignment = forward3D.dot(toObj); + const horizAlignment = forwardHoriz.dot(toHoriz); + const isLookedAt = lookAlignment > 0.82 || (dist < 1.6 && horizAlignment > 0.35); + + out.push({ + id: p.id, + name: p.name || p.type || "primitive", + type: p.type || "primitive", + dist, + isLookedAt, + }); + } + out.sort((a, b) => a.dist - b.dist); + return out.slice(0, 20); +} + + +async function agentInteractAsset({ agent, assetId, actionId }) { + console.log(`[INTERACT] Attempting interaction: assetId="${assetId}", actionId="${actionId}"`); + + const candidates = getNearbyAssetsForAgent(agent, 1.5); // Interaction distance + + // Debug: if no candidates, show what assets exist + if (candidates.length === 0) { + const [ax, ay, az] = agent.getPosition?.() || [0, 0, 0]; + console.log(`[INTERACT] Agent position:`, [ax.toFixed(2), ay.toFixed(2), az.toFixed(2)]); + console.log(`[INTERACT] All assets in scene:`, assets.map(a => { + const obj = assetsGroup.getObjectByName(`asset:${a.id}`); + if (!obj) return { id: a.id, title: a.title, inScene: false }; + const _ds = new THREE.Sphere(); + getAssetWorldSphere(obj, _ds); + const center = _ds.center; + const dx = center.x - ax; + const dy = center.y - ay; + const dz = center.z - az; + const dist = Math.sqrt(dx * dx + dy * dy + dz * dz); + return { id: a.id, title: a.title, dist: dist.toFixed(2), center: [center.x.toFixed(2), center.y.toFixed(2), center.z.toFixed(2)] }; + })); + } + + console.log(`[INTERACT] Nearby candidates:`, candidates.map(c => ({ + id: c.id, + title: c.title, + dist: c.dist.toFixed(2), + isLookedAt: c.isLookedAt, + currentState: c.currentState, + actions: c.actions.map(a => `${a.id}:${a.label}`) + }))); + + const target = candidates.find((x) => x.id === assetId); + if (!target) { + console.warn(`[INTERACT] FAIL: Asset "${assetId}" not in nearby candidates`); + return { ok: false, reason: "not-nearby" }; + } + + console.log(`[INTERACT] Found target: dist=${target.dist.toFixed(2)}m, isLookedAt=${target.isLookedAt}, currentState=${target.currentState}`); + + if (!target.isLookedAt && target.dist > 1.2) { + console.warn(`[INTERACT] FAIL: Asset "${assetId}" not looked at (isLookedAt=false)`); + return { ok: false, reason: "not-looking" }; + } + if (!target.isLookedAt && target.dist <= 1.2) { + console.log(`[INTERACT] Allowing close-range interaction despite look mismatch (dist=${target.dist.toFixed(2)}m).`); + } + + // Check if the actionId exists in the target's available actions + const availableAction = target.actions.find(a => a.id === actionId); + if (!availableAction) { + console.warn(`[INTERACT] actionId "${actionId}" not in available actions:`, target.actions); + // Try to find by label instead + const byLabel = target.actions.find(a => a.label?.toLowerCase() === actionId?.toLowerCase()); + if (byLabel) { + console.log(`[INTERACT] Found action by label match: "${byLabel.id}"`); + actionId = byLabel.id; + } + } + + const ok = await applyAssetAction(assetId, actionId); + console.log(`[INTERACT] applyAssetAction result: ${ok}`); + + if (!ok) { + // Diagnose why it failed + const asset = assets.find(a => a.id === assetId); + if (asset) { + const curState = asset.currentStateId || asset.currentState || "A"; + const allActions = asset.actions || []; + const matchingAction = allActions.find(a => a.id === actionId); + console.warn(`[INTERACT] applyAssetAction FAILED diagnosis:`, { + currentState: curState, + requestedActionId: actionId, + actionFound: !!matchingAction, + actionFromState: matchingAction?.from, + actionToState: matchingAction?.to, + fromMatchesCurrent: matchingAction?.from === curState, + allActionIds: allActions.map(a => `${a.id}(${a.from}->${a.to})`) + }); + } + } + + return { ok, reason: ok ? "ok" : "invalid-action" }; +} + +// ============================================================================ +// PLAYER INTERACTION SYSTEM +// ============================================================================ +const PLAYER_INTERACT_DISTANCE = 1.5; // Max distance player can interact with assets +const _playerInteractRaycaster = new THREE.Raycaster(); +let _interactionPopup = null; +let _currentInteractableAsset = null; +let _crosshairInteractCycleIndex = 0; +let _crosshairInteractCycleSig = ""; +let _crosshairInteractCandidates = []; + +// ============================================================================ +// PICK UP / DROP SYSTEM +// ============================================================================ +let playerHeldAsset = null; // Asset ID currently held by player +let playerHeldGroupId = null; // Group ID currently held by player +const agentHeldAssets = new Map(); // Map - assets held by each agent + +/** + * Check if an asset is currently being held by anyone + */ +function isAssetHeld(assetId) { + if (playerHeldAsset === assetId) return { held: true, by: "player" }; + for (const [agentId, heldId] of agentHeldAssets.entries()) { + if (heldId === assetId) return { held: true, by: "agent", agentId }; + } + return { held: false }; +} + +function isGroupHeld(groupId) { + if (playerHeldGroupId === groupId) return { held: true, by: "player" }; + return { held: false }; +} + +function getGroupById(groupId) { + return groups.find((g) => g.id === groupId) || null; +} + +function getGroupCentroid(groupId) { + const g = getGroupById(groupId); + if (!g || !Array.isArray(g.children) || g.children.length === 0) return null; + let cx = 0, cy = 0, cz = 0, count = 0; + for (const cid of g.children) { + const p = primitives.find((x) => x.id === cid); + const pos = p?.transform?.position; + if (!pos) continue; + cx += pos.x || 0; + cy += pos.y || 0; + cz += pos.z || 0; + count++; + } + if (count === 0) return null; + return { x: cx / count, y: cy / count, z: cz / count }; +} + +function playerPickUpGroup(groupId) { + const g = getGroupById(groupId); + if (!g) return { ok: false, reason: "not-found" }; + if (!g.pickable) return { ok: false, reason: "not-pickable" }; + if (playerHeldAsset || playerHeldGroupId) return { ok: false, reason: "hands-full" }; + const holdStatus = isGroupHeld(groupId); + if (holdStatus.held) return { ok: false, reason: "already-held", by: holdStatus.by }; + + playerHeldGroupId = groupId; + for (const cid of g.children || []) { + const mesh = primitivesGroup.getObjectByName(`prim:${cid}`); + if (mesh) mesh.visible = false; + const prim = primitives.find((p) => p.id === cid); + if (prim) removePrimitiveCollider(prim); + } + setStatus(`Picked up group: ${g.name || "group"}`); + return { ok: true }; +} + +function playerDropGroup() { + if (!playerHeldGroupId) return { ok: false, reason: "not-holding" }; + const g = getGroupById(playerHeldGroupId); + if (!g) { + playerHeldGroupId = null; + return { ok: false, reason: "not-found" }; + } + const centroid = getGroupCentroid(g.id); + if (!centroid) { + playerHeldGroupId = null; + return { ok: false, reason: "invalid-group" }; + } + // Raycast from crosshair to find drop point + const dropRay = new THREE.Raycaster(); + dropRay.setFromCamera({ x: 0, y: 0 }, camera); + dropRay.far = 6; + const candidates = []; + // Exclude held group's own meshes + const heldChildSet = new Set(g.children || []); + primitivesGroup.traverse((c) => { + if (c.isMesh && !heldChildSet.has(c.name?.replace("prim:", ""))) candidates.push(c); + }); + assetsGroup.traverse((c) => { if (c.isMesh) candidates.push(c); }); + scene.traverse((c) => { + if (c.isMesh && !candidates.includes(c) && c.parent !== assetsGroup && c.parent !== primitivesGroup) candidates.push(c); + }); + const hits = dropRay.intersectObjects(candidates, false); + let dropPos; + if (hits.length > 0) { + dropPos = { x: hits[0].point.x, y: hits[0].point.y, z: hits[0].point.z }; + } else { + const forward = new THREE.Vector3(); + camera.getWorldDirection(forward); + dropPos = { + x: camera.position.x + forward.x * 1.5, + y: 0, + z: camera.position.z + forward.z * 1.5, + }; + } + const dx = dropPos.x - centroid.x; + const dz = dropPos.z - centroid.z; + for (const cid of g.children || []) { + const prim = primitives.find((p) => p.id === cid); + if (!prim?.transform?.position) continue; + prim.transform.position.x += dx; + prim.transform.position.z += dz; + const mesh = primitivesGroup.getObjectByName(`prim:${cid}`); + if (mesh) { + mesh.position.x = prim.transform.position.x; + mesh.position.y = prim.transform.position.y; + mesh.position.z = prim.transform.position.z; + mesh.visible = true; + } + rebuildPrimitiveColliderSync(prim); + } + const droppedId = playerHeldGroupId; + playerHeldGroupId = null; + saveTagsForWorld(); + setStatus(`Dropped group: ${g.name || "group"}`); + return { ok: true, groupId: droppedId }; +} + +/** + * Pick up an asset (for player) + */ +function playerPickUpAsset(assetId) { + const asset = assets.find(a => a.id === assetId); + if (!asset) return { ok: false, reason: "not-found" }; + if (!asset.pickable) return { ok: false, reason: "not-pickable" }; + + const holdStatus = isAssetHeld(assetId); + if (holdStatus.held) return { ok: false, reason: "already-held", by: holdStatus.by }; + + if (playerHeldAsset) return { ok: false, reason: "hands-full" }; + + playerHeldAsset = assetId; + + // Hide the asset from the scene (it's now "in hand") + const obj = assetsGroup.getObjectByName(`asset:${assetId}`); + if (obj) obj.visible = false; + + // Remove collider while held + removeAssetCollider(assetId); + + console.log(`[PICKUP] Player picked up: ${asset.title || assetId}`); + setStatus(`Picked up: ${asset.title || "item"}`); + return { ok: true }; +} + +/** + * Drop the held asset (for player) + */ +function playerDropAsset() { + if (!playerHeldAsset) return { ok: false, reason: "not-holding" }; + + const asset = assets.find(a => a.id === playerHeldAsset); + if (!asset) { + playerHeldAsset = null; + return { ok: false, reason: "not-found" }; + } + + // Raycast from crosshair to find where the player is looking + const dropRay = new THREE.Raycaster(); + dropRay.setFromCamera({ x: 0, y: 0 }, camera); + dropRay.far = 6; + // Collect all scene meshes except the held asset itself + const candidates = []; + primitivesGroup.traverse((c) => { if (c.isMesh) candidates.push(c); }); + assetsGroup.traverse((c) => { + if (c.isMesh && !c.name?.includes(playerHeldAsset)) candidates.push(c); + }); + // Also include splat / collision meshes if any + scene.traverse((c) => { + if (c.isMesh && !candidates.includes(c) && c.parent !== assetsGroup && c.parent !== primitivesGroup) candidates.push(c); + }); + const hits = dropRay.intersectObjects(candidates, false); + let dropPos; + if (hits.length > 0) { + // Place at the hit point + dropPos = hits[0].point.clone(); + } else { + // Fallback: fixed distance along look direction, at ground level + const forward = new THREE.Vector3(); + camera.getWorldDirection(forward); + const fallbackDist = 1.5; + dropPos = new THREE.Vector3( + camera.position.x + forward.x * fallbackDist, + 0, + camera.position.z + forward.z * fallbackDist + ); + } + + // Update asset transform + asset.transform.position = { x: dropPos.x, y: dropPos.y, z: dropPos.z }; + + // Show and reposition the asset — traverse to ensure all children are visible + const obj = assetsGroup.getObjectByName(`asset:${playerHeldAsset}`); + if (obj) { + obj.position.copy(dropPos); + obj.visible = true; + obj.traverse((child) => { child.visible = true; }); + } else { + // Object was lost — re-instantiate from asset data + console.warn(`[DROP] 3D object missing for ${playerHeldAsset}, re-instantiating...`); + instantiateAsset(asset); + } + + // Rebuild collider + rebuildAssetCollider(playerHeldAsset); + + console.log(`[DROP] Player dropped: ${asset.title || playerHeldAsset}`); + setStatus(`Dropped: ${asset.title || "item"}`); + + const droppedId = playerHeldAsset; + playerHeldAsset = null; + saveTagsForWorld(); + + return { ok: true, assetId: droppedId }; +} + +/** + * Pick up an asset (for AI agent) + */ +function agentPickUpAsset(agent, assetId) { + const agentId = agent.id || "default"; + const asset = assets.find(a => a.id === assetId); + + if (!asset) return { ok: false, reason: "not-found" }; + if (!asset.pickable) return { ok: false, reason: "not-pickable" }; + + const holdStatus = isAssetHeld(assetId); + if (holdStatus.held) return { ok: false, reason: "already-held", by: holdStatus.by }; + + if (agentHeldAssets.has(agentId)) return { ok: false, reason: "hands-full" }; + + // Check distance + const [ax, ay, az] = agent.getPosition?.() || [0, 0, 0]; + const obj = assetsGroup.getObjectByName(`asset:${assetId}`); + if (obj) { + const _pickSphere = new THREE.Sphere(); + getAssetWorldSphere(obj, _pickSphere); + const center = _pickSphere.center; + const dist = Math.sqrt( + Math.pow(center.x - ax, 2) + + Math.pow(center.y - ay, 2) + + Math.pow(center.z - az, 2) + ); + if (dist > 1.5) return { ok: false, reason: "too-far", dist }; + } + + agentHeldAssets.set(agentId, assetId); + + // Hide the asset from the scene + if (obj) obj.visible = false; + + // Remove collider while held + removeAssetCollider(assetId); + + console.log(`[PICKUP] Agent ${agentId} picked up: ${asset.title || assetId}`); + return { ok: true }; +} + +/** + * Drop the held asset (for AI agent) + */ +function agentDropAsset(agent) { + const agentId = agent.id || "default"; + const assetId = agentHeldAssets.get(agentId); + + if (!assetId) return { ok: false, reason: "not-holding" }; + + const asset = assets.find(a => a.id === assetId); + if (!asset) { + agentHeldAssets.delete(agentId); + return { ok: false, reason: "not-found" }; + } + + // Calculate drop position (in front of agent) + const [ax, ay, az] = agent.getPosition?.() || [0, 0, 0]; + const yaw = agent.group?.rotation?.y ?? 0; + const dropDist = 0.6; + + const dropPos = new THREE.Vector3( + ax + Math.sin(yaw) * dropDist, + ay + 0.1, // Slightly above ground + az + Math.cos(yaw) * dropDist + ); + + // Update asset transform + asset.transform.position = { x: dropPos.x, y: dropPos.y, z: dropPos.z }; + + // Show and reposition the asset + const obj = assetsGroup.getObjectByName(`asset:${assetId}`); + if (obj) { + obj.position.copy(dropPos); + obj.visible = true; + } + + // Rebuild collider + rebuildAssetCollider(assetId); + + console.log(`[DROP] Agent ${agentId} dropped: ${asset.title || assetId}`); + + agentHeldAssets.delete(agentId); + saveTagsForWorld(); + + return { ok: true, assetId }; +} + +/** + * Remove collider for an asset (when picked up) + */ +function removeAssetCollider(assetId) { + const handle = _assetColliderHandles.get(assetId); + if (handle != null && rapierWorld) { + const collider = rapierWorld.getCollider(handle); + if (collider) rapierWorld.removeCollider(collider, true); + _assetColliderHandles.delete(assetId); + } +} + +/** + * Get what the player is currently holding + */ +function getPlayerHeldAsset() { + if (!playerHeldAsset) return null; + return assets.find(a => a.id === playerHeldAsset) || null; +} + +/** + * Get what an agent is currently holding + */ +function getAgentHeldAsset(agent) { + const agentId = agent.id || "default"; + const assetId = agentHeldAssets.get(agentId); + if (!assetId) return null; + return assets.find(a => a.id === assetId) || null; +} + +/** + * Get the interactable asset at the player's crosshair (center of screen). + * Returns { asset, actions, dist, canPickUp } if found, or null if nothing interactable. + */ +const _hintRayOrigin = new THREE.Vector3(); +const _hintRayDir = new THREE.Vector3(); +const _hintTmpSphere = new THREE.Sphere(); +const _hintRay = new THREE.Ray(); +const _cachedSphereCenter = new THREE.Vector3(); + +// Get the world-space bounding sphere of an asset from its cached local data. +// This is O(1) — no vertex traversal, just one matrix-vector multiply. +function getAssetWorldSphere(obj, outSphere) { + const lc = obj.userData._localSphereCenter; + const lr = obj.userData._localSphereRadius; + if (lc && lr) { + _cachedSphereCenter.copy(lc); + obj.localToWorld(_cachedSphereCenter); + const scale = obj.matrixWorld.getMaxScaleOnAxis(); + outSphere.set(_cachedSphereCenter, lr * scale); + return true; + } + return false; +} + +function getInteractableAssetCandidatesAtCrosshair() { + if (!camera) return []; + camera.getWorldPosition(_hintRayOrigin); + camera.getWorldDirection(_hintRayDir); + _hintRay.set(_hintRayOrigin, _hintRayDir); + + const maxDist = PLAYER_INTERACT_DISTANCE + 0.8; + const candidates = []; + for (const child of assetsGroup.children) { + const aid = child.name?.startsWith("asset:") ? child.name.slice(6) : null; + if (!aid) continue; + if (!getAssetWorldSphere(child, _hintTmpSphere)) continue; + _hintTmpSphere.radius = Math.max(_hintTmpSphere.radius, 0.3); + const centerDist = _hintRayOrigin.distanceTo(_hintTmpSphere.center); + if (centerDist > maxDist + _hintTmpSphere.radius) continue; + const hitPoint = _hintRay.intersectSphere(_hintTmpSphere, _tmpV1); + if (!hitPoint) continue; + const d = _hintRayOrigin.distanceTo(hitPoint); + if (d > maxDist) continue; + const toCenter = _tmpV2.copy(_hintTmpSphere.center).sub(_hintRayOrigin).normalize(); + const aim = Math.max(0, _hintRayDir.dot(toCenter)); + const score = aim * 4.0 - d * 0.45; + candidates.push({ id: aid, dist: d, aim, score }); + } + candidates.sort((a, b) => (b.score - a.score) || (a.dist - b.dist)); + return candidates.slice(0, 6); +} + +function cycleInteractableTarget(step = 1) { + const candidates = getInteractableAssetCandidatesAtCrosshair(); + if (!Array.isArray(candidates) || candidates.length <= 1) return false; + const sig = candidates.map((c) => c.id).join("|"); + if (sig !== _crosshairInteractCycleSig) { + _crosshairInteractCycleSig = sig; + _crosshairInteractCycleIndex = 0; + } + const len = candidates.length; + _crosshairInteractCycleIndex = (_crosshairInteractCycleIndex + step + len) % len; + _crosshairInteractCandidates = candidates; + return true; +} + +function getInteractableAssetAtCrosshair() { + const candidates = getInteractableAssetCandidatesAtCrosshair(); + const sig = candidates.map((c) => c.id).join("|"); + if (sig !== _crosshairInteractCycleSig) { + _crosshairInteractCycleSig = sig; + _crosshairInteractCycleIndex = 0; + } + _crosshairInteractCandidates = candidates; + const primary = candidates[_crosshairInteractCycleIndex] || null; + + if (!primary) { + // Fallback: pickable grouped shape assets + _playerInteractRaycaster.setFromCamera({ x: 0, y: 0 }, camera); + const hits = _playerInteractRaycaster.intersectObjects(primitivesGroup.children, false); + for (const hit of hits) { + if (hit.distance > PLAYER_INTERACT_DISTANCE + 0.5) continue; + const name = hit.object?.name || ""; + const m = name.match(/^prim:(.+)$/); + if (!m) continue; + const primId = m[1]; + const g = groups.find((gr) => (gr.children || []).includes(primId) && gr.pickable); + if (!g) continue; + const canPickUp = !playerHeldAsset && !playerHeldGroupId && !isGroupHeld(g.id).held; + return { kind: "group", group: g, actions: [], dist: hit.distance, canPickUp }; + } + return null; + } + + const asset = assets.find((a) => a.id === primary.id); + if (!asset) return null; + + const currentState = asset.currentStateId || asset.currentState || "A"; + const actions = (asset.actions || []).filter((act) => act.from === currentState); + const holdStatus = isAssetHeld(primary.id); + const canPickUp = asset.pickable && !holdStatus.held && !playerHeldAsset && !playerHeldGroupId; + + if (actions.length === 0 && !canPickUp) return null; + + return { + kind: "asset", + asset, + actions, + dist: primary.dist, + canPickUp, + candidateIndex: _crosshairInteractCycleIndex, + candidateCount: candidates.length, + }; +} + +/** + * Create or get the interaction popup element + */ +function getInteractionPopup() { + if (_interactionPopup) return _interactionPopup; + + _interactionPopup = document.createElement("div"); + _interactionPopup.id = "interaction-popup"; + // Styles are now in CSS, just set display none initially + _interactionPopup.style.display = "none"; + document.body.appendChild(_interactionPopup); + return _interactionPopup; +} + +/** + * Show the interaction popup with available actions + */ +function showInteractionPopup(asset, actions) { + const popup = getInteractionPopup(); + + // Build popup content + const title = asset.title || "(asset)"; + const stateObj = Array.isArray(asset.states) + ? asset.states.find((s) => s.id === (asset.currentStateId || asset.currentState)) + : null; + const stateName = stateObj?.name || ""; + + let html = `
${escapeHtml(title)}${stateName ? ` · ${escapeHtml(stateName)}` : ""}
`; + + actions.forEach((act, idx) => { + html += ``; + }); + + html += `
Press 1-${actions.length} or click · Esc to cancel
`; + + popup.innerHTML = html; + popup.style.display = "flex"; + _currentInteractableAsset = { asset, actions }; + + // Add click handlers to buttons + popup.querySelectorAll(".interact-action-btn").forEach((btn) => { + btn.addEventListener("click", async (e) => { + e.stopPropagation(); + const actionId = btn.getAttribute("data-action-id"); + + // Hide popup first + hideInteractionPopup(); + + // Execute the action + if (actionId === "__PICK_UP__") { + playerPickUpAsset(asset.id); + } else { + await executePlayerInteraction(asset.id, actionId); + } + + // Re-lock pointer after a short delay (click events can re-lock) + setTimeout(() => { + try { + controls?.lock?.(); + } catch (err) { + // Ignore + } + }, 50); + }); + // Hover effects handled in CSS + }); +} + +/** + * Hide the interaction popup + */ +function hideInteractionPopup() { + if (_interactionPopup) { + _interactionPopup.style.display = "none"; + } + _currentInteractableAsset = null; +} + +/** + * Check if interaction popup is visible + */ +function isInteractionPopupVisible() { + return _interactionPopup?.style.display === "flex"; +} + +/** + * Execute a player interaction with an asset + */ +async function executePlayerInteraction(assetId, actionId) { + // Handle special pick up action + if (actionId === "__PICK_UP__") { + const result = playerPickUpAsset(assetId); + return result.ok; + } + + const asset = assets.find((a) => a.id === assetId); + if (!asset) { + setStatus("Asset not found."); + return false; + } + + const action = (asset.actions || []).find((a) => a.id === actionId); + if (!action) { + setStatus("Action not available."); + return false; + } + + const ok = await applyAssetAction(assetId, actionId); + if (ok) { + setStatus(`${action.label || "Interacted"}: ${asset.title || "asset"}`); + } else { + setStatus("Interaction failed."); + } + return ok; +} + +/** + * Handle player interaction attempt (click or E key) + */ +async function handlePlayerInteraction() { + // If popup is already showing, do nothing (let popup handle it) + if (isInteractionPopupVisible()) { + return; + } + + // First, check if player is holding something - pressing E drops it + if (playerHeldAsset) { + playerDropAsset(); + return; + } + if (playerHeldGroupId) { + playerDropGroup(); + return; + } + + const target = getInteractableAssetAtCrosshair(); + if (!target) { + // No interactable asset at crosshair + return; + } + + const { kind, asset, group, actions, dist, canPickUp } = target; + if (kind === "group") { + if (canPickUp) playerPickUpGroup(group.id); + return; + } + + // Build combined action list (regular actions + pick up if available) + const combinedActions = [...actions]; + if (canPickUp) { + combinedActions.push({ id: "__PICK_UP__", label: "Pick up", special: true }); + } + + if (combinedActions.length === 1) { + // Single action - execute immediately + if (combinedActions[0].id === "__PICK_UP__") { + playerPickUpAsset(asset.id); + } else { + await executePlayerInteraction(asset.id, combinedActions[0].id); + } + } else if (combinedActions.length > 1) { + // Multiple actions - show selection popup + // Temporarily unlock pointer to allow clicking popup + controls?.unlock?.(); + showInteractionPopup(asset, combinedActions); + } +} + +// ============================================================================ +// END PLAYER INTERACTION SYSTEM +// ============================================================================ + +function deleteSelectedAsset() { + const a = getSelectedAsset(); + if (!a) return; + // remove collider + if (a._colliderHandle != null) { + try { + rapierWorld?.removeCollider?.(a._colliderHandle, true); + } catch {} + } + // remove visual + const obj = assetsGroup.getObjectByName(`asset:${a.id}`); + if (obj?.parent) obj.parent.remove(obj); + _assetBumpVelocities.delete(a.id); + assets = assets.filter((x) => x.id !== a.id); + selectedAssetId = null; + saveTagsForWorld(); + renderAssetsList(); + setStatus("Asset deleted."); +} + +async function interactSelectedAssetDebug() { + const a = getSelectedAsset(); + if (!a) return; + const state = a.currentStateId || a.currentState || "A"; + const outgoing = (a.actions || []).filter((x) => x.from === state); + const act = outgoing[0] || null; + if (!act) { + setStatus("Selected asset has no valid action from its current state."); + return; + } + const ok = await applyAssetAction(a.id, act.id); + setStatus(ok ? `Asset interacted: ${act.label}` : "Asset interaction failed."); +} + +function _newId(prefix) { + return `${prefix}${Date.now().toString(16)}${Math.random().toString(16).slice(2, 6)}`; +} + +function _cloneAssetWithFreshIds(src) { + // Ensure latest schema and interactions exist + const a = normalizeAsset(structuredClone ? structuredClone(src) : JSON.parse(JSON.stringify(src))); + + const newAssetId = _newId("asset_"); + const stateIdMap = new Map(); + const newStates = []; + + for (const s of a.states || []) { + const newSid = _newId("s"); + stateIdMap.set(s.id, newSid); + newStates.push({ + id: newSid, + name: s.name || "", + glbName: s.glbName || "", + dataBase64: s.dataBase64 || "", + interactions: [], + }); + } + + // Copy interactions (and rewrite state ids) + for (const s of a.states || []) { + const fromNew = stateIdMap.get(s.id); + const dstState = newStates.find((x) => x.id === fromNew); + if (!dstState) continue; + const ints = Array.isArray(s.interactions) ? s.interactions : []; + dstState.interactions = ints + .map((it) => ({ + id: _newId("it_"), + label: it.label || "toggle", + to: stateIdMap.get(it.to) || stateIdMap.get(s.id) || fromNew, + })) + .filter((it) => it.to && it.to !== fromNew); + } + + const curOld = a.currentStateId || a.currentState || (a.states?.[0]?.id ?? null); + const curNew = stateIdMap.get(curOld) || newStates[0]?.id || null; + + // Offset placement slightly forward so it doesn't overlap + let transform = a.transform ? structuredClone(a.transform) : null; + const obj = assetsGroup.getObjectByName(`asset:${src.id}`); + if (!transform) { + transform = { position: { x: 0, y: 0, z: 0 }, rotation: { x: 0, y: 0, z: 0 }, scale: { x: 1, y: 1, z: 1 } }; + } + if (obj) { + transform.position = { x: obj.position.x, y: obj.position.y, z: obj.position.z }; + transform.rotation = { x: obj.rotation.x, y: obj.rotation.y, z: obj.rotation.z }; + transform.scale = { x: obj.scale.x, y: obj.scale.y, z: obj.scale.z }; + } else { + transform.position = transform.position || { x: 0, y: 0, z: 0 }; + transform.rotation = transform.rotation || { x: 0, y: 0, z: 0 }; + transform.scale = transform.scale || { x: 1, y: 1, z: 1 }; + } + const fwd = new THREE.Vector3(); + camera.getWorldDirection(fwd); + const offset = 0.7; + transform.position.x += fwd.x * offset; + transform.position.y += fwd.y * offset; + transform.position.z += fwd.z * offset; + + const duplicated = { + id: newAssetId, + title: (src.title || "").trim() ? `${src.title} (copy)` : "Asset (copy)", + notes: src.notes || "", + states: newStates, + currentStateId: curNew, + transform, + actions: [], + _colliderHandle: null, + }; + + // Build actions from interactions for runtime/agent/debug use + duplicated.actions = []; + for (const s of duplicated.states) { + for (const it of s.interactions || []) { + duplicated.actions.push({ id: it.id, label: it.label, from: s.id, to: it.to }); + } + } + + return duplicated; +} + +async function duplicateSelectedAsset() { + const a = getSelectedAsset(); + if (!a) return; + const dup = _cloneAssetWithFreshIds(a); + assets.push(dup); + saveTagsForWorld(); + await instantiateAsset(dup); + renderAssetsList(); + selectAsset(dup.id); + setStatus("Asset duplicated."); +} + +async function buildRapierTriMeshColliderFromObject(obj) { + await ensureRapierLoaded(); + const verts = []; + const indices = []; + let vertBase = 0; + const tmpPos = new THREE.Vector3(); + obj.updateMatrixWorld(true); + + obj.traverse((m) => { + if (!m.isMesh) return; + const geom = m.geometry; + const posAttr = geom?.attributes?.position; + if (!posAttr) return; + const indexAttr = geom.index; + const matWorld = m.matrixWorld; + + for (let i = 0; i < posAttr.count; i++) { + tmpPos.fromBufferAttribute(posAttr, i).applyMatrix4(matWorld); + verts.push(tmpPos.x, tmpPos.y, tmpPos.z); + } + + if (indexAttr) { + for (let i = 0; i < indexAttr.count; i++) indices.push(indexAttr.getX(i) + vertBase); + } else { + for (let i = 0; i < posAttr.count; i++) indices.push(vertBase + i); + } + vertBase += posAttr.count; + }); + + if (verts.length < 9 || indices.length < 3) return null; + const desc = RAPIER.ColliderDesc.trimesh(verts, indices).setFriction(0.9); + return rapierWorld.createCollider(desc); +} + +async function rebuildAssetCollider(assetId) { + const a = assets.find((x) => x.id === assetId); + if (!a) return; + await ensureRapierLoaded(); + if (!rapierWorld || !RAPIER) return; + + // Remove existing collider + if (a._colliderHandle != null) { + try { + if (typeof a._colliderHandle === 'object' && a._colliderHandle.handle !== undefined) { + rapierWorld.removeCollider(a._colliderHandle, true); + } + } catch (e) { + console.warn(`[COLLIDER] Failed to remove collider for ${assetId}:`, e); + } + a._colliderHandle = null; + } + + const obj = assetsGroup.getObjectByName(`asset:${assetId}`); + if (!obj) return; + const collider = await buildRapierTriMeshColliderFromObject(obj); + if (collider) { + a._colliderHandle = collider; + } +} + +function removeAssetColliderHandle(asset) { + if (!asset || asset._colliderHandle == null || !rapierWorld) return; + try { + if (typeof asset._colliderHandle === "object" && asset._colliderHandle.handle !== undefined) { + rapierWorld.removeCollider(asset._colliderHandle, true); + } + } catch (e) { + console.warn(`[COLLIDER] Failed to remove collider for ${asset.id}:`, e); + } + asset._colliderHandle = null; +} + +async function rebuildAssets() { + while (assetsGroup.children.length) assetsGroup.remove(assetsGroup.children[0]); + for (const a of assets) { + try { + await instantiateAsset(a); + } catch (e) { + console.warn("Failed to rebuild asset", a?.glb?.name, e); + } + } + selectAsset(selectedAssetId); +} + +// ============================================================================= +// PRIMITIVES – Parametric Shape System (Level Editor) +// ============================================================================= + +function createPrimitiveGeometry(type, dims) { + dims = dims || {}; + const num = (v, fallback) => { + const n = Number(v); + return Number.isFinite(n) ? n : fallback; + }; + const degToRad = (deg, fallback = 0) => (Number.isFinite(deg) ? deg : fallback) * Math.PI / 180; + const clampInt = (v, fallback, min = 1) => Math.max(min, Math.floor(Number(v) || fallback)); + const clamp01 = (v, fallback = 0) => { + const n = Number(v); + if (!Number.isFinite(n)) return fallback; + return Math.max(0, Math.min(1, n)); + }; + switch (type) { + case "box": { + const width = Math.max(0.01, num(dims.width, 1)); + const height = Math.max(0.01, num(dims.height, 1)); + const depth = Math.max(0.01, num(dims.depth, 1)); + const edgeRadius = Math.max(0, num(dims.edgeRadius, 0)); + if (edgeRadius > 0) { + const radius = Math.min(edgeRadius, width * 0.5, height * 0.5, depth * 0.5); + const edgeSegments = clampInt(dims.edgeSegments, 4, 1); + return new RoundedBoxGeometry(width, height, depth, edgeSegments, radius); + } + return new THREE.BoxGeometry( + width, + height, + depth, + clampInt(dims.widthSegments, 1, 1), + clampInt(dims.heightSegments, 1, 1), + clampInt(dims.depthSegments, 1, 1) + ); + } + case "sphere": + return new THREE.SphereGeometry( + Math.max(0.01, num(dims.radius, 0.5)), + clampInt(dims.widthSegments, 32, 3), + clampInt(dims.heightSegments, 16, 2), + degToRad(num(dims.phiStartDeg, 0), 0), + degToRad(num(dims.phiLengthDeg, 360), 360), + degToRad(num(dims.thetaStartDeg, 0), 0), + degToRad(num(dims.thetaLengthDeg, 180), 180) + ); + case "cylinder": + return new THREE.CylinderGeometry( + Math.max(0.01, num(dims.radiusTop, 0.5)), + Math.max(0.01, num(dims.radiusBottom, 0.5)), + Math.max(0.01, num(dims.height, 1)), + clampInt(dims.radialSegments, 32, 3), + clampInt(dims.heightSegments, 1, 1), + clamp01(dims.openEnded, 0) >= 0.5 + ); + case "cone": + return new THREE.ConeGeometry( + Math.max(0.01, num(dims.radius, 0.5)), + Math.max(0.01, num(dims.height, 1)), + clampInt(dims.radialSegments, 32, 3), + clampInt(dims.heightSegments, 1, 1), + clamp01(dims.openEnded, 0) >= 0.5 + ); + case "torus": + return new THREE.TorusGeometry( + Math.max(0.01, num(dims.radius, 0.5)), + Math.max(0.01, num(dims.tube, 0.15)), + clampInt(dims.radialSegments, 16, 3), + clampInt(dims.tubularSegments, 48, 3), + degToRad(num(dims.arcDeg, 360), 360) + ); + case "plane": + return new THREE.PlaneGeometry( + Math.max(0.01, num(dims.width, 2)), + Math.max(0.01, num(dims.height, 2)), + clampInt(dims.widthSegments, 1, 1), + clampInt(dims.heightSegments, 1, 1) + ); + default: + return new THREE.BoxGeometry(1, 1, 1); + } +} + +const _textureLoader = new THREE.TextureLoader(); +const _textureCache = new Map(); // dataUrl → THREE.Texture +const _glbResultCache = new Map(); // glbUrl → loaded gltf result (shared across instances) + +function createPrimitiveMaterial(mat) { + mat = mat || {}; + const uv = mat.uvTransform || {}; + const clamp01 = (v, fallback = 0) => { + const n = Number(v); + if (!Number.isFinite(n)) return fallback; + return Math.max(0, Math.min(1, n)); + }; + const hardness = clamp01(mat.hardness, 0); + const fluffiness = clamp01(mat.fluffiness, 0); + const params = { + color: new THREE.Color(mat.color || "#808080"), + roughness: mat.softness ?? mat.roughness ?? 0.7, + metalness: mat.metalness ?? 0.0, + specularIntensity: mat.specularIntensity ?? 1.0, + specularColor: new THREE.Color(mat.specularColor || "#ffffff"), + envMapIntensity: mat.envMapIntensity ?? 1.0, + opacity: mat.opacity ?? 1.0, + transparent: (mat.opacity ?? 1.0) < 1 || (mat.transmission ?? 0) > 0, + transmission: mat.transmission ?? 0.0, + ior: mat.ior ?? 1.45, + thickness: mat.thickness ?? 0.0, + attenuationColor: new THREE.Color(mat.attenuationColor || "#ffffff"), + attenuationDistance: Math.max(0.01, mat.attenuationDistance ?? 1.0), + iridescence: mat.iridescence ?? 0.0, + iridescenceIOR: mat.ior ?? 1.45, + emissive: new THREE.Color(mat.emissive || "#000000"), + emissiveIntensity: mat.emissiveIntensity ?? 0.0, + clearcoat: Math.max(mat.clearcoat ?? 0.0, hardness * 0.85), + clearcoatRoughness: Math.min(mat.clearcoatRoughness ?? 0.0, 1 - hardness * 0.8), + sheen: fluffiness, + sheenRoughness: 0.9, + sheenColor: new THREE.Color(mat.sheenColor || mat.color || "#808080"), + side: mat.doubleSided === false ? THREE.FrontSide : THREE.DoubleSide, + flatShading: mat.flatShading === true, + wireframe: mat.wireframe === true, + alphaTest: clamp01(mat.alphaCutoff, 0), + depthWrite: (mat.opacity ?? 1.0) >= 1 && (mat.transmission ?? 0) <= 0, + }; + if (mat.textureDataUrl) { + let baseTex = _textureCache.get(mat.textureDataUrl); + if (!baseTex) { + baseTex = _textureLoader.load(mat.textureDataUrl); + baseTex.colorSpace = THREE.SRGBColorSpace; + baseTex.wrapS = baseTex.wrapT = THREE.RepeatWrapping; + _textureCache.set(mat.textureDataUrl, baseTex); + } + const tex = baseTex.clone(); + tex.needsUpdate = true; + tex.repeat.set(uv.repeatX ?? 1, uv.repeatY ?? 1); + tex.offset.set(uv.offsetX ?? 0, uv.offsetY ?? 0); + tex.rotation = ((uv.rotationDeg ?? 0) * Math.PI) / 180; + tex.center.set(0.5, 0.5); + const textureSoftness = clamp01(mat.textureSoftness, 0.25); + const textureHardness = clamp01(mat.textureHardness, 0.5); + const maxAniso = renderer?.capabilities?.getMaxAnisotropy?.() || 1; + const targetAniso = Math.max(1, Math.round(1 + textureHardness * (maxAniso - 1))); + tex.anisotropy = Math.max(1, Math.round(targetAniso * (1 - textureSoftness * 0.85))); + tex.minFilter = textureSoftness > 0.6 ? THREE.LinearMipmapLinearFilter : THREE.LinearMipmapNearestFilter; + tex.magFilter = textureSoftness > 0.75 ? THREE.LinearFilter : (textureHardness > 0.9 ? THREE.NearestFilter : THREE.LinearFilter); + tex.generateMipmaps = true; + params.map = tex; + } + return new THREE.MeshPhysicalMaterial(params); +} + +function sanitizePrimitiveCutouts(cutouts) { + if (!Array.isArray(cutouts)) return []; + const out = []; + for (const c of cutouts) { + if (!c || typeof c !== "object") continue; + if (!Array.isArray(c.targetToSourceMatrix) || c.targetToSourceMatrix.length !== 16) continue; + const type = String(c.type || ""); + if (!["box", "sphere", "cylinder", "cone", "torus"].includes(type)) continue; + out.push({ + type, + targetToSourceMatrix: c.targetToSourceMatrix.map((n) => Number(n) || 0), + dimensions: { ...(c.dimensions || {}) }, + }); + if (out.length >= 8) break; + } + return out; +} + +function applyPrimitiveCutoutShader(mesh, primData) { + if (!mesh?.material?.isMeshPhysicalMaterial) return; + const cutouts = sanitizePrimitiveCutouts(primData?.cutouts); + if (!cutouts.length) return; + const mat = mesh.material; + const maxCuts = 8; + const cutMatrices = Array.from({ length: maxCuts }, () => new THREE.Matrix4()); + const cutA = Array.from({ length: maxCuts }, () => new THREE.Vector4(0, 0, 0, 0)); + const cutB = Array.from({ length: maxCuts }, () => new THREE.Vector4(0, 0, 0, 0)); + const typeCodeFor = (t) => (t === "sphere" ? 1 : t === "box" ? 2 : t === "cylinder" ? 3 : t === "cone" ? 4 : t === "torus" ? 5 : 0); + for (let i = 0; i < cutouts.length && i < maxCuts; i++) { + const c = cutouts[i]; + cutMatrices[i].fromArray(c.targetToSourceMatrix); + const d = c.dimensions || {}; + switch (c.type) { + case "sphere": + cutA[i].set(Number(d.radius) || 0.5, 0, 0, typeCodeFor(c.type)); + break; + case "box": + cutA[i].set((Number(d.width) || 1) * 0.5, (Number(d.height) || 1) * 0.5, (Number(d.depth) || 1) * 0.5, typeCodeFor(c.type)); + break; + case "cylinder": + case "cone": + cutA[i].set(Math.max(Number(d.radiusTop) || Number(d.radius) || 0.5, Number(d.radiusBottom) || Number(d.radius) || 0.5), Number(d.height) || 1, 0, typeCodeFor(c.type)); + break; + case "torus": + cutA[i].set(Number(d.radius) || 0.5, Number(d.tube) || 0.15, 0, typeCodeFor(c.type)); + break; + default: + break; + } + } + mat.onBeforeCompile = (shader) => { + shader.uniforms.uCutoutCount = { value: cutouts.length }; + shader.uniforms.uCutoutInv = { value: cutMatrices }; + shader.uniforms.uCutoutA = { value: cutA }; + shader.uniforms.uCutoutB = { value: cutB }; + shader.vertexShader = ` +varying vec3 vPrimLocalPos; +${shader.vertexShader}`.replace( + "#include ", + `#include +vPrimLocalPos = position;` + ); + shader.fragmentShader = ` +uniform int uCutoutCount; +uniform mat4 uCutoutInv[8]; +uniform vec4 uCutoutA[8]; +uniform vec4 uCutoutB[8]; +varying vec3 vPrimLocalPos; + +float sdfBox(vec3 p, vec3 b) { + vec3 q = abs(p) - b; + return length(max(q, 0.0)) + min(max(q.x, max(q.y, q.z)), 0.0); +} +float sdfSphere(vec3 p, float r) { return length(p) - r; } +float sdfCylinderY(vec3 p, float r, float h) { + vec2 d = abs(vec2(length(p.xz), p.y)) - vec2(r, h * 0.5); + return min(max(d.x, d.y), 0.0) + length(max(d, 0.0)); +} +float sdfTorus(vec3 p, float r, float t) { + vec2 q = vec2(length(p.xz) - r, p.y); + return length(q) - t; +} +${shader.fragmentShader}`.replace( + "#include ", + `#include +for (int i = 0; i < 8; i++) { + if (i >= uCutoutCount) break; + vec3 lp = (uCutoutInv[i] * vec4(vPrimLocalPos, 1.0)).xyz; + float typ = uCutoutA[i].w; + float d = 1e6; + if (typ < 1.5) d = sdfSphere(lp, uCutoutA[i].x); + else if (typ < 2.5) d = sdfBox(lp, vec3(uCutoutA[i].x, uCutoutA[i].y, uCutoutA[i].z)); + else if (typ < 3.5) d = sdfCylinderY(lp, uCutoutA[i].x, uCutoutA[i].y); + else if (typ < 4.5) d = sdfCylinderY(lp, uCutoutA[i].x, uCutoutA[i].y); + else d = sdfTorus(lp, uCutoutA[i].x, uCutoutA[i].y); + if (d < 0.0) discard; +}` + ); + }; + mat.customProgramCacheKey = () => `cutouts:${cutouts.length}:${cutouts.map((c) => c.type).join(",")}`; + mat.needsUpdate = true; +} + +function disposePrimitiveMaterial(material) { + if (!material) return; + const mats = Array.isArray(material) ? material : [material]; + for (const m of mats) { + if (!m) continue; + const maps = [ + "map", + "alphaMap", + "aoMap", + "normalMap", + "roughnessMap", + "metalnessMap", + "emissiveMap", + "clearcoatMap", + "clearcoatRoughnessMap", + "transmissionMap", + "thicknessMap", + ]; + for (const key of maps) { + const tex = m[key]; + if (tex?.isTexture) tex.dispose(); + } + m.dispose?.(); + } +} + +// Deferred collider queue — colliders are only created at a safe frame boundary +const _pendingColliderBuilds = []; + +function flushPendingColliderBuilds() { + if (!rapierWorld || !worldBody || _pendingColliderBuilds.length === 0) return; + while (_pendingColliderBuilds.length > 0) { + const prim = _pendingColliderBuilds.shift(); + // Verify the primitive still exists and still wants physics + if (primitives.includes(prim) && prim.physics !== false) { + rebuildPrimitiveColliderSync(prim); + } + } +} + +function instantiatePrimitive(prim) { + // Remove existing + const existing = primitivesGroup.getObjectByName(`prim:${prim.id}`); + if (existing) { + existing.geometry?.dispose(); + disposePrimitiveMaterial(existing.material); + primitivesGroup.remove(existing); + } + + const geom = createPrimitiveGeometry(prim.type, prim.dimensions); + const mat = createPrimitiveMaterial(prim.material); + const mesh = new THREE.Mesh(geom, mat); + applyPrimitiveCutoutShader(mesh, prim); + mesh.name = `prim:${prim.id}`; + mesh.userData.primitiveId = prim.id; + mesh.userData.isPrimitive = true; + // Default both to true — shapes should always participate in shadows + mesh.castShadow = prim.castShadow !== false; + mesh.receiveShadow = prim.receiveShadow !== false; + + const tr = prim.transform || {}; + if (tr.position) mesh.position.set(tr.position.x, tr.position.y, tr.position.z); + if (tr.rotation) mesh.rotation.set(tr.rotation.x, tr.rotation.y, tr.rotation.z); + if (tr.scale) mesh.scale.set(tr.scale.x ?? 1, tr.scale.y ?? 1, tr.scale.z ?? 1); + + primitivesGroup.add(mesh); + + // Build collider — if Rapier is ready, do it now; otherwise queue it + if (prim.physics !== false) { + if (rapierWorld && worldBody) { + rebuildPrimitiveColliderSync(prim); + } else { + // Queue for deferred build once Rapier is ready + _pendingColliderBuilds.push(prim); + // Kick off Rapier init (non-blocking, collider will be built by flush) + ensureRapierLoaded(); + } + } +} + +// Safely remove a primitive's existing collider from the Rapier world +function removePrimitiveCollider(prim) { + if (prim._colliderHandle == null || !rapierWorld) return; + try { + if (typeof prim._colliderHandle === "object" && prim._colliderHandle.handle !== undefined) { + rapierWorld.removeCollider(prim._colliderHandle, true); + } + } catch (e) { + console.warn(`[COLLIDER] Primitive collider remove failed for ${prim.id}:`, e); + } + prim._colliderHandle = null; +} + +// SYNCHRONOUS collider creation for native Rapier shapes. +// Only falls back to async for trimesh (torus, plane). +function rebuildPrimitiveColliderSync(prim) { + if (!prim) return; + // Rapier must already be loaded for sync creation + if (!rapierWorld || !RAPIER || !worldBody) return; + + removePrimitiveCollider(prim); + if (prim.physics === false) return; + + const mesh = primitivesGroup.getObjectByName(`prim:${prim.id}`); + if (!mesh) return; + + const dims = prim.dimensions || {}; + const s = prim.transform?.scale || { x: 1, y: 1, z: 1 }; + const pos = prim.transform?.position || { x: 0, y: 0, z: 0 }; + const rot = prim.transform?.rotation || { x: 0, y: 0, z: 0 }; + + // Clamp all half-extents / radii to a safe minimum to avoid WASM traps + const clamp = (v) => Math.max(v, 0.001); + + let desc = null; + + // Use native Rapier collision shapes – far more compute-efficient than trimesh + switch (prim.type) { + case "box": + desc = RAPIER.ColliderDesc.cuboid( + clamp(((dims.width || 1) * (s.x ?? 1)) / 2), + clamp(((dims.height || 1) * (s.y ?? 1)) / 2), + clamp(((dims.depth || 1) * (s.z ?? 1)) / 2) + ); + break; + case "sphere": + desc = RAPIER.ColliderDesc.ball( + clamp((dims.radius || 0.5) * Math.max(s.x ?? 1, s.y ?? 1, s.z ?? 1)) + ); + break; + case "cylinder": + desc = RAPIER.ColliderDesc.cylinder( + clamp(((dims.height || 1) * (s.y ?? 1)) / 2), + clamp(Math.max(dims.radiusTop ?? 0.5, dims.radiusBottom ?? 0.5) * Math.max(s.x ?? 1, s.z ?? 1)) + ); + break; + case "cone": + desc = RAPIER.ColliderDesc.cone( + clamp(((dims.height || 1) * (s.y ?? 1)) / 2), + clamp((dims.radius || 0.5) * Math.max(s.x ?? 1, s.z ?? 1)) + ); + break; + case "plane": { + // PlaneGeometry lies in the XY plane (normal along +Z), so make the + // cuboid thin in Z to match the visual exactly. No rotation offset needed. + const pw = clamp(((dims.width || 2) * (s.x ?? 1)) / 2); + const ph = clamp(((dims.height || 2) * (s.y ?? 1)) / 2); + desc = RAPIER.ColliderDesc.cuboid(pw, ph, 0.005); + break; // fall through to the standard rotation/translation below + } + case "torus": { + // Torus: use trimesh async fallback (deferred, won't block) + rebuildPrimitiveColliderAsync(prim); + return; + } + default: + return; + } + + if (desc) { + desc.setTranslation(pos.x, pos.y, pos.z); + const euler = new THREE.Euler(rot.x, rot.y, rot.z); + const quat = new THREE.Quaternion().setFromEuler(euler); + desc.setRotation({ x: quat.x, y: quat.y, z: quat.z, w: quat.w }); + desc.setFriction(0.9); + try { + const collider = rapierWorld.createCollider(desc); + prim._colliderHandle = collider; + } catch (e) { + console.warn(`[COLLIDER] Failed to create primitive collider for ${prim.type}:`, e); + } + } +} + +// Async fallback only used for torus (trimesh) +async function rebuildPrimitiveColliderAsync(prim) { + if (!prim) return; + await ensureRapierLoaded(); + if (!rapierWorld || !RAPIER || !worldBody) return; + removePrimitiveCollider(prim); + if (prim.physics === false) return; + const mesh = primitivesGroup.getObjectByName(`prim:${prim.id}`); + if (!mesh) return; + try { + const collider = await buildRapierTriMeshColliderFromObject(mesh); + if (collider) prim._colliderHandle = collider; + } catch (e) { + console.warn(`[COLLIDER] Trimesh fallback failed for ${prim.id}:`, e); + } +} + +// Keep old name as alias for callers (e.g. dimension/transform change handlers) +function rebuildPrimitiveCollider(primId) { + const prim = primitives.find((p) => p.id === primId); + if (prim) rebuildPrimitiveColliderSync(prim); +} + +function addPrimitiveAtCrosshair(type) { + const spawnPos = getPlacementAtCrosshair({ raycastDistance: 250, surfaceOffset: 0.5 }).position; + addPrimitiveAtPosition(type, spawnPos); +} + +function addPrimitiveAtPosition(type, spawnPos) { + const prim = { + id: randId(), + type, + name: type.charAt(0).toUpperCase() + type.slice(1), + notes: "", + tags: [], // string tags for filtering / grouping + state: "static", // static | dynamic | interactable | trigger | decoration + metadata: {}, // arbitrary key-value pairs + dimensions: { ...(PRIMITIVE_DEFAULTS[type] || PRIMITIVE_DEFAULTS.box) }, + transform: { + position: spawnPos, + rotation: { x: 0, y: 0, z: 0 }, + scale: { x: 1, y: 1, z: 1 }, + }, + material: { + color: "#808080", + roughness: 0.7, + softness: 0.7, + hardness: 0.0, + fluffiness: 0.0, + metalness: 0.0, + specularIntensity: 1.0, + specularColor: "#ffffff", + envMapIntensity: 1.0, + opacity: 1.0, + transmission: 0.0, + ior: 1.45, + thickness: 0.0, + attenuationColor: "#ffffff", + attenuationDistance: 1.0, + iridescence: 0.0, + emissive: "#000000", + emissiveIntensity: 0.0, + clearcoat: 0.0, + clearcoatRoughness: 0.0, + alphaCutoff: 0.0, + textureSoftness: 0.25, + textureHardness: 0.5, + doubleSided: true, + flatShading: false, + wireframe: false, + uvTransform: { repeatX: 1, repeatY: 1, offsetX: 0, offsetY: 0, rotationDeg: 0 }, + textureDataUrl: null, + }, + physics: true, + castShadow: true, + receiveShadow: true, + }; + + primitives.push(prim); + instantiatePrimitive(prim); + saveTagsForWorld(); + renderPrimitivesList(); + selectPrimitive(prim.id); + setStatus(`${prim.name} placed. Use transform tools to position.`); +} + +function selectPrimitive(id) { + selectedPrimitiveId = id; + if (id) { + selectedAssetId = null; + } + renderPrimitivesList(); +} + +function getPlacementAtCrosshair({ raycastDistance = 500, fallbackDistance = 3, surfaceOffset = 0.02 } = {}) { + const hit = rapierRaycastFromCamera(raycastDistance); + if (hit) { + const n = hit.normal + ? new THREE.Vector3(hit.normal.x, hit.normal.y, hit.normal.z).normalize() + : new THREE.Vector3(0, 1, 0); + return { + hit: true, + point: { x: hit.point.x, y: hit.point.y, z: hit.point.z }, + normal: { x: n.x, y: n.y, z: n.z }, + position: { + x: hit.point.x + n.x * surfaceOffset, + y: hit.point.y + n.y * surfaceOffset, + z: hit.point.z + n.z * surfaceOffset, + }, + }; + } + + // If no collider is hit, place directly in front of the crosshair. + const dir = camera.getWorldDirection(new THREE.Vector3()); + const p = camera.getWorldPosition(new THREE.Vector3()); + return { + hit: false, + point: { + x: p.x + dir.x * fallbackDistance, + y: p.y + dir.y * fallbackDistance, + z: p.z + dir.z * fallbackDistance, + }, + normal: { x: 0, y: 1, z: 0 }, + position: { + x: p.x + dir.x * fallbackDistance, + y: p.y + dir.y * fallbackDistance, + z: p.z + dir.z * fallbackDistance, + }, + }; +} + +function getPlacementFromAgentView(agent, { raycastDistance = 500, fallbackDistance = 2.5, surfaceOffset = 0.02 } = {}) { + const [ax, ay, az] = agent?.getPosition?.() || [0, 0, 0]; + const yaw = agent?.group?.rotation?.y ?? 0; + const pitch = typeof agent?.pitch === "number" ? agent.pitch : 0; + const cp = Math.cos(pitch); + const sp = Math.sin(pitch); + const dx = Math.sin(yaw) * cp; + const dy = sp; + const dz = Math.cos(yaw) * cp; + const eyeY = ay + PLAYER_EYE_HEIGHT * 0.9; + + if (rapierWorld && RAPIER) { + const ray = new RAPIER.Ray({ x: ax, y: eyeY, z: az }, { x: dx, y: dy, z: dz }); + const hit = rapierWorld.queryPipeline.castRayAndGetNormal( + rapierWorld.bodies, + rapierWorld.colliders, + ray, + raycastDistance, + false, + RAPIER.QueryFilterFlags.EXCLUDE_SENSORS, + undefined, + agent?.collider?.handle + ); + if (hit) { + const toi = hit.toi ?? hit.timeOfImpact ?? 0; + const px = ax + dx * toi; + const py = eyeY + dy * toi; + const pz = az + dz * toi; + const n = hit.normal + ? new THREE.Vector3(hit.normal.x, hit.normal.y, hit.normal.z).normalize() + : new THREE.Vector3(0, 1, 0); + return { + hit: true, + point: { x: px, y: py, z: pz }, + normal: { x: n.x, y: n.y, z: n.z }, + position: { + x: px + n.x * surfaceOffset, + y: py + n.y * surfaceOffset, + z: pz + n.z * surfaceOffset, + }, + }; + } + } + + return { + hit: false, + point: { + x: ax + dx * fallbackDistance, + y: eyeY + dy * fallbackDistance, + z: az + dz * fallbackDistance, + }, + normal: { x: 0, y: 1, z: 0 }, + position: { + x: ax + dx * fallbackDistance, + y: eyeY + dy * fallbackDistance, + z: az + dz * fallbackDistance, + }, + }; +} + + +function getSelectedPrimitive() { + return primitives.find((p) => p.id === selectedPrimitiveId) || null; +} + +function buildPrimitiveCutoutFromSource(targetId, sourceId) { + const targetPrim = primitives.find((p) => p.id === targetId); + const sourcePrim = primitives.find((p) => p.id === sourceId); + if (!targetPrim || !sourcePrim) return null; + const targetMesh = primitivesGroup.getObjectByName(`prim:${targetId}`); + const sourceMesh = primitivesGroup.getObjectByName(`prim:${sourceId}`); + if (!targetMesh || !sourceMesh) return null; + targetMesh.updateMatrixWorld(true); + sourceMesh.updateMatrixWorld(true); + const targetWorldInv = new THREE.Matrix4().copy(targetMesh.matrixWorld).invert(); + const sourceInTarget = new THREE.Matrix4().multiplyMatrices(targetWorldInv, sourceMesh.matrixWorld); + const targetToSource = new THREE.Matrix4().copy(sourceInTarget).invert(); + return { + id: randId(), + type: sourcePrim.type, + targetToSourceMatrix: targetToSource.elements.slice(), + dimensions: { ...(sourcePrim.dimensions || {}) }, + }; +} + + +function getOverlappingPrimitiveIds(targetId) { + const targetMesh = primitivesGroup.getObjectByName(`prim:${targetId}`); + if (!targetMesh) return []; + const targetBox = new THREE.Box3().setFromObject(targetMesh).expandByScalar(0.01); + const out = []; + for (const p of primitives) { + if (p.id === targetId) continue; + const mesh = primitivesGroup.getObjectByName(`prim:${p.id}`); + if (!mesh) continue; + const box = new THREE.Box3().setFromObject(mesh); + if (box.isEmpty()) continue; + if (targetBox.intersectsBox(box)) out.push(p.id); + } + return out; +} + +function persistSelectedPrimitiveTransform() { + const prim = getSelectedPrimitive(); + if (!prim) return; + const obj = primitivesGroup.getObjectByName(`prim:${prim.id}`); + if (!obj) return; + prim.transform = { + position: { x: obj.position.x, y: obj.position.y, z: obj.position.z }, + rotation: { x: obj.rotation.x, y: obj.rotation.y, z: obj.rotation.z }, + scale: { x: obj.scale.x, y: obj.scale.y, z: obj.scale.z }, + }; + saveTagsForWorld(); + rebuildPrimitiveColliderSync(prim); +} + +function deletePrimitive(id) { + const idx = primitives.findIndex((p) => p.id === id); + if (idx === -1) return; + const prim = primitives[idx]; + + // Remove collider safely + removePrimitiveCollider(prim); + + // Remove visual + const obj = primitivesGroup.getObjectByName(`prim:${id}`); + if (obj) { + obj.geometry?.dispose(); + disposePrimitiveMaterial(obj.material); + primitivesGroup.remove(obj); + } + + primitives.splice(idx, 1); + if (selectedPrimitiveId === id) { + selectedPrimitiveId = null; + } + saveTagsForWorld(); + renderPrimitivesList(); + setStatus("Primitive deleted."); +} + +function duplicatePrimitive(id) { + const src = primitives.find((p) => p.id === id); + if (!src) return; + // Strip runtime objects (collider handle has circular refs) before deep clone + const { _colliderHandle, ...serializable } = src; + const clone = JSON.parse(JSON.stringify(serializable)); + clone.id = randId(); + clone.name = src.name + " copy"; + clone._colliderHandle = null; + // Offset slightly + if (clone.transform?.position) { + clone.transform.position.x += 1; + } + primitives.push(clone); + instantiatePrimitive(clone); + saveTagsForWorld(); + renderPrimitivesList(); + selectPrimitive(clone.id); + setStatus("Primitive duplicated."); +} + +function updatePrimitiveMaterial(primId) { + const prim = primitives.find((p) => p.id === primId); + if (!prim) return; + const mesh = primitivesGroup.getObjectByName(`prim:${prim.id}`); + if (!mesh) return; + disposePrimitiveMaterial(mesh.material); + mesh.material = createPrimitiveMaterial(prim.material); + applyPrimitiveCutoutShader(mesh, prim); +} + +function updatePrimitiveDimensions(primId) { + const prim = primitives.find((p) => p.id === primId); + if (!prim) return; + const mesh = primitivesGroup.getObjectByName(`prim:${prim.id}`); + if (!mesh) return; + mesh.geometry?.dispose(); + mesh.geometry = createPrimitiveGeometry(prim.type, prim.dimensions); + rebuildPrimitiveCollider(prim.id); +} + +function renderPrimitivesList() { + // No-op in sim-only mode (editor primitives list not present) +} + +function rebuildAllPrimitives() { + // Remove all existing colliders first + for (const p of primitives) { + removePrimitiveCollider(p); + } + // Remove all visual meshes + while (primitivesGroup.children.length) { + const c = primitivesGroup.children[0]; + c.geometry?.dispose(); + disposePrimitiveMaterial(c.material); + primitivesGroup.remove(c); + } + // Rebuild all + for (const p of primitives) { + try { + instantiatePrimitive(p); + } catch (e) { + console.warn("Failed to rebuild primitive", p.id, e); + } + } +} + +// ============================================================================= +// EDITOR LIGHTS – User-placed lights with visible proxy icons +// ============================================================================= + +function instantiateEditorLight(lightData) { + // Remove existing + removeEditorLightObjects(lightData.id); + + let lightObj; + const color = new THREE.Color(lightData.color || "#ffffff"); + const intensity = lightData.intensity ?? 1.0; + + switch (lightData.type) { + case "point": + lightObj = new THREE.PointLight(color, intensity, lightData.distance || 0); + break; + case "spot": { + lightObj = new THREE.SpotLight( + color, + intensity, + lightData.distance || 0, + lightData.angle ?? Math.PI / 4, + lightData.penumbra ?? 0.1 + ); + const tgt = lightData.target || { x: 0, y: 0, z: 0 }; + lightObj.target.position.set(tgt.x, tgt.y, tgt.z); + lightsGroup.add(lightObj.target); + break; + } + case "directional": + default: { + lightObj = new THREE.DirectionalLight(color, intensity); + const tgt = lightData.target || { x: 0, y: 0, z: 0 }; + lightObj.target.position.set(tgt.x, tgt.y, tgt.z); + lightsGroup.add(lightObj.target); + break; + } + } + + const pos = lightData.position || { x: 5, y: 10, z: 5 }; + lightObj.position.set(pos.x, pos.y, pos.z); + lightObj.castShadow = lightData.castShadow ?? false; + lightObj.name = `light:${lightData.id}`; + lightObj.userData.editorLightId = lightData.id; + lightObj.userData.isEditorLight = true; + + // Configure shadow map for this light (only renders when castShadow=true). + // Use 512 for point/spot (6-face cubemap = expensive) and 1024 for directional. + if (lightObj.shadow) { + const res = lightObj.isDirectionalLight ? 1024 : 512; + lightObj.shadow.mapSize.width = res; + lightObj.shadow.mapSize.height = res; + lightObj.shadow.bias = -0.003; + if (lightObj.shadow.camera) { + if (lightObj.isDirectionalLight) { + lightObj.shadow.camera.near = 0.5; + lightObj.shadow.camera.far = 50; + lightObj.shadow.camera.left = -20; + lightObj.shadow.camera.right = 20; + lightObj.shadow.camera.top = 20; + lightObj.shadow.camera.bottom = -20; + } else { + lightObj.shadow.camera.near = 0.5; + lightObj.shadow.camera.far = Math.min(lightData.distance || 30, 30); + } + } + } + + lightsGroup.add(lightObj); + lightData._lightObj = lightObj; + lightData._proxyObj = null; + lightData._helperObj = null; +} + +function removeEditorLightObjects(id) { + const names = [`light:${id}`, `lightHelper:${id}`, `lightProxy:${id}`]; + for (const n of names) { + const obj = lightsGroup.getObjectByName(n); + if (obj) { + // Remove target if it exists (directional/spot) + if (obj.target && obj.target.parent) obj.target.parent.remove(obj.target); + // Dispose children meshes + obj.traverse?.((c) => { + if (c.geometry) c.geometry.dispose(); + if (c.material) { + if (c.material.map) c.material.map.dispose(); + c.material.dispose(); + } + }); + lightsGroup.remove(obj); + } + } +} + + + +function rebuildAllEditorLights() { + // Remove all light objects + while (lightsGroup.children.length) { + const c = lightsGroup.children[0]; + c.traverse?.((m) => { m.geometry?.dispose(); m.material?.dispose(); }); + lightsGroup.remove(c); + } + for (const ld of editorLights) { + ld._lightObj = null; + ld._helperObj = null; + ld._proxyObj = null; + try { + instantiateEditorLight(ld); + } catch (e) { + console.warn("Failed to rebuild light", ld.id, e); + } + } + // Enable/disable the renderer shadow map based on whether any light casts shadows + syncShadowMapEnabled(); +} + +// ============================================================================= +// DETAILS PANEL & TRANSFORM XYZ – UE-style unified properties +// ============================================================================= + +const RAD2DEG = 180 / Math.PI; +const DEG2RAD = Math.PI / 180; + +// Dynamically enable/disable the shadow map system. +// When no light casts shadows, the renderer skips ALL shadow work (zero overhead). +function enforceShadowSamplerBudget() { + // Prevent WebGL shader validation failures: + // "texture image units count exceeds MAX_TEXTURE_IMAGE_UNITS" + // Point-light shadows are especially expensive (cube map = ~6 samplers). + const budget = 8; + const costFor = (lightObj) => (lightObj?.isPointLight ? 6 : 1); + + const candidates = []; + for (const sl of sceneLights) { + if (!sl?.obj || sl.obj.visible === false) continue; + if (!sl.obj.castShadow) continue; + candidates.push({ obj: sl.obj, source: "scene", meta: sl }); + } + for (const ld of editorLights) { + if (!ld?._lightObj || ld._lightObj.visible === false) continue; + if (!ld._lightObj.castShadow) continue; + candidates.push({ obj: ld._lightObj, source: "editor", meta: ld }); + } + + // Prefer non-point shadow lights first (directional/spot), then points. + candidates.sort((a, b) => { + const ac = costFor(a.obj); + const bc = costFor(b.obj); + if (ac !== bc) return ac - bc; // cheaper first + return 0; + }); + + let used = 0; + for (const c of candidates) { + const cost = costFor(c.obj); + if (used + cost <= budget) { + used += cost; + continue; + } + c.obj.castShadow = false; + // keep data model consistent so UI reflects actual runtime state + if (c.source === "editor") c.meta.castShadow = false; + } +} + +function syncShadowMapEnabled() { + enforceShadowSamplerBudget(); + let anyCast = false; + // Check scene lights + for (const sl of sceneLights) { + if (sl.obj?.castShadow && sl.obj?.visible !== false) { anyCast = true; break; } + } + // Check editor lights + if (!anyCast) { + for (const ld of editorLights) { + if (ld._lightObj?.castShadow && ld._lightObj?.visible !== false) { anyCast = true; break; } + } + } + if (renderer.shadowMap.enabled !== anyCast) { + renderer.shadowMap.enabled = anyCast; + // When toggling shadow maps, Three.js needs to recompile materials + scene.traverse((obj) => { if (obj.material) obj.material.needsUpdate = true; }); + } + if (anyCast) renderer.shadowMap.needsUpdate = true; +} + +function renderSceneInMode(mode) { + const savedOverride = scene.overrideMaterial; + const savedBg = scene.background; + const savedAssets = assetsGroup.visible; + const savedPrims = primitivesGroup.visible; + const savedLights = lightsGroup.visible; + const savedTags = tagsGroup.visible; + const savedLidar = lidarVizGroup.visible; + const savedOverlay = rgbdPcOverlayGroup.visible; + + if (mode === "rgb") { + scene.overrideMaterial = null; + assetsGroup.visible = true; + primitivesGroup.visible = true; + lightsGroup.visible = true; + tagsGroup.visible = false; + lidarVizGroup.visible = false; + rgbdPcOverlayGroup.visible = false; + scene.background = DEFAULT_SCENE_BG; + renderer.render(scene, camera); + } else if (mode === "lidar") { + scene.overrideMaterial = null; + assetsGroup.visible = false; + primitivesGroup.visible = false; + lightsGroup.visible = false; + tagsGroup.visible = false; + lidarVizGroup.visible = true; + rgbdPcOverlayGroup.visible = rgbdPcOverlayOnLidar && _rgbdPcOverlayLastCount > 0; + scene.background = RGBD_BG; + renderer.render(scene, camera); + } + + scene.overrideMaterial = savedOverride; + scene.background = savedBg; + assetsGroup.visible = savedAssets; + primitivesGroup.visible = savedPrims; + lightsGroup.visible = savedLights; + tagsGroup.visible = savedTags; + lidarVizGroup.visible = savedLidar; + rgbdPcOverlayGroup.visible = savedOverlay; +} + +function renderCompareViews() { + const sz = renderer.getSize(new THREE.Vector2()); + const W = sz.x; + const H = sz.y; + const halfW = Math.floor(W / 2); + const halfH = Math.floor(H / 2); + + renderer.setScissorTest(true); + renderer.autoClear = false; + + renderer.setViewport(0, 0, W, H); + renderer.setScissor(0, 0, W, H); + renderer.setClearColor(0x000000, 1); + renderer.clear(true, true, true); + + // Top-left: RGB + renderer.setViewport(0, halfH, halfW, halfH); + renderer.setScissor(0, halfH, halfW, halfH); + renderer.setClearColor(DEFAULT_SCENE_BG, 1); + renderer.clear(true, true, true); + renderSceneInMode("rgb"); + + // Top-right: RGB-D + renderRgbdMetricPassOffscreen(); + rgbdVizMaterial.uniforms.uGrayMode.value = rgbdVizMode === "gray" ? 1.0 : 0.0; + renderer.setRenderTarget(null); + renderer.setViewport(halfW, halfH, W - halfW, halfH); + renderer.setScissor(halfW, halfH, W - halfW, halfH); + renderer.setClearColor(RGBD_BG, 1); + renderer.clear(true, true, true); + renderer.render(rgbdVizScene, rgbdPostCamera); + + // Bottom-center: LiDAR + const lidarX = Math.floor((W - halfW) / 2); + renderer.setViewport(lidarX, 0, halfW, halfH); + renderer.setScissor(lidarX, 0, halfW, halfH); + renderer.setClearColor(RGBD_BG, 1); + renderer.clear(true, true, true); + renderSceneInMode("lidar"); + + renderer.setScissorTest(false); + renderer.autoClear = true; + renderer.setViewport(0, 0, W, H); + renderer.setScissor(0, 0, W, H); +} + +function renderActiveView() { + syncShadowMapEnabled(); + if (simCompareView) { + renderCompareViews(); + } else if (simSensorViewMode === "rgbd") { + renderRgbdView(); + } else { + renderer.render(scene, camera); + } +} + +const _tmpCamPos = new THREE.Vector3(); +const _tmpCamDir = new THREE.Vector3(); +const _raycaster = new THREE.Raycaster(); + +function rapierRaycastFromCamera(maxToi = 250) { + if (!rapierWorld || !RAPIER) return null; + // Query pipeline is kept current by rapierWorld.step() in updateRapier + + const o = camera.getWorldPosition(_tmpCamPos); + const d = camera.getWorldDirection(_tmpCamDir).normalize(); + + const ray = new RAPIER.Ray({ x: o.x, y: o.y, z: o.z }, { x: d.x, y: d.y, z: d.z }); + const hit = rapierWorld.queryPipeline.castRayAndGetNormal( + rapierWorld.bodies, + rapierWorld.colliders, + ray, + maxToi, + false, // hollow: can hit boundary even if ray starts inside + RAPIER.QueryFilterFlags.EXCLUDE_SENSORS, + undefined, + playerCollider?.handle + ); + if (!hit) return null; + const toi = hit.toi ?? hit.timeOfImpact ?? 0; + const p = { x: o.x + d.x * toi, y: o.y + d.y * toi, z: o.z + d.z * toi }; + const n = hit.normal ? { x: hit.normal.x, y: hit.normal.y, z: hit.normal.z } : null; + return { point: p, normal: n, colliderHandle: hit.colliderHandle ?? null, toi }; +} + +function isShapeFreeAt(shape, rot, pos, excludeColliderHandle = null) { + if (!rapierWorld || !RAPIER) return false; + const hit = rapierWorld.queryPipeline.intersectionWithShape( + rapierWorld.bodies, + rapierWorld.colliders, + pos, + rot, + shape, + RAPIER.QueryFilterFlags.EXCLUDE_SENSORS, + undefined, + excludeColliderHandle + ); + return hit == null; +} + +function findNearbyFreeSpotForCollider(collider, startPos, maxR = 2.0, step = 0.12) { + if (!collider) return null; + const shape = collider.shape; + const rot = collider.rotation(); + const exclude = collider.handle; + + if (isShapeFreeAt(shape, rot, startPos, exclude)) return startPos; + + const dirs = [ + [1, 0, 0], + [-1, 0, 0], + [0, 0, 1], + [0, 0, -1], + [1, 0, 1], + [1, 0, -1], + [-1, 0, 1], + [-1, 0, -1], + [0, 1, 0], + [0, -1, 0], + ]; + for (let r = step; r <= maxR; r += step) { + for (const [dx, dy, dz] of dirs) { + const len = Math.hypot(dx, dy, dz) || 1; + const pos = { x: startPos.x + (dx / len) * r, y: startPos.y + (dy / len) * r, z: startPos.z + (dz / len) * r }; + if (isShapeFreeAt(shape, rot, pos, exclude)) return pos; + } + } + return null; +} + +function removeAiAgent(agent, reason = "manual") { + if (!agent) return; + const removedId = String(agent.id || ""); + try { + aiAgents = aiAgents.filter((a) => a !== agent); + agentUiPush(`${new Date().toLocaleTimeString()}\nAGENT DESPAWN\n${agent.id} (${reason})`); + agent.dispose?.(); + } catch {} + if (removedId) { + _agentTasks.delete(removedId); + agentInspectorStateById.delete(removedId); + } + if (removedId) removeAgentBadge(removedId); + if (agentCameraFollowId === removedId) { + disableAgentCameraFollow(); + } + if (selectedAgentInspectorId === removedId) { + selectedAgentInspectorId = aiAgents[0]?.id || null; + if (selectedAgentInspectorId) renderAgentInspector(selectedAgentInspectorId); + else { + clearAgentInspectorViews(); + } + } + if (aiAgents.length === 0) { + disableAgentCameraFollow(); + } + renderAgentTaskUi(); +} + +function stopAiAgent(agent, reason = "manual-stop") { + if (!agent) return; + agentUiPush(`${new Date().toLocaleTimeString()}\nAGENT STOP\n${agent.id} (${reason})`); + renderAgentTaskUi(); +} + +function despawnEphemeralAgents(reason = "task-end") { + const doomed = aiAgents.filter((a) => a?._ephemeral === true); + for (const a of doomed) removeAiAgent(a, reason); +} + +function createAiAgent({ ephemeral = false, avatarUrl, radius, halfHeight } = {}) { + const id = `agent-${Date.now().toString(36)}-${Math.random().toString(36).slice(2, 6)}`; + const _avatarUrl = avatarUrl !== undefined + ? avatarUrl + : ["/embodiment/dimsim_unitree_stub.glb"]; + const agent = new AiAvatar({ + id, + scene, + rapierWorld, + RAPIER, + avatarUrl: _avatarUrl, + radius, + halfHeight, + // Headless mode in dimos: skip visual rendering, keep colliders for physics + headless: false, + }); + agent._ephemeral = !!ephemeral; + // Manually spawned editor agents should clean themselves up after task completion. + agent._autoDespawnAfterTask = true; + // Only inherit the active task if this agent was spawned as part of a worker pool (ephemeral). + // Manually spawned agents start idle and wait for their own task assignment. + agent._taskStartedAt = ephemeral ? Number(agentTask.startedAt || 0) : 0; + getOrCreateAgentInspectorState(id); + if (!selectedAgentInspectorId) selectedAgentInspectorId = id; + renderSelectedAgentControls(); + return agent; +} + + +async function ensureRapierLoaded() { + if (RAPIER) return; + if (!_rapierInitPromise) { + _rapierInitPromise = _doRapierInit(); + } + return _rapierInitPromise; +} + +async function _doRapierInit() { + RAPIER = await import("@dimforge/rapier3d-compat"); + await RAPIER.init(); + rapierWorld = new RAPIER.World({ x: 0, y: -9.81, z: 0 }); + worldBody = rapierWorld.createRigidBody(RAPIER.RigidBodyDesc.fixed()); + + const radius = PLAYER_RADIUS; + const halfHeight = PLAYER_HALF_HEIGHT; + playerBody = rapierWorld.createRigidBody( + RAPIER.RigidBodyDesc.kinematicPositionBased().setTranslation(0, 3, 0) + ); + playerCollider = rapierWorld.createCollider( + RAPIER.ColliderDesc.capsule(halfHeight, radius).setFriction(0.0).setSensor(ghostMode), + playerBody + ); + + characterController = rapierWorld.createCharacterController(0.02); + characterController.setSlideEnabled(true); + characterController.enableAutostep(0.55, 0.25, true); + characterController.enableSnapToGround(0.25); + characterController.setMaxSlopeClimbAngle(Math.PI / 3); + characterController.setMinSlopeSlideAngle(Math.PI / 2); +} + +async function spawnOrMoveAiAtAim({ createNew = false, silent = false, ephemeral = false } = {}) { + await ensureRapierLoaded(); + const hit = rapierRaycastFromCamera(500); + const placement = hit + ? { point: hit.point, normal: hit.normal || { x: 0, y: 1, z: 0 } } + : getPlacementAtCrosshair({ raycastDistance: 500, fallbackDistance: 3, surfaceOffset: 0.0 }); + if (!hit && !silent) { + setStatus("No collider hit; spawned AI using crosshair fallback placement."); + } + + let agent = createNew ? null : aiAgents[0] || null; + if (!agent) { + if (aiAgents.length >= MAX_AGENT_COUNT) { + if (!silent) setStatus(`Agent cap reached (${MAX_AGENT_COUNT}).`); + return; + } + agent = createAiAgent({ ephemeral }); + aiAgents.push(agent); + } else if (ephemeral) { + agent._ephemeral = true; + } + + const n = placement.normal + ? new THREE.Vector3(placement.normal.x, placement.normal.y, placement.normal.z).normalize() + : new THREE.Vector3(0, 1, 0); + const offset = Math.max(0.12, (agent.radius ?? PLAYER_RADIUS) + 0.06); + const p0 = placement.point; + const candA = { x: p0.x + n.x * offset, y: p0.y + n.y * offset, z: p0.z + n.z * offset }; + const candB = { x: p0.x - n.x * offset, y: p0.y - n.y * offset, z: p0.z - n.z * offset }; + + let chosen = null; + chosen = findNearbyFreeSpotForCollider(agent.collider, candA, 2.0, 0.12); + if (!chosen) chosen = findNearbyFreeSpotForCollider(agent.collider, candB, 2.0, 0.12); + if (!chosen) chosen = findNearbyFreeSpotForCollider(agent.collider, { x: p0.x, y: p0.y + offset, z: p0.z }, 2.5, 0.12); + // Fallback: use placement point directly (slightly above surface) rather than failing silently. + if (!chosen) { + chosen = { x: p0.x + n.x * 0.5, y: p0.y + n.y * 0.5 + 0.5, z: p0.z + n.z * 0.5 }; + console.warn("[Spawn] No free collision spot found – using direct fallback placement at", chosen); + } + + agent.setPosition(chosen.x, chosen.y, chosen.z); + if (agentTask.active) { + agent._taskStartedAt = agentTask.startedAt; + } + renderAgentTaskUi(); + if (!silent) { + const label = createNew ? "AI worker spawned." : "AI placed."; + setStatus(`${label} (${aiAgents.length} total)`); + } +} + +function pickAgentFromRay(raycaster) { + const agentRoots = aiAgents.map((a) => a?.group).filter(Boolean); + if (agentRoots.length === 0) return null; + + // First try exact mesh hits. + const agentHits = raycaster.intersectObjects(agentRoots, true); + if (agentHits.length > 0) { + let obj = agentHits[0].object; + while (obj && !(typeof obj.name === "string" && obj.name.startsWith("AiAvatar:"))) obj = obj.parent; + const agentId = obj?.name?.slice("AiAvatar:".length) || ""; + const agent = aiAgents.find((a) => a.id === agentId) || null; + if (agent) return agent; + } + + // Fallback: broad proximity test against agent centers. + let best = null; + let bestT = Infinity; + const origin = raycaster.ray.origin; + const dir = raycaster.ray.direction; + const tmp = new THREE.Vector3(); + const to = new THREE.Vector3(); + const pickRadius = 0.45; // generous click radius for tiny capsules + + for (const a of aiAgents) { + if (!a?.group || a.group.visible === false) continue; + const [x, y, z] = a.getPosition?.() || [0, 0, 0]; + // Aim around torso center for better clickability. + tmp.set(x, y + (a.halfHeight || 0.25), z); + const d2 = raycaster.ray.distanceSqToPoint(tmp); + if (d2 > pickRadius * pickRadius) continue; + + // Prefer nearest along-ray candidate in front of camera. + to.copy(tmp).sub(origin); + const t = to.dot(dir); + if (t <= 0) continue; + if (t < bestT) { + bestT = t; + best = a; + } + } + return best; +} + +function pickAgentFromScreenPoint(clientX, clientY, canvasRect) { + if (!Number.isFinite(clientX) || !Number.isFinite(clientY) || !canvasRect || aiAgents.length === 0) return null; + const thresholdPx = 46; + let best = null; + let bestD2 = thresholdPx * thresholdPx; + const v = new THREE.Vector3(); + for (const a of aiAgents) { + if (!a?.group || a.group.visible === false) continue; + const [x, y, z] = a.getPosition?.() || [0, 0, 0]; + v.set(x, y + (a.halfHeight || 0.25), z).project(camera); + if (v.z < -1 || v.z > 1) continue; // behind camera / clipped + const sx = canvasRect.left + (v.x * 0.5 + 0.5) * canvasRect.width; + const sy = canvasRect.top + (-v.y * 0.5 + 0.5) * canvasRect.height; + const dx = sx - clientX; + const dy = sy - clientY; + const d2 = dx * dx + dy * dy; + if (d2 < bestD2) { + bestD2 = d2; + best = a; + } + } + return best; +} + +function ensureAgentBadgeLayer() { + if (agentBadgeLayerEl) return; + installAgentBadgeEventDelegation(); + const el = document.createElement("div"); + el.id = "agent-badge-layer"; + el.className = "agent-badge-layer"; + document.body.appendChild(el); + agentBadgeLayerEl = el; +} + +function getOrCreateAgentBadge(agentId) { + const id = String(agentId || ""); + if (!id) return null; + ensureAgentBadgeLayer(); + if (agentBadgeElsById.has(id)) return agentBadgeElsById.get(id); + const btn = document.createElement("button"); + btn.type = "button"; + btn.className = "agent-badge"; + btn.textContent = id; + btn.dataset.agentId = id; + btn.addEventListener("pointerdown", (e) => { + e.preventDefault(); + e.stopPropagation(); + selectAgentInspector(id); + setStatus(`Inspecting ${id}. Use right panel controls.`); + }); + document.body.appendChild(btn); + agentBadgeElsById.set(id, btn); + return btn; +} + +function installAgentBadgeEventDelegation() { + if (typeof document === "undefined") return; + if (document.body?.dataset?.agentBadgeDelegationInstalled === "1") return; + if (document.body) document.body.dataset.agentBadgeDelegationInstalled = "1"; + // Capture-phase delegation to beat canvas/overlay handlers. + document.addEventListener( + "pointerdown", + (e) => { + const target = e.target; + if (!(target instanceof HTMLElement)) return; + const badge = target.closest(".agent-badge"); + if (!badge) return; + const id = String(badge.dataset.agentId || "").trim(); + if (!id) return; + e.preventDefault(); + e.stopPropagation(); + selectAgentInspector(id); + setStatus(`Inspecting ${id}. Use right panel controls.`); + }, + true + ); +} + +function removeAgentBadge(agentId) { + const id = String(agentId || ""); + const el = agentBadgeElsById.get(id); + if (el?.parentElement) el.parentElement.removeChild(el); + agentBadgeElsById.delete(id); +} + + +function pickTagMarkerFromCamera() { + _raycaster.setFromCamera({ x: 0, y: 0 }, camera); + const hits = _raycaster.intersectObjects(tagsGroup.children, false); + for (const h of hits) { + const obj = h.object; + if (obj?.userData?.isRadius) continue; + const id = obj?.userData?.tagId; + if (id) return id; + } + return null; +} + + + +// Lock pointer and interact on click for FPS navigation. +canvas.addEventListener("click", async (e) => { + if (!controls.isLocked) { + controls.enabled = true; + try { controls.lock(); } catch {} + } else if (e.button === 0) { + await handlePlayerInteraction(); + } +}); + +// Right-click to lock pointer (for FPS navigation) +canvas.addEventListener("contextmenu", (e) => { + e.preventDefault(); + if (!controls.isLocked) { + controls.enabled = true; + try { controls.lock(); } catch {} + } +}); + +controls.addEventListener("lock", () => { + controls.enabled = true; +}); +controls.addEventListener("unlock", () => { + setStatus("Click to look around."); +}); + +resetBtn?.addEventListener("click", () => { + controls.object.position.set(0, 1.7, 4); +}); + + +function setGhostMode(enabled) { + ghostMode = !!enabled; + // Ghost mode indicator shown in status + if (enabled) setStatus("Ghost mode ON"); + + // Disable collisions by turning the player collider into a sensor. + // (Sensors don't generate contact forces, so you can pass through walls.) + try { + if (playerCollider && typeof playerCollider.setSensor === "function") { + playerCollider.setSensor(ghostMode); + } + } catch { + // ignore + } +} + +// Ghost mode toggled via 'G' key only + +// Tagging UI +document.documentElement.dataset.mode = "sim"; +simPanelCollapseBtn?.addEventListener("click", () => { + simPanelCollapsed = true; + applySimPanelCollapsedState(); +}); +simPanelOpenBtn?.addEventListener("click", () => { + simPanelCollapsed = false; + applySimPanelCollapsedState(); +}); +simCameraModeToggleBtn?.addEventListener("click", () => { + simUserCameraMode = simUserCameraMode === "user" ? "agent" : "user"; + localStorage.setItem("sparkWorldSimCameraMode", simUserCameraMode); + updateSimCameraModeToggleUi(); + if (simUserCameraMode === "user") { + if (agentCameraFollow) disableAgentCameraFollow(); + } else if (agentTask.active) { + enableAgentCameraFollow(); + } +}); +simViewRgbdBtn?.addEventListener("click", () => { + simCompareView = false; + setSimSensorViewMode("rgbd"); +}); +simRgbdGrayBtn?.addEventListener("click", () => { + rgbdVizMode = "gray"; + updateSimSensorButtons(); + if (simSensorViewMode === "rgbd") setStatus("RGB-D: metric grayscale"); +}); +simRgbdColormapBtn?.addEventListener("click", () => { + rgbdVizMode = "colormap"; + updateSimSensorButtons(); + if (simSensorViewMode === "rgbd") setStatus("RGB-D: metric colormap"); +}); +simRgbdAutoRangeBtn?.addEventListener("click", () => { + rgbdAutoRange = !rgbdAutoRange; + updateSimSensorButtons(); + if (simSensorViewMode === "rgbd") setStatus(rgbdAutoRange ? "RGB-D auto-range ON (p5/p95)" : "RGB-D auto-range OFF"); +}); +simRgbdNoiseBtn?.addEventListener("click", () => { + rgbdNoiseEnabled = !rgbdNoiseEnabled; + updateSimSensorButtons(); + setStatus(rgbdNoiseEnabled ? "RGB-D noise ON" : "RGB-D noise OFF"); +}); +simRgbdSpeckleBtn?.addEventListener("click", () => { + rgbdSpeckleEnabled = !rgbdSpeckleEnabled; + updateSimSensorButtons(); + setStatus(rgbdSpeckleEnabled ? "RGB-D speckle ON" : "RGB-D speckle OFF"); +}); +simRgbdMinEl?.addEventListener("input", () => { + if (rgbdAutoRange) return; + const minV = Number(simRgbdMinEl.value); + const maxV = Number(simRgbdMaxEl?.value ?? rgbdRangeMaxM); + setRgbdRange(minV, maxV); +}); +simRgbdMaxEl?.addEventListener("input", () => { + if (rgbdAutoRange) return; + const minV = Number(simRgbdMinEl?.value ?? rgbdRangeMinM); + const maxV = Number(simRgbdMaxEl.value); + setRgbdRange(minV, maxV); +}); +simRgbdPcOverlayBtn?.addEventListener("click", () => { + rgbdPcOverlayOnLidar = !rgbdPcOverlayOnLidar; + _rgbdPcOverlayLastUpdateMs = 0; + _rgbdPcOverlayLastPose = null; + _rgbdPcOverlayDirty = rgbdPcOverlayOnLidar; + if (!rgbdPcOverlayOnLidar) { + _rgbdPcGeom.setDrawRange(0, 0); + _rgbdPcOverlayLastCount = 0; + _rgbdPcOverlayDirty = false; + } + if (rgbdPcOverlayOnLidar) { + // Overlay button should directly enter combined LiDAR+RGBD-PC debug mode. + simCompareView = false; + lidarOrderedDebugView = false; + if (simSensorViewMode !== "lidar") simSensorViewMode = "lidar"; + applySimSensorViewMode(); + } + // Actual visibility is finalized by updateRgbdPcOverlayCloud once points are generated. + rgbdPcOverlayGroup.visible = false; + updateSimSensorButtons(); + setStatus(rgbdPcOverlayOnLidar ? `RGB-D->PointCloud overlay ON (${_rgbdPcOverlayLastCount} pts)` : "RGB-D->PointCloud overlay OFF"); +}); +simViewLidarBtn?.addEventListener("click", () => { + // Main LiDAR button always maps to accumulated unordered 3D point cloud. + simCompareView = false; + lidarOrderedDebugView = false; + if (simSensorViewMode !== "lidar") { + _lidarAccumFrames.length = 0; + _lidarLastAccumPose = null; + resetLidarScanState(); + } + setSimSensorViewMode("lidar"); + if (rgbdPcOverlayOnLidar) _rgbdPcOverlayDirty = true; +}); +simViewCompareBtn?.addEventListener("click", () => { + simCompareView = !simCompareView; + if (simCompareView) { + // Auto-collapse panel so tiles get full canvas width. + simPanelCollapsed = true; + applySimPanelCollapsedState(); + simSensorViewMode = "lidar"; + lidarOrderedDebugView = false; + if (rgbdPcOverlayOnLidar) _rgbdPcOverlayDirty = true; + setStatus("Compare view: RGB | RGB-D | LiDAR"); + } else { + simPanelCollapsed = false; + applySimPanelCollapsedState(); + setStatus("Compare view OFF"); + } + applySimSensorViewMode(); +}); +simLidarColorRangeBtn?.addEventListener("click", () => { + lidarColorByRange = !lidarColorByRange; + updateSimSensorButtons(); + if (simSensorViewMode === "lidar") { + updateLidarPointCloud(); + setStatus(lidarColorByRange ? "LiDAR: range-color mode" : "LiDAR: intensity mode"); + } +}); +simLidarOrderedDebugBtn?.addEventListener("click", () => { + // Single Sweep is the explicit ring/scan debug view. + lidarOrderedDebugView = true; + _lidarAccumFrames.length = 0; + _lidarLastAccumPose = null; + resetLidarScanState(); + if (simSensorViewMode !== "lidar") simSensorViewMode = "lidar"; + updateSimSensorButtons(); + applySimSensorViewMode(); + setStatus("LiDAR: single sweep view"); +}); +simLidarNoiseBtn?.addEventListener("click", () => { + lidarNoiseEnabled = !lidarNoiseEnabled; + _lidarAccumFrames.length = 0; + _lidarLastAccumPose = null; + resetLidarScanState(); + updateSimSensorButtons(); + if (simSensorViewMode === "lidar") updateLidarPointCloud(); + setStatus(lidarNoiseEnabled ? "LiDAR noise ON" : "LiDAR noise OFF"); +}); +simLidarMultiReturnBtn?.addEventListener("click", () => { + lidarMultiReturnMode = lidarMultiReturnMode === "strongest" ? "last" : "strongest"; + _lidarAccumFrames.length = 0; + _lidarLastAccumPose = null; + resetLidarScanState(); + updateSimSensorButtons(); + if (simSensorViewMode === "lidar") updateLidarPointCloud(); + setStatus(`LiDAR return mode: ${lidarMultiReturnMode}`); +}); +spawnAiBtn?.addEventListener("click", async () => { + try { + await spawnOrMoveAiAtAim({ createNew: false, ephemeral: false }); + } catch (err) { + console.error("[Spawn] Error spawning agent:", err); + setStatus("Spawn failed: " + (err?.message || String(err))); + } +}); + +// --- Blob shadow live-adjustment helpers --- +// Updates the blob shadow mesh in-place without rebuilding the entire asset. +function updateBlobShadowLive(assetId) { + const a = assets.find((x) => x.id === assetId); + if (!a?.castShadow) return; + const root = assetsGroup.getObjectByName(`asset:${assetId}`); + if (!root) return; + const blob = root.getObjectByName(`blobShadow:${assetId}`); + if (!blob) return; + const bs = a.blobShadow || {}; + // Opacity + if (blob.material) blob.material.opacity = bs.opacity ?? 0.5; + // Scale + stretch + const baseDiam = blob.userData._baseDiameter || 1; + const userScale = bs.scale ?? 1.0; + const stretch = bs.stretch ?? 1.0; + const d = baseDiam * userScale; + blob.scale.set(d * stretch, 1, d / stretch); + // Rotation (Y axis, degrees → radians) + blob.rotation.y = ((bs.rotationDeg ?? 0) * Math.PI) / 180; + // Offset + blob.position.x = bs.offsetX ?? 0; + const baseY = blob.userData._baseLocalY ?? blob.position.y; + blob.position.y = baseY + (bs.offsetY ?? 0); + blob.position.z = bs.offsetZ ?? 0; +} + + +// Initialize agent UI visibility/content. +applySimPanelCollapsedState(); +renderAgentTaskUi(); +agentTaskStartBtn?.addEventListener("click", () => { + if (agentTask.active) return; + void startAgentTask(agentTaskInputEl?.value); +}); +agentTaskEndBtn?.addEventListener("click", () => endAgentTask("manual")); +// Enter key in command input starts task; stop propagation so WASD doesn't trigger +agentTaskInputEl?.addEventListener("keydown", (e) => { + e.stopPropagation(); + if (e.key === "Enter" && !agentTask.active && aiAgents.length > 0) { + void startAgentTask(agentTaskInputEl.value); + } +}); + +// Shared import logic — used by both editor Import and sim Load Level +async function importLevelFromJSON(json, options = {}) { + const importedTags = Array.isArray(json?.tags) ? json.tags : Array.isArray(json) ? json : null; + const preserveAssetsWhenMissing = options.preserveAssetsWhenMissing === true; + const importedAssets = Array.isArray(json?.assets) + ? json.assets + : (preserveAssetsWhenMissing ? assets : []); + const importedPrimitives = Array.isArray(json?.primitives) ? json.primitives : []; + const importedLights = Array.isArray(json?.lights) ? json.lights : []; + const importedSceneSettings = json && typeof json === "object" && json.sceneSettings + ? normalizeSceneSettings(json.sceneSettings) + : null; + if (!importedTags) throw new Error("Invalid level file."); + // Clean up old primitive colliders + for (const p of primitives) removePrimitiveCollider(p); + tags = importedTags; + assets = importedAssets; + primitives = importedPrimitives; + editorLights = importedLights; + if (importedSceneSettings) sceneSettings = importedSceneSettings; + if (!options.skipWorldSave) saveTagsForWorld(); + rebuildTagMarkers(); + await rebuildAssets(); + rebuildAllPrimitives(); + rebuildAllEditorLights(); + renderTagsList(); + renderAssetsList(); + renderPrimitivesList(); + renderTagPanel(); + applySceneSkySettings(); + applySceneRgbBackground(); + syncShadowMapEnabled(); +} + +// Exposed for the sim-authoring UI dropdown and sceneApi.loadJson. +window.importLevelFromJSON = importLevelFromJSON; + + +// Sim-mode "Load Level JSON" input (only exists in sim.html) +const simLevelImportEl = document.getElementById("sim-level-import"); +simLevelImportEl?.addEventListener("change", async (e) => { + const file = e.target.files?.[0]; + if (!file) return; + try { + setStatus("Loading level..."); + const text = await file.text(); + await importLevelFromJSON(JSON.parse(text)); + await ensureRapierLoaded(); + spawnPlayerInsideScene(); + setStatus("Level loaded. Click to enter, then spawn an agent."); + } catch (err) { + console.error(err); + setStatus(err?.message || "Failed to load level."); + } finally { + e.target.value = ""; + } +}); + +canvas?.addEventListener("mousedown", () => { + const id = pickTagMarkerFromCamera(); + if (!id) return; + selectedTagId = id; + draftTag = null; + updateMarkerMaterials(); + renderTagsList(); + renderTagPanel(); +}); + + +// ============================================================================= +// PRIMITIVE & LIGHT EVENT HANDLERS +// ============================================================================= + + +// Expose tag data for "simulation mode" consumers. +globalThis.sparkWorld = globalThis.sparkWorld || {}; +globalThis.sparkWorld.getWorldKey = () => worldKey; +globalThis.sparkWorld.getTags = () => tags.slice(); +globalThis.sparkWorld.getAiAgents = () => aiAgents.map((a) => ({ id: a.id, position: a.getPosition?.() })); + +function teleportPlayerTo(x, y, z) { + if (!playerBody) return; + playerBody.setTranslation({ x, y, z }, true); + playerBody.setLinvel({ x: 0, y: 0, z: 0 }, true); +} + +// Find a reasonable interior floor Y by casting a ray straight down through the +// loaded scene meshes and picking the lowest up-facing surface. This skips the +// roof when a building has both a roof and an interior floor, so the player +// lands inside rather than on top. +function _findSceneFloorY(x = 0, z = 0) { + const bbox = new THREE.Box3(); + const tmp = new THREE.Box3(); + try { tmp.setFromObject(assetsGroup); if (tmp.isEmpty() === false) bbox.union(tmp); } catch {} + try { tmp.setFromObject(primitivesGroup); if (tmp.isEmpty() === false) bbox.union(tmp); } catch {} + const fromY = bbox.isEmpty() ? 50 : bbox.max.y + 5; + const raycaster = new THREE.Raycaster( + new THREE.Vector3(x, fromY, z), + new THREE.Vector3(0, -1, 0), + 0, + fromY + 500, + ); + // Pure-Three.js scenes (e.g. apartment loading structure.glb directly via + // loadGLTF + scene.add) put their floor outside of assetsGroup/primitivesGroup. + // Ray-cast the full scene as a third target — the worldN.y >= 0.5 filter + // below still rules out walls, ceilings, and the skybox. + const hits = [ + ...raycaster.intersectObject(assetsGroup, true), + ...raycaster.intersectObject(primitivesGroup, true), + ...raycaster.intersectObject(scene, true), + ]; + let floorY = null; + for (const h of hits) { + const n = h.face?.normal; + if (!n) continue; + // Transform face normal to world space to test "up-facing" + const worldN = n.clone().transformDirection(h.object.matrixWorld); + if (worldN.y < 0.5) continue; // skip walls/ceilings + if (floorY == null || h.point.y < floorY) floorY = h.point.y; + } + return floorY; +} + +function spawnPlayerInsideScene() { + const floorY = _findSceneFloorY(0, 0); + if (floorY == null) return false; + const y = floorY + PLAYER_EYE_HEIGHT; + camera.position.set(0, y, 0); + teleportPlayerTo(0, y, 0); + return true; +} + + +function safeDisableGhost() { + // If we're currently inside occupied geometry, turning collisions back on will + // trap the character (penetration state). Use Rapier query pipeline to find a safe spot. + if (!playerBody) return setGhostMode(false); + const p = playerBody.translation(); + + // Use Rapier query pipeline to find a non-penetrating spot. + if (rapierWorld && playerCollider) { + try { + const shape = playerCollider.shape; + const rot = playerCollider.rotation(); + const here = { x: p.x, y: p.y, z: p.z }; + + const intersectsHere = rapierWorld.queryPipeline.intersectionWithShape( + rapierWorld.bodies, + rapierWorld.colliders, + here, + rot, + shape, + RAPIER.QueryFilterFlags.EXCLUDE_SENSORS, + undefined, + playerCollider.handle + ); + + // If we're not intersecting anything solid, we can safely disable ghost immediately. + if (intersectsHere == null) { + setGhostMode(false); + setStatus("Ghost disabled."); + return; + } + + const tryOffsets = (maxR, step) => { + for (let r = step; r <= maxR; r += step) { + // sample a handful of directions per radius + const dirs = [ + [1, 0, 0], + [-1, 0, 0], + [0, 0, 1], + [0, 0, -1], + [1, 0, 1], + [1, 0, -1], + [-1, 0, 1], + [-1, 0, -1], + [0, 1, 0], + [0, -1, 0], + ]; + for (const [dx, dy, dz] of dirs) { + const len = Math.hypot(dx, dy, dz) || 1; + const pos = { x: p.x + (dx / len) * r, y: p.y + (dy / len) * r, z: p.z + (dz / len) * r }; + const hit = rapierWorld.queryPipeline.intersectionWithShape( + rapierWorld.bodies, + rapierWorld.colliders, + pos, + rot, + shape, + RAPIER.QueryFilterFlags.EXCLUDE_SENSORS, + undefined, + playerCollider.handle + ); + if (hit == null) return pos; + } + } + return null; + }; + + const pos = tryOffsets(2.5, 0.15); + if (pos) { + teleportPlayerTo(pos.x, pos.y, pos.z); + setGhostMode(false); + setStatus("Ghost disabled (moved to nearest free space)."); + return; + } + } catch { + // ignore + } + } + + setStatus("Couldn't find free space to disable Ghost. Staying in Ghost mode."); + setGhostMode(true); +} + +window.addEventListener("keydown", (e) => { + const tagName = e.target?.tagName?.toLowerCase?.(); + const isTyping = + tagName === "input" || tagName === "textarea" || tagName === "select" || e.target?.isContentEditable; + if (!isTyping) { + if (e.code === "KeyB") { + void spawnOrMoveAiAtAim({ createNew: false, ephemeral: false }); + e.preventDefault(); + } + } + if (e.code === "KeyW") keys.forward = true; + if (e.code === "KeyS") keys.backward = true; + if (e.code === "KeyA") keys.left = true; + if (e.code === "KeyD") keys.right = true; + if (e.code === "Space") keys.up = true; + if (e.code === "ShiftLeft" || e.code === "ShiftRight") keys.down = true; + if (e.code === "KeyF") flyMode = !flyMode; + if (e.code === "KeyG") { + if (ghostMode) safeDisableGhost(); + else setGhostMode(true); + } + + // === PLAYER INTERACTION KEYS === + // E key to interact with asset at crosshair + if (e.code === "KeyE" && controls?.isLocked && !isTyping) { + handlePlayerInteraction(); + e.preventDefault(); + } + if (e.code === "KeyR" && controls?.isLocked && !isTyping && !isInteractionPopupVisible()) { + if (cycleInteractableTarget(1)) { + updatePlayerInteractionHint(); + e.preventDefault(); + } + } + + // Escape to close interaction popup + if (e.code === "Escape" && isInteractionPopupVisible()) { + hideInteractionPopup(); + // Re-lock pointer after closing popup + controls?.lock?.(); + e.preventDefault(); + } + + // Number keys 1-9 to select action when popup is visible + if (isInteractionPopupVisible() && _currentInteractableAsset) { + const numMatch = e.code.match(/^(?:Digit|Numpad)([1-9])$/); + if (numMatch) { + const idx = parseInt(numMatch[1], 10) - 1; + const { asset, actions } = _currentInteractableAsset; + if (idx >= 0 && idx < actions.length) { + const actionId = actions[idx].id; + + // Hide popup and re-lock pointer FIRST (before async operations) + hideInteractionPopup(); + + // Execute the action + if (actionId === "__PICK_UP__") { + playerPickUpAsset(asset.id); + } else { + executePlayerInteraction(asset.id, actionId); + } + + // Re-lock pointer (use setTimeout since pointer lock may need a moment) + setTimeout(() => { + try { + controls?.lock?.(); + } catch (err) { + // Pointer lock requires user gesture, may fail silently + } + }, 10); + + e.preventDefault(); + e.stopPropagation(); + return; + } + } + } +}); + +window.addEventListener("keyup", (e) => { + if (e.code === "KeyW") keys.forward = false; + if (e.code === "KeyS") keys.backward = false; + if (e.code === "KeyA") keys.left = false; + if (e.code === "KeyD") keys.right = false; + if (e.code === "Space") keys.up = false; + if (e.code === "ShiftLeft" || e.code === "ShiftRight") keys.down = false; +}); + + +// Shadow catcher: a large transparent ground plane that only shows shadows. +// ShadowMaterial is fully transparent where there's no shadow, so the splat +// floor shows through, but shadows appear as dark patches on top. +const shadowCatcherMat = new THREE.ShadowMaterial({ opacity: 0.35 }); +const shadowCatcher = new THREE.Mesh( + new THREE.PlaneGeometry(200, 200), + shadowCatcherMat +); +shadowCatcher.rotation.x = -Math.PI / 2; // lie flat +shadowCatcher.position.y = 0.001; // just above grid to avoid z-fighting +shadowCatcher.receiveShadow = true; +shadowCatcher.name = "__shadowCatcher"; +scene.add(shadowCatcher); +// Add to scene lights registry so it's controllable from the editor +sceneLights.push({ id: "_shadow_ground", label: "Shadow Ground", obj: shadowCatcher, type: "shadow_ground" }); + +function _hasBumpableAssets() { + for (const a of assets) { if (a?.bumpable) return true; } + return false; +} + +function updateBumpableAssets(dt, playerPos, agentPushers = []) { + if (!playerPos || !_hasBumpableAssets()) { + _playerPosPrevForBumpValid = false; + return; + } + if (!_playerPosPrevForBumpValid) { + _playerPosPrevForBump.copy(playerPos); + _playerPosPrevForBumpValid = true; + return; + } + const playerVel = new THREE.Vector3().subVectors(playerPos, _playerPosPrevForBump).divideScalar(Math.max(dt, 1e-3)); + _playerPosPrevForBump.copy(playerPos); + const speedXZ = Math.hypot(playerVel.x, playerVel.z); + const playerCanPush = !ghostMode; + const intent = new THREE.Vector3(); + const camForward = new THREE.Vector3(); + camera.getWorldDirection(camForward); + camForward.y = 0; + if (camForward.lengthSq() > 1e-6) camForward.normalize(); + const camRight = new THREE.Vector3().crossVectors(camForward, camera.up).normalize(); + if (keys.forward) intent.add(camForward); + if (keys.backward) intent.sub(camForward); + if (keys.right) intent.add(camRight); + if (keys.left) intent.sub(camRight); + if (intent.lengthSq() > 1e-6) intent.normalize(); + const intentPush = playerCanPush && intent.lengthSq() > 0; + const pushDir = intentPush ? intent.clone() : new THREE.Vector3(playerVel.x, 0, playerVel.z); + if (pushDir.lengthSq() > 1e-6) pushDir.normalize(); + const playerRadius = 0.35; + const pushThreshold = 0.05; + let anyMoved = false; + let anyColliderNeedsSync = false; + for (const a of assets) { + if (!a?.bumpable) continue; + const obj = assetsGroup.getObjectByName(`asset:${a.id}`); + if (!obj) continue; + const vel = _assetBumpVelocities.get(a.id) || new THREE.Vector3(); + const localCenter = obj.userData?._localSphereCenter || new THREE.Vector3(); + const worldCenter = localCenter.clone(); + obj.localToWorld(worldCenter); + const worldRadius = (obj.userData?._localSphereRadius || 0.6) * Math.max(obj.scale.x, obj.scale.y, obj.scale.z); + const dx = worldCenter.x - playerPos.x; + const dz = worldCenter.z - playerPos.z; + const dist = Math.hypot(dx, dz); + const minDist = worldRadius + playerRadius; + const ahead = pushDir.lengthSq() > 0 ? (dx * pushDir.x + dz * pushDir.z) : 0; + const lateral = pushDir.lengthSq() > 0 ? Math.abs(dx * -pushDir.z + dz * pushDir.x) : dist; + const inPushCone = intentPush && ahead > -0.05 && ahead < (minDist + 0.9) && lateral < (worldRadius + 0.55); + if (playerCanPush && (dist < (minDist + 0.35) || inPushCone) && (speedXZ > pushThreshold || intentPush)) { + const dirX = dist > 1e-3 ? dx / dist : (intentPush ? pushDir.x : (Math.sign(playerVel.x) || 1)); + const dirZ = dist > 1e-3 ? dz / dist : (intentPush ? pushDir.z : (Math.sign(playerVel.z) || 0)); + const penetration = minDist - dist; + const response = Number(a.bumpResponse) || 0.9; + const driveSpeed = Math.max(speedXZ, intentPush ? 1.4 : 0); + const intentBonus = inPushCone ? 0.35 : 0; + const impulse = Math.min(2.4, (Math.max(0, penetration) * 3 + driveSpeed * 0.35 + intentBonus) * response); + vel.x += dirX * impulse; + vel.z += dirZ * impulse; + } + // AI agents can push bumpable assets as well. + for (const ap of agentPushers) { + const apPos = ap?.pos; + const apVel = ap?.vel; + if (!apPos || !apVel) continue; + const av = Math.hypot(apVel.x || 0, apVel.z || 0); + if (av <= 0.04) continue; + const adx = worldCenter.x - apPos.x; + const adz = worldCenter.z - apPos.z; + const adist = Math.hypot(adx, adz); + const aminDist = worldRadius + Math.max(0.22, Number(ap.radius) || 0.22); + if (adist > aminDist + 0.3) continue; + const dirX = adist > 1e-3 ? adx / adist : (Math.sign(apVel.x) || 1); + const dirZ = adist > 1e-3 ? adz / adist : (Math.sign(apVel.z) || 0); + const penetration = aminDist - adist; + const response = Number(a.bumpResponse) || 0.9; + const impulse = Math.min(2.2, (Math.max(0, penetration) * 2.4 + av * 0.28) * response); + vel.x += dirX * impulse; + vel.z += dirZ * impulse; + } + const damping = Math.min(0.995, Math.max(0.65, Number(a.bumpDamping) || 0.9)); + const dampPow = Math.pow(damping, dt * 60); + vel.multiplyScalar(dampPow); + const maxSpeed = 2.5; + const speed = Math.hypot(vel.x, vel.z); + if (speed > maxSpeed) { + const s = maxSpeed / speed; + vel.x *= s; + vel.z *= s; + } + if (vel.lengthSq() < 1e-4) { + vel.set(0, 0, 0); + _assetBumpVelocities.set(a.id, vel); + continue; + } + let moveX = THREE.MathUtils.clamp(vel.x * dt, -0.2, 0.2); + let moveZ = THREE.MathUtils.clamp(vel.z * dt, -0.2, 0.2); + const myBox = new THREE.Box3().setFromObject(obj); + const testBoxX = myBox.clone().translate(new THREE.Vector3(moveX, 0, 0)); + const testBoxZ = myBox.clone().translate(new THREE.Vector3(0, 0, moveZ)); + let blockedX = false, blockedZ = false; + const checkCollision = (testBox, excludeObj) => { + for (const child of primitivesGroup.children) { + if (child === excludeObj) continue; + const cb = new THREE.Box3().setFromObject(child); + if (!cb.isEmpty() && testBox.intersectsBox(cb)) return true; + } + for (const child of assetsGroup.children) { + if (child === excludeObj) continue; + if (child.userData?.isBlobShadow) continue; + const cb = new THREE.Box3().setFromObject(child); + if (!cb.isEmpty() && testBox.intersectsBox(cb)) return true; + } + return false; + }; + if (Math.abs(moveX) > 1e-5 && checkCollision(testBoxX, obj)) { + blockedX = true; + vel.x *= -0.15; + } + if (Math.abs(moveZ) > 1e-5 && checkCollision(testBoxZ, obj)) { + blockedZ = true; + vel.z *= -0.15; + } + if (!blockedX) obj.position.x += moveX; + if (!blockedZ) obj.position.z += moveZ; + if (blockedX && blockedZ) { + _assetBumpVelocities.set(a.id, vel); + continue; + } + anyMoved = true; + anyColliderNeedsSync = true; + if (!a.transform) a.transform = {}; + if (!a.transform.position) a.transform.position = { x: 0, y: 0, z: 0 }; + a.transform.position.x = obj.position.x; + a.transform.position.z = obj.position.z; + _assetBumpVelocities.set(a.id, vel); + } + if (anyMoved) { + const now = performance.now(); + if (now - _lastBumpSaveAt > 500) { + _lastBumpSaveAt = now; + saveTagsForWorld(); + } + if (anyColliderNeedsSync && now - _lastBumpColliderSyncAt > 50) { + _lastBumpColliderSyncAt = now; + for (const a of assets) { + if (!a?.bumpable) continue; + if (!_assetBumpVelocities.has(a.id)) continue; + const v = _assetBumpVelocities.get(a.id); + if (!v || v.lengthSq() < 1e-4) continue; + rebuildAssetCollider(a.id); + } + } + } +} + +function collectAgentBumpPushers(dt) { + const pushers = []; + const alive = new Set(); + const invDt = 1 / Math.max(dt, 1e-3); + for (const agent of aiAgents) { + const id = String(agent?.id || ""); + const posRaw = agent?.body?.translation?.(); + if (!id || !posRaw) continue; + alive.add(id); + const pos = new THREE.Vector3(posRaw.x, posRaw.y, posRaw.z); + const prev = _agentPosPrevForBump.get(id); + const vel = prev ? pos.clone().sub(prev).multiplyScalar(invDt) : new THREE.Vector3(); + _agentPosPrevForBump.set(id, pos.clone()); + pushers.push({ + id, + pos, + vel, + radius: Math.max(0.2, Number(agent?.radius) || 0.2), + }); + } + for (const id of _agentPosPrevForBump.keys()) { + if (!alive.has(id)) _agentPosPrevForBump.delete(id); + } + return pushers; +} + +function updateRapier(dt) { + // No physics world loaded → free-fly camera movement so user can still navigate + if (!rapierWorld || !playerBody) { + const flySpeed = 8.0; + const fwd = new THREE.Vector3(); + camera.getWorldDirection(fwd); + const right = new THREE.Vector3().crossVectors(fwd, camera.up).normalize(); + const move = new THREE.Vector3(); + if (keys.forward) move.add(fwd); + if (keys.backward) move.sub(fwd); + if (keys.right) move.add(right); + if (keys.left) move.sub(right); + if (keys.up) move.y += 1; + if (keys.down) move.y -= 1; + if (move.lengthSq() > 0) { + move.normalize().multiplyScalar(flySpeed * dt); + controls.object.position.add(move); + avatar.position.copy(controls.object.position).y -= PLAYER_EYE_HEIGHT; + } + return; + } + + // Flush any deferred collider builds BEFORE stepping + flushPendingColliderBuilds(); + + // Step physics FIRST — this integrates last frame's kinematic moves and + // updates the query pipeline internally, avoiding the RefCell double-borrow + // that happens with manual `queryPipeline.update(colliders)`. + rapierWorld.timestep = dt; + try { + rapierWorld.step(); + _rapierStepFaultCount = 0; + } catch (e) { + _rapierStepFaultCount += 1; + console.warn(`[RAPIER] step() failed (${_rapierStepFaultCount})`, e); + // Prevent hard crash loop; skip this frame and try again next tick. + return; + } + + // Sync camera and avatar to the body position that step() just resolved + const p = playerBody.translation(); + + // Skip player movement when camera is following agent + if (agentCameraFollow) { + avatar.position.set(p.x, p.y, p.z); + return; + } + + const baseSpeed = 6.0; + const runSpeed = 10.0; + const flySpeed = 8.0; + const speed = flyMode ? flySpeed : keys.down ? runSpeed : baseSpeed; + const gravity = 20.0; + const jumpVel = 8.0; + + const forward = new THREE.Vector3(); + camera.getWorldDirection(forward); + forward.y = 0; + forward.normalize(); + const right = new THREE.Vector3().crossVectors(forward, camera.up).normalize(); + + const wish = new THREE.Vector3(); + if (keys.forward) wish.add(forward); + if (keys.backward) wish.sub(forward); + if (keys.right) wish.add(right); + if (keys.left) wish.sub(right); + if (wish.lengthSq() > 0) wish.normalize(); + + const upDown = flyMode ? (keys.up ? 1 : 0) + (keys.down ? -1 : 0) : 0; + + const t = p; // body position after step + let desired = { x: 0, y: 0, z: 0 }; + + if (ghostMode) { + desired = { + x: wish.x * flySpeed * dt, + y: ((keys.up ? 1 : 0) + (keys.down ? -1 : 0)) * flySpeed * dt, + z: wish.z * flySpeed * dt, + }; + playerBody.setNextKinematicTranslation({ + x: t.x + desired.x, + y: t.y + desired.y, + z: t.z + desired.z, + }); + } else if (flyMode) { + desired = { + x: wish.x * flySpeed * dt, + y: upDown * flySpeed * dt, + z: wish.z * flySpeed * dt, + }; + if (characterController && playerCollider) { + characterController.computeColliderMovement( + playerCollider, + desired, + RAPIER.QueryFilterFlags.EXCLUDE_SENSORS + ); + const m = characterController.computedMovement(); + const mx = m.x, my = m.y, mz = m.z; + playerBody.setNextKinematicTranslation({ x: t.x + mx, y: t.y + my, z: t.z + mz }); + } else { + playerBody.setNextKinematicTranslation({ x: t.x + desired.x, y: t.y + desired.y, z: t.z + desired.z }); + } + } else { + walkVerticalVel -= gravity * dt; + + if (keys.up && characterController?.computedGrounded?.()) { + walkVerticalVel = jumpVel; + } + + desired = { x: wish.x * speed * dt, y: walkVerticalVel * dt, z: wish.z * speed * dt }; + + if (characterController && playerCollider) { + characterController.computeColliderMovement( + playerCollider, + desired, + RAPIER.QueryFilterFlags.EXCLUDE_SENSORS + ); + const m = characterController.computedMovement(); + const mx = m.x, my = m.y, mz = m.z; + const grounded = characterController.computedGrounded(); + if (grounded && walkVerticalVel < 0) walkVerticalVel = 0; + playerBody.setNextKinematicTranslation({ x: t.x + mx, y: t.y + my, z: t.z + mz }); + } else { + playerBody.setNextKinematicTranslation({ x: t.x + desired.x, y: t.y + desired.y, z: t.z + desired.z }); + } + } + + // Safety: if Ghost is OFF, ensure the collider is not a sensor + try { + if (!ghostMode && playerCollider && typeof playerCollider.isSensor === "function" && playerCollider.isSensor()) { + playerCollider.setSensor(false); + } + } catch {} + avatar.position.set(p.x, p.y, p.z); + + // If agent camera follow is active, DON'T sync player camera to player body + // The tick() function will handle camera positioning via updateAgentCameraFollow + if (!agentCameraFollow) { + controls.object.position.set(p.x, p.y + PLAYER_EYE_HEIGHT, p.z); + } + + // Expose player position for other modules (AI, etc). + if (typeof window !== "undefined") { + window.__playerPosition = [p.x, p.y, p.z]; + } +} + +function tick() { + const rawDt = clock.getDelta(); + const physicsDt = Math.min(rawDt, 0.05); + const motionDt = Math.min(rawDt, 0.02); + + updateRapier(physicsDt); + + // Bumpable assets: only compute if any exist + if (_hasBumpableAssets()) { + const agentPushers = aiAgents.length ? collectAgentBumpPushers(physicsDt) : []; + let bumpPlayerPos = null; + if (playerBody) { + const p = playerBody.translation(); + bumpPlayerPos = new THREE.Vector3(p.x, p.y, p.z); + } else { + bumpPlayerPos = controls.object.position.clone(); + bumpPlayerPos.y -= PLAYER_EYE_HEIGHT; + } + updateBumpableAssets(physicsDt, bumpPlayerPos, agentPushers); + } + + // Update AI agents (if Rapier is initialized). + if (aiAgents.length && rapierWorld) { + const now = Date.now(); + for (const a of aiAgents) { + try { + // Keep cmd_vel integration tied to wall-clock delta even when physics dt is clamped. + a.update(motionDt, now); + } catch (e) { + console.warn("AI update failed:", e); + } + } + } + + // Update agent camera follow (after agent update, before render) + if (agentCameraFollow) { + updateAgentCameraFollow(physicsDt); + avatar.visible = false; + } + + // Update interaction hint at reduced rate + const now = performance.now(); + if (now - _lastHintUpdate > 300) { + _lastHintUpdate = now; + updateInteractionHint(); + } + + // LiDAR / sensor overlays — run when explicitly enabled OR in dimos mode + // In dimos mode, always skip browser raycasting — server handles lidar via Rapier snapshots. + const _skipBrowserLidar = dimosMode; + if (!_skipBrowserLidar && (simSensorViewMode === "lidar" || simCompareView || dimosMode)) { + lidarVizGroup.visible = true; + updateLidarPointCloud(); + if (_lidarGeom.drawRange.count <= 0 && _lidarLastNonZeroDrawCount > 0) { + _lidarGeom.setDrawRange(0, _lidarLastNonZeroDrawCount); + } + // In dimos mode, hide LiDAR viz from the main scene render — it's only + // needed for data capture + the sidebar LiDAR panel renders it separately. + if (dimosMode && simSensorViewMode !== "lidar" && !simCompareView) { + lidarVizGroup.visible = false; + } + } else if (!_skipBrowserLidar && rgbdPcOverlayOnLidar && (simSensorViewMode === "lidar" || simCompareView)) { + updateRgbdPcOverlayCloud(false); + } + + if (!_skipBrowserLidar) pushLidarPoseSample(); + + // Dimos sensor capture — GPU readback needs rAF, odom runs independently via setInterval + if (dimosMode && window.__dimosBridge) { + const bridge = window.__dimosBridge; + if (bridge._connected) { + // Lidar: skip browser→WS publish when server-side lidar is active + if (bridge._dirty.lidar && !bridge._serverLidar) { + bridge._dirty.lidar = false; + bridge._publishLidar(); + } + // Camera stream disabled for now. + // if (bridge._dirty.images) { + // bridge._dirty.images = false; + // bridge._publishImages(); + // } + } + } + + renderActiveView(); + requestAnimationFrame(tick); +} + +// Interaction hint elements (cached) +let _lastHintUpdate = 0; +let _crosshairEl = null; +let _interactionHintEl = null; + +function updateInteractionHint() { + // Cache DOM elements + if (!_crosshairEl) _crosshairEl = document.getElementById("crosshair"); + if (!_interactionHintEl) _interactionHintEl = document.getElementById("interaction-hint"); + + // Only show when pointer is locked and no popup is visible + if (!controls?.isLocked || isInteractionPopupVisible()) { + _crosshairEl?.classList.remove("interactable"); + if (_interactionHintEl) { + _interactionHintEl.classList.remove("visible"); + } + return; + } + + // If holding something, show drop hint + if (playerHeldAsset) { + const heldAsset = getPlayerHeldAsset(); + const heldName = heldAsset?.title || "item"; + _crosshairEl?.classList.remove("interactable"); + _crosshairEl?.classList.add("holding"); + if (_interactionHintEl) { + _interactionHintEl.innerHTML = `Holding: ${escapeHtml(heldName)} · DropE`; + _interactionHintEl.classList.add("visible"); + } + return; + } + if (playerHeldGroupId) { + const heldGroup = groups.find((g) => g.id === playerHeldGroupId); + const heldName = heldGroup?.name || "group"; + _crosshairEl?.classList.remove("interactable"); + _crosshairEl?.classList.add("holding"); + if (_interactionHintEl) { + _interactionHintEl.innerHTML = `Holding: ${escapeHtml(heldName)} · DropE`; + _interactionHintEl.classList.add("visible"); + } + return; + } + + // Not holding anything - remove holding class + _crosshairEl?.classList.remove("holding"); + + const target = getInteractableAssetAtCrosshair(); + + if (target) { + const { kind, asset, group, actions, dist, canPickUp } = target; + const title = kind === "group" ? (group?.name || "(group)") : (asset.title || "(asset)"); + + // Build action description + let actionText; + if (kind === "group") { + actionText = "Pick up"; + } else if (actions.length === 0 && canPickUp) { + actionText = "Pick up"; + } else if (actions.length === 1 && !canPickUp) { + actionText = actions[0].label || "interact"; + } else { + const count = actions.length + (canPickUp ? 1 : 0); + actionText = `${count} actions`; + } + + _crosshairEl?.classList.add("interactable"); + if (_interactionHintEl) { + const cycleHint = kind === "asset" && target.candidateCount > 1 + ? ` · Cycle ${target.candidateIndex + 1}/${target.candidateCount}R` + : ""; + _interactionHintEl.innerHTML = `${escapeHtml(title)} · ${escapeHtml(actionText)}E${cycleHint}`; + _interactionHintEl.classList.add("visible"); + } + } else { + _crosshairEl?.classList.remove("interactable"); + if (_interactionHintEl) { + _interactionHintEl.classList.remove("visible"); + } + } +} + +setStatus("Select a .ply/.spz to start."); +tick(); + +// Expose debug utilities +window.clearWorldStorage = clearWorldStorage; +window.__robovalLidar = { + // Returns the latest standardized frames (raw + deskewed + optional range image) + getLatestFrames() { + return { + raw: _lidarLatestRawFrame, + deskewed: _lidarLatestDeskewedFrame, + rangeImage: _lidarLatestRangeImage, + }; + }, + // ROS2 PointCloud2-compatible dict converter + toPointCloud2(frame) { + return to_pointcloud2(frame); + }, + // Manual export of the latest frame set to NPZ files. + async exportLatest() { + if (!_lidarLatestRawFrame || !_lidarLatestDeskewedFrame) return false; + await writeLidarFrameFiles(_lidarLatestRawFrame, _lidarLatestDeskewedFrame, _lidarLatestRangeImage); + return true; + }, + // Auto-export each LiDAR frame (warning: downloads many files in browser). + setAutoExport(enabled) { + _lidarAutoExport = !!enabled; + return _lidarAutoExport; + }, + getAutoExport() { + return _lidarAutoExport; + }, + // Force a known-good synthetic cloud to isolate renderer issues from sensor math. + setKnownGoodDebugCloud(enabled) { + _lidarUseKnownGoodDebugCloud = !!enabled; + _lidarAccumFrames.length = 0; + _lidarLastAccumPose = null; + resetLidarScanState(); + if (simSensorViewMode === "lidar") updateLidarPointCloud(); + return _lidarUseKnownGoodDebugCloud; + }, + getKnownGoodDebugCloud() { + return _lidarUseKnownGoodDebugCloud; + }, + // Toggle ordered scan debug render (single-frame, lidar-frame) vs accumulated world cloud. + setOrderedDebugView(enabled) { + lidarOrderedDebugView = !!enabled; + if (!lidarOrderedDebugView) { + _lidarAccumFrames.length = 0; + _lidarLastAccumPose = null; + resetLidarScanState(); + } + updateSimSensorButtons(); + if (simSensorViewMode === "lidar") updateLidarPointCloud(); + return lidarOrderedDebugView; + }, + getOrderedDebugView() { + return lidarOrderedDebugView; + }, + setNoiseModel(enabled) { + lidarNoiseEnabled = !!enabled; + _lidarAccumFrames.length = 0; + _lidarLastAccumPose = null; + resetLidarScanState(); + updateSimSensorButtons(); + if (simSensorViewMode === "lidar") updateLidarPointCloud(); + return lidarNoiseEnabled; + }, + getNoiseModel() { + return lidarNoiseEnabled; + }, + setMultiReturnMode(mode) { + lidarMultiReturnMode = mode === "last" ? "last" : "strongest"; + _lidarAccumFrames.length = 0; + _lidarLastAccumPose = null; + resetLidarScanState(); + updateSimSensorButtons(); + if (simSensorViewMode === "lidar") updateLidarPointCloud(); + return lidarMultiReturnMode; + }, + getMultiReturnMode() { + return lidarMultiReturnMode; + }, +}; + +window.__robovalRgbd = { + // Returns metric camera-space Z depth map in meters (Float32Array length W*H). + // Uses the same render path as on-screen RGB-D mode. + getMetricDepthFrame() { + renderRgbdView(); + const depth = readRgbdMetricDepthFrameMeters(); + if (!depth) return null; + return { + width: rgbdMetricTarget.width, + height: rgbdMetricTarget.height, + depth_m: depth, + semantics: "camera_space_z", + units: "meters", + min_depth_m: RGBD_MIN_DEPTH_M, + max_depth_m: RGBD_MAX_DEPTH_M, + }; + }, + getOverlayStats() { + return { + enabled: rgbdPcOverlayOnLidar, + visible: rgbdPcOverlayGroup.visible, + points: _rgbdPcOverlayLastCount, + rt_w: RGBD_PC_OVERLAY_RT_W, + rt_h: RGBD_PC_OVERLAY_RT_H, + dirty: _rgbdPcOverlayDirty, + }; + }, +}; + +// Debug: List all colliders in the physics world +window.debugColliders = function() { + if (!rapierWorld) { + console.log("[DEBUG] No physics world loaded"); + return; + } + + console.log("[DEBUG] === ALL COLLIDERS IN PHYSICS WORLD ==="); + let count = 0; + rapierWorld.colliders.forEach((collider) => { + const pos = collider.translation(); + const shape = collider.shape; + const isSensor = collider.isSensor(); + const handle = collider.handle; + console.log(`Collider #${count} (handle=${handle}): pos=(${pos.x.toFixed(2)}, ${pos.y.toFixed(2)}, ${pos.z.toFixed(2)}), sensor=${isSensor}, shapeType=${shape.type}`); + count++; + }); + console.log(`[DEBUG] Total colliders: ${count}`); + + // Also show asset collider handles + console.log("[DEBUG] === ASSET COLLIDERS (on asset objects) ==="); + let assetColCount = 0; + for (const a of assets) { + if (a._colliderHandle) { + const handleInfo = typeof a._colliderHandle === 'object' ? `obj.handle=${a._colliderHandle.handle}` : `num=${a._colliderHandle}`; + console.log(` ${a.id}: "${a.title}", _colliderHandle=${handleInfo}`); + assetColCount++; + } + } + console.log(`[DEBUG] Assets with colliders: ${assetColCount}`); + + // Show tracked map + console.log("[DEBUG] === _assetColliderHandles Map ==="); + console.log(`Map size: ${_assetColliderHandles.size}`); +}; + +// Debug: Remove all colliders except world/player +window.debugClearAssetColliders = function() { + if (!rapierWorld) return; + + // Helper to remove a collider (handles both object and number) + const removeCol = (handle) => { + try { + if (typeof handle === 'object' && handle.handle !== undefined) { + rapierWorld.removeCollider(handle, true); + return true; + } else if (typeof handle === 'number') { + const collider = rapierWorld.getCollider(handle); + if (collider) { + rapierWorld.removeCollider(collider, true); + return true; + } + } + } catch (e) {} + return false; + }; + + let removed = 0; + + // Remove all tracked asset colliders + _assetColliderHandles.forEach((handle, assetId) => { + if (removeCol(handle)) removed++; + }); + _assetColliderHandles.clear(); + + // Also clear colliders stored on asset objects + for (const asset of assets) { + if (asset._colliderHandle != null) { + if (removeCol(asset._colliderHandle)) removed++; + asset._colliderHandle = null; + } + } + + console.log(`[DEBUG] Cleared ${removed} asset colliders`); +}; + +// ── dimos integration mode boot ────────────────────────────────────────────── +// When dimosMode is active, auto-load a scene and spawn an agent, then connect +// the LCM bridge so sensor data flows and external /odom drives the agent. +if (dimosMode) { + (async () => { + try { + // 1. Load Rapier first — scene module's build() may create colliders + const sceneName = dimosScene || "empty"; + console.log(`[dimos] Loading scene: ${sceneName}`); + await ensureRapierLoaded(); + + // 2. Initialize the scene-api module shared with the runtime exec sandbox. + // Scenes can either receive the api as a build() arg or — for runtime + // exec via SceneEditor — pick it up off `window.__dimsim`. + const sceneApi = await import("./sceneApi.ts"); + sceneApi._init({ + scene, THREE, RAPIER, rapierWorld, + renderer, camera, agent: null, + assets, assetsGroup, gltfLoader, + // Bridge isn't connected yet; pre-bridge collider sends are dropped + // and the initial-state Rapier snapshot (shipped later) covers them. + sendPhysics: (msg) => window.__dimosBridge?.sendCommand?.(msg), + sceneBaseUrl: new URL(`/scenes/${sceneName}/`, window.location.href).toString(), + importLevelFromJSON, + setSky: (opts) => { + sceneSettings.sky = { ...sceneSettings.sky, enabled: opts.enabled !== false, ...opts }; + applySceneSkySettings(); + applySceneRgbBackground(); + }, + }); + window.__dimsim = sceneApi; + + // 3. Dynamic-import the scene module + run its build() + const sceneMod = await import(/* @vite-ignore */ `/scenes/${sceneName}/index.js`); + if (typeof sceneMod.default !== "function") { + throw new Error(`Scene "${sceneName}" must export a default build function`); + } + const sceneCfg = (await sceneMod.default(sceneApi)) || {}; + if (typeof sceneMod.afterBuild === "function") { + await sceneMod.afterBuild(sceneApi); + } + console.log(`[dimos] Scene loaded: ${sceneName}`); + + // 4. Spawn player + agent based on scene config + spawnPlayerInsideScene(); + // In dimos mode the agent is always driven by an external Python process, + // so an embodiment visual is always wanted. Scenes return `embodiment: + // null` because they don't want to dictate the model — let createAiAgent's + // default avatarUrl (the dimsim_unitree_stub.glb) take over. The legacy + // "hide the group when no embodiment" path predates dimos integration and + // is no longer reached here. + const pendingEmb = sceneApi._getPendingEmbodiment?.(); + const agent = createAiAgent({ + ephemeral: false, + avatarUrl: pendingEmb?.avatarUrl, + radius: pendingEmb?.radius, + halfHeight: pendingEmb?.halfHeight, + }); + aiAgents.push(agent); + sceneApi._setAgent(agent); + const spawnPos = sceneCfg.spawnPoint || { x: 2, y: 0.5, z: 3 }; + agent.setPosition(spawnPos.x, spawnPos.y, spawnPos.z); + renderAgentTaskUi(); // update UI: hide spawn button, enable task controls + // Server-side physics: agent pose is driven by ServerPhysics (Deno). + // Browser just receives position updates and moves the visual avatar. + let _dimosYaw = 0; + // Bridge updates _dimosYaw via this setter when server sends pose + window.__dimosSetYaw = (yaw) => { _dimosYaw = yaw; }; + agent.update = function(_dt) { + this._syncVisual(); + }; + console.log(`[dimos] Agent spawned: ${agent.id}`); + + // 3. Set up fixed-size offscreen capture for dimos. + // Keep sensor cost independent of the headed browser window size. + const _dimosCapW = 640, _dimosCapH = 288; + const _dimosCapTarget = new THREE.WebGLRenderTarget(_dimosCapW, _dimosCapH, { + minFilter: THREE.LinearFilter, magFilter: THREE.LinearFilter, + format: THREE.RGBAFormat, depthBuffer: true, stencilBuffer: false, + }); + // Go2 depth camera: 87° horizontal. At 640x288 (2.22:1 aspect), that's 46° vertical. + const _dimosFov = window.__dimosCameraFov || 46; + const _dimosCapCam = new THREE.PerspectiveCamera(_dimosFov, _dimosCapW / _dimosCapH, camera.near, camera.far); + const _dimosCapBuf = new Uint8Array(_dimosCapW * _dimosCapH * 4); + const _dimosCapCvs = document.createElement("canvas"); + _dimosCapCvs.width = _dimosCapW; + _dimosCapCvs.height = _dimosCapH; + const _dimosCapCtx = _dimosCapCvs.getContext("2d"); + const _dimosDepthTarget = new THREE.WebGLRenderTarget(_dimosCapW, _dimosCapH, { + minFilter: THREE.NearestFilter, + magFilter: THREE.NearestFilter, + format: THREE.RGBAFormat, + type: THREE.UnsignedByteType, + depthBuffer: true, + stencilBuffer: false, + }); + _dimosDepthTarget.texture.generateMipmaps = false; + _dimosDepthTarget.depthTexture = new THREE.DepthTexture(_dimosCapW, _dimosCapH, THREE.UnsignedIntType); + _dimosDepthTarget.depthTexture.minFilter = THREE.NearestFilter; + _dimosDepthTarget.depthTexture.magFilter = THREE.NearestFilter; + _dimosDepthTarget.depthTexture.generateMipmaps = false; + const _dimosMetricTarget = new THREE.WebGLRenderTarget(_dimosCapW, _dimosCapH, { + minFilter: THREE.NearestFilter, + magFilter: THREE.NearestFilter, + format: rgbdMetricUsesR32F ? THREE.RedFormat : THREE.RGBAFormat, + type: rgbdMetricTargetType, + depthBuffer: false, + stencilBuffer: false, + }); + if (rgbdMetricUsesR32F) _dimosMetricTarget.texture.internalFormat = "R32F"; + _dimosMetricTarget.texture.generateMipmaps = false; + + function _dimosReadMetricDepthFrameMeters() { + const w = _dimosMetricTarget.width; + const h = _dimosMetricTarget.height; + if (!w || !h) return null; + + if (rgbdMetricUsesR32F) { + const depth = new Float32Array(w * h); + renderer.readRenderTargetPixels(_dimosMetricTarget, 0, 0, w, h, depth); + return depth; + } + + if (_dimosMetricTarget.texture.type === THREE.FloatType) { + const raw = new Float32Array(w * h * 4); + renderer.readRenderTargetPixels(_dimosMetricTarget, 0, 0, w, h, raw); + const depth = new Float32Array(w * h); + for (let i = 0; i < w * h; i++) depth[i] = raw[i * 4 + 0]; + return depth; + } + + const raw = new Uint16Array(w * h * 4); + renderer.readRenderTargetPixels(_dimosMetricTarget, 0, 0, w, h, raw); + const depth = new Float32Array(w * h); + for (let i = 0; i < w * h; i++) depth[i] = halfToFloat(raw[i * 4 + 0]); + return depth; + } + + function _dimosCaptureRgb() { + const [ax, ay, az] = agent.getPosition?.() || [0, 0, 0]; + const yaw = agent.group?.rotation?.y ?? 0; + const pitch = typeof agent.pitch === "number" ? agent.pitch : 0; + const cp = Math.cos(pitch), sp = Math.sin(pitch); + const feetY = ay - ((agent.halfHeight || 0.25) + (agent.radius || 0.12)); + const eyeY = feetY + GO2_CAMERA_HEIGHT; + const eyeX = ax + Math.sin(yaw) * GO2_CAMERA_FORWARD; + const eyeZ = az + Math.cos(yaw) * GO2_CAMERA_FORWARD; + _dimosCapCam.position.set(eyeX, eyeY, eyeZ); + _dimosCapCam.lookAt(eyeX + Math.sin(yaw)*cp, eyeY + sp, eyeZ + Math.cos(yaw)*cp); + _dimosCapCam.updateProjectionMatrix(); + _dimosCapCam.updateMatrixWorld(true); + + const prev = renderer.getRenderTarget(); + const prevAgentVisible = agent.group?.visible; + if (agent.group) agent.group.visible = false; + renderer.setRenderTarget(_dimosCapTarget); + renderer.render(scene, _dimosCapCam); + renderer.setRenderTarget(prev); + if (agent.group) agent.group.visible = prevAgentVisible; + + renderer.readRenderTargetPixels(_dimosCapTarget, 0, 0, _dimosCapW, _dimosCapH, _dimosCapBuf); + // Flip Y — return raw RGBA pixels (no JPEG encode) + const flipped = new Uint8Array(_dimosCapW * _dimosCapH * 4); + const rowB = _dimosCapW * 4; + for (let y = 0; y < _dimosCapH; y++) { + flipped.set(_dimosCapBuf.subarray((_dimosCapH-1-y)*rowB, (_dimosCapH-y)*rowB), y*rowB); + } + return { data: flipped, width: _dimosCapW, height: _dimosCapH }; + } + + // Offscreen depth capture from agent POV using a dedicated low-res target. + function _dimosCaptureDepth() { + const [ax, ay, az] = agent.getPosition?.() || [0, 0, 0]; + const yaw = agent.group?.rotation?.y ?? 0; + const pitch = typeof agent.pitch === "number" ? agent.pitch : 0; + const cp = Math.cos(pitch), sp = Math.sin(pitch); + const feetY = ay - ((agent.halfHeight || 0.25) + (agent.radius || 0.12)); + const eyeY = feetY + GO2_CAMERA_HEIGHT; + const eyeX = ax + Math.sin(yaw) * GO2_CAMERA_FORWARD; + const eyeZ = az + Math.cos(yaw) * GO2_CAMERA_FORWARD; + _dimosCapCam.position.set(eyeX, eyeY, eyeZ); + _dimosCapCam.lookAt(eyeX + Math.sin(yaw)*cp, eyeY + sp, eyeZ + Math.cos(yaw)*cp); + _dimosCapCam.updateProjectionMatrix(); + _dimosCapCam.updateMatrixWorld(true); + + const prevDepthTex = rgbdMetricMaterial.uniforms.uDepthTex.value; + const prevNear = rgbdMetricMaterial.uniforms.uNear.value; + const prevFar = rgbdMetricMaterial.uniforms.uFar.value; + const prevNoise = rgbdMetricMaterial.uniforms.uNoiseEnabled.value; + const prevSpeckle = rgbdMetricMaterial.uniforms.uSpeckleEnabled.value; + rgbdMetricMaterial.uniforms.uDepthTex.value = _dimosDepthTarget.depthTexture; + rgbdMetricMaterial.uniforms.uNear.value = _dimosCapCam.near; + rgbdMetricMaterial.uniforms.uFar.value = _dimosCapCam.far; + rgbdMetricMaterial.uniforms.uNoiseEnabled.value = rgbdNoiseEnabled ? 1.0 : 0.0; + rgbdMetricMaterial.uniforms.uSpeckleEnabled.value = rgbdSpeckleEnabled ? 1.0 : 0.0; + + const savedOverride = scene.overrideMaterial; + const savedAssets = assetsGroup.visible; + const savedPrims = primitivesGroup.visible; + const savedLights = lightsGroup.visible; + const savedTags = tagsGroup.visible; + const savedLidarViz = lidarVizGroup.visible; + const savedRgbdPc = rgbdPcOverlayGroup.visible; + + scene.overrideMaterial = null; + assetsGroup.visible = true; + primitivesGroup.visible = true; + lightsGroup.visible = true; + tagsGroup.visible = false; + lidarVizGroup.visible = false; + rgbdPcOverlayGroup.visible = false; + const savedAgentVisible = agent.group?.visible; + if (agent.group) agent.group.visible = false; + + renderer.setRenderTarget(_dimosDepthTarget); + renderer.setClearColor(0x000000, RGBD_CLEAR_ALPHA); + renderer.clear(true, true, true); + renderer.render(scene, _dimosCapCam); + + renderer.setRenderTarget(_dimosMetricTarget); + renderer.setClearColor(0x000000, RGBD_CLEAR_ALPHA); + renderer.clear(true, true, true); + renderer.render(rgbdMetricScene, rgbdPostCamera); + + scene.overrideMaterial = savedOverride; + assetsGroup.visible = savedAssets; + primitivesGroup.visible = savedPrims; + lightsGroup.visible = savedLights; + tagsGroup.visible = savedTags; + lidarVizGroup.visible = savedLidarViz; + rgbdPcOverlayGroup.visible = savedRgbdPc; + if (agent.group) agent.group.visible = savedAgentVisible; + rgbdMetricMaterial.uniforms.uDepthTex.value = prevDepthTex; + rgbdMetricMaterial.uniforms.uNear.value = prevNear; + rgbdMetricMaterial.uniforms.uFar.value = prevFar; + rgbdMetricMaterial.uniforms.uNoiseEnabled.value = prevNoise; + rgbdMetricMaterial.uniforms.uSpeckleEnabled.value = prevSpeckle; + renderer.setRenderTarget(null); + + const depthData = _dimosReadMetricDepthFrameMeters(); + if (!depthData) return null; + + const dw = _dimosMetricTarget.width, dh = _dimosMetricTarget.height; + + // Flip rows: WebGL reads bottom-to-top, image convention is top-to-bottom + const flipped = new Float32Array(dw * dh); + for (let y = 0; y < dh; y++) { + flipped.set(depthData.subarray((dh - 1 - y) * dw, (dh - y) * dw), y * dw); + } + return { data: flipped, width: dw, height: dh }; + } + + // 4. Sidebar sensor panel setup (depth + LiDAR canvases) + const _dimosSidebarW = 320, _dimosSidebarH = 145; + const _dimosDepthCanvas = document.getElementById("agent-depth-canvas"); + const _dimosLidarCanvas = document.getElementById("agent-lidar-canvas"); + if (_dimosDepthCanvas) { _dimosDepthCanvas.width = _dimosSidebarW; _dimosDepthCanvas.height = _dimosSidebarH; } + if (_dimosLidarCanvas) { _dimosLidarCanvas.width = _dimosSidebarW; _dimosLidarCanvas.height = _dimosSidebarH; } + const _dimosDepthCtx = _dimosDepthCanvas?.getContext("2d"); + const _dimosLidarCtx = _dimosLidarCanvas?.getContext("2d"); + + // Small offscreen render targets for sidebar panels + const _dimosSidebarDepthTarget = new THREE.WebGLRenderTarget(_dimosSidebarW, _dimosSidebarH, { + minFilter: THREE.LinearFilter, magFilter: THREE.LinearFilter, + format: THREE.RGBAFormat, depthBuffer: true, stencilBuffer: false, + }); + const _dimosSidebarLidarTarget = new THREE.WebGLRenderTarget(_dimosSidebarW, _dimosSidebarH, { + minFilter: THREE.LinearFilter, magFilter: THREE.LinearFilter, + format: THREE.RGBAFormat, depthBuffer: true, stencilBuffer: false, + }); + const _dimosSidebarReadBuf = new Uint8Array(_dimosSidebarW * _dimosSidebarH * 4); + + // Helper: render a target, readback, flip Y, draw to 2D canvas + function _dimosBlitToCanvas(rt, ctx, w, h) { + renderer.readRenderTargetPixels(rt, 0, 0, w, h, _dimosSidebarReadBuf); + const flipped = new Uint8ClampedArray(w * h * 4); + const rowB = w * 4; + for (let y = 0; y < h; y++) { + flipped.set(_dimosSidebarReadBuf.subarray((h-1-y)*rowB, (h-y)*rowB), y*rowB); + } + ctx.putImageData(new ImageData(flipped, w, h), 0, 0); + } + + /** Update the sidebar sensor panels (called after capture) */ + function _dimosUpdateSidebarPanels(rgbBase64) { + if (window.__dimosHeadless) return; + + // RGB — set img src + if (rgbBase64 && agentShotImgEl) { + agentShotImgEl.src = `data:image/jpeg;base64,${rgbBase64}`; + } + + // Depth — render colormap to small target, blit to canvas + if (_dimosDepthCtx) { + const prev = renderer.getRenderTarget(); + rgbdVizMaterial.uniforms.uGrayMode.value = rgbdVizMode === "gray" ? 1.0 : 0.0; + renderer.setRenderTarget(_dimosSidebarDepthTarget); + renderer.setClearColor(0x000000, 1); + renderer.clear(true, true, true); + renderer.render(rgbdVizScene, rgbdPostCamera); + _dimosBlitToCanvas(_dimosSidebarDepthTarget, _dimosDepthCtx, _dimosSidebarW, _dimosSidebarH); + renderer.setRenderTarget(prev); + } + + // LiDAR — render lidar scene from agent POV to small target, blit to canvas + if (_dimosLidarCtx) { + const prev = renderer.getRenderTarget(); + // Save/restore scene visibility for lidar-only render + const savedAssets = assetsGroup.visible; + const savedPrims = primitivesGroup.visible; + const savedLights = lightsGroup.visible; + const savedTags = tagsGroup.visible; + const savedLidar = lidarVizGroup.visible; + const savedOverlay = rgbdPcOverlayGroup.visible; + const savedBg = scene.background; + + assetsGroup.visible = false; + primitivesGroup.visible = false; + lightsGroup.visible = false; + tagsGroup.visible = false; + lidarVizGroup.visible = true; + rgbdPcOverlayGroup.visible = false; + scene.background = RGBD_BG; + + renderer.setRenderTarget(_dimosSidebarLidarTarget); + renderer.setClearColor(0x000000, 1); + renderer.clear(true, true, true); + renderer.render(scene, _dimosCapCam); + + // Restore + assetsGroup.visible = savedAssets; + primitivesGroup.visible = savedPrims; + lightsGroup.visible = savedLights; + tagsGroup.visible = savedTags; + lidarVizGroup.visible = savedLidar; + rgbdPcOverlayGroup.visible = savedOverlay; + scene.background = savedBg; + + _dimosBlitToCanvas(_dimosSidebarLidarTarget, _dimosLidarCtx, _dimosSidebarW, _dimosSidebarH); + renderer.setRenderTarget(prev); + } + } + + // 5. Connect dimos bridge + let _lastRgbBase64 = null; + const { DimosBridge } = await import("./bridge.ts"); + const bridge = new DimosBridge({ + agent, + rates: window.__dimosSensorRates || undefined, + sensorEnable: window.__dimosSensorEnable || undefined, + sensorSources: { + captureRgb: () => { + const frame = _dimosCaptureRgb(); + if (!frame) return null; + // Render to canvas → JPEG (used for both LCM publish and eval/sidebar) + _dimosCapCtx.putImageData(new ImageData(new Uint8ClampedArray(frame.data.buffer, frame.data.byteOffset, frame.data.byteLength), frame.width, frame.height), 0, 0); + const dataUrl = _dimosCapCvs.toDataURL("image/jpeg", 0.75); + _lastRgbBase64 = dataUrl.split("base64,")[1] || null; + if (!_lastRgbBase64) return null; + // Decode base64 → Uint8Array for JPEG LCM transport + const bin = atob(_lastRgbBase64); + const jpegBytes = new Uint8Array(bin.length); + for (let i = 0; i < bin.length; i++) jpegBytes[i] = bin.charCodeAt(i); + return { data: jpegBytes, width: frame.width, height: frame.height }; + }, + captureDepth: () => _dimosCaptureDepth(), + captureLidar: () => { + // Return world-frame points (Three.js Y-up). + // Bridge converts Y-up → ROS Z-up and labels frame_id="world". + const lLen = _lidarLatestWorldPts ? _lidarLatestWorldPts.length : -1; + if (lLen > 0) { + return { + points: _lidarLatestWorldPts, + intensity: _lidarLatestWorldIntensity, + numPoints: lLen / 3, + }; + } + const frames = window.__robovalLidar?.getLatestFrames?.(); + const src = frames?.raw; + if (!src) return null; + return { points: src.points, intensity: src.intensity, numPoints: src.points?.length / 3 || 0 }; + }, + getOdomPose: () => { + const pos = agent.getPosition?.(); + if (!pos) return null; // skip this frame instead of fallback to origin + const [ax, ay, az] = pos; + const qw = Math.cos(_dimosYaw / 2); + const qy = Math.sin(_dimosYaw / 2); + return { x: ax, y: ay, z: az, qx: 0, qy, qz: 0, qw }; + }, + }, + }); + + // Hook: after _publishSensors — RGB capture disabled for now (GPU stall) + // _dimosCaptureRgb() does a full render + readRenderTargetPixels which + // stalls the GPU pipeline. Skip it for lidar-only nav testing. + // const origPublishSensors = bridge._publishSensors.bind(bridge); + // bridge._publishSensors = function() { + // origPublishSensors(); + // _lastRgbBase64 = _dimosCaptureRgb(); + // _dimosUpdateSidebarPanels(_lastRgbBase64); + // }; + + bridge.connect(); + bridge.sceneReady = true; + window.__dimosBridge = bridge; + sceneApi._flushPendingEmbodiment?.(); + window.__dimosCapCam = _dimosCapCam; + window.__dimosAgent = agent; + + // Send Rapier world snapshot to bridge server for server-side physics + lidar. + // Flush any deferred collider builds first — primitives (floor, walls) may be + // queued in _pendingColliderBuilds if they were created before the render loop ran. + flushPendingColliderBuilds(); + + // Chunked snapshot protocol (DSC1) — single-frame send stalls when the + // browser main thread is CPU-saturated (e.g. headless SwiftShader on a + // weak runner): WebSocket.bufferedAmount climbs and never drains. + // Splitting into ~256KB chunks with a setTimeout(0) yield between each + // lets the WS pump run, and bridge reassembles in receive order. + // Wire format: + // prelude: [DSC1 4B BE][total u32 LE][sx f32 LE][sy f32 LE][sz f32 LE] (20B) + // chunks: raw bytes, in order, until `total` accumulated bridge-side. + const SNAPSHOT_CHUNK_SIZE = 256 * 1024; + const _waitSensorWs = () => { + if (bridge.wsSensors && bridge.wsSensors.readyState === WebSocket.OPEN) { + try { + const snapshot = rapierWorld.takeSnapshot(); + const [sx, sy, sz] = agent.getPosition?.() || [2, 0.5, 3]; + const total = snapshot.byteLength; + + const prelude = new Uint8Array(20); + const pdv = new DataView(prelude.buffer); + pdv.setUint32(0, 0x44534331, false); // "DSC1" + pdv.setUint32(4, total, true); + pdv.setFloat32(8, sx, true); + pdv.setFloat32(12, sy, true); + pdv.setFloat32(16, sz, true); + bridge.wsSensors.send(prelude.buffer); + bridge._serverLidar = true; + + let sent = 0; + let chunkN = 0; + const sendNextChunk = () => { + if (bridge.wsSensors.readyState !== WebSocket.OPEN) { + console.warn("[DimosBridge] sensor WS closed mid-snapshot"); + return; + } + // Backpressure: don't outpace the WS pump. + if (bridge.wsSensors.bufferedAmount > 4 * SNAPSHOT_CHUNK_SIZE) { + setTimeout(sendNextChunk, 50); + return; + } + const end = Math.min(sent + SNAPSHOT_CHUNK_SIZE, total); + bridge.wsSensors.send(snapshot.subarray(sent, end)); + sent = end; + chunkN++; + if (sent >= total) return; + setTimeout(sendNextChunk, 0); // yield to event loop + }; + sendNextChunk(); + } catch (e) { + console.warn("[DimosBridge] snapshot send failed:", e); + } + } else { + setTimeout(_waitSensorWs, 200); + } + }; + _waitSensorWs(); + // Expose yaw for lidar pose sampling (avoids reading Three.js Euler) + Object.defineProperty(window, '__dimosYaw', { get: () => _dimosYaw }); + + // Odom: server-side physics publishes odom directly to LCM. + // Browser no longer needs to publish odom — server is authoritative. + + // Eval harness — scores objectDistance rubric when triggered by dimsim eval runner + const harnessMod = await import("../evals/harness.ts"); + const { EvalHarness, setEvalHarness } = harnessMod; + const channel = new URLSearchParams(location.search).get("channel") || undefined; + const evalHarness = new EvalHarness({ + bridge, + channel, + getSceneState: () => { + const enriched = assets.map(a => { + const obj = assetsGroup.getObjectByName(`asset:${a.id}`); + if (obj) { + const bbox = new THREE.Box3().setFromObject(obj); + if (!bbox.isEmpty()) { + const center = new THREE.Vector3(); + const size = new THREE.Vector3(); + bbox.getCenter(center); + bbox.getSize(size); + return { + ...a, + transform: { x: center.x, y: center.y, z: center.z }, + _bbox: { w: size.x, h: size.y, d: size.z }, + }; + } + } + return a; + }); + return { assets: enriched }; + }, + getAgentPose: () => { + const pos = agent.getPosition?.(); + if (!pos) return null; + const camOffset = 0.3; + const cx = pos[0] + Math.sin(_dimosYaw) * camOffset; + const cz = pos[2] + Math.cos(_dimosYaw) * camOffset; + return { x: cx, y: pos[1], z: cz, yaw: _dimosYaw, pitch: 0 }; + }, + }); + window.__evalHarness = evalHarness; + // Register the singleton so workflow files importing `runEval` from + // `@dimsim/eval` (importmap → dist/assets/dimsim-eval.js → this same + // module) get a working runEval. + setEvalHarness(evalHarness); + + // Scene editor — script execution engine for sim editing (exec_js API) + const { SceneEditor } = await import("./sceneEditor.ts"); + const sceneEditor = new SceneEditor({ + bridge, + channel, + globals: { scene, THREE, RAPIER, rapierWorld, worldBody, renderer, camera, agent, assets, assetsGroup, gltfLoader }, + }); + window.__sceneEditor = sceneEditor; + + // Agent POV only in headless (sensor capture needs it). Headed = free orbit. + if (window.__dimosHeadless) { + enableAgentCameraFollow(agent.id); + } + + // 7a. dimos mode UI cleanup handled in CSS via body.dimos-mode class + // (panel hiding) and .shortcuts-floating in index.html (WASD strip). + + // 7b. Debug panel (integration diagnostics) — hidden for now + if (false && !window.__dimosHeadless) { + const dbg = document.createElement("div"); + dbg.id = "dimos-debug"; + dbg.style.cssText = "position:fixed;bottom:8px;left:8px;z-index:99999;background:rgba(0,0,0,0.88);color:#0f0;font:11px/1.4 monospace;padding:10px 14px;border-radius:8px;max-width:460px;max-height:400px;overflow-y:auto;pointer-events:auto;user-select:text;"; + document.body.appendChild(dbg); + + const _dbgState = { + bridgeConn: false, + sensorFps: 0, + agentPos: { x: 0, y: 0, z: 0 }, + agentYaw: 0, + cmdVel: { angY: 0, linZ: 0 }, + _sensorCount: 0, + _sensorLastTs: Date.now(), + }; + + // Hook lidar publish for FPS counter + const _origPubLidar2 = bridge._publishLidar; + bridge._publishLidar = function() { + _dbgState._sensorCount++; + _origPubLidar2.call(bridge); + }; + + // Update loop + setInterval(() => { + const now = Date.now(); + const dt = (now - _dbgState._sensorLastTs) / 1000; + if (dt >= 1) { + _dbgState.sensorFps = Math.round(_dbgState._sensorCount / dt); + _dbgState._sensorCount = 0; + _dbgState._sensorLastTs = now; + } + + const [ax, ay, az] = agent.getPosition?.() || [0, 0, 0]; + _dbgState.agentPos = { x: ax.toFixed(2), y: ay.toFixed(2), z: az.toFixed(2) }; + _dbgState.agentYaw = (agent.group?.rotation?.y ?? 0).toFixed(3); + _dbgState.bridgeConn = bridge.ws?.readyState === WebSocket.OPEN; + const vel = bridge.getCmdVel(); + _dbgState.cmdVel = { angY: vel.angY.toFixed(3), linZ: vel.linZ.toFixed(3) }; + + dbg.innerHTML = ` +
dimos integration
+
Bridge: ${_dbgState.bridgeConn ? 'connected' : 'disconnected'} | Sensors: ${_dbgState.sensorFps} fps
+
Agent: (${_dbgState.agentPos.x}, ${_dbgState.agentPos.y}, ${_dbgState.agentPos.z}) yaw=${_dbgState.agentYaw}
+
cmd_vel: angY=${_dbgState.cmdVel.angY} linZ=${_dbgState.cmdVel.linZ}
+ `; + }, 500); + } + + console.log("[dimos] Bridge connected. Sensor publishing active."); + } catch (err) { + console.error("[dimos] Initialization failed:", err); + } + })(); +} + diff --git a/misc/DimSim/src/main.js b/misc/DimSim/src/main.js new file mode 100644 index 0000000000..f237e9a49d --- /dev/null +++ b/misc/DimSim/src/main.js @@ -0,0 +1,4 @@ +// DimSim engine entry point. +// Imports the full engine from ./engine.js (copied from SimStudio/src/main.js). +// To update: bash copy-sources.sh +import "./engine.js"; diff --git a/misc/DimSim/src/sceneApi.ts b/misc/DimSim/src/sceneApi.ts new file mode 100644 index 0000000000..c0c594763c --- /dev/null +++ b/misc/DimSim/src/sceneApi.ts @@ -0,0 +1,462 @@ +/** + * @dimsim/scene-api — the surface scene modules import. + * + * Usage (in a scene module at scenes//index.js): + * + * import { scene, THREE, agent, physics, loadJson } from '@dimsim/scene-api'; + * + * export default async function build() { + * await loadJson('./apt.json'); + * scene.add(new THREE.DirectionalLight(0xffffff, 1.2)); + * return { embodiment: 'unitree-go2', spawnPoint: { x: 2, y: 0.5, z: 3 } }; + * } + * + * Lifecycle: engine.js calls `_init()` once before dynamic-importing scenes, + * populating the module-level `export let` bindings. ESM live-binding makes + * `import { scene } from '@dimsim/scene-api'` return the engine's live ref. + * + * Implementation note: the collider helpers mirror what `sceneEditor.ts` + * already does in its exec sandbox — browser-side Rapier collider creation + * *and* a `physicsColliderAdd` WS message so server-side physics + LiDAR see + * the same colliders. Factored here so scene modules (load-time) and the + * exec sandbox (runtime) share one implementation. + */ + +export interface SceneApiContext { + scene: any; + THREE: any; + RAPIER: any; + rapierWorld: any; + renderer: any; + camera: any; + agent: any; + assets: any[]; + assetsGroup: any; + gltfLoader: any; + /** Browser → bridge WS send. Used for physicsColliderAdd / Remove. */ + sendPhysics: (msg: Record) => void; + /** Where the scene module lives (e.g. "/scenes/apartment/"). loadJson resolves against this. */ + sceneBaseUrl: string; + /** Engine's existing JSON scene loader, kept so `loadJson` can populate primitives. */ + importLevelFromJSON: (json: any) => Promise; + /** Apply sky settings ({topColor, horizonColor, bottomColor, brightness, softness, sunStrength, sunHeight, enabled?}). */ + setSky: (opts: Record) => void; +} + +// ── Live bindings (ESM re-export pattern) ──────────────────────────────────── + +export let scene: any = null; +export let THREE: any = null; +export let RAPIER: any = null; +export let rapierWorld: any = null; +export let renderer: any = null; +export let camera: any = null; +export let agent: any = null; +export let assets: any[] = []; +export let assetsGroup: any = null; +export let gltfLoader: any = null; + +// ── Internal state ─────────────────────────────────────────────────────────── + +let _sendPhysics: ((msg: Record) => void) | null = null; +let _sceneBaseUrl: string = "/"; +let _importLevelFromJSON: ((json: any) => Promise) | null = null; +let _setSky: ((opts: Record) => void) | null = null; + +const _colliderMap = new Map(); +const _dynamicBodies = new Map(); +let _dynamicSyncRaf: number | null = null; + +let _lastLoadedKey: string | null = null; + +// ── Initialization (called by engine.js once at boot) ──────────────────────── + +export function _init(ctx: SceneApiContext): void { + scene = ctx.scene; + THREE = ctx.THREE; + RAPIER = ctx.RAPIER; + rapierWorld = ctx.rapierWorld; + renderer = ctx.renderer; + camera = ctx.camera; + agent = ctx.agent; + assets = ctx.assets; + assetsGroup = ctx.assetsGroup; + gltfLoader = ctx.gltfLoader; + _sendPhysics = ctx.sendPhysics; + _sceneBaseUrl = ctx.sceneBaseUrl; + _importLevelFromJSON = ctx.importLevelFromJSON; + _setSky = ctx.setSky; +} + +export function setSky(opts: Record): void { + _setSky?.(opts); +} + +/** + * Declare the agent's embodiment — avatar mesh + body dimensions + physics + * mode + control parameters. Sent to the bridge so server-side physics + + * lidar mount reconfigure live, AND applied locally so the browser swaps + * the GLB and re-asserts visibility immediately. + * + * Typical configs: + * setEmbodiment({ embodimentType: 'ground', avatarUrl: '/embodiment/dimsim_unitree_stub.glb', + * radius: 0.18, halfHeight: 0.25, maxSpeed: 1.5, turnRate: 2.5 }); + * + * setEmbodiment({ embodimentType: 'drone', avatarUrl: '/embodiment/drone.glb', + * radius: 0.3, halfHeight: 0.1, gravity: 0, maxSpeed: 3.0 }); + * + * All fields are forwarded to the bridge's EmbodimentConfig (see + * cli/bridge/physics.ts). Falsy fields are passed through unchanged so + * partial reconfigures work — e.g. just bumping maxSpeed mid-scene. + */ +let _pendingEmbodiment: Record | null = null; + +export function _getPendingEmbodiment(): Record | null { + return _pendingEmbodiment; +} + +export function setEmbodiment(config: Record): void { + if (!_sendPhysics) throw new Error("scene-api not initialized"); + const w = window as any; + if (w.__dimosBridge) { + console.log("[sceneApi] setEmbodiment applying:", config.embodimentType, "gravity=" + config.gravity); + if (w.__dimosBridge._handleEmbodimentConfig) { + w.__dimosBridge._handleEmbodimentConfig(config); + } + _sendPhysics({ type: "embodimentConfig", ...config }); + } else { + console.log("[sceneApi] setEmbodiment queued (bridge not ready):", config.embodimentType); + _pendingEmbodiment = config; + } +} + +/** engine.js calls this right after `window.__dimosBridge = bridge`. */ +export function _flushPendingEmbodiment(): void { + if (!_pendingEmbodiment) return; + const cfg = _pendingEmbodiment; + _pendingEmbodiment = null; + setEmbodiment(cfg); +} + +/** Engine.js calls this before loading a new scene, to refresh the base url. */ +export function _setSceneBaseUrl(url: string): void { + _sceneBaseUrl = url; +} + +/** Engine.js calls this when Rapier finishes loading (it's lazy). */ +export function _setRapier(R: any, world: any): void { + RAPIER = R; + rapierWorld = world; +} + +/** Engine.js calls this once the agent is constructed (post-scene-build). */ +export function _setAgent(a: any): void { + agent = a; +} + +// ── Helpers ────────────────────────────────────────────────────────────────── + +export function loadGLTF(url: string): Promise { + const abs = new URL(url, _sceneBaseUrl).toString(); + return new Promise((resolve, reject) => + gltfLoader.load(abs, resolve, undefined, reject), + ); +} + +/** + * Load an existing JSON scene blob into the engine. Idempotent — calling + * twice with the same URL is a no-op. + */ +export async function loadJson(path: string): Promise { + if (!_importLevelFromJSON) throw new Error("scene-api not initialized"); + const url = new URL(path, _sceneBaseUrl).toString(); + const key = `json:${url}`; + if (_lastLoadedKey === key) return; + const resp = await fetch(url); + if (!resp.ok) throw new Error(`loadJson(${path}): HTTP ${resp.status}`); + const json = await resp.json(); + _rewriteTexturePaths(json); + await _importLevelFromJSON(json); + _lastLoadedKey = key; +} + +/** + * Feed an in-memory level blob directly to the engine. Idempotent — if the + * caller hands us the same object reference twice we skip the second import. + * Materials with `texturePath: 'foo.jpg'` are rewritten to absolute + * `textureDataUrl` against the scene base before import. + */ +export async function loadLevel(data: any): Promise { + if (!_importLevelFromJSON) throw new Error("scene-api not initialized"); + const key = `level:${_identityOf(data)}`; + if (_lastLoadedKey === key) return; + _rewriteTexturePaths(data); + await _importLevelFromJSON(data); + _lastLoadedKey = key; +} + +const _identitySym = Symbol("dimsim.loadLevel.id"); +let _identityCounter = 0; +function _identityOf(o: any): string { + if (!o || typeof o !== "object") return String(o); + if (!o[_identitySym]) { + Object.defineProperty(o, _identitySym, { + value: String(++_identityCounter), enumerable: false, writable: false, + }); + } + return o[_identitySym]; +} + +function _rewriteTexturePaths(node: any): void { + if (!node) return; + if (Array.isArray(node)) { + for (const item of node) _rewriteTexturePaths(item); + return; + } + if (typeof node !== "object") return; + const mat = node.material; + if (mat && typeof mat === "object" && typeof mat.texturePath === "string" && !mat.textureDataUrl) { + mat.textureDataUrl = new URL(mat.texturePath, _sceneBaseUrl).toString(); + } + for (const k in node) { + const v = (node as any)[k]; + if (v && typeof v === "object") _rewriteTexturePaths(v); + } +} + +export interface ColliderOpts { + shape?: "trimesh" | "box" | "sphere"; + dynamic?: boolean; + mass?: number; + restitution?: number; +} + +/** Static collider — no rigid body, attached to the world. */ +export function staticCollider(mesh: any, shape: ColliderOpts["shape"] = "trimesh"): any { + return addCollider(mesh, { shape, dynamic: false }); +} + +/** Dynamic collider — gets a rigid body, responds to gravity. */ +export function dynamicCollider(mesh: any, opts: Omit = {}): any { + return addCollider(mesh, { ...opts, dynamic: true }); +} + +/** + * Full-control collider helper. Mirrors sceneEditor.ts addCollider so scene + * modules and the exec sandbox produce identical results. + */ +export function addCollider(obj: any, shapeOrOpts?: ColliderOpts["shape"] | ColliderOpts): any { + if (!_sendPhysics) throw new Error("scene-api not initialized"); + + let shape: ColliderOpts["shape"] = "trimesh"; + let dynamic = false; + let mass = 1.0; + let restitution = 0.3; + if (typeof shapeOrOpts === "string") { + shape = shapeOrOpts; + } else if (shapeOrOpts) { + shape = shapeOrOpts.shape || "trimesh"; + dynamic = !!shapeOrOpts.dynamic; + mass = shapeOrOpts.mass ?? 1.0; + restitution = shapeOrOpts.restitution ?? 0.3; + } + + removeCollider(obj); + + const bbox = new THREE.Box3().setFromObject(obj); + const size = new THREE.Vector3(); + const center = new THREE.Vector3(); + bbox.getSize(size); + bbox.getCenter(center); + const clamp = (v: number) => Math.max(v, 0.001); + + const serverDesc: any = { + shape, + position: { x: center.x, y: center.y, z: center.z }, + }; + + if (shape === "sphere") { + serverDesc.radius = clamp(Math.max(size.x, size.y, size.z) / 2); + } else if (shape === "trimesh") { + const verts: number[] = []; + const indices: number[] = []; + let vertBase = 0; + obj.traverse((m: any) => { + if (!m.isMesh) return; + const geom = m.geometry; + const posAttr = geom?.attributes?.position; + if (!posAttr) return; + const tmpPos = new THREE.Vector3(); + for (let i = 0; i < posAttr.count; i++) { + tmpPos.fromBufferAttribute(posAttr, i).applyMatrix4(m.matrixWorld); + verts.push(tmpPos.x, tmpPos.y, tmpPos.z); + } + if (geom.index) { + for (let i = 0; i < geom.index.count; i++) indices.push(geom.index.getX(i) + vertBase); + } else { + for (let i = 0; i < posAttr.count; i++) indices.push(vertBase + i); + } + vertBase += posAttr.count; + }); + if (verts.length < 9 || indices.length < 3) throw new Error("Not enough geometry for trimesh"); + serverDesc.vertices = verts; + serverDesc.indices = indices; + } else { + serverDesc.halfExtents = { + x: clamp(size.x / 2), + y: clamp(size.y / 2), + z: clamp(size.z / 2), + }; + } + + if (RAPIER && rapierWorld) { + let desc: any; + if (shape === "sphere") { + desc = RAPIER.ColliderDesc.ball(serverDesc.radius); + if (!dynamic) desc.setTranslation(center.x, center.y, center.z); + } else if (shape === "trimesh") { + desc = RAPIER.ColliderDesc.trimesh( + new Float32Array(serverDesc.vertices), + new Uint32Array(serverDesc.indices), + ); + } else { + const h = serverDesc.halfExtents; + desc = RAPIER.ColliderDesc.cuboid(h.x, h.y, h.z); + if (!dynamic) desc.setTranslation(center.x, center.y, center.z); + } + desc.setFriction(0.9); + desc.setRestitution(restitution); + + if (dynamic && shape !== "trimesh") { + const bodyDesc = RAPIER.RigidBodyDesc.dynamic().setTranslation( + center.x, center.y, center.z, + ); + const body = rapierWorld.createRigidBody(bodyDesc); + body.setAdditionalMass(mass); + const collider = rapierWorld.createCollider(desc, body); + _colliderMap.set(obj.uuid, collider); + _dynamicBodies.set(obj.uuid, { body, mesh: obj }); + _ensureDynamicSyncLoop(); + } else { + const collider = rapierWorld.createCollider(desc); + _colliderMap.set(obj.uuid, collider); + } + } + + serverDesc.dynamic = dynamic; + if (dynamic) { + serverDesc.mass = mass; + serverDesc.restitution = restitution; + } + _sendPhysics({ type: "physicsColliderAdd", uuid: obj.uuid, desc: serverDesc }); + + return { + shape, dynamic, uuid: obj.uuid, + size: { x: +size.x.toFixed(3), y: +size.y.toFixed(3), z: +size.z.toFixed(3) }, + }; +} + +export function removeCollider(obj: any): boolean { + const existing = _colliderMap.get(obj.uuid); + if (existing) { + try { rapierWorld?.removeCollider(existing, true); } catch { /* already removed */ } + _colliderMap.delete(obj.uuid); + } + const dyn = _dynamicBodies.get(obj.uuid); + if (dyn) { + try { rapierWorld?.removeRigidBody(dyn.body); } catch { /* already removed */ } + _dynamicBodies.delete(obj.uuid); + } + _sendPhysics?.({ type: "physicsColliderRemove", uuid: obj.uuid }); + return !!existing; +} + +/** + * Kinematic-position-based body for script-driven actors (NPCs, doors). + * Caller updates the world position each frame via + * body.setNextKinematicTranslation({ x, y, z }) + * The body collides with the static world (walls, floor) and pushes dynamic + * bodies, but is not itself pushed. + * + * Returns the Rapier RigidBody handle (so the caller can drive it). The body + * is also registered for cleanup via removeCollider(mesh). + */ +export function kinematicCollider( + mesh: any, + opts: { shape?: "box" | "sphere"; radius?: number } = {}, +): any { + if (!RAPIER || !rapierWorld) throw new Error("rapier not loaded"); + removeCollider(mesh); + mesh.updateMatrixWorld(true); + const bbox = new THREE.Box3().setFromObject(mesh); + const size = new THREE.Vector3(); bbox.getSize(size); + const center = new THREE.Vector3(); bbox.getCenter(center); + const offset = center.clone().sub(mesh.position); + + const bodyDesc = RAPIER.RigidBodyDesc.kinematicPositionBased().setTranslation( + mesh.position.x, mesh.position.y, mesh.position.z, + ); + const body = rapierWorld.createRigidBody(bodyDesc); + + let desc: any; + if (opts.shape === "sphere") { + const r = opts.radius ?? Math.max(size.x, size.z) / 2; + desc = RAPIER.ColliderDesc.ball(Math.max(r, 0.01)); + } else { + desc = RAPIER.ColliderDesc.cuboid( + Math.max(size.x / 2, 0.01), Math.max(size.y / 2, 0.01), Math.max(size.z / 2, 0.01), + ); + } + desc.setTranslation(offset.x, offset.y, offset.z); + desc.setFriction(0.9); + const collider = rapierWorld.createCollider(desc, body); + _colliderMap.set(mesh.uuid, collider); + return body; +} + +/** Bundled namespace so scene modules can `import { physics } from '@dimsim/scene-api'`. */ +export const physics = { + staticCollider, + dynamicCollider, + kinematicCollider, + addCollider, + removeCollider, +}; + +// ── Dynamic body → mesh sync loop ──────────────────────────────────────────── + +function _ensureDynamicSyncLoop(): void { + if (_dynamicSyncRaf != null) return; + const tick = () => { + if (_dynamicBodies.size === 0) { + _dynamicSyncRaf = null; + return; + } + for (const { body, mesh } of _dynamicBodies.values()) { + const t = body.translation(); + const r = body.rotation(); + mesh.position.set(t.x, t.y, t.z); + mesh.quaternion.set(r.x, r.y, r.z, r.w); + } + _dynamicSyncRaf = requestAnimationFrame(tick); + }; + _dynamicSyncRaf = requestAnimationFrame(tick); +} + +// ── autoScale (kept verbatim from sceneEditor) ─────────────────────────────── + +export function autoScale(obj: any, targetMaxDim = 50): number { + const bbox = new THREE.Box3().setFromObject(obj); + const size = new THREE.Vector3(); + bbox.getSize(size); + const maxDim = Math.max(size.x, size.y, size.z); + if (maxDim <= 0.001) return 1.0; + let scaleFactor = 1.0; + if (maxDim > targetMaxDim * 2) scaleFactor = 0.01; + else if (maxDim > targetMaxDim) scaleFactor = targetMaxDim / maxDim; + if (scaleFactor !== 1.0) { + obj.scale.multiplyScalar(scaleFactor); + obj.updateMatrixWorld(true); + } + return scaleFactor; +} diff --git a/misc/DimSim/src/sceneEditor.ts b/misc/DimSim/src/sceneEditor.ts new file mode 100644 index 0000000000..558ca8db61 --- /dev/null +++ b/misc/DimSim/src/sceneEditor.ts @@ -0,0 +1,452 @@ +/** + * SceneEditor — Browser-side script execution engine. + * + * Receives {type: "exec", code, id?} commands via the DimosBridge control WS, + * evaluates user JS with full Three.js + Rapier globals exposed, and returns + * {type: "execResult", id, success, result?, error?}. + * + * Must NOT modify engine.js — hooks into DimosBridge WS the same way EvalHarness does. + */ + +import type { DimosBridge } from "./bridge.ts"; + +export interface SceneEditorGlobals { + scene: any; // THREE.Scene + THREE: any; // Three.js namespace + RAPIER: any; // Rapier namespace (may be null until ensureRapierLoaded) + rapierWorld: any; // Rapier.World (may be null) + worldBody: any; // Fixed RigidBody for static colliders + renderer: any; // THREE.WebGLRenderer + camera: any; // THREE.PerspectiveCamera + agent: any; // Player agent (has getPosition, setPosition, group) + assets: any[]; // Scene assets array + assetsGroup: any; // THREE.Group containing loaded asset meshes + gltfLoader: any; // THREE GLTFLoader instance +} + +export interface SceneEditorOptions { + bridge: DimosBridge; + globals: SceneEditorGlobals; + channel?: string; +} + +// AsyncFunction constructor — allows top-level await in user scripts +const AsyncFunction = Object.getPrototypeOf(async function () {}).constructor; + +export class SceneEditor { + bridge: DimosBridge; + globals: SceneEditorGlobals; + channel: string; + + constructor({ bridge, globals, channel }: SceneEditorOptions) { + this.bridge = bridge; + this.globals = globals; + this.channel = channel || ""; + this._hookBridgeMessages(); + } + + _hookBridgeMessages(): void { + const origConnect = this.bridge.connect.bind(this.bridge); + this.bridge.connect = () => { + origConnect(); + setTimeout(() => { + const ws = this.bridge.ws; + if (ws) this._patchWsOnMessage(ws); + }, 100); + }; + const ws = this.bridge.ws; + if (ws) this._patchWsOnMessage(ws); + } + + _patchWsOnMessage(ws: WebSocket): void { + const origOnMessage = ws.onmessage; + ws.onmessage = (event: MessageEvent) => { + if (typeof event.data === "string") { + try { + const cmd = JSON.parse(event.data); + if (cmd.type === "exec" || cmd.type === "loadScript") { + this._handleCommand(cmd); + return; + } + } catch { /* not JSON or not for us */ } + } + // Pass through to existing handlers (EvalHarness, DimosBridge) + if (origOnMessage) (origOnMessage as (e: MessageEvent) => void).call(ws, event); + }; + } + + _send(msg: Record): void { + if (this.channel) msg.channel = this.channel; + this.bridge.sendCommand(msg); + } + + async _handleCommand(cmd: { type: string; code?: string; url?: string; id?: string; channel?: string }): Promise { + if (this.channel && cmd.channel && cmd.channel !== this.channel) return; + + if (cmd.type === "exec" && cmd.code) { + await this._execCode(cmd.code, cmd.id); + } else if (cmd.type === "loadScript" && cmd.url) { + await this._loadScript(cmd.url, cmd.id); + } + } + + // Track colliders created by addCollider so removeCollider can clean up + _colliderMap: Map = new Map(); // mesh.uuid → Rapier collider + // Track dynamic rigid bodies (body + mesh ref for position sync) + _dynamicBodies: Map = new Map(); + // Track NPC mixers for animation updates + _npcMixers: Map = new Map(); // npc name → THREE.AnimationMixer + _npcAnimFrame: number | null = null; + _npcClock: any = null; // THREE.Clock + + async _execCode(code: string, id?: string): Promise { + console.log(`[sceneEditor] exec${id ? ` (${id})` : ""}:`, code.slice(0, 100)); + try { + const g = this.globals; + const colliderMap = this._colliderMap; + + // loadGLTF: convenience async helper for loading GLTF/GLB models + const loadGLTF = (url: string): Promise => + new Promise((resolve, reject) => + g.gltfLoader.load(url, resolve, undefined, reject), + ); + + // addCollider: create a physics collider for a mesh/group + // shape: "trimesh" (default) | "box" | "sphere" + // opts.dynamic: if true, creates a dynamic rigid body (responds to gravity/collisions) + // opts.mass: mass in kg (default 1.0, only for dynamic) + // opts.restitution: bounciness 0-1 (default 0.3, only for dynamic) + // Creates collider browser-side AND sends command to server (for lidar/physics) + const sendPhysics = this._send.bind(this); + const dynamicBodies = this._dynamicBodies; + const selfRef = this; + const addCollider = (obj: any, shapeOrOpts?: string | { shape?: string; dynamic?: boolean; mass?: number; restitution?: number }): any => { + let shape = "trimesh"; + let dynamic = false; + let mass = 1.0; + let restitution = 0.3; + if (typeof shapeOrOpts === "string") { + shape = shapeOrOpts; + } else if (shapeOrOpts) { + shape = shapeOrOpts.shape || "trimesh"; + dynamic = !!shapeOrOpts.dynamic; + mass = shapeOrOpts.mass ?? 1.0; + restitution = shapeOrOpts.restitution ?? 0.3; + } + + // Remove existing collider if any + removeCollider(obj); + + const bbox = new g.THREE.Box3().setFromObject(obj); + const size = new g.THREE.Vector3(); + const center = new g.THREE.Vector3(); + bbox.getSize(size); + bbox.getCenter(center); + + const clamp = (v: number) => Math.max(v, 0.001); + + // Build server-side descriptor (shape-agnostic) + const serverDesc: any = { + shape, + position: { x: center.x, y: center.y, z: center.z }, + }; + + if (shape === "sphere") { + const r = clamp(Math.max(size.x, size.y, size.z) / 2); + serverDesc.radius = r; + } else if (shape === "trimesh") { + const verts: number[] = []; + const indices: number[] = []; + let vertBase = 0; + obj.traverse((m: any) => { + if (!m.isMesh) return; + const geom = m.geometry; + const posAttr = geom?.attributes?.position; + if (!posAttr) return; + const tmpPos = new g.THREE.Vector3(); + for (let i = 0; i < posAttr.count; i++) { + tmpPos.fromBufferAttribute(posAttr, i).applyMatrix4(m.matrixWorld); + verts.push(tmpPos.x, tmpPos.y, tmpPos.z); + } + if (geom.index) { + for (let i = 0; i < geom.index.count; i++) indices.push(geom.index.getX(i) + vertBase); + } else { + for (let i = 0; i < posAttr.count; i++) indices.push(vertBase + i); + } + vertBase += posAttr.count; + }); + if (verts.length < 9 || indices.length < 3) throw new Error("Not enough geometry for trimesh"); + serverDesc.vertices = Array.from(verts); + serverDesc.indices = Array.from(indices); + } else { + // box (default) + serverDesc.halfExtents = { + x: clamp(size.x / 2), y: clamp(size.y / 2), z: clamp(size.z / 2), + }; + } + + // Browser-side collider (for standalone / non-dimos mode) + if (g.RAPIER && g.rapierWorld) { + let desc: any; + if (shape === "sphere") { + desc = g.RAPIER.ColliderDesc.ball(serverDesc.radius); + if (!dynamic) desc.setTranslation(center.x, center.y, center.z); + } else if (shape === "trimesh") { + desc = g.RAPIER.ColliderDesc.trimesh( + new Float32Array(serverDesc.vertices), new Uint32Array(serverDesc.indices) + ); + } else { + const h = serverDesc.halfExtents; + desc = g.RAPIER.ColliderDesc.cuboid(h.x, h.y, h.z); + if (!dynamic) desc.setTranslation(center.x, center.y, center.z); + } + desc.setFriction(0.9); + desc.setRestitution(restitution); + + if (dynamic && shape !== "trimesh") { + // Dynamic: create rigid body + attach collider + const bodyDesc = g.RAPIER.RigidBodyDesc.dynamic() + .setTranslation(center.x, center.y, center.z); + const body = g.rapierWorld.createRigidBody(bodyDesc); + body.setAdditionalMass(mass); + const collider = g.rapierWorld.createCollider(desc, body); + colliderMap.set(obj.uuid, collider); + dynamicBodies.set(obj.uuid, { body, mesh: obj }); + selfRef._ensureDynamicSyncLoop(); + } else { + // Static: collider with no parent body + const collider = g.rapierWorld.createCollider(desc); + colliderMap.set(obj.uuid, collider); + } + } + + // Server-side collider (for lidar + dimos physics) + serverDesc.dynamic = dynamic; + if (dynamic) { serverDesc.mass = mass; serverDesc.restitution = restitution; } + sendPhysics({ type: "physicsColliderAdd", uuid: obj.uuid, desc: serverDesc }); + + return { shape, dynamic, uuid: obj.uuid, size: { x: +size.x.toFixed(3), y: +size.y.toFixed(3), z: +size.z.toFixed(3) } }; + }; + + // removeCollider: remove collider browser-side + server-side + const removeCollider = (obj: any): boolean => { + const existing = colliderMap.get(obj.uuid); + if (existing) { + try { + g.rapierWorld?.removeCollider(existing, true); + } catch { /* already removed */ } + colliderMap.delete(obj.uuid); + } + // Clean up dynamic rigid body if any + const dynEntry = dynamicBodies.get(obj.uuid); + if (dynEntry) { + try { g.rapierWorld?.removeRigidBody(dynEntry.body); } catch { /* already removed */ } + dynamicBodies.delete(obj.uuid); + } + // Always tell server to remove (even if browser didn't have it) + sendPhysics({ type: "physicsColliderRemove", uuid: obj.uuid }); + return !!existing; + }; + + // addNPC: load an animated GLTF character, place it, and play an animation + const npcMixers = this._npcMixers; + const self = this; + const addNPC = async (opts: { + url: string; + name?: string; + position?: { x: number; y: number; z: number }; + rotation?: number; // yaw in radians + scale?: number; + animation?: string | number; // clip name or index (default: 0) + collider?: boolean; // add trimesh collider (default: true) + }): Promise => { + const gltf = await loadGLTF(opts.url); + const model = gltf.scene; + const npcName = opts.name || `npc-${Date.now().toString(36)}`; + model.name = npcName; + if (opts.position) model.position.set(opts.position.x, opts.position.y, opts.position.z); + if (opts.rotation != null) model.rotation.y = opts.rotation; + if (opts.scale != null) model.scale.setScalar(opts.scale); + model.traverse((child: any) => { if (child.isMesh) { child.castShadow = true; child.receiveShadow = true; } }); + g.scene.add(model); + + // Set up animation + let activeClipName = ""; + const clipNames: string[] = []; + if (gltf.animations && gltf.animations.length > 0) { + const mixer = new g.THREE.AnimationMixer(model); + npcMixers.set(npcName, mixer); + + for (const clip of gltf.animations) clipNames.push(clip.name); + // Store clips on model so they can be switched at runtime + model.animations = gltf.animations; + + // Select animation clip + let clipIndex = 0; + if (typeof opts.animation === "string") { + const idx = gltf.animations.findIndex((c: any) => c.name.toLowerCase().includes(opts.animation!.toString().toLowerCase())); + if (idx >= 0) clipIndex = idx; + } else if (typeof opts.animation === "number") { + clipIndex = Math.min(opts.animation, gltf.animations.length - 1); + } + + const clip = gltf.animations[clipIndex]; + activeClipName = clip.name; + const action = mixer.clipAction(clip); + action.play(); + + // Start the animation loop if not already running + self._ensureNpcAnimLoop(); + } + + // Add collider (default: trimesh) + let colliderInfo = null; + if (opts.collider !== false) { + colliderInfo = addCollider(model, "trimesh"); + } + + return { + name: npcName, + animations: clipNames, + activeAnimation: activeClipName, + collider: colliderInfo, + }; + }; + + // removeNPC: remove an NPC from scene and clean up its mixer + const removeNPC = (name: string): boolean => { + const obj = g.scene.getObjectByName(name); + if (!obj) return false; + // Stop animation mixer + const mixer = npcMixers.get(name); + if (mixer) { mixer.stopAllAction(); npcMixers.delete(name); } + // Remove collider + removeCollider(obj); + // Clear name before removal so getObjectByName won't find stale refs + obj.name = ""; + // Remove from scene + obj.traverse((child: any) => { + if (child.isMesh) { child.geometry?.dispose(); child.material?.dispose(); } + }); + g.scene.remove(obj); + return true; + }; + + // autoScale: detect cm/m mismatch and normalize model to scene scale. + // Heuristic: if bounding box exceeds targetMaxDim (default 50m) in any axis, + // assume the model is in centimeters and scale by 0.01. For intermediate cases + // (10-50m), scale proportionally so the largest dimension equals targetMaxDim. + // Returns the scale factor applied (1.0 if no change). + const autoScale = (obj: any, targetMaxDim = 50): number => { + const bbox = new g.THREE.Box3().setFromObject(obj); + const size = new g.THREE.Vector3(); + bbox.getSize(size); + const maxDim = Math.max(size.x, size.y, size.z); + if (maxDim <= 0.001) return 1.0; // degenerate + let scaleFactor = 1.0; + if (maxDim > targetMaxDim * 2) { + // Very large — likely centimeters (100x off) + scaleFactor = 0.01; + } else if (maxDim > targetMaxDim) { + // Moderately large — scale down proportionally + scaleFactor = targetMaxDim / maxDim; + } + if (scaleFactor !== 1.0) { + obj.scale.multiplyScalar(scaleFactor); + obj.updateMatrixWorld(true); + console.log(`[sceneEditor] autoScale: ${maxDim.toFixed(1)}m → ${(maxDim * scaleFactor).toFixed(1)}m (×${scaleFactor.toFixed(4)})`); + } + return scaleFactor; + }; + + const fn = new AsyncFunction( + "scene", "THREE", "RAPIER", "rapierWorld", "renderer", "camera", + "agent", "playerBody", "assets", "assetsGroup", + "loadGLTF", "addCollider", "removeCollider", "addNPC", "removeNPC", "autoScale", + code, + ); + const result = await fn( + g.scene, g.THREE, g.RAPIER, g.rapierWorld, g.renderer, g.camera, + g.agent, g.agent, g.assets, g.assetsGroup, + loadGLTF, addCollider, removeCollider, addNPC, removeNPC, autoScale, + ); + this._send({ type: "execResult", id, success: true, result: _serialize(result) }); + } catch (err: any) { + console.error("[sceneEditor] exec error:", err); + this._send({ type: "execResult", id, success: false, error: String(err) }); + } + } + + async _loadScript(url: string, id?: string): Promise { + console.log(`[sceneEditor] loadScript${id ? ` (${id})` : ""}:`, url); + try { + const resp = await fetch(url); + if (!resp.ok) throw new Error(`HTTP ${resp.status}: ${resp.statusText}`); + const code = await resp.text(); + await this._execCode(code, id); + } catch (err: any) { + console.error("[sceneEditor] loadScript error:", err); + this._send({ type: "execResult", id, success: false, error: String(err) }); + } + } + + _ensureNpcAnimLoop(): void { + if (this._npcAnimFrame != null) return; + this._startUpdateLoop(); + } + + _ensureDynamicSyncLoop(): void { + if (this._npcAnimFrame != null) return; + this._startUpdateLoop(); + } + + /** Shared rAF loop for NPC animations + dynamic body position sync. */ + _startUpdateLoop(): void { + if (this._npcAnimFrame != null) return; + if (!this._npcClock) { + this._npcClock = new this.globals.THREE.Clock(); + } + const tick = () => { + const hasWork = this._npcMixers.size > 0 || this._dynamicBodies.size > 0; + if (!hasWork) { + this._npcAnimFrame = null; + return; + } + const dt = this._npcClock.getDelta(); + + // Update NPC animations + for (const mixer of this._npcMixers.values()) { + mixer.update(dt); + } + + // Sync dynamic body positions → Three.js meshes + for (const { body, mesh } of this._dynamicBodies.values()) { + const t = body.translation(); + const r = body.rotation(); + mesh.position.set(t.x, t.y, t.z); + mesh.quaternion.set(r.x, r.y, r.z, r.w); + } + + this._npcAnimFrame = requestAnimationFrame(tick); + }; + this._npcAnimFrame = requestAnimationFrame(tick); + } + + dispose(): void { + if (this._npcAnimFrame != null) cancelAnimationFrame(this._npcAnimFrame); + for (const mixer of this._npcMixers.values()) mixer.stopAllAction(); + this._npcMixers.clear(); + this._dynamicBodies.clear(); + } +} + +/** Safely serialize a return value for JSON transport. */ +function _serialize(val: any): any { + if (val === undefined || val === null) return val; + if (typeof val === "number" || typeof val === "string" || typeof val === "boolean") return val; + if (Array.isArray(val)) return val.map(_serialize); + // Three.js objects have .toJSON() but it's huge — just return type + id + if (val.isObject3D) return { _type: "Object3D", type: val.type, name: val.name, uuid: val.uuid }; + if (val.isMesh) return { _type: "Mesh", name: val.name, uuid: val.uuid }; + try { return JSON.parse(JSON.stringify(val)); } catch { return String(val); } +} diff --git a/misc/DimSim/src/style.css b/misc/DimSim/src/style.css new file mode 100644 index 0000000000..ec258b99a1 --- /dev/null +++ b/misc/DimSim/src/style.css @@ -0,0 +1,3191 @@ +/* ============================================================================ + SimStudio - Professional Training Environment + ============================================================================ */ + +:root { + color-scheme: dark; + + /* Core Colors — flat terminal/cyberdeck */ + --bg-primary: #06080b; + --bg-secondary: #0b0e13; + --bg-tertiary: #10141b; + --bg-elevated: rgba(9, 12, 17, 0.96); + + /* Surface Colors */ + --surface-1: rgba(255, 255, 255, 0.02); + --surface-2: rgba(255, 255, 255, 0.04); + --surface-3: rgba(255, 255, 255, 0.07); + + /* Border Colors — hairline */ + --border-subtle: rgba(255, 255, 255, 0.06); + --border-default: rgba(255, 255, 255, 0.10); + --border-strong: rgba(255, 255, 255, 0.16); + + /* Text Colors */ + --text-primary: rgba(255, 255, 255, 0.95); + --text-secondary: rgba(255, 255, 255, 0.68); + --text-tertiary: rgba(255, 255, 255, 0.44); + + /* Accent Colors — dimos-style cool cyan-white */ + --accent-primary: #d6dde6; + --accent-primary-hover: #ffffff; + --accent-primary-subtle: rgba(214, 221, 230, 0.14); + --accent-primary-glow: rgba(214, 221, 230, 0.28); + + --accent-success: #7fe3c4; + --accent-success-subtle: rgba(127, 227, 196, 0.14); + + --accent-warning: #f5c06b; + --accent-warning-subtle: rgba(245, 192, 107, 0.12); + + --accent-info: #7fd4f5; + --accent-info-subtle: rgba(127, 212, 245, 0.12); + + /* Shadows — flat, no heavy drop shadows */ + --shadow-sm: 0 0 0 1px rgba(0, 0, 0, 0.2); + --shadow-md: 0 0 0 1px rgba(0, 0, 0, 0.3); + --shadow-lg: 0 0 0 1px rgba(0, 0, 0, 0.4); + --shadow-xl: 0 0 0 1px rgba(0, 0, 0, 0.5); + + /* Transitions */ + --transition-fast: 0.1s linear; + --transition-normal: 0.15s linear; + --transition-slow: 0.2s linear; + + /* Border Radius — sharp corners */ + --radius-sm: 0px; + --radius-md: 0px; + --radius-lg: 0px; + --radius-xl: 2px; + + /* Font Stacks */ + --font-mono: 'JetBrains Mono', 'IBM Plex Mono', 'SF Mono', 'Fira Code', 'Menlo', 'Monaco', 'Consolas', ui-monospace, monospace; + --font-sans: 'Inter', ui-sans-serif, system-ui, -apple-system, BlinkMacSystemFont, 'Segoe UI', Roboto, 'Helvetica Neue', Arial, sans-serif; +} + +/* ============================================================================ + Base Styles + ============================================================================ */ + +html, body { + height: 100%; + margin: 0; +} + +body { + overflow: hidden; + font-family: var(--font-sans); + background: var(--bg-primary); + color: var(--text-primary); + font-size: 13px; + line-height: 1.5; + -webkit-font-smoothing: antialiased; + -moz-osx-font-smoothing: grayscale; +} + +/* Google Font Import */ +@import url('https://fonts.googleapis.com/css2?family=Inter:wght@400;500;600;700;800;900&display=swap'); + +/* ============================================================================ + Canvas + ============================================================================ */ + +#c { + position: fixed; + inset: 0; + width: 100%; + height: 100%; + display: block; +} + +/* ============================================================================ + Overlay Layout + ============================================================================ */ + +#overlay { + position: fixed; + inset: 0; + pointer-events: none; + z-index: 100; + padding: 0; + box-sizing: border-box; + display: grid; + grid-template-columns: 330px 1fr 380px; + grid-template-rows: auto 1fr; + grid-template-areas: + "top top top" + "left . right"; + gap: 0; +} + +/* Collapsed states for edit mode panels */ +#overlay.left-collapsed { + grid-template-columns: 0 1fr 380px; +} +#overlay.right-collapsed { + grid-template-columns: 330px 1fr 0; +} +#overlay.left-collapsed.right-collapsed { + grid-template-columns: 0 1fr 0; +} + +html[data-mode="sim"] #overlay { + grid-template-columns: 1fr 340px; + grid-template-rows: 1fr; + grid-template-areas: ". panel"; + padding: 16px; + gap: 16px; +} + +html[data-mode="sim"] #overlay.sim-panel-collapsed { + grid-template-columns: 1fr 0; +} + +/* ============================================================================ + Slim Toolbar (UE-inspired) + ============================================================================ */ + +#overlay-top { + pointer-events: auto; + grid-area: top; + display: flex; + gap: 4px; + align-items: center; + padding: 4px 8px; + background: #1a1d24; + border-bottom: 1px solid rgba(255,255,255,0.08); + box-shadow: 0 2px 8px rgba(0,0,0,0.4); + flex-wrap: wrap; + overflow: visible; + min-height: 36px; + position: relative; + z-index: 10; +} + +/* Toolbar generic button */ +.tb-btn { + display: inline-flex; + align-items: center; + gap: 5px; + padding: 5px 10px; + font-size: 11px; + font-weight: 500; + font-family: var(--font-mono); + letter-spacing: 0.04em; + text-transform: uppercase; + color: var(--text-secondary); + background: transparent; + border: 1px solid transparent; + border-radius: 0; + cursor: pointer; + white-space: nowrap; + transition: all 0.1s linear; +} +.tb-btn:hover { background: rgba(255,255,255,0.04); color: var(--text-primary); border-color: var(--border-default); } +.tb-btn.active { color: var(--accent-primary); background: var(--accent-primary-subtle); border-color: var(--accent-primary); } +.tb-btn.tb-primary { background: transparent; color: var(--accent-primary); border: 1px solid var(--accent-primary); } +.tb-btn.tb-primary:hover { background: var(--accent-primary-subtle); color: var(--accent-primary-hover); border-color: var(--accent-primary-hover); } +.tb-btn.tb-danger { color: #ef4444; } +.tb-btn.tb-danger:hover { background: rgba(239,68,68,0.12); color: #f87171; } +.tb-btn.tb-muted { color: var(--text-tertiary); font-weight: 500; } +.tb-btn.tb-muted:hover { color: var(--text-secondary); } +.tb-btn svg { flex-shrink: 0; } + +/* File upload styled as toolbar button */ +.tb-file-label { cursor: pointer; } +.tb-file-label input[type="file"] { display: none; } + +/* Toolbar select */ +.tb-select { + padding: 4px 8px; + font-size: 11px; + font-weight: 500; + font-family: var(--font-mono); + background: rgba(255,255,255,0.03); + border: 1px solid var(--border-default); + border-radius: 0; + color: var(--text-primary); + cursor: pointer; + outline: none; + max-width: 130px; +} +.tb-select:focus { border-color: var(--accent-primary); } + +/* Toolbar separator */ +.tb-sep { + width: 1px; + height: 20px; + background: rgba(255,255,255,0.1); + margin: 0 2px; + flex-shrink: 0; +} +.tb-spacer { flex: 1; } + +/* Toolbar transform group */ +.tb-transform { + display: flex; + gap: 2px; + padding: 2px; + background: rgba(255,255,255,0.02); + border: 1px solid var(--border-subtle); + border-radius: 0; +} + +/* Toolbar status */ +.tb-status { + font-size: 11px; + color: var(--text-tertiary); + white-space: nowrap; + overflow: hidden; + text-overflow: ellipsis; + max-width: 200px; +} +.tb-status:empty { display: none; } + +/* Toolbar group */ +.tb-group { display: flex; gap: 3px; align-items: center; } + +.workspace-tab-strip { + display: inline-flex; + gap: 0; + padding: 0; + background: transparent; + border: 1px solid var(--border-default); + border-radius: 0; + margin: 0 4px; +} +.workspace-tab-strip .tb-btn { + padding: 4px 12px; + font-size: 11px; + font-weight: 500; + border-radius: 0; + border: none; + color: var(--text-tertiary); + transition: all 0.1s linear; +} +.workspace-tab-strip .tb-btn:hover { + color: var(--text-secondary); + background: rgba(255,255,255,0.04); +} +.workspace-tab-strip .tb-btn.active { + color: var(--accent-primary-hover); + background: var(--accent-primary-subtle); + box-shadow: inset 0 -2px 0 var(--accent-primary); +} + +/* Builder-mode inline shape palette */ +.builder-shape-bar { + display: inline-flex; + gap: 2px; + padding: 2px; + background: rgba(255,255,255,0.02); + border: 1px solid var(--border-subtle); + border-radius: 0; +} +.builder-shape-bar .tb-btn { + padding: 4px 8px; + font-size: 12px; + gap: 3px; +} +.builder-shape-bar .shape-icon { + font-size: 11px; + opacity: 0.7; +} + +/* Advanced dropdown */ +.tb-advanced { position: relative; } +.tb-advanced > summary { list-style: none; } +.tb-advanced > summary::-webkit-details-marker { display: none; } +.tb-advanced-body { + position: absolute; + top: calc(100% + 4px); + right: 0; + z-index: 50; + background: var(--bg-secondary); + border: 1px solid var(--border-default); + border-radius: 0; + padding: 4px; + display: flex; + gap: 4px; + box-shadow: none; +} + +/* Legacy world-selector compat (now .tb-group) */ +.world-selector { display: contents; } + +/* ============================================================================ + Buttons + ============================================================================ */ + +button, +.file span { + cursor: pointer; + user-select: none; + padding: 7px 14px; + border-radius: 0; + border: 1px solid var(--border-default); + background: transparent; + color: var(--text-primary); + font-weight: 500; + font-size: 12px; + font-family: var(--font-mono); + letter-spacing: 0.05em; + text-transform: uppercase; + transition: all var(--transition-fast); + display: inline-flex; + align-items: center; + justify-content: center; + gap: 6px; +} + +/* Toolbar buttons override the heavy defaults */ +.tb-btn, #overlay-top button, #overlay-top .file span { + padding: 5px 10px; + border-radius: 0; + border: 1px solid transparent; + background: transparent; + font-size: 11px; + font-family: var(--font-mono); + transform: none !important; +} + +button:hover, +.file span:hover { + border-color: var(--accent-primary); + background: var(--accent-primary-subtle); + color: var(--accent-primary-hover); +} + +button:active, +.file span:active { + transform: none; +} + +button:disabled { + opacity: 0.5; + cursor: not-allowed; + transform: none; +} + +/* Primary Action Button */ +button.primary { + background: transparent; + border: 1px solid var(--accent-primary); + color: var(--accent-primary); + box-shadow: none; +} + +button.primary:hover { + background: var(--accent-primary-subtle); + border-color: var(--accent-primary-hover); + color: var(--accent-primary-hover); + box-shadow: none; +} + +/* Portal Button */ +#portal-create-btn { + background: var(--surface-2); + border: 1px solid var(--border-default); + color: var(--text-primary); + box-shadow: none; +} + +#portal-create-btn:hover { + background: var(--surface-3); + border-color: var(--border-strong); + box-shadow: var(--shadow-sm); +} + +/* Portal Exit Modal */ +#portal-exit-modal .modal-title { + background: var(--surface-1); +} + +#portal-exit-modal .modal-hint { + border-left-color: var(--accent-primary); + background: var(--accent-primary-subtle); +} + +#portal-exit-world-name { + color: var(--text-primary); + font-weight: 700; +} + +/* Watermark logo */ +.watermark-logo { + position: fixed; + bottom: 16px; + right: 16px; + height: 32px; + width: auto; + opacity: 0.35; + pointer-events: none; + z-index: 9999; + user-select: none; +} + +/* ============================================ + PORTAL LOADING SCREEN + ============================================ */ +.portal-loading { + position: fixed; + inset: 0; + z-index: 10000; + background: radial-gradient(ellipse at center, #1a1035 0%, #0a0a0f 70%, #000 100%); + display: flex; + align-items: center; + justify-content: center; + opacity: 1; + transition: opacity 0.5s ease-out; +} + +.portal-loading.hidden { + opacity: 0; + pointer-events: none; +} + +.portal-loading.fade-out { + opacity: 0; +} + +.portal-loading-content { + display: flex; + flex-direction: column; + align-items: center; + gap: 40px; +} + +.portal-loading-effect { + position: relative; + width: 150px; + height: 150px; +} + +.portal-ring { + position: absolute; + inset: 0; + border-radius: 50%; + border: 3px solid transparent; + border-top-color: #8b5cf6; + border-bottom-color: #a78bfa; + animation: portal-spin 1.5s linear infinite; +} + +.portal-ring:nth-child(2) { + inset: 15px; + border-top-color: #7c3aed; + border-bottom-color: #8b5cf6; + animation-duration: 2s; + animation-direction: reverse; +} + +.portal-ring:nth-child(3) { + inset: 30px; + border-top-color: #6d28d9; + border-bottom-color: #7c3aed; + animation-duration: 2.5s; +} + +@keyframes portal-spin { + 0% { + transform: rotate(0deg); + } + 100% { + transform: rotate(360deg); + } +} + +/* Inner glow effect */ +.portal-loading-effect::before { + content: ''; + position: absolute; + inset: 40px; + border-radius: 50%; + background: radial-gradient(circle, rgba(139, 92, 246, 0.4) 0%, rgba(109, 40, 217, 0.2) 50%, transparent 70%); + animation: portal-pulse 2s ease-in-out infinite; +} + +@keyframes portal-pulse { + 0%, 100% { + transform: scale(0.9); + opacity: 0.6; + } + 50% { + transform: scale(1.1); + opacity: 1; + } +} + +/* Particle effect */ +.portal-loading-effect::after { + content: ''; + position: absolute; + inset: 20px; + border-radius: 50%; + background: transparent; + box-shadow: + 0 0 30px rgba(139, 92, 246, 0.5), + 0 0 60px rgba(139, 92, 246, 0.3), + 0 0 90px rgba(139, 92, 246, 0.1); + animation: portal-glow 2s ease-in-out infinite alternate; +} + +@keyframes portal-glow { + 0% { + box-shadow: + 0 0 30px rgba(139, 92, 246, 0.5), + 0 0 60px rgba(139, 92, 246, 0.3), + 0 0 90px rgba(139, 92, 246, 0.1); + } + 100% { + box-shadow: + 0 0 40px rgba(167, 139, 250, 0.6), + 0 0 80px rgba(139, 92, 246, 0.4), + 0 0 120px rgba(139, 92, 246, 0.2); + } +} + +.portal-loading-text { + display: flex; + flex-direction: column; + align-items: center; + gap: 8px; + text-align: center; +} + +#portal-loading-title { + font-size: 18px; + font-weight: 600; + color: #e2e8f0; + letter-spacing: 1px; +} + +#portal-loading-dest { + font-size: 24px; + font-weight: 700; + color: #a78bfa; + text-shadow: 0 0 20px rgba(139, 92, 246, 0.5); +} + +/* Success Button */ +button.success { + background: linear-gradient(135deg, var(--accent-success) 0%, #16a34a 100%); + border: none; + color: white; +} + +/* Danger Button */ +button.danger { + background: linear-gradient(135deg, #ef4444 0%, #dc2626 100%); + border: none; + color: white; +} + +/* Ghost Button */ +button.ghost { + background: transparent; + border-color: transparent; + color: var(--text-secondary); +} + +button.ghost:hover { + background: var(--surface-2); + color: var(--text-primary); +} + +.file input { + display: none; +} + +/* ============================================================================ + Form Elements + ============================================================================ */ + +input[type="text"], +input[type="email"], +input[type="password"], +textarea, +.select { + width: 100%; + box-sizing: border-box; + padding: 10px 14px; + border-radius: var(--radius-md); + border: 1px solid var(--border-default); + background: var(--surface-2); + color: var(--text-primary); + font-weight: 500; + font-size: 14px; + outline: none; + transition: all var(--transition-fast); +} + +input[type="text"]:hover, +textarea:hover, +.select:hover { + border-color: var(--border-strong); +} + +input[type="text"]:focus, +textarea:focus, +.select:focus { + border-color: var(--accent-primary); + box-shadow: 0 0 0 3px var(--accent-primary-subtle); +} + +input[type="text"]::placeholder, +textarea::placeholder { + color: var(--text-tertiary); +} + +textarea { + resize: vertical; + min-height: 100px; + font-family: inherit; + line-height: 1.5; +} + +/* Checkbox Styling */ +input[type="checkbox"] { + width: 18px; + height: 18px; + border-radius: var(--radius-sm); + border: 2px solid var(--border-strong); + background: var(--surface-2); + cursor: pointer; + appearance: none; + -webkit-appearance: none; + transition: all var(--transition-fast); + position: relative; +} + +input[type="checkbox"]:checked { + background: var(--accent-primary); + border-color: var(--accent-primary); +} + +input[type="checkbox"]:checked::after { + content: "✓"; + position: absolute; + top: 50%; + left: 50%; + transform: translate(-50%, -50%); + color: white; + font-size: 12px; + font-weight: 700; +} + +input[type="checkbox"]:hover { + border-color: var(--accent-primary); +} + +/* ============================================================================ + Status Bar + ============================================================================ */ + +.status { + margin-left: auto; + padding: 6px 12px; + font-size: 12px; + font-weight: 500; + color: var(--text-secondary); + background: var(--surface-1); + border-radius: var(--radius-sm); + max-width: 300px; + white-space: nowrap; + overflow: hidden; + text-overflow: ellipsis; +} + +/* ============================================================================ + Details / Accordion + ============================================================================ */ + +.details { + border: 1px solid var(--border-default); + border-radius: var(--radius-md); + background: var(--surface-1); + padding: 0; + overflow: hidden; +} + +.details > summary { + cursor: pointer; + user-select: none; + font-weight: 600; + color: var(--text-secondary); + font-size: 12px; + padding: 10px 14px; + list-style: none; + transition: all var(--transition-fast); + display: flex; + align-items: center; + gap: 8px; +} + +.details > summary::-webkit-details-marker { + display: none; +} + +.details > summary::before { + content: "▸"; + font-size: 10px; + transition: transform var(--transition-fast); +} + +.details[open] > summary::before { + transform: rotate(90deg); +} + +.details > summary:hover { + background: var(--surface-2); + color: var(--text-primary); +} + +.details-body { + padding: 12px 14px; + border-top: 1px solid var(--border-subtle); + display: flex; + flex-direction: column; + gap: 12px; +} + +.details-row { + display: flex; + align-items: center; + gap: 10px; + flex-wrap: wrap; +} + +/* ============================================================================ + Slider + ============================================================================ */ + +.slider { + display: flex; + align-items: center; + gap: 6px; + padding: 4px 0; +} + +.slider-label { + font-size: 10px; + color: var(--text-tertiary); + font-weight: 600; + min-width: 40px; + text-transform: uppercase; + letter-spacing: 0.02em; +} + +.slider input[type="range"] { + flex: 1; + height: 3px; + border-radius: 2px; + background: rgba(255,255,255,0.1); + appearance: none; + -webkit-appearance: none; +} + +.slider input[type="range"]::-webkit-slider-thumb { + appearance: none; + -webkit-appearance: none; + width: 12px; + height: 12px; + border-radius: 50%; + background: var(--accent-primary); + cursor: pointer; + border: 1.5px solid rgba(255,255,255,0.3); +} + +.slider-value { + font-variant-numeric: tabular-nums; + font-weight: 600; + font-size: 10px; + color: var(--text-secondary); + min-width: 30px; + text-align: right; +} + + +/* ============================================================================ + Side Panel (UE-inspired) + ============================================================================ */ + +.side-panel { + pointer-events: auto; + width: 100%; + height: calc(100vh - 36px); /* below toolbar */ + display: flex; + flex-direction: column; + background: #1a1d24; + overflow: hidden; +} + +.side-panel-left { + grid-area: left; + border-right: 1px solid rgba(255,255,255,0.06); +} + +.side-panel-right { + grid-area: right; + border-left: 1px solid rgba(255,255,255,0.06); +} + +/* Hide panels when overlay is collapsed */ +#overlay.left-collapsed .side-panel-left { + display: none; +} +#overlay.right-collapsed .side-panel-right { + display: none; +} + +html[data-mode="sim"] .side-panel { + grid-area: panel; + height: calc(100vh - 32px); + border-radius: 0; + border: 1px solid var(--border-default); + backdrop-filter: blur(20px); + background: var(--bg-elevated); +} + +.panel-header { + flex-shrink: 0; + display: flex; + align-items: center; + justify-content: space-between; + padding: 6px 10px; + border-bottom: 1px solid rgba(255,255,255,0.06); + background: rgba(255,255,255,0.02); +} + +.panel-title { + font-family: var(--font-mono); + font-weight: 600; + font-size: 11px; + letter-spacing: 0.16em; + text-transform: uppercase; + color: var(--text-secondary); + display: flex; + align-items: center; + gap: 8px; +} + +.panel-title::before { + content: "["; + color: var(--accent-primary); + font-family: var(--font-mono); + font-weight: 500; + font-size: 12px; + background: transparent; + width: auto; + height: auto; + border-radius: 0; + letter-spacing: 0; +} +.panel-title::after { + content: "]"; + color: var(--accent-primary); + font-family: var(--font-mono); + font-weight: 500; + font-size: 12px; + margin-left: 2px; + letter-spacing: 0; +} + +.mode-toggle { + padding: 3px 8px !important; + font-size: 11px !important; + font-weight: 500 !important; + font-family: var(--font-mono) !important; + background: transparent !important; + border: 1px solid var(--border-default) !important; + color: var(--text-tertiary) !important; + display: flex !important; + align-items: center !important; + gap: 5px !important; + border-radius: 0 !important; + cursor: pointer; + transition: all 0.1s !important; + text-transform: none !important; + letter-spacing: 0 !important; +} +.mode-toggle:hover { background: rgba(255,255,255,0.06) !important; color: var(--text-primary) !important; } +.mode-icon { font-size: 9px; } + +.panel-content { + flex: 1; + overflow-y: auto; + overflow-x: hidden; +} + +.panel-footer { + flex-shrink: 0; + padding: 5px 10px; + border-top: 1px solid rgba(255,255,255,0.06); + background: rgba(255,255,255,0.02); +} + +/* Panel collapse/expand buttons */ +.panel-collapse-btn { + padding: 4px 8px !important; + font-size: 10px !important; + font-weight: 500 !important; + font-family: var(--font-mono) !important; + background: transparent !important; + border: 1px solid var(--border-default) !important; + color: var(--text-tertiary) !important; + border-radius: 0 !important; + cursor: pointer; + transition: all 0.1s !important; + display: flex !important; + align-items: center !important; + justify-content: center !important; + line-height: 1 !important; +} +.panel-collapse-btn:hover { background: rgba(255,255,255,0.06) !important; color: var(--text-primary) !important; } + +/* Left panel open button (shown when collapsed) */ +.left-panel-open { + pointer-events: auto; + position: fixed; + top: 44px; + left: 8px; + width: 30px; + height: 30px; + border-radius: 0; + border: 1px solid var(--border-default); + background: var(--bg-elevated); + color: var(--text-secondary); + cursor: pointer; + z-index: 150; + font-size: 14px; + display: flex; + align-items: center; + justify-content: center; + backdrop-filter: blur(12px); +} +.left-panel-open:hover { color: var(--text-primary); background: rgba(255,255,255,0.08); } +.left-panel-open.hidden { display: none; } + +/* Right AI panel open button (shown when collapsed) */ +.ai-panel-open { + pointer-events: auto; + position: fixed; + top: 44px; + right: 8px; + width: 30px; + height: 30px; + border-radius: 0; + border: 1px solid var(--border-default); + background: var(--bg-elevated); + color: var(--text-secondary); + cursor: pointer; + z-index: 150; + font-size: 14px; + display: flex; + align-items: center; + justify-content: center; + backdrop-filter: blur(12px); +} +.ai-panel-open:hover { color: var(--text-primary); background: rgba(255,255,255,0.08); } +.ai-panel-open.hidden { display: none; } + +.sim-panel-open { + pointer-events: auto; + position: fixed; + top: 16px; + right: 16px; + width: 30px; + height: 30px; + border-radius: 0; + border: 1px solid var(--border-default); + background: var(--bg-elevated); + color: var(--text-secondary); + cursor: pointer; + z-index: 150; + font-family: var(--font-mono); +} +.sim-panel-open:hover { color: var(--text-primary); background: rgba(255,255,255,0.08); } +.sim-panel-open.hidden { display: none; } + +.shortcuts { + display: flex; + flex-wrap: wrap; + gap: 6px 10px; + font-size: 10px; + font-family: var(--font-mono); + letter-spacing: 0.04em; + color: var(--text-tertiary); +} + +.shortcuts b { + color: var(--accent-primary); + font-weight: 500; + background: transparent; + border: 1px solid var(--border-default); + padding: 0 4px; + border-radius: 0; + font-size: 9px; + font-family: var(--font-mono); +} + +/* Floating bottom-left shortcuts strip (always visible in sim mode) */ +.shortcuts-floating { + position: fixed; + bottom: 16px; + left: 16px; + padding: 8px 12px; + background: rgba(8, 10, 14, 0.82); + border: 1px solid rgba(255, 255, 255, 0.12); + border-radius: 0; + font-size: 11px; + letter-spacing: 0.06em; + text-transform: uppercase; + z-index: 9998; + backdrop-filter: blur(4px); +} +.shortcuts-floating b { + font-size: 10px; + padding: 1px 5px; +} + +/* Dimos-only: hide the sim side panel + command bar + top-left status + pill (the small "Click to look around" + B/G chip is the human-player + prompt; the agent is driven externally). Bottom-left WASD shortcuts + stay visible. */ +body.dimos-mode #agent-panel, +body.dimos-mode #sim-panel-open, +body.dimos-mode #agent-command-bar, +body.dimos-mode .status-floating { + display: none !important; +} + +/* Tag form / tag-selected (legacy compat) */ +.tag-selected { display: none; } +.tag-form { /* managed by details-panel */ } +.tag-form.hidden { display: none; } + +/* Floating status for sim mode */ +.status-floating { + position: fixed; + top: 16px; + left: 16px; + padding: 6px 12px; + font-size: 11px; + font-weight: 500; + font-family: var(--font-mono); + letter-spacing: 0.04em; + color: var(--text-secondary); + background: var(--bg-elevated); + border: 1px solid var(--border-default); + border-radius: 0; + backdrop-filter: blur(12px); + pointer-events: auto; + max-width: 300px; + white-space: nowrap; + overflow: hidden; + text-overflow: ellipsis; +} +.status-floating:empty { display: none; } + +/* ============================================================================ + Outliner (Scene tree, collapsible sections) + ============================================================================ */ + +.outliner { + border-bottom: 1px solid rgba(255,255,255,0.06); +} + +.ol-section { + border-bottom: 1px solid rgba(255,255,255,0.04); +} +.ol-section:last-child { border-bottom: none; } +.ol-section > summary { list-style: none; } +.ol-section > summary::-webkit-details-marker { display: none; } + +.ol-header { + display: flex; + align-items: center; + gap: 6px; + padding: 5px 10px; + font-size: 11px; + font-weight: 500; + font-family: var(--font-mono); + letter-spacing: 0.08em; + text-transform: uppercase; + color: var(--text-secondary); + cursor: pointer; + user-select: none; + transition: background 0.1s; +} +.ol-header:hover { background: rgba(255,255,255,0.04); } + +.ol-header::before { + content: "▸"; + font-size: 9px; + color: var(--text-tertiary); + transition: transform 0.15s; + display: inline-block; + width: 10px; +} +.ol-section[open] > .ol-header::before { transform: rotate(90deg); } + +.ol-icon { font-size: 12px; } +.ol-count { + margin-left: auto; + font-size: 10px; + font-weight: 500; + color: var(--text-tertiary); + background: rgba(255,255,255,0.04); + padding: 1px 6px; + border-radius: 0; + min-width: 16px; + text-align: center; + font-family: var(--font-mono); +} + +.ol-list { + display: flex; + flex-direction: column; + gap: 1px; + padding: 0 0 2px 0; + max-height: 160px; + overflow-y: auto; +} + +/* Compact outliner items (replaces old .tag-item) */ +.tag-item, .ol-item { + display: flex; + align-items: center; + gap: 6px; + padding: 4px 10px 4px 26px; + cursor: pointer; + font-size: 12px; + font-weight: 500; + color: var(--text-secondary); + transition: all 0.08s; + border: none; + background: transparent; + border-radius: 0; +} + +.tag-item:hover { + background: rgba(255,255,255,0.04); + color: var(--text-primary); +} + +.tag-item small { + margin-left: auto; + color: var(--text-tertiary); + font-size: 10px; + font-weight: 400; + margin-top: 0; + display: inline; + flex-shrink: 0; +} + +.tag-item.active { + background: var(--accent-primary-subtle); + color: var(--accent-primary-hover); + border: none; + box-shadow: inset 3px 0 0 var(--accent-primary); +} + +/* ============================================================================ + Groups in Outliner + ============================================================================ */ + +.ol-group { + border-left: 2px solid transparent; + margin-bottom: 2px; +} +.ol-group.active { + border-left-color: var(--accent-primary); + background: rgba(99,102,241,0.04); +} + +.ol-group-header { + display: flex; + align-items: center; + gap: 5px; + padding: 4px 8px 4px 14px; + cursor: pointer; + font-size: 12px; + font-weight: 600; + color: var(--text-secondary); + transition: background 0.08s; + user-select: none; +} +.ol-group-collapse-btn { + width: 18px; + height: 18px; + padding: 0; + border: 1px solid transparent; + border-radius: 4px; + background: transparent; + color: var(--text-tertiary); + font-size: 11px; + line-height: 1; + cursor: pointer; +} +.ol-group-collapse-btn:hover { + background: rgba(255,255,255,0.06); + color: var(--text-primary); +} +.ol-group-header:hover { + background: rgba(255,255,255,0.05); + color: var(--text-primary); +} + +.ol-group-icon { + font-size: 11px; + flex-shrink: 0; +} +.ol-group-name { + flex: 1; + overflow: hidden; + text-overflow: ellipsis; + white-space: nowrap; +} +.ol-group-count { + font-size: 10px; + font-weight: 400; + color: var(--text-tertiary); + flex-shrink: 0; +} +.ol-group-pickable { + font-size: 11px; + flex-shrink: 0; + opacity: 0.85; +} + +.ol-group-actions { + display: flex; + gap: 2px; + margin-left: auto; + flex-shrink: 0; + opacity: 0; + transition: opacity 0.1s; +} +.ol-group-header:hover .ol-group-actions { + opacity: 1; +} + +.ol-group-btn { + padding: 1px 6px; + font-size: 10px; + font-weight: 600; + font-family: inherit; + border: 1px solid var(--border-default); + border-radius: var(--radius-sm); + background: var(--surface-2); + color: var(--text-tertiary); + cursor: pointer; + transition: all 0.08s; +} +.ol-group-btn:hover { + background: var(--surface-3); + color: var(--text-primary); + border-color: var(--border-strong); +} + +.ol-group-children { + padding-left: 12px; + border-left: 1px solid var(--border-subtle); + margin-left: 18px; +} +.ol-group-child { + padding-left: 14px !important; + font-size: 11px !important; +} + +/* Multi-select (shift+click) */ +.tag-item.multi-selected { + background: rgba(139, 92, 246, 0.12); + color: var(--text-primary); + box-shadow: inset 3px 0 0 #8B5CF6; +} +.tag-item.multi-selected:hover { + background: rgba(139, 92, 246, 0.18); +} + +/* Group action bar (shown when 2+ shapes are shift-selected) */ +.ol-group-action-bar { + display: flex; + align-items: center; + gap: 6px; + padding: 6px 10px; + background: rgba(139, 92, 246, 0.08); + border: 1px solid rgba(139, 92, 246, 0.25); + border-radius: var(--radius-md); + margin: 4px 6px; +} +.ol-group-action-label { + font-size: 11px; + font-weight: 600; + color: #a78bfa; + flex: 1; + white-space: nowrap; +} +.ol-group-action-btn { + padding: 3px 10px; + font-size: 11px; + font-weight: 600; + font-family: inherit; + border: none; + border-radius: var(--radius-sm); + cursor: pointer; + white-space: nowrap; + transition: all 0.1s; + background: #8B5CF6; + color: #fff; +} +.ol-group-action-btn:hover { + background: #7C3AED; +} +.ol-group-cancel-btn { + background: var(--surface-2); + color: var(--text-secondary); + border: 1px solid var(--border-default); +} +.ol-group-cancel-btn:hover { + background: var(--surface-3); +} + +/* ============================================================================ + Details Panel (Properties of selected object) + ============================================================================ */ + +.details-panel { + border-top: 2px solid rgba(99,102,241,0.3); +} +.details-panel.hidden { display: none; } + +.details-title { + padding: 6px 10px; + font-size: 11px; + font-weight: 700; + text-transform: uppercase; + letter-spacing: 0.04em; + color: var(--accent-primary-hover); + background: rgba(99,102,241,0.06); + border-bottom: 1px solid rgba(255,255,255,0.04); +} + +/* Details collapsible sections */ +.dt-section { + border-bottom: 1px solid rgba(255,255,255,0.04); +} +.dt-section > summary { list-style: none; } +.dt-section > summary::-webkit-details-marker { display: none; } + +.dt-header { + display: flex; + align-items: center; + gap: 6px; + padding: 5px 10px; + font-size: 11px; + font-weight: 600; + color: var(--text-tertiary); + cursor: pointer; + user-select: none; + text-transform: uppercase; + letter-spacing: 0.03em; +} +.dt-header:hover { color: var(--text-secondary); } +.dt-header::before { + content: "▸"; + font-size: 9px; + transition: transform 0.15s; + display: inline-block; + width: 10px; +} +.dt-section[open] > .dt-header::before { transform: rotate(90deg); } + +.dt-body { + padding: 6px 10px 8px; +} + +/* Inputs inside details */ +.dt-input { + width: 100%; + padding: 5px 8px; + background: rgba(0,0,0,0.3); + border: 1px solid var(--border-default); + border-radius: 0; + color: var(--text-primary); + font-family: var(--font-mono); + font-size: 12px; + margin-bottom: 6px; + transition: border-color 0.1s; + resize: vertical; +} +.dt-input:focus { outline: none; border-color: var(--accent-primary); } + +.dt-select { + flex: 1; + padding: 4px 8px; + background: rgba(0,0,0,0.3); + border: 1px solid var(--border-default); + border-radius: 0; + color: var(--text-primary); + font-family: var(--font-mono); + font-size: 12px; +} + +.dt-row { + display: flex; + gap: 6px; + align-items: center; + margin-bottom: 6px; +} + +/* Asset-builder transition rows: keep remove button visible in narrow panels */ +.builder-interaction-row { + flex-wrap: wrap; +} +.builder-interaction-row .builder-transition-label { + flex: 1 1 180px; + min-width: 150px; + margin-bottom: 0; +} +.builder-interaction-row .builder-transition-target { + flex: 0 1 140px; + min-width: 120px; +} +.builder-interaction-row .builder-transition-remove { + flex: 0 0 auto; +} + +.dt-actions { + display: flex; + gap: 4px; +} +.dt-actions .tb-btn { flex: 1; justify-content: center; } + +/* ============================================================================ + Transform XYZ Grid (UE-style) + ============================================================================ */ + +.xform-row { + display: grid; + grid-template-columns: 56px 1fr 1fr 1fr; + gap: 3px; + margin-bottom: 3px; + align-items: center; +} + +.xform-label { + font-size: 10px; + font-weight: 600; + color: var(--text-tertiary); + text-transform: uppercase; + letter-spacing: 0.03em; + padding-left: 2px; +} + +.xform-in { + width: 100%; + padding: 4px 6px; + font-size: 11px; + font-family: var(--font-mono); + font-weight: 500; + background: rgba(0,0,0,0.3); + border: 1px solid var(--border-subtle); + border-radius: 0; + color: var(--text-primary); + text-align: right; + -moz-appearance: textfield; +} +.xform-in::-webkit-outer-spin-button, +.xform-in::-webkit-inner-spin-button { -webkit-appearance: none; margin: 0; } +.xform-in:focus { outline: none; border-color: rgba(255,255,255,0.2); } + +/* Color-coded X/Y/Z borders (UE style) */ +.xform-x { border-left: 2px solid #ef4444; } +.xform-y { border-left: 2px solid #22c55e; } +.xform-z { border-left: 2px solid #3b82f6; } + +/* Legacy compat: hide old elements that are now in toolbar */ +.panel-section { padding: 0; border: none; } +.section-label { display: none; } +.asset-tools { display: none; /* now in toolbar */ } + +/* ============================================================================ + Modal + ============================================================================ */ + +.modal { + pointer-events: auto; + position: fixed; + inset: 0; + background: rgba(0, 0, 0, 0.7); + backdrop-filter: blur(4px); + display: grid; + place-items: center; + z-index: 200; + animation: modalFadeIn 0.2s ease; +} + +@keyframes modalFadeIn { + from { opacity: 0; } + to { opacity: 1; } +} + +.modal-card { + width: min(560px, calc(100vw - 48px)); + border-radius: 0; + border: 1px solid var(--border-default); + background: var(--bg-secondary); + box-shadow: none; + overflow: hidden; + max-height: calc(100vh - 96px); + display: flex; + flex-direction: column; + animation: modalSlideIn 0.3s ease; +} + +@keyframes modalSlideIn { + from { + opacity: 0; + transform: translateY(-20px) scale(0.98); + } + to { + opacity: 1; + transform: translateY(0) scale(1); + } +} + +.modal-title { + padding: 16px 20px; + font-weight: 500; + font-size: 13px; + font-family: var(--font-mono); + letter-spacing: 0.14em; + text-transform: uppercase; + color: var(--accent-primary); + border-bottom: 1px solid var(--border-subtle); + background: var(--surface-1); +} + +.modal-body { + padding: 20px; + overflow-y: auto; +} + +.modal-body input, +.modal-body textarea { + margin-bottom: 12px; +} + +.modal-subtitle { + margin: 16px 0 10px; + font-size: 12px; + color: var(--text-secondary); + font-weight: 700; + text-transform: uppercase; + letter-spacing: 0.05em; +} + +.modal-hint { + margin-top: 12px; + padding: 12px 14px; + font-size: 12px; + color: var(--text-tertiary); + line-height: 1.5; + background: var(--surface-1); + border-radius: var(--radius-md); + border-left: 3px solid var(--accent-info); +} + +.modal-hint b { + color: var(--text-secondary); +} + +/* Asset States */ +.asset-states { + display: flex; + flex-direction: column; + gap: 10px; +} + +.asset-state-row { + border: 1px solid var(--border-default); + border-radius: var(--radius-md); + padding: 14px; + background: var(--surface-1); + display: flex; + flex-direction: column; + gap: 10px; +} + +.asset-state-row-top { + display: flex; + gap: 10px; + align-items: center; + flex-wrap: wrap; +} + +.asset-state-row-top label { + font-size: 12px; + color: var(--text-secondary); + font-weight: 600; + display: flex; + align-items: center; + gap: 6px; +} + +.asset-interactions-title { + font-size: 11px; + color: var(--text-tertiary); + font-weight: 700; + text-transform: uppercase; + letter-spacing: 0.05em; + margin-top: 4px; +} + +.asset-interactions { + display: flex; + flex-direction: column; + gap: 8px; +} + +.asset-interaction-row { + display: flex; + gap: 8px; + align-items: center; + flex-wrap: wrap; +} + +.asset-interaction-row input[type="text"] { + flex: 1; + min-width: 140px; + margin: 0; + padding: 8px 12px; + font-size: 13px; +} + +/* ============================================================================ + Agent Panel Components + ============================================================================ */ + +/* ---------- Floating Command Bar ---------- */ +.agent-cmd-bar { + pointer-events: auto; + position: fixed; + bottom: 24px; + left: 50%; + transform: translateX(-50%); + display: flex; + align-items: center; + gap: 6px; + padding: 6px 10px; + background: var(--bg-elevated); + border: 1px solid var(--border-default); + border-radius: 0; + backdrop-filter: blur(16px); + box-shadow: none; + z-index: 160; + max-width: min(600px, calc(100vw - 32px)); + transition: opacity var(--transition-fast); + opacity: 0.75; +} +.agent-cmd-bar:hover, +.agent-cmd-bar:focus-within, +.agent-cmd-bar.active { + opacity: 1; +} + +.agent-cmd-spawn { + flex-shrink: 0; + padding: 6px 12px; + font-size: 11px; + font-weight: 500; + letter-spacing: 0.06em; + text-transform: uppercase; + background: transparent; + color: var(--text-primary); + border: 1px solid var(--border-default); + border-radius: 0; + cursor: pointer; + white-space: nowrap; + transition: all var(--transition-fast); + font-family: var(--font-mono); +} +.agent-cmd-spawn:hover { + background: var(--accent-primary-subtle); + border-color: var(--accent-primary); + color: var(--accent-primary-hover); +} + +.agent-cmd-status { + flex-shrink: 0; + font-size: 11px; + font-weight: 600; + color: var(--text-secondary); + white-space: nowrap; + max-width: 80px; + min-width: 0; + overflow: hidden; + text-overflow: ellipsis; +} +.agent-cmd-status:empty { + display: none; +} + +.agent-cmd-input { + flex: 1; + min-width: 140px; + padding: 6px 10px; + font-size: 12px; + font-weight: 500; + font-family: var(--font-mono); + background: rgba(0,0,0,0.35); + color: var(--text-primary); + border: 1px solid var(--border-default); + border-radius: 0; + outline: none; + transition: border-color var(--transition-fast); +} +.agent-cmd-input:focus { + border-color: var(--accent-primary); +} +.agent-cmd-input::placeholder { + color: var(--text-tertiary); +} + +.agent-cmd-btn { + flex-shrink: 0; + padding: 6px 14px; + font-size: 11px; + font-weight: 500; + font-family: var(--font-mono); + letter-spacing: 0.06em; + text-transform: uppercase; + background: transparent; + color: var(--accent-primary); + border: 1px solid var(--accent-primary); + border-radius: 0; + cursor: pointer; + white-space: nowrap; + transition: all var(--transition-fast); +} +.agent-cmd-btn:hover { + background: var(--accent-primary-subtle); + color: var(--accent-primary-hover); + border-color: var(--accent-primary-hover); +} +.agent-cmd-btn:disabled { + opacity: 0.35; + cursor: not-allowed; +} +.agent-cmd-stop { + background: transparent; + color: var(--text-secondary); + border: 1px solid var(--border-default); +} +.agent-cmd-stop:hover { + background: rgba(239,68,68,0.08); + border-color: #ef4444; + color: #f87171; +} + +.agent-control-strip { + padding: 8px 10px; + border-bottom: 1px solid rgba(255, 255, 255, 0.08); + background: rgba(255, 255, 255, 0.02); +} +.agent-control-selected { + font-size: 11px; + font-weight: 600; + color: var(--text-tertiary); + margin-bottom: 6px; + overflow: hidden; + text-overflow: ellipsis; + white-space: nowrap; +} +.agent-control-actions { + display: flex; + gap: 6px; +} +.agent-control-actions .tb-btn { + flex: 1; + justify-content: center; + padding: 5px 8px; + font-size: 11px; +} +.agent-control-task-row { + margin-top: 6px; + display: flex; + gap: 6px; +} +.agent-control-task-input { + flex: 1; + min-width: 0; + padding: 6px 8px; + font-size: 11px; + color: var(--text-primary); + background: var(--surface-1); + border: 1px solid var(--border-default); + border-radius: var(--radius-sm); + outline: none; +} +.agent-control-task-input:focus { + border-color: var(--accent-primary); +} + +.agent-badge-layer { + position: fixed; + inset: 0; + pointer-events: none; + z-index: 170; +} +.agent-badge { + position: fixed; + transform: translate(-50%, -50%); + pointer-events: auto; + z-index: 220; + touch-action: none; + padding: 3px 8px; + font-size: 10px; + font-weight: 500; + font-family: var(--font-mono); + letter-spacing: 0.06em; + text-transform: uppercase; + color: var(--text-primary); + background: rgba(16, 22, 32, 0.9); + border: 1px solid var(--border-strong); + border-radius: 0; + cursor: pointer; + white-space: nowrap; + box-shadow: none; +} +.agent-badge.active { + border-color: var(--accent-primary); + box-shadow: 0 0 0 2px var(--accent-primary-subtle), var(--shadow-md); +} + +/* ===== Vibe Creator – Right Panel Layout ===== */ +.vibe-panel-header { + flex-shrink: 0; + display: flex; + align-items: center; + justify-content: space-between; + padding: 6px 10px; + border-bottom: 1px solid rgba(255,255,255,0.06); + background: rgba(255,255,255,0.02); +} + +.vibe-panel-title { + font-weight: 600; + font-size: 11px; + font-family: var(--font-mono); + letter-spacing: 0.16em; + text-transform: uppercase; + color: var(--text-secondary); + display: flex; + align-items: center; + gap: 6px; +} +.vibe-panel-title::before { + content: ">"; + font-family: var(--font-mono); + font-size: 12px; + color: var(--accent-primary); +} + +.vibe-tabs { + display: flex; + gap: 4px; + padding: 6px 10px; + border-bottom: 1px solid var(--border-subtle); + background: rgba(255,255,255,0.01); +} +.vibe-tab-btn { + padding: 5px 10px; + border-radius: 0; + border: 1px solid transparent; + background: transparent; + color: var(--text-tertiary); + font-size: 11px; + font-weight: 500; + font-family: var(--font-mono); + letter-spacing: 0.08em; + text-transform: uppercase; + cursor: pointer; +} +.vibe-tab-btn:hover { + color: var(--text-secondary); + background: rgba(255,255,255,0.04); +} +.vibe-tab-btn.active { + color: var(--text-primary); + border-color: rgba(139, 92, 246, 0.35); + background: rgba(139, 92, 246, 0.15); +} + +.vibe-content { + flex: 1; + min-height: 0; + display: flex; +} +.vibe-tab-pane { + flex: 1; + min-height: 0; + display: flex; + flex-direction: column; +} + +.vibe-assets-help { + font-size: 11px; + color: var(--text-tertiary); + line-height: 1.6; + padding: 10px; + border-bottom: 1px solid var(--border-subtle); +} +.vibe-asset-controls { + display: flex; + gap: 6px; + padding: 10px; + border-bottom: 1px solid var(--border-subtle); +} +.vibe-asset-aux-controls { + display: flex; + gap: 6px; + padding: 8px 10px; + border-bottom: 1px solid var(--border-subtle); +} +.vibe-asset-aux-controls .vibe-btn { + flex: 1; + padding: 6px 8px; + font-size: 11px; + border: 1px solid var(--border-default); + background: var(--surface-2); + color: var(--text-secondary); +} +.vibe-asset-aux-controls .vibe-btn:hover { + background: var(--surface-3); + color: var(--text-primary); +} +.vibe-asset-list { + flex: 1; + min-height: 0; + overflow-y: auto; + padding: 8px; + display: grid; + grid-template-columns: repeat(auto-fill, minmax(132px, 1fr)); + grid-auto-rows: max-content; + align-content: start; + align-items: start; + gap: 10px; +} +.vibe-asset-empty { + font-size: 12px; + color: var(--text-tertiary); + padding: 16px 10px; +} +.vibe-asset-item { + border: 1px solid var(--border-subtle); + border-radius: 0; + background: rgba(255,255,255,0.02); + padding: 6px; + height: auto; + align-self: start; +} +.vibe-asset-thumb { + width: 100%; + aspect-ratio: 1 / 1; + object-fit: cover; + border-radius: 0; + border: 1px solid rgba(255,255,255,0.08); + background: #0b0d11; + display: block; +} +.vibe-asset-item-head { + display: flex; + justify-content: space-between; + align-items: center; + gap: 8px; + margin: 6px 2px 0; +} +.vibe-asset-name { + font-size: 11px; + font-weight: 600; + color: var(--text-primary); + overflow: hidden; + text-overflow: ellipsis; + white-space: nowrap; +} +.vibe-asset-status { + font-size: 9px; + font-family: var(--font-mono); + text-transform: uppercase; + letter-spacing: 0.08em; + padding: 2px 6px; + border-radius: 0; + border: 1px solid var(--border-default); + color: var(--text-tertiary); +} +.vibe-asset-status.approved { + border-color: rgba(74, 222, 128, 0.4); + color: #86efac; + background: rgba(74, 222, 128, 0.12); +} +.vibe-asset-prompt { + font-size: 10px; + color: var(--text-tertiary); + line-height: 1.4; + margin: 4px 2px 0; + overflow: hidden; + text-overflow: ellipsis; + white-space: nowrap; +} +.vibe-asset-actions { + display: flex; + gap: 4px; + margin-top: 6px; +} +.vibe-asset-actions .vibe-btn { + flex: 1; + padding: 5px 6px; + font-size: 10px; +} +.vibe-asset-item[draggable="true"] { + cursor: grab; +} +.vibe-asset-item[draggable="true"]:active { + cursor: grabbing; +} + +/* Staging editor visual mode */ +body.staging-mode { + background: #000; +} +body.staging-mode .watermark-logo { + opacity: 0.08; +} +body.staging-mode #overlay-top { + background: rgba(8, 10, 14, 0.92); + border-bottom-color: rgba(255,255,255,0.08); +} +/* In builder mode, change left panel header to reflect context */ +body.staging-mode .panel-title::after { + content: " · Asset Builder"; + color: var(--accent-primary); + font-weight: 600; +} +/* Hide the shape dropdown in builder mode — inline bar replaces it */ +body.staging-mode .shape-dropdown-wrapper { + display: none; +} + +/* Bottom input bar pinned to panel bottom */ +.vibe-bar { + flex-shrink: 0; + display: flex; + align-items: center; + gap: 6px; + padding: 8px 10px; + background: rgba(255,255,255,0.02); + border-top: 1px solid rgba(255,255,255,0.06); +} +.vibe-bar.active { + background: rgba(139, 92, 246, 0.04); + border-top-color: rgba(139, 92, 246, 0.15); +} + +.vibe-icon { + display: none; +} + +.vibe-input { + flex: 1; + min-width: 0; + padding: 6px 10px; + font-size: 12px; + font-weight: 500; + font-family: var(--font-mono); + background: rgba(0,0,0,0.35); + color: var(--text-primary); + border: 1px solid var(--border-default); + border-radius: 0; + outline: none; + transition: border-color var(--transition-fast); +} +.vibe-input:focus { + border-color: var(--accent-primary); +} +.vibe-input::placeholder { + color: var(--text-tertiary); +} +.vibe-input:disabled { + opacity: 0.5; +} + +.vibe-mode-toggle { + flex-shrink: 0; + display: flex; + align-items: center; + gap: 4px; + font-size: 11px; + font-weight: 600; + color: var(--text-tertiary); + cursor: pointer; + user-select: none; + padding: 4px 6px; + border-radius: var(--radius-sm); + transition: all var(--transition-fast); +} +.vibe-mode-toggle:hover { + color: var(--text-secondary); + background: var(--surface-1); +} +.vibe-mode-toggle input[type="checkbox"] { + width: 14px; + height: 14px; + margin: 0; + cursor: pointer; +} + +.vibe-btn { + flex-shrink: 0; + padding: 6px 12px; + font-size: 11px; + font-weight: 500; + font-family: var(--font-mono); + letter-spacing: 0.06em; + text-transform: uppercase; + border: 1px solid var(--border-default); + border-radius: 0; + cursor: pointer; + white-space: nowrap; + transition: all var(--transition-fast); + background: transparent; + color: var(--text-secondary); +} +.vibe-btn:disabled { + opacity: 0.35; + cursor: not-allowed; +} +.vibe-btn-primary { + background: transparent; + color: var(--accent-primary); + border: 1px solid var(--accent-primary); +} +.vibe-btn-primary:hover { + background: var(--accent-primary-subtle); + color: var(--accent-primary-hover); + border-color: var(--accent-primary-hover); + box-shadow: none; +} +.vibe-btn-stop { + background: transparent; + color: var(--text-secondary); + border: 1px solid var(--border-default); +} +.vibe-btn-stop:hover { + background: rgba(239,68,68,0.08); + border-color: #ef4444; + color: #f87171; +} + +.vibe-status { + flex-shrink: 0; + font-size: 11px; + font-weight: 500; + color: var(--text-tertiary); + white-space: nowrap; + max-width: 180px; + overflow: hidden; + text-overflow: ellipsis; +} +.vibe-status:empty { + display: none; +} + +/* ===== Vibe Creator – Task Tracker (in-panel) ===== */ +.vibe-tracker { + flex: 1; + overflow-y: auto; + padding: 6px 0; + font-size: 12px; + scrollbar-width: thin; +} +.vibe-stream-details { + margin: 8px 10px 2px; + border: 1px solid var(--border-subtle); + border-radius: 0; + background: rgba(255,255,255,0.02); + overflow: hidden; +} +.vibe-stream-summary { + cursor: pointer; + padding: 8px 10px; + font-size: 11px; + color: var(--text-secondary); + border-bottom: 1px solid rgba(255,255,255,0.05); +} +.vibe-stream-body { + margin: 0; + padding: 10px; + max-height: 160px; + overflow: auto; + white-space: pre-wrap; + word-break: break-word; + font-size: 10px; + line-height: 1.45; + color: #cdd6f4; + background: rgba(8, 10, 14, 0.7); +} +.vibe-tracker::-webkit-scrollbar { + width: 4px; +} +.vibe-tracker::-webkit-scrollbar-thumb { + background: var(--border-default); + border-radius: 2px; +} + +/* Tracker header */ +.vt-header { + padding: 6px 14px 8px; + font-size: 11px; + font-weight: 500; + font-family: var(--font-mono); + letter-spacing: 0.12em; + text-transform: uppercase; + color: var(--accent-primary); + border-bottom: 1px solid var(--border-subtle); + display: flex; + align-items: center; + gap: 8px; +} +.vt-count { + font-size: 10px; + font-weight: 500; + font-family: var(--font-mono); + color: var(--text-tertiary); + background: transparent; + border: 1px solid var(--border-default); + padding: 0 6px; + border-radius: 0; +} + +/* Task items */ +.vt-task { + border-top: 1px solid transparent; +} +.vt-task + .vt-task { + border-top-color: var(--border-subtle); +} + +.vt-task-row { + display: flex; + align-items: center; + gap: 8px; + padding: 5px 14px; + min-height: 28px; +} + +.vt-icon { + flex-shrink: 0; + width: 16px; + text-align: center; + font-size: 11px; + line-height: 1; +} + +/* Status-specific icon colors */ +.vt-pending .vt-icon { + color: var(--text-tertiary); +} +.vt-active .vt-icon { + color: #8B5CF6; + animation: vt-pulse 1.2s ease-in-out infinite; +} +.vt-done .vt-icon { + color: #4ade80; +} +.vt-failed .vt-icon { + color: #ef4444; +} + +@keyframes vt-pulse { + 0%, 100% { opacity: 1; } + 50% { opacity: 0.4; } +} + +.vt-title { + flex: 1; + font-weight: 500; + color: var(--text-secondary); + overflow: hidden; + text-overflow: ellipsis; + white-space: nowrap; +} +.vt-active .vt-title { + color: var(--text-primary); + font-weight: 600; +} +.vt-done .vt-title { + color: var(--text-secondary); +} +.vt-pending .vt-title { + color: var(--text-tertiary); +} + +.vt-meta { + flex-shrink: 0; + font-size: 10px; + font-weight: 500; + color: var(--text-tertiary); + white-space: nowrap; +} +.vt-active .vt-meta { + color: #a78bfa; +} + +/* Task detail sub-entries */ +.vt-details { + padding: 0 14px 4px 38px; +} +.vt-detail { + font-size: 11px; + color: var(--text-tertiary); + line-height: 1.6; + overflow: hidden; + text-overflow: ellipsis; + white-space: nowrap; +} +.vt-detail::before { + content: "› "; + color: var(--border-strong); +} + +/* Final polish note */ +.vt-final { + padding: 6px 14px; + font-size: 11px; + color: var(--text-secondary); + border-top: 1px solid var(--border-subtle); + display: flex; + align-items: baseline; + gap: 6px; +} +.vt-final-icon { + color: #fbbf24; + font-size: 12px; +} + +/* Vibe Creator – Empty state (shown when no generation is active) */ +.vibe-empty-state { + display: flex; + flex-direction: column; + align-items: center; + justify-content: center; + padding: 40px 20px; + gap: 12px; + text-align: center; + height: 100%; + min-height: 200px; +} +.vibe-empty-icon { + font-size: 32px; + opacity: 0.25; + user-select: none; +} +.vibe-empty-text { + font-size: 12px; + color: var(--text-tertiary); + max-width: 240px; + line-height: 1.6; +} + +/* Vibe Creator – Activity bar (what the agent is doing right now) */ +.vt-activity { + padding: 8px 14px; + font-size: 11px; + font-weight: 500; + color: #a78bfa; + background: rgba(139, 92, 246, 0.06); + border-top: 1px solid rgba(139, 92, 246, 0.15); + line-height: 1.5; + word-wrap: break-word; + white-space: normal; + animation: vt-pulse 1.2s ease-in-out infinite; +} +.vt-activity.hidden { + display: none; +} + +/* Agent Vision */ +.agent-vision { + border-bottom: 1px solid var(--border-subtle); +} + +.agent-shot-img { + width: 100%; + height: auto; + display: block; + background: var(--bg-primary); + aspect-ratio: 2.2 / 1; + object-fit: cover; +} + +.agent-decision-content { + margin: 0; + padding: 10px 12px; + font-size: 11px; + line-height: 1.5; + color: var(--text-primary); + white-space: pre-wrap; + word-break: break-word; + font-family: var(--font-mono); + background: var(--surface-1); + border-radius: 0; + border: 1px solid var(--border-subtle); + max-height: 160px; + overflow-y: auto; +} + +/* Collapsible Sections */ +.agent-collapse { + border-bottom: 1px solid var(--border-subtle); +} + +.agent-collapse:last-child { + border-bottom: none; +} + +.agent-collapse > summary { + cursor: pointer; + padding: 9px 12px; + font-size: 11px; + color: var(--text-secondary); + font-weight: 500; + font-family: var(--font-mono); + letter-spacing: 0.1em; + text-transform: uppercase; + user-select: none; + transition: all var(--transition-fast); + display: flex; + align-items: center; + gap: 8px; + list-style: none; +} + +.agent-collapse > summary::-webkit-details-marker { + display: none; +} + +.agent-collapse > summary::before { + content: "▸"; + font-size: 10px; + transition: transform var(--transition-fast); +} + +.agent-collapse[open] > summary::before { + transform: rotate(90deg); +} + +.agent-collapse > summary:hover { + background: var(--surface-1); + color: var(--text-primary); +} + +.agent-collapse-content { + padding: 0 12px 12px; +} + +.agent-observation-panel { + margin: 16px 12px 16px; + padding: 10px; + border: 1px solid var(--border-subtle); + border-radius: var(--radius-md); + background: var(--surface-1); +} + +.agent-observation-panel .section-label { + margin-bottom: 8px; +} + +.agent-meta { + font-size: 11px; + color: var(--text-tertiary); + margin-bottom: 8px; + line-height: 1.5; +} + +/* Sub-collapse (nested details) */ +.agent-sub-collapse { + border: 1px solid var(--border-subtle); + border-radius: 0; + margin-bottom: 6px; + background: var(--surface-1); +} + +.agent-sub-collapse:last-child { + margin-bottom: 0; +} + +.agent-sub-collapse > summary { + cursor: pointer; + padding: 7px 10px; + font-size: 10px; + color: var(--text-tertiary); + font-weight: 500; + font-family: var(--font-mono); + letter-spacing: 0.08em; + text-transform: uppercase; + user-select: none; + transition: all var(--transition-fast); + display: flex; + align-items: center; + gap: 6px; + list-style: none; +} + +.agent-sub-collapse > summary::-webkit-details-marker { + display: none; +} + +.agent-sub-collapse > summary::before { + content: "▸"; + font-size: 9px; + transition: transform var(--transition-fast); +} + +.agent-sub-collapse[open] > summary::before { + transform: rotate(90deg); +} + +.agent-sub-collapse > summary:hover { + color: var(--text-secondary); +} + +.agent-pre { + margin: 0; + padding: 10px; + font-size: 10px; + line-height: 1.5; + color: var(--text-secondary); + white-space: pre-wrap; + word-break: break-word; + font-family: var(--font-mono); + background: var(--bg-primary); + max-height: 300px; + overflow-y: auto; + border-top: 1px solid var(--border-subtle); +} + +/* Activity Log */ +.agent-log { + padding: 8px 12px 12px; + display: flex; + flex-direction: column; + gap: 4px; + max-height: 200px; + overflow-y: auto; +} + +.agent-log-item { + padding: 8px 10px; + border-radius: 0; + background: var(--surface-1); + border-left: 2px solid var(--border-default); + font-size: 10px; + font-family: var(--font-mono); + color: var(--text-secondary); + white-space: pre-wrap; + line-height: 1.4; +} + +/* ============================================================================ + Crosshair + ============================================================================ */ + +#crosshair { + position: fixed; + left: 50%; + top: 50%; + width: 20px; + height: 20px; + transform: translate(-50%, -50%); + pointer-events: none; + opacity: 0.9; +} + +#crosshair::before, +#crosshair::after { + content: ""; + position: absolute; + left: 50%; + top: 50%; + background: rgba(255, 255, 255, 0.9); + transform: translate(-50%, -50%); + border-radius: 1px; + transition: all var(--transition-fast); +} + +#crosshair::before { + width: 12px; + height: 2px; +} + +#crosshair::after { + width: 2px; + height: 12px; +} + +#crosshair.interactable::before, +#crosshair.interactable::after { + background: var(--accent-primary); + box-shadow: 0 0 10px var(--accent-primary-glow); +} + +#crosshair.interactable { + opacity: 1; +} + +#crosshair.holding::before, +#crosshair.holding::after { + background: var(--accent-warning); + box-shadow: 0 0 10px rgba(245, 158, 11, 0.5); +} + +#crosshair.holding { + opacity: 1; +} + +/* ============================================================================ + Interaction Hint + ============================================================================ */ + +#interaction-hint { + position: fixed; + left: 50%; + top: 50%; + transform: translate(-50%, -50%) translateY(40px); + pointer-events: none; + opacity: 0; + transition: all var(--transition-normal); + z-index: 101; + background: var(--bg-elevated); + border: 1px solid var(--accent-primary); + border-radius: 0; + padding: 6px 12px; + font-size: 11px; + font-weight: 500; + font-family: var(--font-mono); + letter-spacing: 0.06em; + text-transform: uppercase; + color: var(--text-primary); + white-space: nowrap; + backdrop-filter: blur(12px); + box-shadow: none; +} + +#interaction-hint.visible { + opacity: 1; + transform: translate(-50%, -50%) translateY(35px); +} + +#interaction-hint .hint-key { + display: inline-flex; + align-items: center; + justify-content: center; + min-width: 20px; + height: 20px; + background: transparent; + border: 1px solid var(--accent-primary); + border-radius: 0; + padding: 0 6px; + margin-left: 8px; + font-size: 10px; + font-weight: 500; + font-family: var(--font-mono); + color: var(--accent-primary); + box-shadow: none; +} + +/* ============================================================================ + Interaction Popup + ============================================================================ */ + +#interaction-popup { + position: fixed; + left: 50%; + top: 50%; + transform: translate(-50%, -50%) translateY(70px); + background: var(--bg-elevated); + border: 1px solid var(--border-default); + border-radius: 0; + padding: 6px; + z-index: 150; + min-width: 220px; + backdrop-filter: blur(20px); + box-shadow: none; + animation: popupSlideIn 0.2s ease; + flex-direction: column; + gap: 4px; + pointer-events: auto; +} + +@keyframes popupSlideIn { + from { + opacity: 0; + transform: translate(-50%, -50%) translateY(60px) scale(0.95); + } + to { + opacity: 1; + transform: translate(-50%, -50%) translateY(70px) scale(1); + } +} + +.interact-action-btn { + width: 100%; + padding: 10px 14px !important; + text-align: left !important; + justify-content: flex-start !important; + margin-bottom: 4px; + background: var(--surface-1) !important; + border: 1px solid var(--border-subtle) !important; +} + +.interact-action-btn:last-child { + margin-bottom: 0; +} + +.interact-action-btn:hover { + background: var(--accent-primary-subtle) !important; + border-color: rgba(99, 102, 241, 0.3) !important; +} + +/* ============================================================================ + Visibility Utilities + ============================================================================ */ + +.hidden { + display: none !important; +} + +.edit-only, +.sim-only { + /* default shown */ +} + +html[data-mode="sim"] .edit-only { + display: none !important; +} + +html[data-mode="edit"] .sim-only { + display: none !important; +} + +/* Keep the agent command bar available in edit mode for iterative scene edits. */ +html[data-mode="edit"] #agent-command-bar.sim-only { + display: flex !important; +} + +/* In edit mode, keep Agent Vision/Response visible as a floating inspector. */ +html[data-mode="edit"] #agent-panel.sim-only { + display: flex !important; + position: fixed; + right: 16px; + bottom: 72px; + width: 360px; + max-height: 56vh; + z-index: 145; + border: 1px solid var(--border-default); + border-radius: var(--radius-lg); + backdrop-filter: blur(20px); + background: var(--bg-elevated); +} + +/* ============================================================================ + Responsive Design + ============================================================================ */ + +@media (max-width: 1100px) { + #overlay { + grid-template-columns: 280px 1fr 320px; + } + .tb-btn span { display: none; } /* hide text labels, keep icons */ + .tb-btn svg + span { display: none; } +} + +@media (max-width: 900px) { + #overlay { + grid-template-columns: 0 1fr 320px; + } + .side-panel-left { display: none; } + .left-panel-open { display: none !important; } +} + +@media (max-width: 640px) { + #overlay { + grid-template-columns: 1fr; + grid-template-rows: auto 1fr; + grid-template-areas: "top" "."; + } + .side-panel { + height: auto; + max-height: 50vh; + } + .side-panel-left, .side-panel-right { display: none; } +} + +/* ============================================================================ + Scrollbar Styling + ============================================================================ */ + +::-webkit-scrollbar { + width: 8px; + height: 8px; +} + +::-webkit-scrollbar-track { + background: transparent; +} + +::-webkit-scrollbar-thumb { + background: var(--surface-3); + border-radius: 0; +} + +::-webkit-scrollbar-thumb:hover { + background: rgba(255, 255, 255, 0.15); +} + +/* ============================================================================ + Selection + ============================================================================ */ + +::selection { + background: var(--accent-primary-subtle); + color: var(--text-primary); +} + +/* ============================================================================ + Level Editor – Shape Dropdown, Primitives, Lights + ============================================================================ */ + +/* Shape Dropdown */ +.shape-dropdown-wrapper { + position: relative; + display: inline-block; +} + +.shape-dropdown-menu { + position: absolute; + top: calc(100% + 4px); + left: 0; + z-index: 200; + background: var(--bg-secondary); + border: 1px solid var(--border-default); + border-radius: 0; + box-shadow: none; + padding: 4px; + min-width: 140px; + display: flex; + flex-direction: column; + gap: 2px; +} + +.shape-dropdown-menu.hidden { + display: none; +} + +.shape-dropdown-menu button { + display: flex; + align-items: center; + gap: 8px; + width: 100%; + padding: 8px 12px; + background: transparent; + border: none; + color: var(--text-primary); + font-size: 13px; + font-family: inherit; + font-weight: 500; + border-radius: var(--radius-sm); + cursor: pointer; + transition: background var(--transition-fast); + text-align: left; +} + +.shape-dropdown-menu button:hover { + background: var(--surface-2); +} + +.shape-icon { + display: inline-flex; + width: 18px; + justify-content: center; + font-size: 14px; + opacity: 0.7; +} + +/* Primitive & Light Properties Panel */ +.prim-props { + padding: 0; +} + +.prim-props.hidden { + display: none; +} + +.prop-group { + margin-bottom: 6px; +} + +.prop-group-title { + font-size: 10px; + font-weight: 600; + text-transform: uppercase; + letter-spacing: 0.04em; + color: var(--text-tertiary); + margin-bottom: 4px; +} + +.prop-row, .dt-row { + display: flex; + align-items: center; + gap: 6px; + margin-bottom: 6px; +} + +.prop-label { + font-size: 11px; + font-weight: 600; + color: var(--text-tertiary); + min-width: 48px; + flex-shrink: 0; +} + +input[type="color"] { + -webkit-appearance: none; + appearance: none; + width: 32px; + height: 24px; + border: 1px solid var(--border-default); + border-radius: 0; + background: transparent; + cursor: pointer; + padding: 2px; +} + +input[type="color"]::-webkit-color-swatch-wrapper { padding: 0; } +input[type="color"]::-webkit-color-swatch { border: none; border-radius: 0; } + +.prop-check { + display: flex; + align-items: center; + gap: 6px; + font-size: 11px; + color: var(--text-secondary); + cursor: pointer; + padding: 4px 0; +} + +.prop-check input[type="checkbox"] { + accent-color: var(--accent-primary); + width: 13px; + height: 13px; +} + +/* Blob shadow sub-controls */ +.blob-shadow-controls { + padding: 4px 0 4px 19px; /* indent under the checkbox */ + display: flex; + flex-direction: column; + gap: 3px; +} +.blob-shadow-controls.hidden { display: none; } +.blob-shadow-controls .prop-row { + display: flex; + align-items: center; + gap: 6px; + font-size: 11px; + color: var(--text-secondary); +} +.blob-shadow-controls .prop-row label { + min-width: 52px; + flex-shrink: 0; +} +.blob-shadow-controls .prop-row input[type="range"] { + flex: 1; + height: 3px; + accent-color: var(--accent-primary); +} +.blob-shadow-controls .prop-row span { + min-width: 28px; + text-align: right; + font-variant-numeric: tabular-nums; +} +.blob-shadow-controls .prop-row input[type="number"] { + width: 60px; +} + +.prop-row-3 { + display: grid; + grid-template-columns: 1fr 1fr 1fr; + gap: 6px; + margin-bottom: 8px; +} + +.prop-input-group { + display: flex; + flex-direction: column; + gap: 2px; +} + +.prop-input-group label { + font-size: 10px; + font-weight: 700; + text-transform: uppercase; + color: var(--text-tertiary); +} + +.prop-input-group input[type="number"] { + width: 100%; + padding: 6px 8px; + background: var(--surface-1); + border: 1px solid var(--border-subtle); + border-radius: var(--radius-sm); + color: var(--text-primary); + font-family: inherit; + font-size: 12px; + -moz-appearance: textfield; +} + +.prop-input-group input[type="number"]::-webkit-outer-spin-button, +.prop-input-group input[type="number"]::-webkit-inner-spin-button { + -webkit-appearance: none; + margin: 0; +} + +.prop-input-group input[type="number"]:focus { + outline: none; + border-color: var(--accent-primary); +} + +.file-sm { + font-size: 12px !important; + padding: 4px 10px !important; +} + +.btn-sm { + font-size: 12px; + padding: 4px 10px; + background: var(--surface-2); + border: 1px solid var(--border-subtle); + border-radius: var(--radius-sm); + color: var(--text-secondary); + cursor: pointer; + font-family: inherit; + transition: all var(--transition-fast); +} + +.btn-sm:hover { + background: var(--surface-3); + color: var(--text-primary); +} + +.btn-sm.danger { + color: #ef4444; +} + +.btn-sm.danger:hover { + background: rgba(239, 68, 68, 0.15); + color: #f87171; +} + +/* Primitive textarea */ +.prim-props textarea { + width: 100%; + padding: 8px 10px; + background: var(--surface-1); + border: 1px solid var(--border-subtle); + border-radius: var(--radius-sm); + color: var(--text-primary); + font-family: inherit; + font-size: 13px; + margin-bottom: 8px; + resize: vertical; + min-height: 40px; + transition: border-color var(--transition-fast); +} + +.prim-props textarea:focus { + outline: none; + border-color: var(--accent-primary); +} + +/* Metadata Key-Value Editor */ +.meta-kv-list { + display: flex; + flex-direction: column; + gap: 4px; +} + +.meta-kv-empty { + font-size: 11px; + color: var(--text-tertiary); + font-style: italic; + padding: 4px 0; +} + +.meta-kv-row { + display: flex; + gap: 4px; + align-items: center; +} + +.meta-kv-key, +.meta-kv-val { + flex: 1; + min-width: 0; + padding: 5px 8px; + background: var(--surface-1); + border: 1px solid var(--border-subtle); + border-radius: var(--radius-sm); + color: var(--text-primary); + font-family: inherit; + font-size: 12px; + transition: border-color var(--transition-fast); +} + +.meta-kv-key { + flex: 0.45; + font-weight: 600; + color: var(--accent-info); +} + +.meta-kv-val { + flex: 0.55; +} + +.meta-kv-key:focus, +.meta-kv-val:focus { + outline: none; + border-color: var(--accent-primary); +} + +/* ============================================================================ + Agent Sensor Panels (sidebar) + ============================================================================ */ +.agent-sensor-label { + font-size: 10px; + font-weight: 600; + color: var(--text-tertiary); + text-transform: uppercase; + letter-spacing: 0.5px; + padding: 4px 8px 2px; +} + +.agent-sensor-canvas { + width: 100%; + height: auto; + display: block; + background: #000; + aspect-ratio: 2.2 / 1; +} diff --git a/misc/DimSim/vite.config.js b/misc/DimSim/vite.config.js new file mode 100644 index 0000000000..61760f311f --- /dev/null +++ b/misc/DimSim/vite.config.js @@ -0,0 +1,35 @@ +import { defineConfig } from "vite"; + +export default defineConfig({ + optimizeDeps: { + exclude: ["@sparkjsdev/spark", "@dimforge/rapier3d-compat"], + }, + assetsInclude: ["**/*.wasm"], + build: { + assetsInlineLimit: 0, + rollupOptions: { + external: [/^https:\/\/esm\.sh\//], + output: { + // Eval workflow files under scenes/*/evals/*.js import runEval from + // '@dimsim/eval' via the importmap in index.html. That map needs to + // point at a *stable* URL, so pin the harness chunk's filename here + // (it's the public ESM surface for evals). Everything else keeps + // its content-hashed name. + chunkFileNames(chunk) { + if (chunk.facadeModuleId?.endsWith("/evals/harness.ts")) { + return "assets/dimsim-eval.js"; + } + return "assets/[name]-[hash].js"; + }, + }, + }, + }, + server: { + proxy: { + "/vlm": { + target: "http://127.0.0.1:8000", + changeOrigin: true, + }, + }, + }, +}); diff --git a/pyproject.toml b/pyproject.toml index 93c3d32d34..99ca5c3c8a 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -606,4 +606,7 @@ ignore = [ "dimos/manipulation/manipulation_module.py", "dimos/navigation/nav_stack/modules/*/main.cpp", "dimos/navigation/nav_stack/common/*.hpp", + "misc/DimSim/src/AiAvatar.js", + "misc/DimSim/src/style.css", + "misc/DimSim/src/engine.js", ]