Skip to content

Commit 7ae197b

Browse files
feat(sim): dimsim as connection (#1735)
Co-authored-by: Viswajit Nair <viswajitnair@gmail.com>
1 parent 89ada29 commit 7ae197b

27 files changed

Lines changed: 1778 additions & 95 deletions

.github/workflows/ci.yml

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -76,9 +76,6 @@ jobs:
7676
- os: ubuntu
7777
pyver: "3.14t"
7878
experimental: false
79-
- os: ubuntu
80-
pyver: "3.15"
81-
experimental: true
8279
fail-fast: true
8380
runs-on: ${{ matrix.os }}-latest
8481
continue-on-error: ${{ matrix.experimental }}
@@ -112,13 +109,13 @@ jobs:
112109
if: ${{ endsWith(matrix.pyver, 't') }}
113110
run: echo "PYTHON_GIL=0" >> $GITHUB_ENV
114111
- name: Run tests
115-
run: uv run pytest --numprocesses=3 --cov=dimos/ --junitxml=junit.xml -m 'not (tool or self_hosted or mujoco)'
112+
run: uv run pytest --numprocesses=3 --cov=dimos/ --junitxml=junit.xml -m 'not (tool or self_hosted or mujoco or dimsim)'
116113
- name: Re-run the failing tests with maximum verbosity
117114
if: failure()
118115
env:
119116
COLOR: yes
120117
run: >- # `exit 1` makes sure that the job remains red with flaky runs
121-
uv run pytest --no-cov -vvvvv --lf -m 'not (tool or self_hosted or mujoco)' && exit 1
118+
uv run pytest --no-cov -vvvvv --lf -m 'not (tool or self_hosted or mujoco or dimsim)' && exit 1
122119
shell: bash
123120
- name: Turn coverage into xml
124121
run: uv run python -m coverage xml

dimos/agents/skills/person_follow.py

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -78,14 +78,18 @@ def __init__(self, **kwargs: Any) -> None:
7878
self._should_stop: Event = Event()
7979
self._lock = RLock()
8080

81-
# Use MuJoCo camera intrinsics in simulation mode
81+
# Use simulator camera intrinsics in simulation mode
8282
camera_info = self.config.camera_info
83-
if self.config.g.simulation:
83+
if self.config.g.simulation == "mujoco":
8484
from dimos.robot.unitree.mujoco_connection import MujocoConnection
8585

8686
camera_info = MujocoConnection.camera_info_static
87+
elif self.config.g.simulation == "dimsim":
88+
from dimos.robot.unitree.dimsim_connection import DimSimConnection
8789

88-
self._visual_servo = VisualServoing2D(camera_info, self.config.g.simulation)
90+
camera_info = DimSimConnection.camera_info_static
91+
92+
self._visual_servo = VisualServoing2D(camera_info, bool(self.config.g.simulation))
8993
self._detection_navigation = DetectionNavigation(self.tf, camera_info)
9094

9195
@rpc

dimos/conftest.py

Lines changed: 24 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -20,19 +20,27 @@
2020
import tempfile
2121
import threading
2222

23-
# Pick a per-xdist-worker bucket and pin env vars *before* any dimos
24-
# module is imported. ``LCMConfig`` captures ``LCM_DEFAULT_URL`` at import
25-
# time; ``GlobalConfig`` captures ``MCP_PORT``; ``run_registry`` captures
26-
# ``XDG_STATE_HOME``. ``LCM_DEFAULT_URL`` in particular has to be an env
27-
# var (not just a fixture) because subprocess workers spawned by
23+
# With pytest-xdist, pick a per-worker bucket and pin env vars *before*
24+
# any dimos module is imported, so parallel workers don't share LCM bus,
25+
# MCP port, or state directory. ``LCMConfig`` captures ``LCM_DEFAULT_URL``
26+
# at import time; ``GlobalConfig`` captures ``MCP_PORT``; ``run_registry``
27+
# captures ``XDG_STATE_HOME``. ``LCM_DEFAULT_URL`` in particular has to be
28+
# an env var (not just a fixture) because subprocess workers spawned by
2829
# ``ModuleCoordinator`` create their own ``LCMConfig`` / ``LCMRPC``
2930
# instances internally and can't receive a fixture value — they inherit
3031
# our env at fork time.
31-
_worker = os.environ.get("PYTEST_XDIST_WORKER", "main")
32-
_BUCKET = int.from_bytes(hashlib.blake2b(_worker.encode(), digest_size=2).digest(), "big") % 5000
33-
os.environ["LCM_DEFAULT_URL"] = f"udpm://239.255.76.67:{7700 + _BUCKET}?ttl=0"
34-
os.environ["MCP_PORT"] = str(20000 + _BUCKET)
35-
os.environ["XDG_STATE_HOME"] = tempfile.mkdtemp(prefix=f"dimos-test-state-{_worker}-")
32+
#
33+
# Single-worker runs (no xdist) keep the defaults, so external processes
34+
# with hard-coded ports (e.g. the dimsim Deno bridge, which binds to LCM
35+
# 7667) can still talk to the test bus.
36+
_worker = os.environ.get("PYTEST_XDIST_WORKER")
37+
if _worker:
38+
_BUCKET = (
39+
int.from_bytes(hashlib.blake2b(_worker.encode(), digest_size=2).digest(), "big") % 5000
40+
)
41+
os.environ["LCM_DEFAULT_URL"] = f"udpm://239.255.76.67:{7700 + _BUCKET}?ttl=0"
42+
os.environ["MCP_PORT"] = str(20000 + _BUCKET)
43+
os.environ["XDG_STATE_HOME"] = tempfile.mkdtemp(prefix=f"dimos-test-state-{_worker}-")
3644

3745
# Raise the open-file limit. Each LCM transport opens at least one
3846
# multicast socket; with pytest-xdist workers running many in parallel,
@@ -77,6 +85,7 @@ def pytest_configure(config):
7785
"self_hosted: tests that need the self-hosted runner (LFS, ROS, CUDA, etc.)",
7886
)
7987
config.addinivalue_line("markers", "mujoco: tests which open mujoco")
88+
config.addinivalue_line("markers", "dimsim: tests which require dimsim")
8089
config.addinivalue_line("markers", "skipif_in_ci: skip when CI env var is set")
8190
config.addinivalue_line("markers", "skipif_no_openai: skip when OPENAI_API_KEY is not set")
8291
config.addinivalue_line("markers", "skipif_no_alibaba: skip when ALIBABA_API_KEY is not set")
@@ -90,20 +99,20 @@ def pytest_configure(config):
9099

