Skip to content
Draft
19 changes: 19 additions & 0 deletions changes.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
# PR #1643 (rconnect) — Paul Review Fixes

## Commits (local, not pushed)

### 1. `81769d273` — Log exception + unblock stop() on startup failure
- If `_serve()` throws, `_server_ready` was never set → `stop()` blocked 5s
- Now logs exception and sets `_server_ready` in finally
- **Revert:** `git revert 81769d273`

## Reviewer was wrong on
- `_server_ready` race — it IS set inside `async with` (after bind), not before
- `msg.get("x") or 0` — code already uses `msg.get("x", 0)` correctly

## Not addressed (need Jeff's input)
- `vis_module` always bundling `RerunWebSocketServer` — opt-out design choice
- `LCM()` instantiated for non-rerun backends — wasted resource
- `rerun-connect` skipping `WebsocketVisModule` — intentional?
- Default `host = "0.0.0.0"` — intentional for remote viewer use case
- Hardcoded test ports — should use port=0 for parallel safety
4 changes: 2 additions & 2 deletions dimos/hardware/sensors/camera/module.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
from dimos.msgs.sensor_msgs.CameraInfo import CameraInfo
from dimos.msgs.sensor_msgs.Image import Image, sharpness_barrier
from dimos.spec import perception
from dimos.visualization.rerun.bridge import RerunBridgeModule
from dimos.visualization.vis_module import vis_module


def default_transform() -> Transform:
Expand Down Expand Up @@ -120,5 +120,5 @@ def stop(self) -> None:

demo_camera = autoconnect(
CameraModule.blueprint(),
RerunBridgeModule.blueprint(),
vis_module("rerun"),
)
39 changes: 24 additions & 15 deletions dimos/hardware/sensors/lidar/fastlio2/fastlio_blueprints.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,36 +15,45 @@
from dimos.core.blueprints import autoconnect
from dimos.hardware.sensors.lidar.fastlio2.module import FastLio2
from dimos.mapping.voxels import VoxelGridMapper
from dimos.visualization.rerun.bridge import RerunBridgeModule
from dimos.visualization.vis_module import vis_module

voxel_size = 0.05

