Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
52 commits
Select commit Hold shift + click to select a range
8f2e658
add support for step simulation
nepyope Jan 7, 2026
c82bd70
convert obs to dict
nepyope Jan 7, 2026
cbe923f
modify holosoma/groot to support dict obs, fix send_actions
nepyope Jan 7, 2026
bf4b970
pre-commit
nepyope Jan 7, 2026
8a60006
begin zmq camera integration, shared protocol between mujoco g1 and l…
nepyope Jan 8, 2026
916099b
integrate zmq from real and sim robot
nepyope Jan 8, 2026
20e7fda
add g1 to replay
nepyope Jan 8, 2026
6bace44
removeg129 magic number
nepyope Jan 8, 2026
dba5b36
removeg129 magic number
nepyope Jan 8, 2026
3b26520
remove leftover magic variable
nepyope Jan 8, 2026
b33f8b2
update config defaults
nepyope Jan 8, 2026
e6b9019
remove references to realsense
nepyope Jan 8, 2026
c2ce7e1
pre-commit
nepyope Jan 8, 2026
38e71ee
reset env between episodes
nepyope Jan 9, 2026
4219f67
perform controller logic inside of g1
nepyope Jan 9, 2026
7fbc854
fix sim reset
nepyope Jan 9, 2026
3f2f438
connect robot outside of init
nepyope Jan 9, 2026
48a8a1c
Merge branch 'main' into feat/g1_improvements_record_sim
nepyope Jan 9, 2026
4c175f4
merge conflicts g1/so arm
nepyope Jan 9, 2026
26c2ce2
use lerobot opencv camera
nepyope Jan 9, 2026
223b635
fix bgr conversion
nepyope Jan 9, 2026
64c7a97
revert test defaults
nepyope Jan 9, 2026
b9dfdf3
fix comments for locomotion policies
nepyope Jan 9, 2026
4999321
fix exception chaining
nepyope Jan 9, 2026
0e53bfd
fix typing
nepyope Jan 9, 2026
3a9c3dd
simplify test_camera_class
nepyope Jan 9, 2026
87cc978
update docs
nepyope Jan 12, 2026
c748dc9
fix ruff
nepyope Jan 12, 2026
7944fd1
Merge branch 'main' into feat/g1_improvements_record_sim
michel-aractingi Jan 12, 2026
ffeddbb
add unitree_g1 specific clauses, merge reset_simulation and reset
nepyope Jan 12, 2026
184139c
remove while trues from examples
nepyope Jan 12, 2026
428ea9a
simplify sim code
nepyope Jan 12, 2026
c744400
move reset logic to sim, remove mujoco import
nepyope Jan 12, 2026
cd87fea
set positions directly for sim
nepyope Jan 12, 2026
edee1bd
remove zmq camera test
nepyope Jan 12, 2026
7eef2eb
add header
nepyope Jan 12, 2026
27cf8e6
2026
nepyope Jan 12, 2026
8c1c119
Merge branch 'main' into feat/g1_improvements_record_sim
nepyope Jan 12, 2026
cc0e5f8
remove comment
nepyope Jan 12, 2026
2b7d05a
Merge branch 'main' into feat/g1_improvements_record_sim
nepyope Jan 12, 2026
f60077d
remove comment from camera
nepyope Jan 12, 2026
51741fe
remove autoplay feature from g1
nepyope Jan 12, 2026
3562120
remove camera sleep
nepyope Jan 12, 2026
485f1ad
remove record/replay from docs
nepyope Jan 12, 2026
67bd9e8
add zmq to camera utils
nepyope Jan 12, 2026
6d650bc
remove color mode
nepyope Jan 12, 2026
ee42fd2
Update src/lerobot/cameras/zmq/__init__.py
nepyope Jan 12, 2026
de90f3b
replace print with logging
nepyope Jan 12, 2026
0f2f07b
re add color mode since it's required by base camera class
nepyope Jan 12, 2026
72328c1
fix zmq imports for pytest
nepyope Jan 12, 2026
f4a2742
Merge branch 'main' into feat/g1_improvements_record_sim
nepyope Jan 12, 2026
b8d4d9a
fix unitree_sdk dependency for pytest
nepyope Jan 12, 2026
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions docs/source/unitree_g1.mdx
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ This guide covers the complete setup process for the Unitree G1 humanoid, from i
We support both 29 and 23 DOF G1 EDU version. We introduce:

- **`unitree g1` robot class, handling low level read/write from/to the humanoid**
- **ZMQ socket bridge** for remote communication over wlan, allowing for remote policy deployment as well as over eth or directly on the Orin
- **ZMQ socket bridge** for remote communication and camera streaming, allowing for remote policy deployment over wlan, eth or directly on the robot
- **Locomotion policies** from NVIDIA gr00t and Amazon FAR Holosoma
- **Simulation mode** for testing policies without the physical robot in mujoco

Expand Down Expand Up @@ -110,7 +110,7 @@ ssh unitree@<YOUR_ROBOT_IP>
# Password: 123
```

Replace `<YOUR_ROBOT_IP>` with your robot's actual WiFi IP address (e.g., `172.18.129.215`).
Replace `<YOUR_ROBOT_IP>` with your robot's actual WiFi IP address.

---

Expand Down Expand Up @@ -188,7 +188,7 @@ Press `Ctrl+C` to stop the policy.

## Running in Simulation Mode (MuJoCo)

You can now test and develop policies without a physical robot using MuJoCo. To do so simply set `is_simulation=True` in config.
You can now test policies before unleashing them on the physical robot using MuJoCo. To do so simply set `is_simulation=True` in config.

## Additional Resources

Expand Down
51 changes: 24 additions & 27 deletions examples/unitree_g1/gr00t_locomotion.py
Original file line number Diff line number Diff line change
Expand Up @@ -111,34 +111,29 @@ def __init__(self, policy_balance, policy_walk, robot, config):

def run_step(self):
# Get current observation
robot_state = self.robot.get_observation()
obs = self.robot.get_observation()

if robot_state is None:
if not obs:
return

# Get command from remote controller
if robot_state.wireless_remote is not None:
self.robot.remote_controller.set(robot_state.wireless_remote)
if self.robot.remote_controller.button[0]: # R1 - raise waist
self.groot_height_cmd += 0.001
self.groot_height_cmd = np.clip(self.groot_height_cmd, 0.50, 1.00)
if self.robot.remote_controller.button[4]: # R2 - lower waist
self.groot_height_cmd -= 0.001
self.groot_height_cmd = np.clip(self.groot_height_cmd, 0.50, 1.00)
else:
self.robot.remote_controller.lx = 0.0
self.robot.remote_controller.ly = 0.0
self.robot.remote_controller.rx = 0.0
self.robot.remote_controller.ry = 0.0

self.cmd[0] = self.robot.remote_controller.ly # Forward/backward
self.cmd[1] = self.robot.remote_controller.lx * -1 # Left/right
self.cmd[2] = self.robot.remote_controller.rx * -1 # Rotation rate

# Get joint positions and velocities
for i in range(29):
self.groot_qj_all[i] = robot_state.motor_state[i].q
self.groot_dqj_all[i] = robot_state.motor_state[i].dq
if obs["remote.buttons"][0]: # R1 - raise waist
self.groot_height_cmd += 0.001
self.groot_height_cmd = np.clip(self.groot_height_cmd, 0.50, 1.00)
if obs["remote.buttons"][4]: # R2 - lower waist
self.groot_height_cmd -= 0.001
self.groot_height_cmd = np.clip(self.groot_height_cmd, 0.50, 1.00)

self.cmd[0] = obs["remote.ly"] # Forward/backward
self.cmd[1] = obs["remote.lx"] * -1 # Left/right
self.cmd[2] = obs["remote.rx"] * -1 # Rotation rate

# Get joint positions and velocities from flat dict
for motor in G1_29_JointIndex:
name = motor.name
idx = motor.value
self.groot_qj_all[idx] = obs[f"{name}.q"]
self.groot_dqj_all[idx] = obs[f"{name}.dq"]

# Adapt observation for g1_23dof
for idx in MISSING_JOINTS:
Expand All @@ -150,8 +145,8 @@ def run_step(self):
dqj_obs = self.groot_dqj_all.copy()

# Express IMU data in gravity frame of reference
quat = robot_state.imu_state.quaternion
ang_vel = np.array(robot_state.imu_state.gyroscope, dtype=np.float32)
quat = [obs["imu.quat.w"], obs["imu.quat.x"], obs["imu.quat.y"], obs["imu.quat.z"]]
ang_vel = np.array([obs["imu.gyro.x"], obs["imu.gyro.y"], obs["imu.gyro.z"]], dtype=np.float32)
gravity_orientation = self.robot.get_gravity_orientation(quat)

# Scale joint positions and velocities before policy inference
Expand Down Expand Up @@ -219,6 +214,8 @@ def run(repo_id: str = DEFAULT_GROOT_REPO_ID) -> None:
config = UnitreeG1Config()
robot = UnitreeG1(config)

robot.connect()

# Initialize gr00T locomotion controller
groot_controller = GrootLocomotionController(
policy_balance=policy_balance,
Expand All @@ -234,7 +231,7 @@ def run(repo_id: str = DEFAULT_GROOT_REPO_ID) -> None:
logger.info("Press Ctrl+C to stop")

# Run step
while True:
while not robot._shutdown_event.is_set():
start_time = time.time()
groot_controller.run_step()
elapsed = time.time() - start_time
Expand Down
28 changes: 14 additions & 14 deletions examples/unitree_g1/holosoma_locomotion.py
Original file line number Diff line number Diff line change
Expand Up @@ -126,33 +126,32 @@ def __init__(self, policy, robot, kp: np.ndarray, kd: np.ndarray):

def run_step(self):
# Get current observation
robot_state = self.robot.get_observation()
obs = self.robot.get_observation()

if robot_state is None:
if not obs:
return

# Get command from remote controller
if robot_state.wireless_remote is not None:
self.robot.remote_controller.set(robot_state.wireless_remote)

ly = self.robot.remote_controller.ly if abs(self.robot.remote_controller.ly) > 0.1 else 0.0
lx = self.robot.remote_controller.lx if abs(self.robot.remote_controller.lx) > 0.1 else 0.0
rx = self.robot.remote_controller.rx if abs(self.robot.remote_controller.rx) > 0.1 else 0.0
ly = obs["remote.ly"] if abs(obs["remote.ly"]) > 0.1 else 0.0
lx = obs["remote.lx"] if abs(obs["remote.lx"]) > 0.1 else 0.0
rx = obs["remote.rx"] if abs(obs["remote.rx"]) > 0.1 else 0.0
self.cmd[:] = [ly, -lx, -rx]

# Get joint positions and velocities
for i in range(29):
self.qj[i] = robot_state.motor_state[i].q
self.dqj[i] = robot_state.motor_state[i].dq
for motor in G1_29_JointIndex:
name = motor.name
idx = motor.value
self.qj[idx] = obs[f"{name}.q"]
self.dqj[idx] = obs[f"{name}.dq"]

# Adapt observation for g1_23dof
for idx in MISSING_JOINTS:
self.qj[idx] = 0.0
self.dqj[idx] = 0.0

# Express IMU data in gravity frame of reference
quat = robot_state.imu_state.quaternion
ang_vel = np.array(robot_state.imu_state.gyroscope, dtype=np.float32)
quat = [obs["imu.quat.w"], obs["imu.quat.x"], obs["imu.quat.y"], obs["imu.quat.z"]]
ang_vel = np.array([obs["imu.gyro.x"], obs["imu.gyro.y"], obs["imu.gyro.z"]], dtype=np.float32)
gravity = self.robot.get_gravity_orientation(quat)

# Scale joint positions and velocities before policy inference
Expand Down Expand Up @@ -220,6 +219,7 @@ def run(repo_id: str = DEFAULT_HOLOSOMA_REPO_ID, policy_type: str = "fastsac") -
# Initialize robot
config = UnitreeG1Config()
robot = UnitreeG1(config)
robot.connect()

holosoma_controller = HolosomaLocomotionController(policy, robot, kp, kd)

Expand All @@ -230,7 +230,7 @@ def run(repo_id: str = DEFAULT_HOLOSOMA_REPO_ID, policy_type: str = "fastsac") -
logger.info("Press Ctrl+C to stop")

# Run step
while True:
while not robot._shutdown_event.is_set():
start_time = time.time()
holosoma_controller.run_step()
elapsed = time.time() - start_time
Expand Down
5 changes: 5 additions & 0 deletions src/lerobot/cameras/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,11 @@ def make_cameras_from_configs(camera_configs: dict[str, CameraConfig]) -> dict[s

cameras[key] = Reachy2Camera(cfg)

elif cfg.type == "zmq":
from .zmq.camera_zmq import ZMQCamera

cameras[key] = ZMQCamera(cfg)

else:
try:
cameras[key] = cast(Camera, make_device_from_device_class(cfg))
Expand Down
20 changes: 20 additions & 0 deletions src/lerobot/cameras/zmq/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
#!/usr/bin/env python

# Copyright 2026 The HuggingFace Inc. team. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from .camera_zmq import ZMQCamera
from .configuration_zmq import ZMQCameraConfig

__all__ = ["ZMQCamera", "ZMQCameraConfig"]
Loading