91100
@pytest.fixture(scope="session")
92101
def mcp_port() -> int:
93-
"""The MCP server port pinned for this xdist worker."""
94-
return 20000 + _BUCKET
102+
"""The MCP server port pinned for this xdist worker (or the default)."""
103+
return int(os.environ.get("MCP_PORT", "9990"))
95104

96105

97106
@pytest.fixture(scope="session")
98107
def mcp_url(mcp_port: int) -> str:
99-
"""The MCP server URL pinned for this xdist worker."""
108+
"""The MCP server URL pinned for this xdist worker (or the default)."""
100109
return f"http://localhost:{mcp_port}/mcp"
101110

102111

103112
@pytest.fixture(scope="session")
104113
def lcm_url() -> str:
105-
"""The LCM bus URL pinned for this xdist worker."""
106-
return f"udpm://239.255.76.67:{7700 + _BUCKET}?ttl=0"
114+
"""The LCM bus URL pinned for this xdist worker (or the default)."""
115+
return os.environ.get("LCM_DEFAULT_URL", "udpm://239.255.76.67:7667?ttl=0")
107116

108117

109118
@pytest.hookimpl(tryfirst=True)

dimos/core/global_config.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ class GlobalConfig(BaseSettings):
3636
xarm7_ip: str | None = None
3737
xarm6_ip: str | None = None
3838
can_port: str | None = None
39-
simulation: bool = False
39+
simulation: str = ""
4040
replay: bool = False
4141
replay_db: str = "go2_short"
4242
new_memory: bool = False
@@ -65,6 +65,8 @@ class GlobalConfig(BaseSettings):
6565
obstacle_avoidance: bool = True
6666
detection_model: VlModelName = "moondream"
6767
listen_host: str = "127.0.0.1"
68+
dimsim_scene: str = "apt"
69+
dimsim_port: int = 8090
6870