mid360_fastlio = autoconnect(
FastLio2.blueprint(voxel_size=voxel_size, map_voxel_size=voxel_size, map_freq=-1),
RerunBridgeModule.blueprint(
visual_override={
"world/lidar": lambda grid: grid.to_rerun(voxel_size=voxel_size, mode="boxes"),
}
vis_module(
"rerun",
rerun_config={
"visual_override": {
"world/lidar": lambda grid: grid.to_rerun(voxel_size=voxel_size, mode="boxes"),
},
},
),
).global_config(n_workers=2, robot_model="mid360_fastlio2")

mid360_fastlio_voxels = autoconnect(
FastLio2.blueprint(),
VoxelGridMapper.blueprint(publish_interval=1.0, voxel_size=voxel_size, carve_columns=False),
RerunBridgeModule.blueprint(
visual_override={
"world/global_map": lambda grid: grid.to_rerun(voxel_size=voxel_size, mode="boxes"),
"world/lidar": None,
}
vis_module(
"rerun",
rerun_config={
"visual_override": {
"world/global_map": lambda grid: grid.to_rerun(voxel_size=voxel_size, mode="boxes"),
"world/lidar": None,
},
},
),
).global_config(n_workers=3, robot_model="mid360_fastlio2_voxels")

mid360_fastlio_voxels_native = autoconnect(
FastLio2.blueprint(voxel_size=voxel_size, map_voxel_size=voxel_size, map_freq=3.0),
RerunBridgeModule.blueprint(
visual_override={
"world/lidar": None,
"world/global_map": lambda grid: grid.to_rerun(voxel_size=voxel_size, mode="boxes"),
}
vis_module(
"rerun",
rerun_config={
"visual_override": {
"world/lidar": None,
"world/global_map": lambda grid: grid.to_rerun(voxel_size=voxel_size, mode="boxes"),
},
},
),
).global_config(n_workers=2, robot_model="mid360_fastlio2")
4 changes: 2 additions & 2 deletions dimos/hardware/sensors/lidar/livox/livox_blueprints.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,9 @@

from dimos.core.blueprints import autoconnect
from dimos.hardware.sensors.lidar.livox.module import Mid360
from dimos.visualization.rerun.bridge import RerunBridgeModule
from dimos.visualization.vis_module import vis_module

mid360 = autoconnect(
Mid360.blueprint(),
RerunBridgeModule.blueprint(),
vis_module("rerun"),
).global_config(n_workers=2, robot_model="mid360")
4 changes: 2 additions & 2 deletions dimos/manipulation/blueprints.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,8 @@
from dimos.msgs.geometry_msgs.Vector3 import Vector3
from dimos.msgs.sensor_msgs.JointState import JointState
from dimos.perception.object_scene_registration import ObjectSceneRegistrationModule
from dimos.robot.foxglove_bridge import FoxgloveBridge # TODO: migrate to rerun
from dimos.utils.data import get_data
from dimos.visualization.vis_module import vis_module


def _make_base_pose(
Expand Down Expand Up @@ -409,7 +409,7 @@ def _make_piper_config(
base_transform=_XARM_PERCEPTION_CAMERA_TRANSFORM,
),
ObjectSceneRegistrationModule.blueprint(target_frame="world"),
FoxgloveBridge.blueprint(), # TODO: migrate to rerun
vis_module("foxglove"),
)
.transports(
{
Expand Down
10 changes: 4 additions & 6 deletions dimos/manipulation/grasping/demo_grasping.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,15 +14,14 @@
# limitations under the License.
from pathlib import Path

from dimos.agents.mcp.mcp_client import McpClient
from dimos.agents.mcp.mcp_server import McpServer
from dimos.agents.agent import Agent
from dimos.core.blueprints import autoconnect
from dimos.hardware.sensors.camera.realsense.camera import RealSenseCamera
from dimos.manipulation.grasping.graspgen_module import graspgen
from dimos.manipulation.grasping.grasping import GraspingModule
from dimos.perception.detection.detectors.yoloe import YoloePromptMode
from dimos.perception.object_scene_registration import ObjectSceneRegistrationModule
from dimos.robot.foxglove_bridge import FoxgloveBridge
from dimos.visualization.vis_module import vis_module

camera_module = RealSenseCamera.blueprint(enable_pointcloud=False)

Expand All @@ -44,7 +43,6 @@
("/tmp", "/tmp", "rw")
], # Grasp visualization debug standalone: python -m dimos.manipulation.grasping.visualize_grasps
),
FoxgloveBridge.blueprint(),
McpServer.blueprint(),
McpClient.blueprint(),
vis_module("foxglove"),
Agent.blueprint(),
).global_config(viewer="foxglove")
10 changes: 4 additions & 6 deletions dimos/perception/demo_object_scene_registration.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,14 +13,13 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from dimos.agents.mcp.mcp_client import McpClient
from dimos.agents.mcp.mcp_server import McpServer
from dimos.agents.agent import Agent
from dimos.core.blueprints import autoconnect
from dimos.hardware.sensors.camera.realsense.camera import RealSenseCamera
from dimos.hardware.sensors.camera.zed.compat import ZEDCamera
from dimos.perception.detection.detectors.yoloe import YoloePromptMode
from dimos.perception.object_scene_registration import ObjectSceneRegistrationModule
from dimos.robot.foxglove_bridge import FoxgloveBridge
from dimos.visualization.vis_module import vis_module

camera_choice = "zed"

Expand All @@ -34,7 +33,6 @@
demo_object_scene_registration = autoconnect(
camera_module,
ObjectSceneRegistrationModule.blueprint(target_frame="world", prompt_mode=YoloePromptMode.LRPC),
FoxgloveBridge.blueprint(),
McpServer.blueprint(),
McpClient.blueprint(),
vis_module("foxglove"),
Agent.blueprint(),
).global_config(viewer="foxglove")
1 change: 1 addition & 0 deletions dimos/robot/all_blueprints.py
Original file line number Diff line number Diff line change
Expand Up @@ -157,6 +157,7 @@
"reid-module": "dimos.perception.detection.reid.module",
"replanning-a-star-planner": "dimos.navigation.replanning_a_star.module",
"rerun-bridge-module": "dimos.visualization.rerun.bridge",
"rerun-web-socket-server": "dimos.visualization.rerun.websocket_server",
"ros-nav": "dimos.navigation.rosnav",
"simple-phone-teleop": "dimos.teleop.phone.phone_extensions",
"spatial-memory": "dimos.perception.spatial_perception",
Expand Down
17 changes: 2 additions & 15 deletions dimos/robot/drone/blueprints/basic/drone_basic.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,10 +20,9 @@

from dimos.core.blueprints import autoconnect
from dimos.core.global_config import global_config
from dimos.protocol.pubsub.impl.lcmpubsub import LCM
from dimos.robot.drone.camera_module import DroneCameraModule
from dimos.robot.drone.connection_module import DroneConnectionModule
from dimos.web.websocket_vis.websocket_vis_module import WebsocketVisModule
from dimos.visualization.vis_module import vis_module


def _static_drone_body(rr: Any) -> list[Any]:
Expand Down Expand Up @@ -60,23 +59,12 @@ def _drone_rerun_blueprint() -> Any:

_rerun_config = {
"blueprint": _drone_rerun_blueprint,
"pubsubs": [LCM()],
"static": {
"world/tf/base_link": _static_drone_body,
},
}

# Conditional visualization
if global_config.viewer == "foxglove":
from dimos.robot.foxglove_bridge import FoxgloveBridge

_vis = FoxgloveBridge.blueprint()
elif global_config.viewer.startswith("rerun"):
from dimos.visualization.rerun.bridge import RerunBridgeModule, _resolve_viewer_mode

_vis = RerunBridgeModule.blueprint(viewer_mode=_resolve_viewer_mode(), **_rerun_config)
else:
_vis = autoconnect()
_vis = vis_module(global_config.viewer, rerun_config=_rerun_config)

# Determine connection string based on replay flag
connection_string = "udp:0.0.0.0:14550"
Expand All @@ -92,7 +80,6 @@ def _drone_rerun_blueprint() -> Any:
outdoor=False,
),
DroneCameraModule.blueprint(camera_intrinsics=[1000.0, 1000.0, 960.0, 540.0]),
WebsocketVisModule.blueprint(),
)

