diff --git a/.gitignore b/.gitignore index 4045db012e..d4c7adc989 100644 --- a/.gitignore +++ b/.gitignore @@ -27,6 +27,7 @@ __pycache__ /assets/saved_maps/ /assets/model-cache/ /assets/agent/memory.txt +/assets/temporal_memory/ .bash_history diff --git a/dimos/e2e_tests/dimos_cli_call.py b/dimos/e2e_tests/dimos_cli_call.py index 569dcfa386..620008e28c 100644 --- a/dimos/e2e_tests/dimos_cli_call.py +++ b/dimos/e2e_tests/dimos_cli_call.py @@ -38,6 +38,18 @@ def start(self) -> None: start_new_session=True, ) + def _kill_group(self, sig: int) -> None: + """Send *sig* to the process group, falling back to the process itself. + + On macOS with ``start_new_session=True`` the child runs in its own + session and ``os.killpg`` can raise ``PermissionError``. In that case + we fall back to signalling just the lead process. + """ + try: + os.killpg(self.process.pid, sig) + except PermissionError: + os.kill(self.process.pid, sig) + def stop(self) -> None: if self.process is None: return @@ -45,7 +57,7 @@ def stop(self) -> None: try: # Send SIGTERM to the entire process group so child processes # (e.g. the mujoco viewer subprocess) are also terminated. - os.killpg(self.process.pid, signal.SIGTERM) + self._kill_group(signal.SIGTERM) # Record the time when we sent the kill signal shutdown_start = time.time() @@ -62,7 +74,7 @@ def stop(self) -> None: ) except subprocess.TimeoutExpired: # If we reach here, the process didn't terminate in 30 seconds - os.killpg(self.process.pid, signal.SIGKILL) + self._kill_group(signal.SIGKILL) self.process.wait() # Clean up raise AssertionError( "Process did not shut down within 30 seconds after receiving SIGTERM" @@ -72,7 +84,7 @@ def stop(self) -> None: # Clean up if something goes wrong if self.process.poll() is None: # Process still running try: - os.killpg(self.process.pid, signal.SIGKILL) + self._kill_group(signal.SIGKILL) except ProcessLookupError: pass self.process.wait() diff --git a/dimos/e2e_tests/test_dimsim_eval.py b/dimos/e2e_tests/test_dimsim_eval.py new file mode 100644 index 0000000000..dd07a983c2 --- /dev/null +++ b/dimos/e2e_tests/test_dimsim_eval.py @@ -0,0 +1,219 @@ +# Copyright 2025-2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Sequential eval tests — 1 dimos instance, run workflows one at a time. + +Uses sim-eval blueprint (includes rerun/browser for manual observation). +Run individual evals or all of them: + + pytest dimos/e2e_tests/test_dimsim_eval.py -v -s -m slow + pytest dimos/e2e_tests/test_dimsim_eval.py::TestSimEvalSequential::test_go_to_tv -v -s -m slow +""" + +import json +import os +from pathlib import Path +import signal +import socket +import subprocess +import sys +import time + +import pytest +import websocket + +from dimos.e2e_tests.dimos_cli_call import DimosCliCall +from dimos.e2e_tests.lcm_spy import LcmSpy + +PORT = 8090 +EVALS_DIR = Path.home() / ".dimsim" / "evals" + + +def _force_kill_port(port: int) -> None: + """Kill any process listening on the given port.""" + try: + result = subprocess.run( + ["lsof", "-ti", f":{port}"], + capture_output=True, + text=True, + timeout=5, + ) + pids = result.stdout.strip().split() + for pid in pids: + if pid: + try: + os.kill(int(pid), signal.SIGKILL) + except (ProcessLookupError, ValueError): + pass + except Exception: + pass + + +def _wait_for_port(port: int, timeout: float = 120) -> bool: + deadline = time.time() + timeout + while time.time() < deadline: + try: + with socket.create_connection(("localhost", port), timeout=2): + return True + except OSError: + time.sleep(1) + return False + + +def _wait_for_port_free(port: int, timeout: float = 30) -> bool: + """Wait until nothing is listening on *port*.""" + deadline = time.time() + timeout + while time.time() < deadline: + try: + with socket.create_connection(("localhost", port), timeout=1): + time.sleep(1) + except OSError: + return True + return False + + +class EvalClient: + """Talks to the browser eval harness via the bridge WebSocket.""" + + def __init__(self, port: int = PORT): + self.ws = websocket.WebSocket() + self.ws.connect(f"ws://localhost:{port}") + + def _send(self, msg: dict) -> None: + self.ws.send(json.dumps(msg)) + + def _wait_for(self, msg_type: str, timeout: float = 120) -> dict: + self.ws.settimeout(timeout) + while True: + raw = self.ws.recv() + if isinstance(raw, bytes): + continue + msg = json.loads(raw) + if msg.get("type") == msg_type: + return msg + + def wait_for_harness(self, timeout: float = 60) -> bool: + deadline = time.time() + timeout + while time.time() < deadline: + try: + self._send({"type": "ping"}) + self.ws.settimeout(3) + raw = self.ws.recv() + if isinstance(raw, str): + msg = json.loads(raw) + if msg.get("type") == "pong": + return True + except (websocket.WebSocketTimeoutException, Exception): + time.sleep(1) + return False + + def run_workflow(self, workflow: dict) -> dict: + """Send loadEnv + startWorkflow, wait for workflowComplete.""" + timeout = workflow.get("timeoutSec", 120) + 30 + self._send({"type": "loadEnv", "scene": workflow.get("environment", "apt")}) + self._wait_for("envReady", timeout=30) + self._send({"type": "startWorkflow", "workflow": workflow}) + return self._wait_for("workflowComplete", timeout=timeout) + + def close(self): + self.ws.close() + + +def _load_workflow(env: str, name: str) -> dict: + path = EVALS_DIR / env / f"{name}.json" + return json.loads(path.read_text()) + + +@pytest.fixture(scope="class") +def sim_eval(): + """Start dimos sim-eval headless, tear down after.""" + _force_kill_port(PORT) + assert _wait_for_port_free(PORT, timeout=10), f"Port {PORT} still in use after force-kill" + log_dir = os.environ.get("DIMSIM_EVAL_LOG_DIR", "") + if log_dir: + log_path = Path(log_dir) + log_path.mkdir(parents=True, exist_ok=True) + log_file = open(log_path / "dimos-sequential.log", "w") + print(f"\n dimos logs → {log_path}/dimos-sequential.log") + else: + log_file = None + + spy = LcmSpy() + spy.save_topic("/color_image#sensor_msgs.Image") + spy.save_topic("/odom#geometry_msgs.PoseStamped") + spy.start() + + venv_bin = str(Path(sys.prefix) / "bin") + env = { + **os.environ, + "DIMSIM_HEADLESS": "1", + "DIMSIM_RENDER": "gpu", + "PATH": venv_bin + os.pathsep + os.environ.get("PATH", ""), + } + call = DimosCliCall() + call.demo_args = ["sim-eval"] + call.process = subprocess.Popen( + ["dimos", "--simulation", "run", "sim-eval"], + env=env, + stdout=log_file or subprocess.DEVNULL, + stderr=log_file or subprocess.DEVNULL, + start_new_session=True, + ) + + try: + assert _wait_for_port(PORT, timeout=120), f"Bridge not ready on port {PORT}" + spy.wait_for_saved_topic("/color_image#sensor_msgs.Image", timeout=60.0) + spy.wait_for_saved_topic("/odom#geometry_msgs.PoseStamped", timeout=60.0) + + yield call + finally: + call.stop() + spy.stop() + if log_file: + log_file.close() + _force_kill_port(PORT) + + +@pytest.fixture(scope="class") +def eval_client(sim_eval): + """Connect to bridge WS and wait for eval harness.""" + client = EvalClient(PORT) + assert client.wait_for_harness(timeout=60), "Eval harness not responding" + yield client + client.close() + + +@pytest.mark.skipif_in_ci +@pytest.mark.slow +class TestSimEvalSequential: + """Run DimSim evals sequentially against a live dimos sim-eval instance.""" + + def _run_and_assert(self, eval_client: EvalClient, env: str, workflow_name: str) -> None: + workflow = _load_workflow(env, workflow_name) + result = eval_client.run_workflow(workflow) + scores = result.get("rubricScores", {}) + od = scores.get("objectDistance", {}) + passed = od.get("pass", False) + details = od.get("details", result.get("reason", "unknown")) + print(f" {workflow_name}: {'PASS' if passed else 'FAIL'} — {details}") + assert passed, f"Eval '{workflow_name}' failed: {details}" + + def test_go_to_tv(self, eval_client) -> None: + self._run_and_assert(eval_client, "apt", "television") + + def test_go_to_couch(self, eval_client) -> None: + self._run_and_assert(eval_client, "apt", "go-to-couch") + + def test_go_to_kitchen(self, eval_client) -> None: + self._run_and_assert(eval_client, "apt", "go-to-kitchen") diff --git a/dimos/e2e_tests/test_dimsim_eval_parallel.py b/dimos/e2e_tests/test_dimsim_eval_parallel.py new file mode 100644 index 0000000000..57d73ff1c2 --- /dev/null +++ b/dimos/e2e_tests/test_dimsim_eval_parallel.py @@ -0,0 +1,388 @@ +# Copyright 2025-2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Parallel eval tests for DimSim simulation. + +3 dimos instances + 3 headless browser pages, 1 eval workflow each. +Runs all workflows concurrently, cutting wall-clock time to ~1 min. + + pytest dimos/e2e_tests/test_dimsim_eval_parallel.py -v -s -m slow +""" + +from concurrent.futures import ThreadPoolExecutor, as_completed +import json +import os +from pathlib import Path +import signal +import socket +import subprocess +import sys +import time + +import pytest +import websocket + +from dimos.e2e_tests.dimos_cli_call import DimosCliCall + +PORT = 8090 +EVALS_DIR = Path.home() / ".dimsim" / "evals" +NUM_CHANNELS = 3 +LCM_BASE_PORT = 7667 + + +def _force_kill_port(port: int) -> None: + """Kill any process listening on the given port.""" + try: + result = subprocess.run( + ["lsof", "-ti", f":{port}"], + capture_output=True, + text=True, + timeout=5, + ) + pids = result.stdout.strip().split() + for pid in pids: + if pid: + try: + os.kill(int(pid), signal.SIGKILL) + except (ProcessLookupError, ValueError): + pass + except Exception: + pass + + +def _wait_for_port(port: int, timeout: float = 120) -> bool: + deadline = time.time() + timeout + while time.time() < deadline: + try: + with socket.create_connection(("localhost", port), timeout=2): + return True + except OSError: + time.sleep(1) + return False + + +def _wait_for_all_pages(log_path: Path, num_pages: int, timeout: float = 90) -> None: + """Wait until dimsim's log shows all headless pages are sending sensor data. + + Checks for sensor messages from the last channel (page-N-1) which proves + all pages have loaded their Three.js scenes and are rendering. + """ + last_channel = f"page-{num_pages - 1}" + marker = f"bridge:{last_channel}] sensor" + deadline = time.time() + timeout + while time.time() < deadline: + try: + text = log_path.read_text() + if marker in text: + print(f" All {num_pages} headless pages confirmed ready (sensor data flowing)") + return + except FileNotFoundError: + pass + time.sleep(2) + print( + f" WARNING: page-{num_pages - 1} sensor data not seen after {timeout}s, proceeding anyway" + ) + + +def _wait_for_port_free(port: int, timeout: float = 30) -> bool: + """Wait until nothing is listening on *port*.""" + deadline = time.time() + timeout + while time.time() < deadline: + try: + with socket.create_connection(("localhost", port), timeout=1): + time.sleep(1) # still occupied + except OSError: + return True # connection refused → port is free + return False + + +def _load_workflow(env: str, name: str) -> dict: + path = EVALS_DIR / env / f"{name}.json" + return json.loads(path.read_text()) + + +# ── Eval clients ───────────────────────────────────────────────────────────── + + +class EvalClient: + """Talks to the browser eval harness via the bridge WebSocket.""" + + def __init__(self, port: int = PORT): + self.ws = websocket.WebSocket() + self.ws.connect(f"ws://localhost:{port}") + + def _send(self, msg: dict) -> None: + self.ws.send(json.dumps(msg)) + + def _wait_for(self, msg_type: str, timeout: float = 120) -> dict: + self.ws.settimeout(timeout) + while True: + raw = self.ws.recv() + if isinstance(raw, bytes): + continue + msg = json.loads(raw) + if msg.get("type") == msg_type: + return msg + + def wait_for_harness(self, timeout: float = 60) -> bool: + deadline = time.time() + timeout + while time.time() < deadline: + try: + self._send({"type": "ping"}) + self.ws.settimeout(3) + raw = self.ws.recv() + if isinstance(raw, str): + msg = json.loads(raw) + if msg.get("type") == "pong": + return True + except (websocket.WebSocketTimeoutException, Exception): + time.sleep(1) + return False + + def run_workflow(self, workflow: dict) -> dict: + """Send loadEnv + startWorkflow, wait for workflowComplete.""" + timeout = workflow.get("timeoutSec", 120) + 30 + self._send({"type": "loadEnv", "scene": workflow.get("environment", "apt")}) + self._wait_for("envReady", timeout=30) + self._send({"type": "startWorkflow", "workflow": workflow}) + return self._wait_for("workflowComplete", timeout=timeout) + + def close(self): + self.ws.close() + + +class ChannelEvalClient(EvalClient): + """EvalClient that connects to a specific channel's control WS. + + Inherits run_workflow (loadEnv + startWorkflow) from EvalClient. + Only overrides _send/_wait_for for channel routing. + """ + + def __init__(self, port: int, channel: str): + self._port = port + self.channel = channel + self.ws = websocket.WebSocket() + self.ws.connect(f"ws://localhost:{port}?channel={channel}") + + def wait_for_harness(self, timeout: float = 60) -> bool: + """Override: drain pose/sensor messages to find the pong. + + The bridge sends pose updates at 50Hz to all control clients. + The base class reads only one message per loop and misses the pong. + """ + deadline = time.time() + timeout + while time.time() < deadline: + try: + self._send({"type": "ping"}) + self._wait_for("pong", timeout=5) + return True + except Exception: + time.sleep(1) + return False + + def _send(self, msg: dict) -> None: + msg["channel"] = self.channel + self.ws.send(json.dumps(msg)) + + def _wait_for(self, msg_type: str, timeout: float = 120) -> dict: + self.ws.settimeout(timeout) + while True: + raw = self.ws.recv() + if isinstance(raw, bytes): + continue + if not raw: + continue + try: + msg = json.loads(raw) + except json.JSONDecodeError: + continue + msg_ch = msg.get("channel", "") + if msg.get("type") == msg_type and (not msg_ch or msg_ch == self.channel): + return msg + + +# ── Fixtures ───────────────────────────────────────────────────────────────── + + +@pytest.fixture(scope="class") +def parallel_env(): + """Start dimos-0 (launches dimsim with 3 channels), then dimos-1/2 (connect-only).""" + _force_kill_port(PORT) + assert _wait_for_port_free(PORT, timeout=10), f"Port {PORT} still in use after force-kill" + + calls: list[DimosCliCall] = [] + log_files: list = [] + venv_bin = str(Path(sys.prefix) / "bin") + base_env = { + **os.environ, + "DIMSIM_HEADLESS": "1", + "DIMSIM_RENDER": "gpu", + "PATH": venv_bin + os.pathsep + os.environ.get("PATH", ""), + } + log_dir_env = os.environ.get("DIMSIM_EVAL_LOG_DIR", "") + log_dir = Path(log_dir_env) if log_dir_env else None + if log_dir: + log_dir.mkdir(parents=True, exist_ok=True) + + # dimos-0: launches dimsim normally with --channels 3 + env0 = { + **base_env, + "LCM_DEFAULT_URL": f"udpm://239.255.76.67:{LCM_BASE_PORT}?ttl=0", + "DIMSIM_CHANNELS": str(NUM_CHANNELS), + "EVAL_INSTANCE_ID": "0", + } + log0 = open(log_dir / "dimos-0.log", "w") if log_dir else None + log_files.append(log0) + call0 = DimosCliCall() + call0.demo_args = ["sim-parallel-eval"] + call0.process = subprocess.Popen( + ["dimos", "--simulation", "run", "sim-parallel-eval"], + env=env0, + stdout=log0 or subprocess.DEVNULL, + stderr=log0 or subprocess.DEVNULL, + start_new_session=True, + ) + calls.append(call0) + + try: + # Wait for dimsim bridge + all headless pages before starting dimos-1/2 + assert _wait_for_port(PORT, timeout=120), f"Bridge not ready on port {PORT}" + if log_dir: + _wait_for_all_pages(log_dir / "dimos-0.log", NUM_CHANNELS, timeout=90) + else: + time.sleep(30) # No log file to check — wait a fixed period for pages to load + + # dimos-1 and dimos-2: connect-only (skip dimsim launch) + for i in range(1, NUM_CHANNELS): + env_i = { + **base_env, + "DIMSIM_CONNECT_ONLY": "1", + "LCM_DEFAULT_URL": f"udpm://239.255.76.67:{LCM_BASE_PORT + i}?ttl=0", + "EVAL_INSTANCE_ID": str(i), + } + log_i = open(log_dir / f"dimos-{i}.log", "w") if log_dir else None + log_files.append(log_i) + call_i = DimosCliCall() + call_i.demo_args = ["sim-parallel-eval"] + call_i.process = subprocess.Popen( + ["dimos", "--simulation", "run", "sim-parallel-eval"], + env=env_i, + stdout=log_i or subprocess.DEVNULL, + stderr=log_i or subprocess.DEVNULL, + start_new_session=True, + ) + calls.append(call_i) + + # Give connect-only instances time to start and establish LCM connections + time.sleep(10) + + if log_dir: + print(f"\n dimos logs → {log_dir}/dimos-{{0,1,2}}.log") + yield calls + finally: + # Teardown: stop in reverse (connect-only first, then the one that owns dimsim) + for call in reversed(calls): + call.stop() + for f in log_files: + if f: + f.close() + _force_kill_port(PORT) + + +def _connect_channel(port: int, channel: str, timeout: float = 120) -> ChannelEvalClient: + """Connect to a channel with retries (bridge may be under load).""" + deadline = time.time() + timeout + last_err = None + while time.time() < deadline: + try: + client = ChannelEvalClient(port, channel) + if client.wait_for_harness(timeout=min(30, deadline - time.time())): + return client + client.close() + except Exception as e: + last_err = e + time.sleep(2) + raise ConnectionError(f"Could not connect to {channel} after {timeout}s: {last_err}") + + +@pytest.fixture(scope="class") +def parallel_eval_clients(parallel_env): + """Create one ChannelEvalClient per channel, wait for each harness.""" + clients: list[ChannelEvalClient] = [] + for i in range(NUM_CHANNELS): + channel = f"page-{i}" + client = _connect_channel(PORT, channel, timeout=120) + print(f" {channel}: harness ready") + clients.append(client) + yield clients + for client in clients: + client.close() + + +# ── Test ───────────────────────────────────────────────────────────────────── + + +@pytest.mark.skipif_in_ci +@pytest.mark.slow +class TestSimEvalParallel: + """Run DimSim evals in parallel — 3 dimos instances, 3 browser pages.""" + + WORKFLOWS = [ + ("apt", "television"), + ("apt", "go-to-couch"), + ("apt", "go-to-kitchen"), + ] + + def test_parallel_evals(self, parallel_eval_clients: list[ChannelEvalClient]) -> None: + """Run all 3 eval workflows concurrently, one per channel.""" + results: dict[str, dict] = {} + errors: dict[str, str] = {} + + def run_one(idx: int) -> tuple[str, dict]: + # Stagger starts so loadEnv doesn't hammer the bridge simultaneously + time.sleep(idx * 3) + env, name = self.WORKFLOWS[idx] + workflow = _load_workflow(env, name) + result = parallel_eval_clients[idx].run_workflow(workflow) + return name, result + + with ThreadPoolExecutor(max_workers=NUM_CHANNELS) as pool: + futures = {pool.submit(run_one, i): i for i in range(NUM_CHANNELS)} + for future in as_completed(futures): + try: + name, result = future.result() + results[name] = result + except Exception as exc: + idx = futures[future] + errors[self.WORKFLOWS[idx][1]] = str(exc) + + # Report and assert all results + failures: list[str] = [] + + for name, result in results.items(): + scores = result.get("rubricScores", {}) + od = scores.get("objectDistance", {}) + passed = od.get("pass", False) + details = od.get("details", result.get("reason", "unknown")) + print(f" {name}: {'PASS' if passed else 'FAIL'} — {details}") + if not passed: + failures.append(f"{name}: {details}") + + for name, err in errors.items(): + print(f" {name}: ERROR — {err}") + failures.append(f"{name}: ERROR — {err}") + + assert not failures, f"{len(failures)}/{NUM_CHANNELS} evals failed:\n" + "\n".join( + f" - {f}" for f in failures + ) diff --git a/dimos/e2e_tests/test_dimsim_nav.py b/dimos/e2e_tests/test_dimsim_nav.py new file mode 100644 index 0000000000..2ba727f91b --- /dev/null +++ b/dimos/e2e_tests/test_dimsim_nav.py @@ -0,0 +1,265 @@ +# Copyright 2025-2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""E2E smoke tests for sim-nav — verifies the full sensor + control pipeline. + +Starts dimos sim-nav headless (GPU rendering), then checks that all LCM +topics are publishing and that cmd_vel actually moves the robot. + + pytest dimos/e2e_tests/test_dimsim_nav.py -v -s +""" + +import math +import os +from pathlib import Path +import signal +import socket +import subprocess +import sys +import time + +import pytest + +from dimos.e2e_tests.dimos_cli_call import DimosCliCall +from dimos.e2e_tests.lcm_spy import LcmSpy +from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped +from dimos.msgs.geometry_msgs.Twist import Twist +from dimos.msgs.geometry_msgs.Vector3 import Vector3 +from dimos.msgs.sensor_msgs.Image import Image +from dimos.msgs.sensor_msgs.PointCloud2 import PointCloud2 + +BRIDGE_PORT = 8090 + + +def _force_kill_port(port: int) -> None: + """Kill any process listening on the given port.""" + try: + result = subprocess.run( + ["lsof", "-ti", f":{port}"], + capture_output=True, + text=True, + timeout=5, + ) + pids = result.stdout.strip().split() + for pid in pids: + if pid: + try: + os.kill(int(pid), signal.SIGKILL) + except (ProcessLookupError, ValueError): + pass + except Exception: + pass + + +def _wait_for_port(port: int, timeout: float = 120) -> bool: + deadline = time.time() + timeout + while time.time() < deadline: + try: + with socket.create_connection(("localhost", port), timeout=2): + return True + except OSError: + time.sleep(1) + return False + + +def _wait_for_port_free(port: int, timeout: float = 30) -> bool: + deadline = time.time() + timeout + while time.time() < deadline: + try: + with socket.create_connection(("localhost", port), timeout=1): + time.sleep(1) + except OSError: + return True + return False + + +@pytest.fixture(scope="class") +def sim_nav(): + """Start dimos sim-nav headless with GPU rendering, tear down after.""" + # Kill any leftover processes from a previous crashed run + _force_kill_port(BRIDGE_PORT) + assert _wait_for_port_free(BRIDGE_PORT, timeout=10), ( + f"Port {BRIDGE_PORT} still in use after force-kill" + ) + + log_dir = os.environ.get("DIMSIM_EVAL_LOG_DIR", "") + if log_dir: + log_path = Path(log_dir) + log_path.mkdir(parents=True, exist_ok=True) + log_file = open(log_path / "dimos-sim-nav.log", "w") + print(f"\n dimos logs → {log_path}/dimos-sim-nav.log") + else: + log_file = None + + render = os.environ.get("DIMSIM_RENDER", "cpu") + venv_bin = str(Path(sys.prefix) / "bin") + env = { + **os.environ, + "DIMSIM_HEADLESS": "1", + "DIMSIM_RENDER": render, + "PATH": venv_bin + os.pathsep + os.environ.get("PATH", ""), + } + call = DimosCliCall() + call.demo_args = ["sim-nav"] + call.process = subprocess.Popen( + ["dimos", "--simulation", "run", "sim-nav"], + env=env, + stdout=log_file or subprocess.DEVNULL, + stderr=log_file or subprocess.DEVNULL, + start_new_session=True, + ) + + try: + assert _wait_for_port(BRIDGE_PORT, timeout=120), f"Bridge not ready on port {BRIDGE_PORT}" + yield call + finally: + call.stop() + if log_file: + log_file.close() + # Ensure port is freed even if stop() doesn't fully clean up + _force_kill_port(BRIDGE_PORT) + + +@pytest.fixture(scope="class") +def spy(sim_nav): + """LCM spy that subscribes to all topics and waits for initial sensor data.""" + s = LcmSpy() + s.save_topic("/color_image#sensor_msgs.Image") + s.save_topic("/depth_image#sensor_msgs.Image") + s.save_topic("/odom#geometry_msgs.PoseStamped") + s.save_topic("/lidar#sensor_msgs.PointCloud2") + s.start() + + # Wait for at least one message on color_image before tests start + s.wait_for_saved_topic("/color_image#sensor_msgs.Image", timeout=60.0) + + yield s + + s.stop() + + +@pytest.mark.slow +class TestSimNav: + """Smoke tests for the sim-nav pipeline — sensors, control, and data integrity.""" + + def test_color_image_publishing(self, spy: LcmSpy) -> None: + """Verify /color_image is publishing and decodable.""" + spy.wait_for_saved_topic("/color_image#sensor_msgs.Image", timeout=30) + msgs = spy.messages.get("/color_image#sensor_msgs.Image", []) + assert len(msgs) > 0, "No color_image messages received" + + # Decode the latest image — DimSim sends JPEG encoding + img = Image.lcm_jpeg_decode(msgs[-1]) + assert img.width > 0, f"Image width is {img.width}" + assert img.height > 0, f"Image height is {img.height}" + print(f" color_image: {img.width}x{img.height}, {len(msgs)} messages") + + def test_depth_image_publishing(self, spy: LcmSpy) -> None: + """Verify /depth_image is publishing and decodable.""" + spy.wait_for_saved_topic("/depth_image#sensor_msgs.Image", timeout=30) + msgs = spy.messages.get("/depth_image#sensor_msgs.Image", []) + assert len(msgs) > 0, "No depth_image messages received" + + # Depth images use raw encoding (16UC1), not JPEG + img = Image.lcm_decode(msgs[-1]) + assert img.width > 0, f"Depth image width is {img.width}" + assert img.height > 0, f"Depth image height is {img.height}" + print(f" depth_image: {img.width}x{img.height}, {len(msgs)} messages") + + def test_odom_publishing(self, spy: LcmSpy) -> None: + """Verify /odom is publishing with sane values.""" + spy.wait_for_saved_topic("/odom#geometry_msgs.PoseStamped", timeout=30) + msgs = spy.messages.get("/odom#geometry_msgs.PoseStamped", []) + assert len(msgs) > 0, "No odom messages received" + + pose = PoseStamped.lcm_decode(msgs[-1]) + pos = pose.position + # Position should be finite (not NaN or inf) + assert math.isfinite(pos.x), f"odom x is {pos.x}" + assert math.isfinite(pos.y), f"odom y is {pos.y}" + assert math.isfinite(pos.z), f"odom z is {pos.z}" + # Position should be within reasonable bounds (scene is ~50m) + assert abs(pos.x) < 100, f"odom x out of bounds: {pos.x}" + assert abs(pos.y) < 100, f"odom y out of bounds: {pos.y}" + assert abs(pos.z) < 100, f"odom z out of bounds: {pos.z}" + print(f" odom: ({pos.x:.2f}, {pos.y:.2f}, {pos.z:.2f}), {len(msgs)} messages") + + def test_lidar_publishing(self, spy: LcmSpy) -> None: + """Verify /lidar is publishing with non-empty point cloud.""" + spy.wait_for_saved_topic("/lidar#sensor_msgs.PointCloud2", timeout=30) + msgs = spy.messages.get("/lidar#sensor_msgs.PointCloud2", []) + assert len(msgs) > 0, "No lidar messages received" + + cloud = PointCloud2.lcm_decode(msgs[-1]) + num_points = len(cloud) + assert num_points > 0, "Lidar point cloud is empty" + print(f" lidar: {num_points} points, {len(msgs)} messages") + + def test_cmd_vel_moves_robot(self, spy: LcmSpy) -> None: + """Publish cmd_vel and verify odom position changes.""" + # Record initial position + spy.wait_for_saved_topic("/odom#geometry_msgs.PoseStamped", timeout=30) + initial_msgs = spy.messages.get("/odom#geometry_msgs.PoseStamped", []) + assert len(initial_msgs) > 0, "No initial odom" + initial_pose = PoseStamped.lcm_decode(initial_msgs[-1]) + initial_pos = initial_pose.position + print( + f" initial position: ({initial_pos.x:.2f}, {initial_pos.y:.2f}, {initial_pos.z:.2f})" + ) + + # Send forward velocity for 3 seconds + twist = Twist( + linear=Vector3(0.5, 0.0, 0.0), + angular=Vector3(0.0, 0.0, 0.0), + ) + deadline = time.time() + 3.0 + while time.time() < deadline: + spy.publish("/cmd_vel#geometry_msgs.Twist", twist) + time.sleep(0.05) # 20 Hz + + # Wait a bit for physics to settle and odom to update + time.sleep(1.0) + + # Check position changed + final_msgs = spy.messages.get("/odom#geometry_msgs.PoseStamped", []) + final_pose = PoseStamped.lcm_decode(final_msgs[-1]) + final_pos = final_pose.position + + dx = final_pos.x - initial_pos.x + dy = final_pos.y - initial_pos.y + distance = math.sqrt(dx * dx + dy * dy) + print(f" final position: ({final_pos.x:.2f}, {final_pos.y:.2f}, {final_pos.z:.2f})") + print(f" distance moved: {distance:.2f}m") + + assert distance > 0.1, ( + f"Robot didn't move after cmd_vel: distance={distance:.3f}m " + f"(initial=({initial_pos.x:.2f},{initial_pos.y:.2f}), " + f"final=({final_pos.x:.2f},{final_pos.y:.2f}))" + ) + + def test_odom_rate(self, spy: LcmSpy) -> None: + """Verify odom publishes at a reasonable rate (>5 Hz).""" + # Clear existing messages and collect fresh ones + topic = "/odom#geometry_msgs.PoseStamped" + with spy._messages_lock: + spy.messages[topic] = [] + + time.sleep(2.0) + + with spy._messages_lock: + count = len(spy.messages.get(topic, [])) + + rate = count / 2.0 + print(f" odom rate: {rate:.1f} Hz ({count} messages in 2s)") + assert rate > 5, f"Odom rate too low: {rate:.1f} Hz (expected >5 Hz)" diff --git a/dimos/robot/all_blueprints.py b/dimos/robot/all_blueprints.py index 5910093d61..c6ad00ef66 100644 --- a/dimos/robot/all_blueprints.py +++ b/dimos/robot/all_blueprints.py @@ -56,6 +56,13 @@ "mid360-fastlio": "dimos.hardware.sensors.lidar.fastlio2.fastlio_blueprints:mid360_fastlio", "mid360-fastlio-voxels": "dimos.hardware.sensors.lidar.fastlio2.fastlio_blueprints:mid360_fastlio_voxels", "mid360-fastlio-voxels-native": "dimos.hardware.sensors.lidar.fastlio2.fastlio_blueprints:mid360_fastlio_voxels_native", + "sim-agentic": "dimos.robot.sim.blueprints.agentic.sim_agentic:sim_agentic", + "sim-basic": "dimos.robot.sim.blueprints.basic.sim_basic:sim_basic", + "sim-eval": "dimos.robot.sim.blueprints.agentic.sim_eval:sim_eval", + "sim-nav": "dimos.robot.sim.blueprints.nav.sim_nav:sim_nav", + "sim-parallel-eval": "dimos.robot.sim.blueprints.agentic.sim_parallel_eval:sim_parallel_eval", + "sim-spatial": "dimos.robot.sim.blueprints.nav.sim_spatial:sim_spatial", + "sim-temporal-memory": "dimos.robot.sim.blueprints.agentic.sim_temporal_memory:sim_temporal_memory", "teleop-phone": "dimos.teleop.phone.blueprints:teleop_phone", "teleop-phone-go2": "dimos.teleop.phone.blueprints:teleop_phone_go2", "teleop-phone-go2-fleet": "dimos.teleop.phone.blueprints:teleop_phone_go2_fleet", @@ -109,6 +116,8 @@ "demo-robot": "dimos.agents.skills.demo_robot", "detection2-d-module": "dimos.perception.detection.module2D", "detection3-d-module": "dimos.perception.detection.module3D", + "dim-sim-bridge": "dimos.robot.sim.bridge", + "dim-sim-tf": "dimos.robot.sim.tf_module", "drone-camera-module": "dimos.robot.drone.camera_module", "drone-connection-module": "dimos.robot.drone.connection_module", "drone-tracking-module": "dimos.robot.drone.drone_tracking_module", diff --git a/dimos/robot/sim/blueprints/agentic/sim_agentic.py b/dimos/robot/sim/blueprints/agentic/sim_agentic.py new file mode 100644 index 0000000000..915b9f5f61 --- /dev/null +++ b/dimos/robot/sim/blueprints/agentic/sim_agentic.py @@ -0,0 +1,39 @@ +# Copyright 2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""DimSim agentic blueprint — spatial + MCP agent + skills + human input.""" + +from dimos.agents.mcp.mcp_client import McpClient +from dimos.agents.mcp.mcp_server import McpServer +from dimos.agents.skills.navigation import NavigationSkillContainer +from dimos.agents.skills.person_follow import PersonFollowSkillContainer +from dimos.agents.skills.speak_skill import SpeakSkill +from dimos.agents.web_human_input import WebInput +from dimos.core.blueprints import autoconnect +from dimos.navigation.patrolling.module import PatrollingModule +from dimos.robot.sim.blueprints.nav.sim_spatial import sim_spatial +from dimos.robot.sim.tf_module import _camera_info_static + +sim_agentic = autoconnect( + sim_spatial, + McpServer.blueprint(), + McpClient.blueprint(), + NavigationSkillContainer.blueprint(), + PersonFollowSkillContainer.blueprint(camera_info=_camera_info_static()), + PatrollingModule.blueprint(), + WebInput.blueprint(), + SpeakSkill.blueprint(), +) + +__all__ = ["sim_agentic"] diff --git a/dimos/robot/sim/blueprints/agentic/sim_eval.py b/dimos/robot/sim/blueprints/agentic/sim_eval.py new file mode 100644 index 0000000000..226529cd93 --- /dev/null +++ b/dimos/robot/sim/blueprints/agentic/sim_eval.py @@ -0,0 +1,31 @@ +# Copyright 2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""DimSim sequential eval blueprint — full stack with visualization. + +Same as sim_temporal_memory. Use this for single-instance eval runs where +you want rerun + browser open to watch the agent. + +For parallel (headless, multi-instance) evals, use sim-parallel-eval instead. + +Usage: + dimos --simulation run sim-eval +""" + +from dimos.core.blueprints import autoconnect +from dimos.robot.sim.blueprints.agentic.sim_temporal_memory import sim_temporal_memory + +sim_eval = autoconnect(sim_temporal_memory) + +__all__ = ["sim_eval"] diff --git a/dimos/robot/sim/blueprints/agentic/sim_parallel_eval.py b/dimos/robot/sim/blueprints/agentic/sim_parallel_eval.py new file mode 100644 index 0000000000..c509458fe4 --- /dev/null +++ b/dimos/robot/sim/blueprints/agentic/sim_parallel_eval.py @@ -0,0 +1,77 @@ +# Copyright 2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""DimSim parallel eval blueprint — full temporal memory stack without visualization. + +Same as sim_temporal_memory but replaces sim_basic with a headless variant +that skips rerun and websocket_vis. This avoids port conflicts when running +multiple dimos instances in parallel for eval. + +Each instance gets isolated ChromaDB/visual-memory paths derived from +EVAL_INSTANCE_ID (defaults to "0"). + +Usage: + EVAL_INSTANCE_ID=0 dimos --simulation run sim-parallel-eval + EVAL_INSTANCE_ID=1 dimos --simulation run sim-parallel-eval +""" + +import os + +from dimos.core.blueprints import autoconnect +from dimos.core.transport import JpegLcmTransport +from dimos.mapping.costmapper import CostMapper +from dimos.mapping.voxels import VoxelGridMapper +from dimos.msgs.sensor_msgs import Image +from dimos.navigation.frontier_exploration.wavefront_frontier_goal_selector import ( + WavefrontFrontierExplorer, +) +from dimos.navigation.replanning_a_star.module import ReplanningAStarPlanner +from dimos.perception.experimental.temporal_memory.temporal_memory import TemporalMemory +from dimos.perception.spatial_perception import SpatialMemory +from dimos.robot.sim.bridge import sim_bridge +from dimos.robot.sim.tf_module import sim_tf +from dimos.utils.data import DIMOS_PROJECT_ROOT + +# Per-instance isolation: separate ChromaDB + visual memory paths +_instance_id = os.environ.get("EVAL_INSTANCE_ID", "0") +_instance_dir = DIMOS_PROJECT_ROOT / "assets" / "output" / "memory" / f"eval_{_instance_id}" +_db_path = str(_instance_dir / "chromadb_data") +_visual_memory_path = str(_instance_dir / "visual_memory.pkl") + +# Headless sim_basic: LCM transports + bridge + TF +# No rerun, websocket_vis, web_input, speak_skill, or agent +# (these bind fixed ports that conflict when running multiple instances) +_transports = autoconnect().transports( + {("color_image", Image): JpegLcmTransport("/color_image", Image)} +) + +sim_parallel_eval = autoconnect( + # sim_basic (headless — no visualization) + _transports, + sim_bridge(), + sim_tf(), + # sim_nav + VoxelGridMapper.blueprint(voxel_size=0.1), + CostMapper.blueprint(), + ReplanningAStarPlanner.blueprint(), + WavefrontFrontierExplorer.blueprint(), + # sim_spatial (isolated DB per instance) + SpatialMemory.blueprint( + db_path=_db_path, visual_memory_path=_visual_memory_path, new_memory=True + ), + # temporal_memory + TemporalMemory.blueprint(), +).global_config(n_workers=8, robot_model="dimsim") + +__all__ = ["sim_parallel_eval"] diff --git a/dimos/robot/sim/blueprints/agentic/sim_temporal_memory.py b/dimos/robot/sim/blueprints/agentic/sim_temporal_memory.py new file mode 100644 index 0000000000..c4e7388cc9 --- /dev/null +++ b/dimos/robot/sim/blueprints/agentic/sim_temporal_memory.py @@ -0,0 +1,26 @@ +# Copyright 2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""DimSim temporal memory blueprint — agentic + temporal memory.""" + +from dimos.core.blueprints import autoconnect +from dimos.perception.experimental.temporal_memory.temporal_memory import TemporalMemory +from dimos.robot.sim.blueprints.agentic.sim_agentic import sim_agentic + +sim_temporal_memory = autoconnect( + sim_agentic, + TemporalMemory.blueprint(), +) + +__all__ = ["sim_temporal_memory"] diff --git a/dimos/robot/sim/blueprints/basic/sim_basic.py b/dimos/robot/sim/blueprints/basic/sim_basic.py new file mode 100644 index 0000000000..9a61da3161 --- /dev/null +++ b/dimos/robot/sim/blueprints/basic/sim_basic.py @@ -0,0 +1,147 @@ +# Copyright 2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Basic DimSim blueprint — connection + visualization.""" + +from typing import Any + +from dimos.core.blueprints import autoconnect +from dimos.core.global_config import global_config +from dimos.core.transport import JpegLcmTransport +from dimos.msgs.sensor_msgs.Image import Image +from dimos.protocol.pubsub.impl.lcmpubsub import LCM +from dimos.robot.sim.bridge import sim_bridge +from dimos.robot.sim.tf_module import sim_tf +from dimos.web.websocket_vis.websocket_vis_module import WebsocketVisModule + + +class _SimLCM(LCM): # type: ignore[misc] + """LCM that JPEG-decodes image topics and standard-decodes everything else.""" + + _JPEG_TOPICS = frozenset({"/color_image"}) + + def decode(self, msg: bytes, topic: Any) -> Any: # type: ignore[override] + if getattr(topic, "topic", None) in self._JPEG_TOPICS: + return Image.lcm_jpeg_decode(msg) + return super().decode(msg, topic) + + +# DimSim sends JPEG-compressed images over LCM — use JpegLcmTransport to decode. +_transports_base = autoconnect().transports( + {("color_image", Image): JpegLcmTransport("/color_image", Image)} +) + + +def _convert_camera_info(camera_info: Any) -> Any: + # Log pinhole under TF tree (3D frustum) — NOT at the image entity. + # Pinhole at the image entity blocks rerun's 2D viewer. + import rerun as rr + + fx, fy = camera_info.K[0], camera_info.K[4] + cx, cy = camera_info.K[2], camera_info.K[5] + return [ + ( + "world/tf/camera_optical", + rr.Pinhole( + focal_length=[fx, fy], + principal_point=[cx, cy], + width=camera_info.width, + height=camera_info.height, + image_plane_distance=1.0, + ), + ), + ( + "world/tf/camera_optical", + rr.Transform3D(parent_frame="tf#/camera_optical"), + ), + ] + + +def _convert_color_image(image: Any) -> Any: + # Log image at both: + # world/color_image — 2D view (no pinhole ancestor) + # world/tf/camera_optical/image — 3D view (child of pinhole) + rerun_data = image.to_rerun() + return [ + ("world/color_image", rerun_data), + ("world/tf/camera_optical/image", rerun_data), + ] + + +def _convert_global_map(grid: Any) -> Any: + return grid.to_rerun(voxel_size=0.1, mode="boxes") + + +def _convert_navigation_costmap(grid: Any) -> Any: + return grid.to_rerun( + colormap="Accent", + z_offset=0.015, + opacity=0.2, + background="#484981", + ) + + +def _suppress(_msg: Any) -> None: + return None + + +def _static_base_link(rr: Any) -> list[Any]: + return [ + rr.Boxes3D( + half_sizes=[0.3, 0.15, 0.12], + colors=[(0, 180, 255)], + ), + rr.Transform3D(parent_frame="tf#/base_link"), + ] + + +rerun_config = { + "pubsubs": [_SimLCM()], + "visual_override": { + "world/camera_info": _convert_camera_info, + "world/color_image": _convert_color_image, + "world/global_map": _convert_global_map, + "world/navigation_costmap": _convert_navigation_costmap, + "world/pointcloud": _suppress, + }, + "static": { + "world/tf/base_link": _static_base_link, + }, +} + +if global_config.viewer == "foxglove": + from dimos.robot.foxglove_bridge import FoxgloveBridge + + with_vis = autoconnect( + _transports_base, + FoxgloveBridge.blueprint(shm_channels=["/color_image#sensor_msgs.Image"]), + ) +elif global_config.viewer.startswith("rerun"): + from dimos.visualization.rerun.bridge import RerunBridgeModule, _resolve_viewer_mode + + with_vis = autoconnect( + _transports_base, + RerunBridgeModule.blueprint(viewer_mode=_resolve_viewer_mode(), **rerun_config), + ) +else: + with_vis = _transports_base + +sim_basic = autoconnect( + with_vis, + sim_bridge(), + sim_tf(), + WebsocketVisModule.blueprint(), +).global_config(n_workers=4, robot_model="dimsim") + +__all__ = ["sim_basic"] diff --git a/dimos/robot/sim/blueprints/nav/sim_nav.py b/dimos/robot/sim/blueprints/nav/sim_nav.py new file mode 100644 index 0000000000..6554fd9534 --- /dev/null +++ b/dimos/robot/sim/blueprints/nav/sim_nav.py @@ -0,0 +1,39 @@ +# Copyright 2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""DimSim navigation blueprint — basic + mapping + planning + exploration.""" + +from dimos.core.blueprints import autoconnect +from dimos.mapping.costmapper import CostMapper +from dimos.mapping.pointclouds.occupancy import ( + HeightCostConfig, +) +from dimos.mapping.voxels import VoxelGridMapper +from dimos.navigation.frontier_exploration.wavefront_frontier_goal_selector import ( + WavefrontFrontierExplorer, +) +from dimos.navigation.replanning_a_star.module import ReplanningAStarPlanner +from dimos.robot.sim.blueprints.basic.sim_basic import sim_basic + +sim_nav = autoconnect( + sim_basic, + VoxelGridMapper.blueprint(voxel_size=0.1, publish_interval=0.5), + CostMapper.blueprint( + algo="height_cost", config=HeightCostConfig(can_pass_under=1.5, smoothing=2.0) + ), + ReplanningAStarPlanner.blueprint(), + WavefrontFrontierExplorer.blueprint(), +).global_config(n_workers=6, robot_model="dimsim") + +__all__ = ["sim_nav"] diff --git a/dimos/robot/sim/blueprints/nav/sim_spatial.py b/dimos/robot/sim/blueprints/nav/sim_spatial.py new file mode 100644 index 0000000000..f2610dbc8d --- /dev/null +++ b/dimos/robot/sim/blueprints/nav/sim_spatial.py @@ -0,0 +1,26 @@ +# Copyright 2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""DimSim spatial blueprint — nav + spatial memory.""" + +from dimos.core.blueprints import autoconnect +from dimos.perception.spatial_perception import SpatialMemory +from dimos.robot.sim.blueprints.nav.sim_nav import sim_nav + +sim_spatial = autoconnect( + sim_nav, + SpatialMemory.blueprint(), +).global_config(n_workers=8) + +__all__ = ["sim_spatial"] diff --git a/dimos/robot/sim/bridge.py b/dimos/robot/sim/bridge.py new file mode 100644 index 0000000000..ea594eac2f --- /dev/null +++ b/dimos/robot/sim/bridge.py @@ -0,0 +1,316 @@ +# Copyright 2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""NativeModule wrapper for the DimSim bridge subprocess. + +Launches the DimSim bridge as a managed subprocess. On first run, downloads +a compiled binary from GitHub Releases — no Deno runtime required. The bridge +publishes sensor data (odom, lidar, images) directly to LCM — no Python +decode/re-encode hop. Python only handles lifecycle and TF (via DimSimTF). + +Usage:: + + from dimos.robot.sim.bridge import sim_bridge + from dimos.robot.sim.tf_module import sim_tf + from dimos.core.blueprints import autoconnect + + autoconnect(sim_bridge(), sim_tf(), some_consumer()).build().loop() +""" + +import os +from pathlib import Path +import shutil + +from pydantic import Field + +from dimos.core.core import rpc +from dimos.core.native_module import NativeModule, NativeModuleConfig +from dimos.core.stream import In, Out +from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped +from dimos.msgs.geometry_msgs.Twist import Twist +from dimos.msgs.sensor_msgs.CameraInfo import CameraInfo +from dimos.msgs.sensor_msgs.Image import Image +from dimos.msgs.sensor_msgs.PointCloud2 import PointCloud2 +from dimos.spec.perception import Camera, Pointcloud +from dimos.utils.logging_config import setup_logger + +logger = setup_logger() + +_GITHUB_REPO = "Antim-Labs/DimSim" +_RELEASES_API = f"https://api.github.com/repos/{_GITHUB_REPO}/releases/latest" + + +def _dimsim_bin() -> Path: + """Path to the dimsim compiled binary.""" + return Path.home() / ".dimsim" / "bin" / "dimsim" + + +def _find_deno() -> str: + """Find the deno binary (only needed for local dev mode).""" + return shutil.which("deno") or str(Path.home() / ".deno" / "bin" / "deno") + + +def _find_local_cli() -> Path | None: + """Find local DimSim/dimos-cli/cli.ts for development.""" + repo_root = Path(__file__).resolve().parents[4] + candidate = repo_root / "DimSim" / "dimos-cli" / "cli.ts" + return candidate if candidate.exists() else None + + +class DimSimBridgeConfig(NativeModuleConfig): + """Configuration for the DimSim bridge subprocess.""" + + # Resolved in _resolve_paths() — compiled binary or deno (local dev). + executable: str = "dimsim" + build_command: str | None = None + cwd: str | None = None + + scene: str = "apt" + port: int = 8090 + local: bool = False # Use local DimSim repo instead of installed CLI + + # These fields are handled via extra_args, not to_cli_args(). + cli_exclude: frozenset[str] = frozenset({"scene", "port", "local"}) + + # Populated by _resolve_paths() — deno run args + dev subcommand + scene/port. + extra_args: list[str] = Field(default_factory=list) + + +class DimSimBridge(NativeModule, Camera, Pointcloud): + """NativeModule that manages the DimSim bridge subprocess. + + The bridge (Deno process) handles Browser-LCM translation and publishes + sensor data directly to LCM. Ports declared here exist for blueprint + wiring / autoconnect but data flows through LCM, not Python. + """ + + config: DimSimBridgeConfig + default_config = DimSimBridgeConfig + + # Sensor outputs (bridge publishes these directly to LCM) + odom: Out[PoseStamped] + color_image: Out[Image] + depth_image: Out[Image] + lidar: Out[PointCloud2] + pointcloud: Out[PointCloud2] + camera_info: Out[CameraInfo] + + # Control input (consumers publish cmd_vel to LCM, bridge reads it) + cmd_vel: In[Twist] + + @rpc + def start(self) -> None: + """Start the DimSim bridge subprocess. + + Set DIMSIM_CONNECT_ONLY=1 to skip subprocess launch — used when + connecting to a shared dimsim server already started by another instance. + """ + if os.environ.get("DIMSIM_CONNECT_ONLY", "").strip() in ("1", "true"): + logger.info("DIMSIM_CONNECT_ONLY: skipping subprocess, connecting to existing server") + return + super().start() + + def _resolve_paths(self) -> None: + """Resolve executable and build extra_args. + + Set DIMSIM_LOCAL=1 to use local DimSim repo instead of installed CLI. + """ + dev_args = ["dev", "--scene", self.config.scene, "--port", str(self.config.port)] + + # DIMSIM_HEADLESS=1 → launch headless Chrome (no browser tab needed) + # Uses CPU rendering (SwiftShader) by default — no GPU required for CI. + # Set DIMSIM_RENDER=gpu for Metal/ANGLE on macOS. + if os.environ.get("DIMSIM_HEADLESS", "").strip() in ("1", "true"): + render = os.environ.get("DIMSIM_RENDER", "cpu").strip() + dev_args.extend(["--headless", "--render", render]) + + # DIMSIM_CHANNELS=N → multi-page mode (N browser pages for parallel evals) + channels = os.environ.get("DIMSIM_CHANNELS", "").strip() + if channels: + dev_args.extend(["--channels", channels]) + + # Allow env var override: DIMSIM_LOCAL=1 dimos run sim-nav + if os.environ.get("DIMSIM_LOCAL", "").strip() in ("1", "true"): + self.config.local = True + + if self.config.local: + cli_ts = _find_local_cli() + if not cli_ts: + raise FileNotFoundError( + "Local DimSim not found. Expected DimSim/dimos-cli/cli.ts " + "next to the dimos repo." + ) + logger.info(f"Using local DimSim: {cli_ts}") + self.config.executable = _find_deno() + self.config.extra_args = [ + "run", + "--allow-all", + "--unstable-net", + str(cli_ts), + *dev_args, + ] + self.config.cwd = None + return + + # Prefer compiled binary over PATH (PATH may have stale deno-installed version) + dimsim_bin = _dimsim_bin() + dimsim_path = ( + str(dimsim_bin) if dimsim_bin.exists() else shutil.which("dimsim") or str(dimsim_bin) + ) + self.config.executable = dimsim_path + self.config.extra_args = dev_args + self.config.cwd = None + + def _maybe_build(self) -> None: + """Ensure dimsim binary, core assets, and scene are installed. + + Tries compiled binary from GitHub Releases first. Falls back to + existing dimsim in PATH (e.g. installed via deno) for older releases + that don't ship compiled binaries yet. + """ + if self.config.local: + return # Local dev — skip install + + import json + import platform + import stat + import subprocess + import urllib.request + + scene = self.config.scene + dimsim = _dimsim_bin() + dimsim.parent.mkdir(parents=True, exist_ok=True) + + # Check installed version (compiled binary or PATH) + dimsim_path = str(dimsim) if dimsim.exists() else shutil.which("dimsim") + installed_ver = None + if dimsim_path: + try: + result = subprocess.run( + [dimsim_path, "--version"], + capture_output=True, + text=True, + timeout=5, + ) + installed_ver = result.stdout.strip() if result.returncode == 0 else None + except Exception: + pass + + # Fetch latest version from GitHub Releases + latest_ver = None + release_tag = None + try: + req = urllib.request.Request( + _RELEASES_API, + headers={"Accept": "application/vnd.github.v3+json"}, + ) + with urllib.request.urlopen(req, timeout=10) as resp: + data = json.loads(resp.read()) + release_tag = data["tag_name"] + latest_ver = release_tag.lstrip("v") + except Exception: + pass + + if not dimsim_path or installed_ver != latest_ver: + # Try downloading compiled binary from GitHub Releases + downloaded = False + if release_tag: + system = platform.system().lower() + machine = platform.machine().lower() + if system == "darwin" and machine in ("arm64", "aarch64"): + binary_name = "dimsim-darwin-arm64" + elif system == "darwin": + binary_name = "dimsim-darwin-x64" + elif system == "linux" and machine in ("x86_64", "amd64"): + binary_name = "dimsim-linux-x64" + else: + binary_name = None + + if binary_name: + url = ( + f"https://github.com/{_GITHUB_REPO}/releases/download" + f"/{release_tag}/{binary_name}" + ) + try: + logger.info(f"Downloading dimsim {latest_ver} for {system}/{machine}...") + urllib.request.urlretrieve(url, str(dimsim)) + dimsim.chmod( + dimsim.stat().st_mode | stat.S_IEXEC | stat.S_IXGRP | stat.S_IXOTH + ) + # macOS quarantines downloaded binaries — clear all xattrs + if system == "darwin": + subprocess.run( + ["xattr", "-c", str(dimsim)], + capture_output=True, + ) + dimsim_path = str(dimsim) + downloaded = True + logger.info("dimsim binary installed.") + except Exception as exc: + logger.warning( + f"Compiled binary not available ({exc}), trying deno fallback..." + ) + + # Fallback: install via deno if compiled binary not available + if not downloaded and not dimsim_path: + deno = shutil.which("deno") or str(Path.home() / ".deno" / "bin" / "deno") + logger.info("Installing dimsim via deno (compiled binary not yet available)...") + subprocess.run( + [deno, "install", "-gAf", "--reload", "--unstable-net", "jsr:@antim/dimsim"], + check=True, + ) + dimsim_path = shutil.which("dimsim") + if not dimsim_path: + dimsim_path = str(Path.home() / ".deno" / "bin" / "dimsim") + else: + logger.info(f"dimsim up-to-date (v{installed_ver})") + + if not dimsim_path: + raise FileNotFoundError( + "dimsim not found — install Deno and retry, or wait for next release with compiled binaries" + ) + + # Always update executable to the resolved path (may differ from _resolve_paths) + self.config.executable = dimsim_path + + # Symlink to ~/.local/bin so `dimsim` is on PATH for eval authoring + # Must happen BEFORE setup so that `dimsim eval list` etc. use the new binary + local_bin = Path.home() / ".local" / "bin" + local_bin.mkdir(parents=True, exist_ok=True) + symlink = local_bin / "dimsim" + try: + target = Path(dimsim_path).resolve() + if symlink.is_symlink() and symlink.resolve() != target: + symlink.unlink() + if not symlink.exists(): + symlink.symlink_to(target) + logger.info(f"Symlinked dimsim → {symlink}") + except OSError: + pass # no permission + + # setup/scene have version-aware caching (only downloads if version changed) + logger.info("Checking core assets...") + subprocess.run([dimsim_path, "setup"], check=True) + + logger.info(f"Checking scene '{scene}'...") + subprocess.run([dimsim_path, "scene", "install", scene], check=True) + + def _collect_topics(self) -> dict[str, str]: + """Bridge hardcodes LCM channel names — no topic args needed.""" + return {} + + +sim_bridge = DimSimBridge.blueprint + +__all__ = ["DimSimBridge", "DimSimBridgeConfig", "sim_bridge"] diff --git a/dimos/robot/sim/tf_module.py b/dimos/robot/sim/tf_module.py new file mode 100644 index 0000000000..a2d531129e --- /dev/null +++ b/dimos/robot/sim/tf_module.py @@ -0,0 +1,184 @@ +# Copyright 2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Lightweight TF publisher for DimSim. + +Subscribes to odometry from the DimSim bridge (via LCM, wired by autoconnect) +and publishes the transform chain: world -> base_link -> {camera_link -> +camera_optical, lidar_link}. Also publishes CameraInfo at 1 Hz, forwards +cmd_vel to the bridge, and exposes a ``move()`` RPC. + +This module replaces the TF / camera_info / cmd_vel parts of the old +DimSimConnection while the NativeModule bridge handles sensor data directly. +""" + +import math +from threading import Thread +import time + +from dimos.core.core import rpc +from dimos.core.module import Module +from dimos.core.stream import In, Out +from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped +from dimos.msgs.geometry_msgs.Quaternion import Quaternion +from dimos.msgs.geometry_msgs.Transform import Transform +from dimos.msgs.geometry_msgs.Twist import Twist +from dimos.msgs.geometry_msgs.Vector3 import Vector3 +from dimos.msgs.sensor_msgs.CameraInfo import CameraInfo +from dimos.utils.logging_config import setup_logger + +logger = setup_logger() + +# DimSim captures at 960x432 with 80-degree horizontal FOV. +_DIMSIM_WIDTH = 960 +_DIMSIM_HEIGHT = 432 +_DIMSIM_FOV_DEG = 80 + + +def _camera_info_static() -> CameraInfo: + """Build CameraInfo for DimSim's virtual camera.""" + fov_rad = math.radians(_DIMSIM_FOV_DEG) + fx = (_DIMSIM_WIDTH / 2) / math.tan(fov_rad / 2) + fy = fx # square pixels + cx = _DIMSIM_WIDTH / 2.0 + cy = _DIMSIM_HEIGHT / 2.0 + + return CameraInfo( + frame_id="camera_optical", + height=_DIMSIM_HEIGHT, + width=_DIMSIM_WIDTH, + distortion_model="plumb_bob", + D=[0.0, 0.0, 0.0, 0.0, 0.0], + K=[fx, 0.0, cx, 0.0, fy, cy, 0.0, 0.0, 1.0], + R=[1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0], + P=[fx, 0.0, cx, 0.0, 0.0, fy, cy, 0.0, 0.0, 0.0, 1.0, 0.0], + binning_x=0, + binning_y=0, + ) + + +class DimSimTF(Module): + """Lightweight TF publisher for the DimSim simulator. + + Wired by autoconnect to receive odom from the bridge's LCM output. + Publishes TF transforms and camera intrinsics. Exposes ``move()`` RPC + for sending cmd_vel to the bridge. + """ + + # Odom input — autoconnect wires this to DimSimBridge.odom via LCM + odom: In[PoseStamped] + + # Outputs + camera_info: Out[CameraInfo] + cmd_vel: Out[Twist] + + _camera_info_thread: Thread | None = None + _latest_odom: PoseStamped | None = None + _odom_last_ts: float = 0.0 + _odom_count: int = 0 + + @classmethod + def _odom_to_tf(cls, odom: PoseStamped) -> list[Transform]: + """Build transform chain from odometry pose. + + Transform tree: world -> base_link -> {camera_link -> camera_optical, lidar_link} + """ + camera_link = Transform( + translation=Vector3(0.3, 0.0, 0.0), # camera 30cm forward + rotation=Quaternion(0.0, 0.0, 0.0, 1.0), + frame_id="base_link", + child_frame_id="camera_link", + ts=odom.ts, + ) + + camera_optical = Transform( + translation=Vector3(0.0, 0.0, 0.0), + rotation=Quaternion(-0.5, 0.5, -0.5, 0.5), + frame_id="camera_link", + child_frame_id="camera_optical", + ts=odom.ts, + ) + + lidar_link = Transform( + translation=Vector3(0.0, 0.0, 0.0), + rotation=Quaternion(0.0, 0.0, 0.0, 1.0), + frame_id="base_link", + child_frame_id="lidar_link", + ts=odom.ts, + ) + + return [ + Transform.from_pose("base_link", odom), + camera_link, + camera_optical, + lidar_link, + ] + + def _on_odom(self, pose: PoseStamped) -> None: + """Handle incoming odometry — publish TF transforms.""" + self._latest_odom = pose + self._odom_count += 1 + + transforms = self._odom_to_tf(pose) + self.tf.publish(*transforms) + + def _publish_camera_info_loop(self) -> None: + """Publish camera intrinsics at 1 Hz.""" + while self._camera_info_thread is not None: + self.camera_info.publish(_camera_info_static()) + time.sleep(1.0) + + @rpc + def start(self) -> None: + super().start() + + from reactivex.disposable import Disposable + + self._disposables.add(Disposable(self.odom.subscribe(self._on_odom))) + + self._camera_info_thread = Thread(target=self._publish_camera_info_loop, daemon=True) + self._camera_info_thread.start() + + logger.info("DimSimTF started — listening for odom, publishing TF + camera_info") + + @rpc + def stop(self) -> None: + thread = self._camera_info_thread + self._camera_info_thread = None + if thread and thread.is_alive(): + thread.join(timeout=1.0) + super().stop() + + @rpc + def move(self, twist: Twist, duration: float = 0.0) -> bool: + """Send movement command to the simulator via cmd_vel. + + If *duration* > 0, publishes at 20 Hz for that many seconds then sends + a zero-velocity stop command. If 0, publishes once (caller controls). + """ + if duration > 0: + stop = Twist(linear=Vector3(0, 0, 0), angular=Vector3(0, 0, 0)) + deadline = time.monotonic() + duration + while time.monotonic() < deadline: + self.cmd_vel.publish(twist) + time.sleep(0.05) + self.cmd_vel.publish(stop) + else: + self.cmd_vel.publish(twist) + return True + + +sim_tf = DimSimTF.blueprint + +__all__ = ["DimSimTF", "sim_tf"] diff --git a/docs/development/simulation.md b/docs/development/simulation.md new file mode 100644 index 0000000000..8a105e0c00 --- /dev/null +++ b/docs/development/simulation.md @@ -0,0 +1,196 @@ +# Simulation + +DimSim is a browser-based 3D simulator that provides the same sensor and control interface as physical robots. When you run any `sim-*` blueprint, dimos automatically downloads and launches DimSim — no manual setup or external dependencies required. + +## Running + +```bash +# Basic sim — camera feed + visualization +dimos --simulation run sim-basic + +# With navigation stack +dimos --simulation run sim-nav + +# Full agentic stack (navigation + VLM agent + skills) +dimos --simulation run sim-agentic +``` + +This opens a browser tab with the 3D environment. The robot is controlled via the same `cmd_vel` topic as physical hardware. + +## Blueprints + +| Blueprint | What it includes | +|-----------|-----------------| +| `sim-basic` | Sensor bridge + TF + visualization | +| `sim-nav` | + voxel mapper, costmap, A* planner, frontier explorer | +| `sim-spatial` | + spatial memory | +| `sim-agentic` | + VLM agent, navigation/speak/follow skills, web input | +| `sim-eval` | Agentic + temporal memory, for running eval workflows | +| `sim-parallel-eval` | Headless parallel eval (3 concurrent instances) | +| `sim-temporal-memory` | Full agentic stack with temporal memory | + +Each blueprint builds on the previous one. Pick the one that matches the modules you need. + +## Sensor Topics + +DimSim publishes the same topics as physical robots: + +| Topic | Message Type | Notes | +|-------|-------------|-------| +| `/odom` | `PoseStamped` | Robot pose in world frame | +| `/color_image` | `Image` | JPEG, 960x432 | +| `/depth_image` | `Image` | Depth buffer | +| `/lidar` | `PointCloud2` | Simulated 2D LiDAR | +| `/pointcloud` | `PointCloud2` | 3D point cloud | +| `/camera_info` | `CameraInfo` | Camera intrinsics (1 Hz) | +| `/cmd_vel` | `Twist` | Velocity commands (input) | + +Transform tree: `world -> base_link -> camera_link -> camera_optical`, plus `base_link -> lidar_link`. + +## Headless Mode + +To run without a browser window (for CI or automated testing): + +```bash +DIMSIM_HEADLESS=1 dimos --simulation run sim-basic +``` + +Add `DIMSIM_RENDER=gpu` on macOS for faster rendering (uses Metal). Default is `cpu` (SwiftShader, works without GPU). + +## Running Evals + +Evals test navigation accuracy by sending the agent to target locations and scoring distance. + +### Sequential + +```bash +pytest dimos/e2e_tests/test_dimsim_eval.py -v -s -m slow +``` + +### Parallel (3 concurrent workflows) + +```bash +pytest dimos/e2e_tests/test_dimsim_eval_parallel.py -v -s -m slow +``` + +### Single eval + +```bash +pytest dimos/e2e_tests/test_dimsim_eval.py::TestSimEvalSequential::test_go_to_tv -v -s -m slow +``` + +### With log capture + +```bash +DIMSIM_EVAL_LOG_DIR=./logs pytest dimos/e2e_tests/test_dimsim_eval.py -v -s -m slow +``` + +## Creating Evals + +Evals are JSON workflow files that define a task, starting pose, timeout, and success criteria. They live in `~/.dimsim/evals//.json`. + +### Interactive Wizard + +The fastest way to create an eval: + +```bash +dimsim eval create +``` + +This walks you through picking a scene, rubric type, target object, task prompt, threshold, and timeout. It writes the workflow JSON and prints the command to run it. + +### Manual Creation + +Create a JSON file in `~/.dimsim/evals//.json`: + +```json +{ + "name": "go-to-tv", + "environment": "apt", + "task": "Go to the TV", + "startPose": { "x": 0, "y": 0.5, "z": 3, "yaw": 0 }, + "timeoutSec": 30, + "successCriteria": { + "objectDistance": { + "object": "agent", + "target": "television", + "thresholdM": 2.0 + } + } +} +``` + +**Fields:** + +| Field | Required | Description | +|-------|----------|-------------| +| `name` | Yes | Unique identifier (used in CLI and test selection) | +| `environment` | Yes | Scene name (must be installed via `dimsim scene install`) | +| `task` | Yes | Natural language prompt sent to the agent | +| `startPose` | Yes | Agent spawn position: `x`, `y`, `z`, `yaw` (radians) | +| `timeoutSec` | Yes | Max seconds before the eval is scored | +| `successCriteria` | Yes | One or more rubrics (see below) | + +### Rubric Types + +**`objectDistance`** — Agent must reach a target object within a distance threshold. + +```json +"successCriteria": { + "objectDistance": { + "object": "agent", + "target": "refrigerator", + "thresholdM": 3.0 + } +} +``` + +- `target` is matched by substring against scene object titles/IDs (case-insensitive) +- `thresholdM` is Euclidean distance in meters from agent to the target's bounding box surface +- Use `dimsim list objects --scene ` to see available target objects + +**`llmJudge`** — A VLM judges success from screenshots. + +```json +"successCriteria": { + "llmJudge": { + "prompt": "Did the agent successfully navigate to the kitchen?" + } +} +``` + +**`groundTruth`** — Check spatial ground truth conditions. + +```json +"successCriteria": { + "groundTruth": {} +} +``` + +### Registering in the Manifest + +To include your eval in automated test runs, add it to `~/.dimsim/evals/manifest.json`: + +```json +{ + "version": "1.0", + "environments": [ + { + "name": "apt", + "scene": "apt", + "workflows": ["go-to-tv", "go-to-couch", "your-new-eval"] + } + ] +} +``` + +## Environment Variables + +| Variable | Purpose | Default | +|----------|---------|---------| +| `DIMSIM_HEADLESS` | Run headless (no browser window) | unset (browser opens) | +| `DIMSIM_RENDER` | Headless rendering: `gpu` or `cpu` | `cpu` | +| `DIMSIM_CHANNELS` | Number of parallel browser pages | unset | +| `DIMSIM_CONNECT_ONLY` | Skip DimSim launch, connect to existing server | unset | +| `EVAL_INSTANCE_ID` | Isolate memory paths per parallel instance | `0` | +| `DIMSIM_EVAL_LOG_DIR` | Directory for subprocess logs (eval tests) | unset |