6971
model_config = SettingsConfigDict(
7072
env_file=".env",
@@ -84,7 +86,7 @@ def unitree_connection_type(self) -> str:
8486
if self.replay:
8587
return "replay"
8688
if self.simulation:
87-
return "mujoco"
89+
return self.simulation
8890
return "webrtc"
8991

9092
@property

dimos/core/transport.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -133,10 +133,12 @@ def broadcast(self, _, msg) -> None: # type: ignore[no-untyped-def]
133133

134134
self.lcm.publish(self.topic, msg)
135135

136-
def subscribe(self, callback: Callable[[T], None], selfstream: In[T] = None) -> None: # type: ignore[assignment, override]
136+
def subscribe(
137+
self, callback: Callable[[T], Any], selfstream: Stream[T] | None = None
138+
) -> Callable[[], None]:
137139
if not self._started:
138140
self.start()
139-
return self.lcm.subscribe(self.topic, lambda msg, topic: callback(msg)) # type: ignore[arg-type, return-value]
141+
return self.lcm.subscribe(self.topic, lambda msg, topic: callback(msg)) # type: ignore[arg-type]
140142

141143

142144
class JpegLcmTransport(LCMTransport): # type: ignore[type-arg]

dimos/e2e_tests/conftest.py

Lines changed: 99 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020

2121
from dimos.core.transport import pLCMTransport
2222
from dimos.e2e_tests.conf_types import StartPersonTrack
23+
from dimos.e2e_tests.dim_sim_client import DimSimClient
2324
from dimos.e2e_tests.dimos_cli_call import DimosCliCall
2425
from dimos.e2e_tests.lcm_spy import LcmSpy
2526
from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped
@@ -66,12 +67,17 @@ def fun(*, points: list[tuple[float, float, float]], fail_message: str) -> None:
6667

6768

6869
@pytest.fixture
69-
def start_blueprint() -> Iterator[Callable[..., DimosCliCall]]:
70+
def start_blueprint(mcp_port: int) -> Iterator[Callable[..., DimosCliCall]]:
7071
dimos_robot_call = DimosCliCall()
72+
dimos_robot_call.mcp_port = mcp_port
7173

72-
def set_name_and_start(*demo_args: str, mcp_port: int | None = None) -> DimosCliCall:
74+
def set_name_and_start(
75+
*demo_args: str,
76+
simulator: str | None = None,
77+
) -> DimosCliCall:
7378
dimos_robot_call.demo_args = list(demo_args)
74-
dimos_robot_call.mcp_port = mcp_port
79+
if simulator is not None:
80+
dimos_robot_call.simulator = simulator
7581
dimos_robot_call.start()
7682
return dimos_robot_call
7783

@@ -153,3 +159,93 @@ def explore() -> None:
153159
direct_cmd_vel_explorer.follow_points(points)
154160

155161
return explore
162+
163+
164+
@pytest.fixture
165+
def dim_sim():
166+
client = DimSimClient()
167+
client.start()
168+
yield client
169+
client.stop()
170+
171+
172+
@pytest.fixture
173+
def spawn_wall_on_pose(lcm_spy: LcmSpy, dim_sim: DimSimClient):
174+
"""Spawn a dim_sim wall when the robot's /odom comes within `threshold` metres of `point`."""
175+
odom_topic = "/odom#geometry_msgs.PoseStamped"
176+
stop_event = threading.Event()
177+
workers: list[threading.Thread] = []
178+
errors: list[BaseException] = []
179+
180+
def spawn(*, point, threshold, wall) -> None:
181+
px, py = point
182+
threshold_sq = threshold * threshold
183+
triggered = threading.Event()
184+
185+
def on_odom(data):
186+
if triggered.is_set():
187+
return
188+
pose = PoseStamped.lcm_decode(data)
189+
dx = pose.x - px
190+
dy = pose.y - py
191+
if dx * dx + dy * dy < threshold_sq:
192+
triggered.set()
193+
194+
def worker():
195+
try:
196+
with lcm_spy.topic_listener(odom_topic, on_odom):
197+
while not stop_event.is_set():
198+
if triggered.wait(timeout=0.1):
199+
dim_sim.add_wall(*wall)
200+
return
201+
except BaseException as e:
202+
errors.append(e)
203+
204+
thread = threading.Thread(target=worker, daemon=True)
205+
thread.start()
206+
workers.append(thread)
207+
208+
yield spawn
209+
210+
stop_event.set()
211+
for thread in workers:
212+
thread.join(timeout=5.0)
213+
if errors:
214+
raise errors[0]
215+
216+
217+
@pytest.fixture
218+
def explore_house(
219+
direct_cmd_vel_explorer: DirectCmdVelExplorer,
220+
) -> Callable[[], None]:
221+
points = [
222+
(3.881, 4.803),
223+
(4.160, 1.615),
224+
(1.596, 1.505),
225+
(1.649, 0.137),
226+
(-3.644, -0.064),
227+
(-3.759, -2.661),
228+
(-4.186, -4.830),
229+
(-3.759, -2.661),
230+
(-1.070, -3.285),
231+
(-2.504, -2.452),
232+
(-2.647, 5.243),
233+
(-3.663, 3.591),
234+
(-1.178, 1.974),
235+
(-2.416, 2.629),
236+
(-2.581, 0.164),
237+
(1.834, 0.072),
238+
(3.010, -3.883),
239+
(1.756, -3.742),
240+
(6.336, -4.077),
241+
(8.264, -5.119),
242+
(6.258, -0.964),
243+
(6.453, 5.327),
244+
]
245+
246+
direct_cmd_vel_explorer.linear_speed = 0.5
247+
248+
def explore() -> None:
249+
direct_cmd_vel_explorer.follow_points(points)
250+
251+
return explore

dimos/e2e_tests/dim_sim_client.py

Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,56 @@
1+
# Copyright 2026 Dimensional Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
from dimos.core.transport import LCMTransport
16+
from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped
17+
from dimos.simulation.dimsim.scene_client import SceneClient
18+
19+
20+
class DimSimClient:
21+
_client: SceneClient | None = None
22+
23+
def __init__(self) -> None:
24+
self._client = None
25+
self._goal_request: LCMTransport[PoseStamped] = LCMTransport("/goal_request", PoseStamped)
26+
27+
def start(self) -> None:
28+
# self.client should be started lazily to avoid starting the dimsim
29+
# process before pytest fixtures are ready
30+
self._goal_request.start()
31+
32+
def stop(self) -> None:
33+
self.client.stop()
34+
self._goal_request.stop()
35+
36+
@property
37+
def client(self) -> SceneClient:
38+
if self._client is None:
39+
self._client = SceneClient()
40+
self._client.start()
41+
return self._client
42+
43+
def set_agent_position(self, x: float, y: float, z: float = 0.52) -> None:
44+
self.client.set_agent_position(y, z, x)
45+
46+
def add_wall(self, x1: float, y1: float, x2: float, y2: float) -> None:
47+
self.client.add_wall(y1, x1, y2, x2)
48+
49+
def publish_goal(self, x: float, y: float) -> None:
50+
self._goal_request.publish(
51+
PoseStamped(
52+
position=(x, y, 0),
53+
orientation=(0, 0, 0, 1),
54+
frame_id="world",
55+
)
56+
)

dimos/e2e_tests/dimos_cli_call.py

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@ class DimosCliCall:
2222
process: subprocess.Popen[bytes] | None
2323
demo_args: list[str] | None = None
2424
mcp_port: int | None = None
25+
simulator: str = "mujoco"
2526

2627
def __init__(self) -> None:
2728
self.process = None
@@ -48,7 +49,14 @@ def start(self) -> None:
4849
]
4950

