Skip to content

Commit df986f5

Browse files
authored
feat: add Rerun split layout (Camera | 3D) to Go2 and G1 base blueprints (#1525)
* feat: add Rerun split layout (Camera | 3D) to Go2 and G1 base blueprints Adds a horizontal split view (camera feed 1/3, 3D world 2/3) to the Rerun viewer for Go2 basic and G1 primitive blueprints, matching the existing drone blueprint pattern. All downstream blueprints inherit the layout automatically. * fix(g1): use MuJoCo computed camera intrinsics instead of hardcoded Go2 values Same fix as PR #1516 for Go2. G1 sim was using hardcoded 1280x720 Go2 real-camera intrinsics while MuJoCo renders at 320x240, causing the projected camera image to appear tiny in Rerun.
1 parent 00d8dcc commit df986f5

File tree

3 files changed

+30
-20
lines changed

3 files changed

+30
-20
lines changed

dimos/robot/unitree/g1/blueprints/primitive/uintree_g1_primitive_no_nav.py

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,21 @@ def _static_base_link(rr: Any) -> list[Any]:
6767
]
6868

6969

70+
def _g1_rerun_blueprint() -> Any:
71+
"""Split layout: camera feed + 3D world view side by side."""
72+
import rerun.blueprint as rrb
73+
74+
return rrb.Blueprint(
75+
rrb.Horizontal(
76+
rrb.Spatial2DView(origin="world/color_image", name="Camera"),
77+
rrb.Spatial3DView(origin="world", name="3D"),
78+
column_shares=[1, 2],
79+
),
80+
)
81+
82+
7083
rerun_config = {
84+
"blueprint": _g1_rerun_blueprint,
7185
"pubsubs": [LCM()],
7286
"visual_override": {
7387
"world/camera_info": _convert_camera_info,

dimos/robot/unitree/g1/sim.py

Lines changed: 2 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -41,25 +41,6 @@
4141
logger = setup_logger()
4242

4343

44-
def _camera_info_static() -> CameraInfo:
45-
"""Camera intrinsics for rerun visualization (matches Go2 convention)."""
46-
fx, fy, cx, cy = (819.553492, 820.646595, 625.284099, 336.808987)
47-
width, height = (1280, 720)
48-
49-
return CameraInfo(
50-
frame_id="camera_optical",
51-
height=height,
52-
width=width,
53-
distortion_model="plumb_bob",
54-
D=[0.0, 0.0, 0.0, 0.0, 0.0],
55-
K=[fx, 0.0, cx, 0.0, fy, cy, 0.0, 0.0, 1.0],
56-
R=[1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0],
57-
P=[fx, 0.0, cx, 0.0, 0.0, fy, cy, 0.0, 0.0, 0.0, 1.0, 0.0],
58-
binning_x=0,
59-
binning_y=0,
60-
)
61-
62-
6344
class G1SimConnection(G1ConnectionBase):
6445
cmd_vel: In[Twist]
6546
lidar: Out[PointCloud2]
@@ -114,7 +95,8 @@ def stop(self) -> None:
11495
super().stop()
11596

11697
def _publish_camera_info_loop(self) -> None:
117-
info = _camera_info_static()
98+
assert self.connection is not None
99+
info = self.connection.camera_info_static
118100
while not self._stop_event.is_set():
119101
self.camera_info.publish(info)
120102
self._stop_event.wait(1.0)

dimos/robot/unitree/go2/blueprints/basic/unitree_go2_basic.py

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,21 @@ def _static_base_link(rr: Any) -> list[Any]:
7272
]
7373

7474

75+
def _go2_rerun_blueprint() -> Any:
76+
"""Split layout: camera feed + 3D world view side by side."""
77+
import rerun.blueprint as rrb
78+
79+
return rrb.Blueprint(
80+
rrb.Horizontal(
81+
rrb.Spatial2DView(origin="world/color_image", name="Camera"),
82+
rrb.Spatial3DView(origin="world", name="3D"),
83+
column_shares=[1, 2],
84+
),
85+
)
86+
87+
7588
rerun_config = {
89+
"blueprint": _go2_rerun_blueprint,
7690
# any pubsub that supports subscribe_all and topic that supports str(topic)
7791
# is acceptable here
7892
"pubsubs": [LCM()],

0 commit comments

Comments
 (0)