__all__ = [
Expand Down
10 changes: 5 additions & 5 deletions dimos/robot/unitree/g1/blueprints/perceptive/unitree_g1_shm.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,11 @@

from dimos.constants import DEFAULT_CAPACITY_COLOR_IMAGE
from dimos.core.blueprints import autoconnect
from dimos.core.global_config import global_config
from dimos.core.transport import pSHMTransport
from dimos.msgs.sensor_msgs.Image import Image
from dimos.robot.foxglove_bridge import FoxgloveBridge
from dimos.robot.unitree.g1.blueprints.perceptive.unitree_g1 import unitree_g1
from dimos.visualization.vis_module import vis_module

unitree_g1_shm = autoconnect(
unitree_g1.transports(
Expand All @@ -30,10 +31,9 @@
),
}
),
FoxgloveBridge.blueprint(
shm_channels=[
"/color_image#sensor_msgs.Image",
]
vis_module(
global_config.viewer,
foxglove_config={"shm_channels": ["/color_image#sensor_msgs.Image"]},
),
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,7 @@
from dimos.navigation.frontier_exploration.wavefront_frontier_goal_selector import (
WavefrontFrontierExplorer,
)
from dimos.protocol.pubsub.impl.lcmpubsub import LCM
from dimos.web.websocket_vis.websocket_vis_module import WebsocketVisModule
from dimos.visualization.vis_module import vis_module


def _convert_camera_info(camera_info: Any) -> Any:
Expand Down Expand Up @@ -90,7 +89,6 @@ def _g1_rerun_blueprint() -> Any:

rerun_config = {
"blueprint": _g1_rerun_blueprint,
"pubsubs": [LCM()],
"visual_override": {
"world/camera_info": _convert_camera_info,
"world/global_map": _convert_global_map,
Expand All @@ -101,18 +99,7 @@ def _g1_rerun_blueprint() -> Any:
},
}

if global_config.viewer == "foxglove":
from dimos.robot.foxglove_bridge import FoxgloveBridge

_with_vis = autoconnect(FoxgloveBridge.blueprint())
elif global_config.viewer.startswith("rerun"):
from dimos.visualization.rerun.bridge import RerunBridgeModule, _resolve_viewer_mode

_with_vis = autoconnect(
RerunBridgeModule.blueprint(viewer_mode=_resolve_viewer_mode(), **rerun_config)
)
else:
_with_vis = autoconnect()
_with_vis = vis_module(global_config.viewer, rerun_config=rerun_config)


def _create_webcam() -> Webcam:
Expand Down Expand Up @@ -147,8 +134,6 @@ def _create_webcam() -> Webcam:
VoxelGridMapper.blueprint(voxel_size=0.1),
CostMapper.blueprint(),
WavefrontFrontierExplorer.blueprint(),
# Visualization
WebsocketVisModule.blueprint(),
)
.global_config(n_workers=4, robot_model="unitree_g1")
.transports(
Expand Down
34 changes: 10 additions & 24 deletions dimos/robot/unitree/go2/blueprints/basic/unitree_go2_basic.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,9 @@
from dimos.core.global_config import global_config
from dimos.core.transport import pSHMTransport
from dimos.msgs.sensor_msgs.Image import Image
from dimos.protocol.pubsub.impl.lcmpubsub import LCM
from dimos.protocol.service.system_configurator.clock_sync import ClockSyncConfigurator
from dimos.robot.unitree.go2.connection import GO2Connection
from dimos.web.websocket_vis.websocket_vis_module import WebsocketVisModule
from dimos.visualization.vis_module import vis_module

# Mac has some issue with high bandwidth UDP, so we use pSHMTransport for color_image
# actually we can use pSHMTransport for all platforms, and for all streams
Expand Down Expand Up @@ -87,9 +86,6 @@ def _go2_rerun_blueprint() -> Any:

rerun_config = {
"blueprint": _go2_rerun_blueprint,
# any pubsub that supports subscribe_all and topic that supports str(topic)
# is acceptable here
"pubsubs": [LCM()],
# Custom converters for specific rerun entity paths
# Normally all these would be specified in their respectative modules
# Until this is implemented we have central overrides here
Expand All @@ -106,29 +102,19 @@ def _go2_rerun_blueprint() -> Any:
},
}


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
_with_vis = autoconnect(
_transports_base,
vis_module(
global_config.viewer,
rerun_config=rerun_config,
foxglove_config={"shm_channels": ["/color_image#sensor_msgs.Image"]},
),
)

unitree_go2_basic = (
autoconnect(
with_vis,
_with_vis,
GO2Connection.blueprint(),
WebsocketVisModule.blueprint(),
)
.global_config(n_workers=4, robot_model="unitree_go2")
.configurators(ClockSyncConfigurator())
Expand Down
6 changes: 2 additions & 4 deletions dimos/robot/unitree/go2/blueprints/basic/unitree_go2_fleet.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,15 +22,13 @@

from dimos.core.blueprints import autoconnect
from dimos.protocol.service.system_configurator.clock_sync import ClockSyncConfigurator
from dimos.robot.unitree.go2.blueprints.basic.unitree_go2_basic import with_vis
from dimos.robot.unitree.go2.blueprints.basic.unitree_go2_basic import _with_vis
from dimos.robot.unitree.go2.fleet_connection import Go2FleetConnection
from dimos.web.websocket_vis.websocket_vis_module import WebsocketVisModule

unitree_go2_fleet = (
autoconnect(
with_vis,
_with_vis,
Go2FleetConnection.blueprint(),
WebsocketVisModule.blueprint(),
)
.global_config(n_workers=4, robot_model="unitree_go2")
.configurators(ClockSyncConfigurator())
Expand Down
Loading