5051
self.process = subprocess.Popen(
51-
["dimos", *global_overrides, "--simulation", *args, *blueprint_overrides],
52+
[
53+
"dimos",
54+
*global_overrides,
55+
"--simulation",
56+
self.simulator,
57+
*args,
58+
*blueprint_overrides,
59+
],
5260
start_new_session=True,
5361
)
5462

dimos/e2e_tests/lcm_spy.py

Lines changed: 6 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -73,25 +73,21 @@ def save_topic(self, topic: str) -> None:
7373
with self._saved_topics_lock:
7474
self._saved_topics.add(topic)
7575

76-
def register_topic_listener(self, topic: str, listener: Callable[[bytes], None]) -> int:
76+
def register_topic_listener(self, topic: str, listener: Callable[[bytes], None]) -> None:
7777
with self._topic_listeners_lock:
78-
listeners = self._topic_listeners.setdefault(topic, [])
79-
listener_index = len(listeners)
80-
listeners.append(listener)
81-
return listener_index
78+
self._topic_listeners.setdefault(topic, []).append(listener)
8279

83-
def unregister_topic_listener(self, topic: str, listener_index: int) -> None:
80+
def unregister_topic_listener(self, topic: str, listener: Callable[[bytes], None]) -> None:
8481
with self._topic_listeners_lock:
85-
listeners = self._topic_listeners[topic]
86-
listeners.pop(listener_index)
82+
self._topic_listeners[topic].remove(listener)
8783

8884
@contextmanager
8985
def topic_listener(self, topic: str, listener: Callable[[bytes], None]) -> Iterator[None]:
90-
listener_index = self.register_topic_listener(topic, listener)
86+
self.register_topic_listener(topic, listener)
9187
try:
9288
yield
9389
finally:
94-
self.unregister_topic_listener(topic, listener_index)
90+
self.unregister_topic_listener(topic, listener)
9591

9692
def wait_until(
9793
self,

0 commit comments

Comments
 (0)