Real-robot bridge¶
The sim-to-real story in RoboSandbox is centered on SimBackend. If a
backend satisfies that protocol, the layers above it can stay largely
the same.
SimBackend Protocol¶
class SimBackend(Protocol):
def load(self, scene: Scene) -> None: ...
def reset(self) -> None: ...
def step(self, target_joints=None, gripper=None) -> None: ...
def observe(self) -> Observation: ...
def get_object_pose(self, object_id: str) -> Pose | None: ...
def set_object_pose(self, object_id: str, pose: Pose) -> None: ...
@property
def n_dof(self) -> int: ...
@property
def joint_names(self) -> list[str]: ...
def close(self) -> None: ...
Every skill, planner, and recorder uses this interface rather than calling MuJoCo directly.
The swap pattern¶
# sim
from robosandbox.sim.mujoco_backend import MuJoCoBackend
sim = MuJoCoBackend(render_size=(240, 320))
sim.load(scene)
# real
from my_driver import MySO101Backend
sim = MySO101Backend("/dev/ttyACM0")
sim.load(scene)
# Observation+step skills (Home, teleop, LeRobotPolicyAdapter-wrapped
# policies via run_policy) then run against MySO101Backend through the
# same SimBackend Protocol. Motion-planning skills (Pick, PlaceOn, Push)
# are the exception — they read sim.model / sim.data, which a real
# backend doesn't expose. See tutorials/sim-to-real-handoff.md for the
# "plan in sim, execute on real" pattern.
RealRobotBackend stub¶
RoboSandbox ships
robosandbox.backends.real.RealRobotBackend
— a stub that satisfies SimBackend at the Protocol level and raises
NotImplementedError with actionable messages from every method.
To use it, subclass it and wire in your hardware driver:
from robosandbox.backends.real import (
RealRobotBackend, RealRobotBackendConfig,
)
class MySO101Backend(RealRobotBackend):
def __init__(self, serial_port: str):
super().__init__(RealRobotBackendConfig(
n_dof=6,
joint_names=("j1", "j2", "j3", "j4", "j5", "j6"),
control_hz=200.0,
home_qpos=(0.0, 0.2, -0.8, 0.0, 0.5, 0.0),
gripper_open=0.04,
gripper_closed=0.0,
))
self._arm = SO101Arm(serial_port)
def load(self, scene):
self._arm.connect()
self._arm.home()
def reset(self):
self._arm.goto(self._config.home_qpos)
def step(self, target_joints=None, gripper=None):
if target_joints is not None:
self._arm.write_joint_positions(target_joints)
if gripper is not None:
self._arm.write_gripper(gripper)
def observe(self):
return Observation(
rgb=self._camera.read(),
depth=None,
robot_joints=self._arm.read_joints(),
ee_pose=self._arm.fk(),
gripper_width=self._arm.read_gripper(),
scene_objects={}, # or fill from a pose estimator
timestamp=time.time(),
)
# get_object_pose: query your tracker (AprilTag, OptiTrack, keypoint net)
# set_object_pose: no-op (real hardware can't teleport)
What a production backend usually wires up¶
load— connect cameras, zero the arm, home the gripper, verifyscene.workspace_aabb.step— streamtarget_jointsto the position controller at roughly the sim rate (200 Hz). Clamp against joint limits and max-velocity safety.observe— read joints from the robot state interface, capture one frame from the overhead camera, optionally fuse with an external pose tracker forscene_objects.reset— send home_qpos; block until settled.get_object_pose— AprilTag / OptiTrack / learned keypoint detector. ReturnNoneif you don't have one and rely on VLM perception instead.
Worked example¶
See examples/real_robot_swap.py. It defines a FakeSO101Backend that
prints what it would do instead of talking to hardware, which is useful
for checking the control flow before you wire in a real driver.
Run:
Expected:
[fake_so101] load scene with 0 objects
[fake_so101] reset to home
[example] sim-or-real run ok. n_dof=6 t=0.025
What is still missing¶
RealRobotBackendships as a stub only. No concrete subclass ships in core — the first target is SO-101 (LeRobot's reference driver). See roadmap 4.6.
Related¶
- Policy replay — same
SimBackendinterface, but driven by a policy rather than the agent. - Skills & agents — what consumes the backend.