Skip to content

Commit 43e04cf

Browse files
nepyopesandhya-cb
authored andcommitted
Feat/g1 improvements record sim (huggingface#2765)
This PR extends the integration of Unitree g1 with the LeRobot codebase. By converting robot state to a flat dict we can now record and replay episodes (example groot/holosoma scripts need to be adjusted as well). We also improve the simulation integration by calling .step @ _subscribe_motor_state instead of it running in a separate thread. We also add ZMQ camera to lerobot, streaming base64 images over json
1 parent 2544f85 commit 43e04cf

File tree

12 files changed

+679
-149
lines changed

12 files changed

+679
-149
lines changed

docs/source/unitree_g1.mdx

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ This guide covers the complete setup process for the Unitree G1 humanoid, from i
77
We support both 29 and 23 DOF G1 EDU version. We introduce:
88

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

@@ -110,7 +110,7 @@ ssh unitree@<YOUR_ROBOT_IP>
110110
# Password: 123
111111
```
112112

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

115115
---
116116

@@ -188,7 +188,7 @@ Press `Ctrl+C` to stop the policy.
188188

189189
## Running in Simulation Mode (MuJoCo)
190190

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

193193
## Additional Resources
194194

examples/unitree_g1/gr00t_locomotion.py

Lines changed: 24 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -111,34 +111,29 @@ def __init__(self, policy_balance, policy_walk, robot, config):
111111

112112
def run_step(self):
113113
# Get current observation
114-
robot_state = self.robot.get_observation()
114+
obs = self.robot.get_observation()
115115

116-
if robot_state is None:
116+
if not obs:
117117
return
118118

119119
# Get command from remote controller
120-
if robot_state.wireless_remote is not None:
121-
self.robot.remote_controller.set(robot_state.wireless_remote)
122-
if self.robot.remote_controller.button[0]: # R1 - raise waist
123-
self.groot_height_cmd += 0.001
124-
self.groot_height_cmd = np.clip(self.groot_height_cmd, 0.50, 1.00)
125-
if self.robot.remote_controller.button[4]: # R2 - lower waist
126-
self.groot_height_cmd -= 0.001
127-
self.groot_height_cmd = np.clip(self.groot_height_cmd, 0.50, 1.00)
128-
else:
129-
self.robot.remote_controller.lx = 0.0
130-
self.robot.remote_controller.ly = 0.0
131-
self.robot.remote_controller.rx = 0.0
132-
self.robot.remote_controller.ry = 0.0
133-
134-
self.cmd[0] = self.robot.remote_controller.ly # Forward/backward
135-
self.cmd[1] = self.robot.remote_controller.lx * -1 # Left/right
136-
self.cmd[2] = self.robot.remote_controller.rx * -1 # Rotation rate
137-
138-
# Get joint positions and velocities
139-
for i in range(29):
140-
self.groot_qj_all[i] = robot_state.motor_state[i].q
141-
self.groot_dqj_all[i] = robot_state.motor_state[i].dq
120+
if obs["remote.buttons"][0]: # R1 - raise waist
121+
self.groot_height_cmd += 0.001
122+
self.groot_height_cmd = np.clip(self.groot_height_cmd, 0.50, 1.00)
123+
if obs["remote.buttons"][4]: # R2 - lower waist
124+
self.groot_height_cmd -= 0.001
125+
self.groot_height_cmd = np.clip(self.groot_height_cmd, 0.50, 1.00)
126+
127+
self.cmd[0] = obs["remote.ly"] # Forward/backward
128+
self.cmd[1] = obs["remote.lx"] * -1 # Left/right
129+
self.cmd[2] = obs["remote.rx"] * -1 # Rotation rate
130+
131+
# Get joint positions and velocities from flat dict
132+
for motor in G1_29_JointIndex:
133+
name = motor.name
134+
idx = motor.value
135+
self.groot_qj_all[idx] = obs[f"{name}.q"]
136+
self.groot_dqj_all[idx] = obs[f"{name}.dq"]
142137

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

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

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

217+
robot.connect()
218+
222219
# Initialize gr00T locomotion controller
223220
groot_controller = GrootLocomotionController(
224221
policy_balance=policy_balance,
@@ -234,7 +231,7 @@ def run(repo_id: str = DEFAULT_GROOT_REPO_ID) -> None:
234231
logger.info("Press Ctrl+C to stop")
235232

236233
# Run step
237-
while True:
234+
while not robot._shutdown_event.is_set():
238235
start_time = time.time()
239236
groot_controller.run_step()
240237
elapsed = time.time() - start_time

examples/unitree_g1/holosoma_locomotion.py

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -126,33 +126,32 @@ def __init__(self, policy, robot, kp: np.ndarray, kd: np.ndarray):
126126

127127
def run_step(self):
128128
# Get current observation
129-
robot_state = self.robot.get_observation()
129+
obs = self.robot.get_observation()
130130

131-
if robot_state is None:
131+
if not obs:
132132
return
133133

134134
# Get command from remote controller
135-
if robot_state.wireless_remote is not None:
136-
self.robot.remote_controller.set(robot_state.wireless_remote)
137-
138-
ly = self.robot.remote_controller.ly if abs(self.robot.remote_controller.ly) > 0.1 else 0.0
139-
lx = self.robot.remote_controller.lx if abs(self.robot.remote_controller.lx) > 0.1 else 0.0
140-
rx = self.robot.remote_controller.rx if abs(self.robot.remote_controller.rx) > 0.1 else 0.0
135+
ly = obs["remote.ly"] if abs(obs["remote.ly"]) > 0.1 else 0.0
136+
lx = obs["remote.lx"] if abs(obs["remote.lx"]) > 0.1 else 0.0
137+
rx = obs["remote.rx"] if abs(obs["remote.rx"]) > 0.1 else 0.0
141138
self.cmd[:] = [ly, -lx, -rx]
142139

143140
# Get joint positions and velocities
144-
for i in range(29):
145-
self.qj[i] = robot_state.motor_state[i].q
146-
self.dqj[i] = robot_state.motor_state[i].dq
141+
for motor in G1_29_JointIndex:
142+
name = motor.name
143+
idx = motor.value
144+
self.qj[idx] = obs[f"{name}.q"]
145+
self.dqj[idx] = obs[f"{name}.dq"]
147146

148147
# Adapt observation for g1_23dof
149148
for idx in MISSING_JOINTS:
150149
self.qj[idx] = 0.0
151150
self.dqj[idx] = 0.0
152151

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

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

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

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

232232
# Run step
233-
while True:
233+
while not robot._shutdown_event.is_set():
234234
start_time = time.time()
235235
holosoma_controller.run_step()
236236
elapsed = time.time() - start_time

src/lerobot/cameras/utils.py

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,11 @@ def make_cameras_from_configs(camera_configs: dict[str, CameraConfig]) -> dict[s
4646

4747
cameras[key] = Reachy2Camera(cfg)
4848

49+
elif cfg.type == "zmq":
50+
from .zmq.camera_zmq import ZMQCamera
51+
52+
cameras[key] = ZMQCamera(cfg)
53+
4954
else:
5055
try:
5156
cameras[key] = cast(Camera, make_device_from_device_class(cfg))
Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
#!/usr/bin/env python
2+
3+
# Copyright 2026 The HuggingFace Inc. team. All rights reserved.
4+
#
5+
# Licensed under the Apache License, Version 2.0 (the "License");
6+
# you may not use this file except in compliance with the License.
7+
# You may obtain a copy of the License at
8+
#
9+
# http://www.apache.org/licenses/LICENSE-2.0
10+
#
11+
# Unless required by applicable law or agreed to in writing, software
12+
# distributed under the License is distributed on an "AS IS" BASIS,
13+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14+
# See the License for the specific language governing permissions and
15+
# limitations under the License.
16+
17+
from .camera_zmq import ZMQCamera
18+
from .configuration_zmq import ZMQCameraConfig
19+
20+
__all__ = ["ZMQCamera", "ZMQCameraConfig"]

0 commit comments

Comments
 (0)