#!/usr/bin/env python3 """Visualize a LeRobot-format episode in Rerun. Usage: python visualize-lerobot.py [episode_index] dataset_dir Path to the LeRobot dataset root (contains meta/ and data/). episode_index Integer episode index to visualize (default: 0). Setup (one-time): pip install av pyarrow rerun-sdk """ import json import sys from pathlib import Path import numpy as np from PIL import Image import pyarrow.parquet as pq import rerun as rr import rerun.blueprint as rrb import av DATASET_DIR = Path(sys.argv[1]).resolve() if len(sys.argv) > 1 else Path(__file__).parent / "sample-lerobot" EPISODE_IDX = int(sys.argv[2]) if len(sys.argv) > 2 else 0 MAX_DEPTH_M = 3.0 POINT_CLOUD_STRIDE = 4 bbox_min = np.array([-0.26, -0.25, 0.055]) bbox_max = np.array([ 0.45, 0.36, 0.82]) # --------------------------------------------------------------------------- # Hardcoded camera intrinsics (Unitree G1 BrainCo — fixed hardware) # --------------------------------------------------------------------------- HEAD_DEPTH_INTR = dict(fx=644.346, fy=644.346, ppx=643.024, ppy=368.778, width=1280, height=720) HEAD_COLOR_INTR = dict(fx=907.402, fy=906.652, ppx=649.867, ppy=371.686, width=1280, height=720) SURROUND_DEPTH_INTR = dict(fx=243.466, fy=243.466, ppx=238.749, ppy=132.400, width=480, height=270) SURROUND_COLOR_INTR = dict(fx=245.124, fy=244.839, ppx=236.889, ppy=133.223, width=480, height=270) CAM_INTRINSICS = { "head_camera": (HEAD_DEPTH_INTR, HEAD_COLOR_INTR), "surround_camera": (SURROUND_DEPTH_INTR, SURROUND_COLOR_INTR), } # Camera name → parquet pose key (head is the scene origin) CAM_POSE_KEY = { "surround_camera": "observation.camera_pose_surround", } FINGER_NAMES = ["thumb", "index", "middle", "ring", "pinky"] FINGER_COLORS = { "thumb": [255, 200, 80], "index": [ 80, 255, 80], "middle": [ 80, 200, 255], "ring": [255, 80, 200], "pinky": [200, 80, 255], } # --------------------------------------------------------------------------- # TURBO depth inversion # --------------------------------------------------------------------------- def _build_turbo_table(): """Build the 256-entry TURBO colormap as float32 RGB (0-255). Polynomial coefficients from Google Brain's TURBO colormap specification. Matches cv2.COLORMAP_TURBO within ~5 RGB units (well within AV1 compression noise). """ t = np.linspace(0.0, 1.0, 256) # Coefficients in descending power order for np.polyval (t^5 … t^0) r = np.polyval([ 59.28637943, -152.94239396, 132.13108234, -42.66032258, 4.61539260, 0.13572138], t) g = np.polyval([ 2.82956604, 4.27729857, -14.18503333, 4.84296658, 2.19418839, 0.09140261], t) b = np.polyval([ 27.34824973, -89.90310912, 110.36276771, -60.58204836, 12.64194608, 0.10667330], t) rgb = np.clip(np.stack([r, g, b], axis=-1), 0.0, 1.0) * 255.0 return rgb.astype(np.float32) TURBO_RGB = _build_turbo_table() # (256, 3) float32 def depth_rgb_to_points_and_colors(depth_rgb_arr, color_arr, depth_intr, color_intr, stride=1): """Invert a TURBO depth_rgb frame to 3D points with colors. Mirrors precompute-depth-points.py: strides in full pixel-coordinate space so that u, v correctly reference full-image intrinsics. """ h, w = depth_rgb_arr.shape[:2] dfx, dfy = depth_intr["fx"], depth_intr["fy"] dcx, dcy = depth_intr["ppx"], depth_intr["ppy"] cfx, cfy = color_intr["fx"], color_intr["fy"] ccx, ccy = color_intr["ppx"], color_intr["ppy"] cw, ch = color_intr["width"], color_intr["height"] # Sample at stride — v, u are FULL-IMAGE pixel coordinates (like precompute-depth-points) v, u = np.mgrid[0:h:stride, 0:w:stride] sampled = depth_rgb_arr[0:h:stride, 0:w:stride].reshape(-1, 3).astype(np.float32) # Nearest-neighbor TURBO inversion: depth_m = idx/255 * MAX_DEPTH_M dot = sampled @ TURBO_RGB.T p_sq = (sampled ** 2).sum(axis=1, keepdims=True) t_sq = (TURBO_RGB ** 2).sum(axis=1, keepdims=True).T idx = (p_sq + t_sq - 2 * dot).argmin(axis=1).astype(np.float32) idx[sampled.max(axis=1) < 5] = 0 # black → no depth depth_m = (idx / 255.0 * MAX_DEPTH_M).reshape(v.shape) mask = (depth_m > 0) & (depth_m <= MAX_DEPTH_M) z = depth_m[mask] x = (u[mask].astype(np.float32) - dcx) * z / dfx y = (v[mask].astype(np.float32) - dcy) * z / dfy colors = None if color_arr is not None: if color_arr.shape[1] != cw or color_arr.shape[0] != ch: color_arr = np.array(Image.fromarray(color_arr).resize((cw, ch))) cu = np.clip((x * cfx / z + ccx).astype(np.int32), 0, cw - 1) cv_ = np.clip((y * cfy / z + ccy).astype(np.int32), 0, ch - 1) colors = color_arr[cv_, cu] return np.stack([x, y, z], axis=-1), colors # --------------------------------------------------------------------------- # Camera pose decode # --------------------------------------------------------------------------- def decode_camera_pose(vals): """Decode 13-value camera pose: [tx, ty, tz, r00..r22, detected].""" if not vals or len(vals) < 13 or not vals[12]: return None, None return vals[0:3], np.array(vals[3:12]).reshape(3, 3) # --------------------------------------------------------------------------- # Data loading helpers # --------------------------------------------------------------------------- def load_episode_data(dataset_dir, episode_idx, chunks_size): chunk_idx = episode_idx // chunks_size chunk_dir = dataset_dir / "data" / f"chunk-{chunk_idx:03d}" rows = [] for parquet_file in sorted(chunk_dir.glob("file-*.parquet")): table = pq.read_table(str(parquet_file)) ep_col = table.column("episode_index").to_pylist() for i, ep in enumerate(ep_col): if ep == episode_idx: rows.append({col: table.column(col)[i].as_py() for col in table.column_names}) rows.sort(key=lambda r: r["frame_index"]) return rows class VideoReader: def __init__(self, path): self.container = av.open(str(path)) self._iter = self.container.decode(video=0) def read(self): try: return next(self._iter) except StopIteration: return None def close(self): self.container.close() def find_video(dataset_dir, video_key, episode_idx, chunks_size): chunk_idx = episode_idx // chunks_size file_idx = episode_idx % chunks_size path = dataset_dir / "videos" / video_key / f"chunk-{chunk_idx:03d}" / f"file-{file_idx:03d}.mp4" if path.exists(): return path for p in sorted((dataset_dir / "videos" / video_key).glob("**/*.mp4")): return p return None # --------------------------------------------------------------------------- # Main # --------------------------------------------------------------------------- def main(): with open(DATASET_DIR / "meta" / "info.json") as f: info = json.load(f) fps = float(info["fps"]) chunks_size = int(info.get("chunks_size", 1000)) features = info["features"] state_names = features["observation.state"]["names"][0] # 26 joint names img_keys = sorted(k for k in features if k.startswith("observation.images.")) color_keys = [k for k in img_keys if "depth" not in k] depth_keys = [k for k in img_keys if "depth" in k] color_names = [k.replace("observation.images.", "") for k in color_keys] # Map depth key → base camera name (e.g. head_camera_depth_rgb → head_camera) depth_cam_names = [k.replace("observation.images.", "").replace("_depth_rgb", "") for k in depth_keys] print(f"Loading episode {EPISODE_IDX} from {DATASET_DIR}...") rows = load_episode_data(DATASET_DIR, EPISODE_IDX, chunks_size) num_frames = len(rows) print(f" {num_frames} frames\n") # Blueprint: 3D scene + all camera streams + joint plots depth_rgb_names = [k.replace("observation.images.", "") for k in depth_keys] color_views = [rrb.Spatial2DView(name=n, origin=f"cameras/{n}") for n in color_names] depth_views = [rrb.Spatial2DView(name=n, origin=f"cameras/{n}") for n in depth_rgb_names] blueprint = rrb.Blueprint( rrb.Grid( rrb.Spatial3DView(name="3D Scene", origin="world"), rrb.Grid( *color_views, *depth_views, rrb.TimeSeriesView(name="Joint States", origin="states"), rrb.BarChartView(name="Left Hand", origin="fingers/left_hand"), rrb.BarChartView(name="Right Hand", origin="fingers/right_hand"), grid_columns=1, ), grid_columns=2, ), ) rr.init(f"lerobot_episode_{EPISODE_IDX:03d}", spawn=True) rr.send_blueprint(blueprint) rr.log("world", rr.ViewCoordinates.RDF, static=True) # Static: log Pinhole intrinsics so cameras project correctly in 3D for cam_name, (d_intr, c_intr) in CAM_INTRINSICS.items(): rr.log( f"world/{cam_name}/image", rr.Pinhole( focal_length=[c_intr["fx"], c_intr["fy"]], principal_point=[c_intr["ppx"], c_intr["ppy"]], resolution=[c_intr["width"], c_intr["height"]], image_plane_distance=0.15, ), static=True, ) # Open video readers color_readers = {} depth_rgb_readers = {} for key, name in zip(color_keys, color_names): vpath = find_video(DATASET_DIR, key, EPISODE_IDX, chunks_size) if vpath: color_readers[name] = VideoReader(vpath) else: print(f" Warning: video not found for {key}") for key, cam_name, display_name in zip(depth_keys, depth_cam_names, depth_rgb_names): vpath = find_video(DATASET_DIR, key, EPISODE_IDX, chunks_size) if vpath: depth_rgb_readers[cam_name] = (VideoReader(vpath), display_name) else: print(f" Warning: video not found for {key}") print("Logging frames...") for fi, row in enumerate(rows): rr.set_time("frame", sequence=row["frame_index"]) rr.set_time("time", duration=row["timestamp"]) # -- Camera transforms (surround only; head is scene origin) -- surround_trans, surround_rot = None, None for cam_name, pose_key in CAM_POSE_KEY.items(): trans, rot = decode_camera_pose(row.get(pose_key) or []) if trans is not None: rr.log(f"world/{cam_name}", rr.Transform3D(translation=trans, mat3x3=rot)) if cam_name == "surround_camera": surround_trans, surround_rot = trans, rot # -- Color images: 2D panels + projected into 3D scene -- color_frames = {} for name, reader in color_readers.items(): av_frame = reader.read() if av_frame is not None: arr = av_frame.to_ndarray(format="rgb24") color_frames[name] = arr rr.log(f"cameras/{name}", rr.Image(arr)) rr.log(f"world/{name}/image", rr.Image(arr)) # -- Depth RGB images + point clouds -- for cam_name, (reader, display_name) in depth_rgb_readers.items(): av_frame = reader.read() if av_frame is None: continue depth_rgb_arr = av_frame.to_ndarray(format="rgb24") rr.log(f"cameras/{display_name}", rr.Image(depth_rgb_arr)) depth_intr, color_intr = CAM_INTRINSICS[cam_name] color_arr = color_frames.get(cam_name) points, colors = depth_rgb_to_points_and_colors( depth_rgb_arr, color_arr, depth_intr, color_intr, stride=POINT_CLOUD_STRIDE ) if len(points) == 0: continue # Surround: transform from surround frame to head (world) frame if cam_name == "surround_camera" and surround_rot is not None: points = (surround_rot @ points.T).T + np.array(surround_trans) log_path = "world/points/surround_camera" else: log_path = f"world/{cam_name}/points" mask = np.all((points >= bbox_min) & (points <= bbox_max), axis=1) points = points[mask] if colors is not None: colors = colors[mask] rr.log(log_path, rr.Points3D(points, colors=colors, radii=0.003)) # -- End-effector positions (left xyz=[0:3], right xyz=[3:6]) -- cart_pos = row.get("observation.cartesian_pos") or [] if len(cart_pos) >= 6: rr.log("world/ee/left_arm", rr.Points3D([cart_pos[0:3]], colors=[[255, 50, 50]], radii=0.015)) rr.log("world/ee/right_arm", rr.Points3D([cart_pos[3:6]], colors=[[ 50, 50, 255]], radii=0.015)) # -- Action EE command -- act_cart = row.get("action.cartesian_pos") or [] if len(act_cart) >= 6: rr.log("world/ee_cmd/left_arm", rr.Points3D([act_cart[0:3]], colors=[[255, 150, 150]], radii=0.01)) rr.log("world/ee_cmd/right_arm", rr.Points3D([act_cart[3:6]], colors=[[150, 150, 255]], radii=0.01)) # -- Fingertip positions (left=[0:15]→5×3, right=[15:30]→5×3) -- ftips = row.get("observation.fingertip_positions") or [] if len(ftips) == 30: left_tips = np.array(ftips[ 0:15]).reshape(5, 3) right_tips = np.array(ftips[15:30]).reshape(5, 3) for side, tips, base in [ ("left_arm", left_tips, cart_pos[0:3] if len(cart_pos) >= 3 else None), ("right_arm", right_tips, cart_pos[3:6] if len(cart_pos) >= 6 else None), ]: for i, finger in enumerate(FINGER_NAMES): rr.log(f"world/ee/{side}/{finger}", rr.Points3D([tips[i]], colors=[FINGER_COLORS[finger]], radii=0.008)) if base: rr.log(f"world/ee/{side}/{finger}/line", rr.LineStrips3D([[base, tips[i].tolist()]], colors=[FINGER_COLORS[finger]], radii=0.002)) # -- Arm joint scalars (left=[0:7], right=[7:14]) -- state = row.get("observation.state") or [] vel = row.get("observation.velocity") or [] effort = row.get("observation.effort") or [] for arm_key, sl in [("left_arm", slice(0, 7)), ("right_arm", slice(7, 14))]: arm_state, arm_vel, arm_effort = state[sl], vel[sl], effort[sl] for j, jname in enumerate(state_names[sl]): if j < len(arm_state): rr.log(f"states/{arm_key}/qpos/{jname}", rr.Scalars(arm_state[j])) if j < len(arm_vel): rr.log(f"states/{arm_key}/qvel/{jname}", rr.Scalars(arm_vel[j])) if j < len(arm_effort): rr.log(f"states/{arm_key}/torque/{jname}", rr.Scalars(arm_effort[j])) # -- Hand joint states + bar charts (left=[14:20], right=[20:26]) -- if len(state) >= 26: left_hand, right_hand = state[14:20], state[20:26] for j, jname in enumerate(state_names[14:20]): rr.log(f"states/left_hand/qpos/{jname}", rr.Scalars(left_hand[j])) for j, jname in enumerate(state_names[20:26]): rr.log(f"states/right_hand/qpos/{jname}", rr.Scalars(right_hand[j])) rr.log("fingers/left_hand", rr.BarChart(np.array(left_hand, dtype=float))) rr.log("fingers/right_hand", rr.BarChart(np.array(right_hand, dtype=float))) # -- Tactile (left=[0:5], right=[5:10]) -- for modality in ("tactile_normal_force", "tactile_tangential_force", "tactile_tangential_direction", "tactile_proximity"): vals = row.get(f"observation.{modality}") or [] for j, v in enumerate(vals[:5]): rr.log(f"states/left_ee/{modality}/t{j}", rr.Scalars(v)) for j, v in enumerate(vals[5:10]): rr.log(f"states/right_ee/{modality}/t{j}", rr.Scalars(v)) if (fi + 1) % 50 == 0 or fi == num_frames - 1: print(f" [{fi+1}/{num_frames}] frames logged") for reader in color_readers.values(): reader.close() for reader, _ in depth_rgb_readers.values(): reader.close() print(f"\nDone — logged {num_frames} frames.") if __name__ == "__main__": main()