Skip to content

Commit efad415

Browse files
committed
v2.3.2
Added support for the Unitree G1
1 parent 14368ee commit efad415

File tree

73 files changed

+2021
-22
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

73 files changed

+2021
-22
lines changed

data/motions/g1_walk.npy

3.46 MB
Binary file not shown.

data/scripts/convert_amass_to_isaac.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ def main(
4343
):
4444
if robot_type is None:
4545
robot_type = humanoid_type
46-
elif robot_type in ["h1"]:
46+
elif robot_type in ["h1", "g1"]:
4747
assert (
4848
force_retarget
4949
), f"Data is either SMPL or SMPL-X. The {robot_type} robot must use the retargeting pipeline."
@@ -416,7 +416,7 @@ def main(
416416
outpath.stem + "_flipped" + outpath.suffix
417417
)
418418
print(f"Saving to {outpath}")
419-
if robot_type == "h1":
419+
if robot_type in ["h1", "g1"]:
420420
torch.save(new_sk_motion, str(outpath))
421421
else:
422422
new_sk_motion.to_file(str(outpath))

data/scripts/retargeting/config.py

Lines changed: 62 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -73,6 +73,66 @@ def h1_mapping():
7373
smpl_pose_modifier=smpl_pose_modifier,
7474
asset_file=asset_file,
7575
)
76+
77+
78+
def g1_mapping():
79+
#### Config for extension
80+
extend_config = [
81+
{
82+
"joint_name": "left_rubber_hand_2",
83+
"parent_name": "left_wrist_yaw_link",
84+
"pos": [0.12, 0, 0.0],
85+
"rot": [1.0, 0.0, 0.0, 0.0],
86+
},
87+
{
88+
"joint_name": "right_rubber_hand_2",
89+
"parent_name": "right_wrist_yaw_link",
90+
"pos": [0.12, 0, 0.0],
91+
"rot": [1.0, 0.0, 0.0, 0.0],
92+
},
93+
{
94+
"joint_name": "head",
95+
"parent_name": "pelvis",
96+
"pos": [0.0, 0.0, 0.4],
97+
"rot": [1.0, 0.0, 0.0, 0.0],
98+
},
99+
]
100+
101+
base_link = "torso_link"
102+
joint_matches = [
103+
["pelvis", "Pelvis"],
104+
["left_hip_yaw_link", "L_Hip"],
105+
["left_knee_link", "L_Knee"],
106+
["left_ankle_roll_link", "L_Ankle"],
107+
["right_hip_yaw_link", "R_Hip"],
108+
["right_knee_link", "R_Knee"],
109+
["right_ankle_roll_link", "R_Ankle"],
110+
["left_shoulder_pitch_link", "L_Shoulder"],
111+
["left_elbow_link", "L_Elbow"],
112+
["left_rubber_hand_2", "L_Hand"],
113+
["right_shoulder_pitch_link", "R_Shoulder"],
114+
["right_elbow_link", "R_Elbow"],
115+
["right_rubber_hand_2", "R_Hand"],
116+
["head", "Head"],
117+
]
118+
119+
smpl_pose_modifier = [
120+
{"Pelvis": "[np.pi/2, 0, np.pi/2]"},
121+
{"L_Shoulder": "[0, 0, -np.pi/2]"},
122+
{"R_Shoulder": "[0, 0, np.pi/2]"},
123+
{"L_Elbow": "[0, -np.pi/2, 0]"},
124+
{"R_Elbow": "[0, np.pi/2, 0]"},
125+
]
126+
127+
asset_file = "protomotions/data/assets/mjcf/g1_original.xml"
128+
129+
return EasyDict(
130+
extend_config=extend_config,
131+
base_link=base_link,
132+
joint_matches=joint_matches,
133+
smpl_pose_modifier=smpl_pose_modifier,
134+
asset_file=asset_file,
135+
)
76136

77137

78138
def h1_no_head_mapping():
@@ -250,5 +310,7 @@ def get_config(humanoid_type: str):
250310
return h1_no_head_no_hands_mapping()
251311
elif humanoid_type == "smplx_humanoid_with_limits":
252312
return smplx_with_limits_mapping()
313+
elif humanoid_type == "g1":
314+
return g1_mapping()
253315
else:
254316
raise NotImplementedError

data/scripts/retargeting/mink_retarget.py

Lines changed: 38 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -64,12 +64,33 @@ def __call__(self, key: int) -> None:
6464
"R_Shoulder": {"name": "right_shoulder_pitch_link", "weight": 1.0},
6565
}
6666

67+
_G1_KEYPOINT_TO_JOINT = {
68+
"Pelvis": {"name": "pelvis", "weight": 1.0},
69+
"Head": {"name": "head", "weight": 1.0},
70+
# Legs.
71+
"L_Hip": {"name": "left_hip_yaw_link", "weight": 1.0},
72+
"R_Hip": {"name": "right_hip_yaw_link", "weight": 1.0},
73+
"L_Knee": {"name": "left_knee_link", "weight": 1.0},
74+
"R_Knee": {"name": "right_knee_link", "weight": 1.0},
75+
"L_Ankle": {"name": "left_ankle_roll_link", "weight": 1.0},
76+
"R_Ankle": {"name": "right_ankle_roll_link", "weight": 1.0},
77+
# Arms.
78+
"L_Elbow": {"name": "left_elbow_link", "weight": 1.0},
79+
"R_Elbow": {"name": "right_elbow_link", "weight": 1.0},
80+
"L_Wrist": {"name": "left_wrist_yaw_link", "weight": 1.0},
81+
"R_Wrist": {"name": "right_wrist_yaw_link", "weight": 1.0},
82+
"L_Shoulder": {"name": "left_shoulder_pitch_link", "weight": 1.0},
83+
"R_Shoulder": {"name": "right_shoulder_pitch_link", "weight": 1.0},
84+
}
85+
6786
_KEYPOINT_TO_JOINT_MAP = {
6887
"h1": _H1_KEYPOINT_TO_JOINT,
88+
"g1": _G1_KEYPOINT_TO_JOINT,
6989
}
7090

7191
_RESCALE_FACTOR = {
7292
"h1": np.array([1.0, 1.0, 1.1]),
93+
"g1": np.array([0.75, 1.0, 0.8]),
7394
}
7495

7596
_OFFSET = {
@@ -78,6 +99,7 @@ def __call__(self, key: int) -> None:
7899

79100
_ROOT_LINK = {
80101
"h1": "pelvis",
102+
"g1": "pelvis",
81103
}
82104

83105
_H1_VELOCITY_LIMITS = {
@@ -189,15 +211,17 @@ def construct_model(robot_name: str, keypoint_names: Sequence[str]):
189211

190212
if robot_name == "h1":
191213
humanoid_mjcf = mjcf.from_path("protomotions/data/assets/mjcf/h1.xml")
192-
humanoid_mjcf.worldbody.add(
193-
"camera",
194-
name="front_track",
195-
pos="-0.120 3.232 1.064",
196-
xyaxes="-1.000 -0.002 -0.000 0.000 -0.103 0.995",
197-
mode="trackcom",
198-
)
214+
elif robot_name == "g1":
215+
humanoid_mjcf = mjcf.from_path("protomotions/data/assets/mjcf/g1.xml")
199216
else:
200217
raise ValueError(f"Unknown robot name: {robot_name}")
218+
humanoid_mjcf.worldbody.add(
219+
"camera",
220+
name="front_track",
221+
pos="-0.120 3.232 1.064",
222+
xyaxes="-1.000 -0.002 -0.000 0.000 -0.103 0.995",
223+
mode="trackcom",
224+
)
201225
root.include_copy(humanoid_mjcf)
202226

203227
root_str = to_string(root, pretty=True)
@@ -265,8 +289,8 @@ def get_assets(root: mjcf.RootElement) -> dict[str, bytes]:
265289
return assets
266290

267291

268-
def create_h1_motion(
269-
poses: np.ndarray, trans: np.ndarray, orig_global_trans: np.ndarray, mocap_fr: float
292+
def create_robot_motion(
293+
poses: np.ndarray, trans: np.ndarray, orig_global_trans: np.ndarray, mocap_fr: float, robot_type: str
270294
) -> SkeletonMotion:
271295
"""Create a SkeletonMotion for H1 robot from poses and translations.
272296
Args:
@@ -281,7 +305,7 @@ def create_h1_motion(
281305
from data.scripts.retargeting.config import get_config
282306

283307
# Initialize H1 humanoid batch with config
284-
cfg = get_config("h1")
308+
cfg = get_config(robot_type)
285309
humanoid_batch = Humanoid_Batch(cfg)
286310

287311
# Convert poses to proper format
@@ -558,9 +582,9 @@ def retarget_motion(motion: SkeletonMotion, robot_type: str, render: bool = Fals
558582
retargeted_trans = np.stack(retargeted_trans)
559583

560584
# Create skeleton motion
561-
if robot_type == "h1":
562-
return create_h1_motion(
563-
retargeted_poses, retargeted_trans, global_translations, fps
585+
if robot_type in ["h1", "g1"]:
586+
return create_robot_motion(
587+
retargeted_poses, retargeted_trans, global_translations, fps, robot_type
564588
)
565589
else:
566590
skeleton_tree = SkeletonTree.from_mjcf(
@@ -687,7 +711,7 @@ def manually_retarget_motion(
687711
)
688712
new_sk_motion = SkeletonMotion.from_skeleton_state(new_sk_state, fps=30)
689713
sk_motion = retarget_motion(new_sk_motion, robot_type, render=render)
690-
if robot_type == "h1":
714+
if robot_type in ["h1", "g1"]:
691715
torch.save(sk_motion, output_path)
692716
else:
693717
sk_motion.to_file(output_path)

protomotions/config/robot/g1.yaml

Lines changed: 144 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,144 @@
1+
# @package _global_
2+
3+
defaults:
4+
- base
5+
6+
robot:
7+
body_names: ['pelvis', 'head', 'left_hip_pitch_link', 'left_hip_roll_link', 'left_hip_yaw_link', 'left_knee_link', 'left_ankle_pitch_link', 'left_ankle_roll_link', 'right_hip_pitch_link', 'right_hip_roll_link', 'right_hip_yaw_link', 'right_knee_link', 'right_ankle_pitch_link', 'right_ankle_roll_link', 'waist_yaw_link', 'waist_roll_link', 'torso_link', 'left_shoulder_pitch_link', 'left_shoulder_roll_link', 'left_shoulder_yaw_link', 'left_elbow_link', 'left_wrist_roll_link', 'left_wrist_pitch_link', 'left_wrist_yaw_link', 'left_rubber_hand', 'right_shoulder_pitch_link', 'right_shoulder_roll_link', 'right_shoulder_yaw_link', 'right_elbow_link', 'right_wrist_roll_link', 'right_wrist_pitch_link', 'right_wrist_yaw_link', 'right_rubber_hand']
8+
dof_names: ['left_hip_pitch_joint', 'left_hip_roll_joint', 'left_hip_yaw_joint', 'left_knee_joint', 'left_ankle_pitch_joint', 'left_ankle_roll_joint', 'right_hip_pitch_joint', 'right_hip_roll_joint', 'right_hip_yaw_joint', 'right_knee_joint', 'right_ankle_pitch_joint', 'right_ankle_roll_joint', 'waist_yaw_joint', 'waist_roll_joint', 'waist_pitch_joint', 'left_shoulder_pitch_joint', 'left_shoulder_roll_joint', 'left_shoulder_yaw_joint', 'left_elbow_joint', 'left_wrist_roll_joint', 'left_wrist_pitch_joint', 'left_wrist_yaw_joint', 'right_shoulder_pitch_joint', 'right_shoulder_roll_joint', 'right_shoulder_yaw_joint', 'right_elbow_joint', 'right_wrist_roll_joint', 'right_wrist_pitch_joint', 'right_wrist_yaw_joint']
9+
10+
trackable_bodies_subset: ['pelvis', 'head', 'left_ankle_link', 'right_ankle_link', 'left_rubber_hand', 'right_rubber_hand']
11+
12+
# Observation parameters
13+
dof_obs_size: ${eval:${len:${.dof_body_ids}}*6}
14+
number_of_actions: 29
15+
self_obs_max_coords_size: 493 # ${eval:1+33*(3+6+3+3)-3}
16+
17+
# Control parameters
18+
dof_body_ids: [ 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29 ]
19+
dof_effort_limits: [88.0, 88.0, 88.0, 139.0, 50.0, 50.0, 88.0, 88.0, 88.0, 139.0, 50.0, 50.0, 88.0, 50.0, 50.0, 25.0, 25.0, 25.0, 25.0, 25.0, 5.0, 5.0, 25.0, 25.0, 25.0, 25.0, 25.0, 5.0, 5.0]
20+
dof_vel_limits: [32.0, 32.0, 32.0, 20.0, 37.0, 37.0, 32.0, 32.0, 32.0, 20.0, 37.0, 37.0, 32.0, 37.0, 37.0, 37.0, 37.0, 37.0, 37.0, 37.0, 22.0, 22.0, 37.0, 37.0, 37.0, 37.0, 37.0, 22.0, 22.0]
21+
dof_armatures: [0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03]
22+
dof_joint_frictions: [0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03, 0.03]
23+
24+
key_bodies: [ "left_wrist_yaw_link", "right_wrist_yaw_link", "left_ankle_pitch_link", "right_ankle_pitch_link" ]
25+
non_termination_contact_bodies: [ "left_wrist_yaw_link", "left_wrist_pitch_link", "left_wrist_roll_link", "right_wrist_yaw_link", "right_wrist_pitch_link", "right_wrist_roll_link", "left_ankle_pitch_link", "left_ankle_roll_link", "right_ankle_pitch_link", "right_ankle_roll_link", ]
26+
right_foot_name: "right_ankle_pitch_link"
27+
left_foot_name: "left_ankle_pitch_link"
28+
head_body_name: "head"
29+
30+
init_state:
31+
pos: [0.0, 0.0, 0.8] # x,y,z [m]
32+
default_joint_angles: # = target angles [rad] when action = 0.0
33+
# These bias the controller and are recommended to be set at 0.
34+
left_hip_pitch_joint: -0.1
35+
left_hip_roll_joint: 0.
36+
left_hip_yaw_joint: 0.
37+
left_knee_joint: 0.3
38+
left_ankle_pitch_joint: -0.2
39+
left_ankle_roll_joint: 0.
40+
right_hip_pitch_joint: -0.1
41+
right_hip_roll_joint: 0.
42+
right_hip_yaw_joint: 0.
43+
right_knee_joint: 0.3
44+
right_ankle_pitch_joint: -0.2
45+
right_ankle_roll_joint: 0.
46+
waist_yaw_joint : 0.
47+
waist_roll_joint : 0.
48+
waist_pitch_joint : 0.
49+
left_shoulder_pitch_joint: 0.
50+
left_shoulder_roll_joint: 0.
51+
left_shoulder_yaw_joint: 0.
52+
left_elbow_joint: 0.
53+
left_wrist_roll_joint: 0.
54+
left_wrist_pitch_joint: 0.
55+
left_wrist_yaw_joint: 0.
56+
right_shoulder_pitch_joint: 0.
57+
right_shoulder_roll_joint: 0.
58+
right_shoulder_yaw_joint: 0.
59+
right_elbow_joint: 0.
60+
right_wrist_roll_joint: 0.
61+
right_wrist_pitch_joint: 0.
62+
right_wrist_yaw_joint: 0.
63+
64+
control:
65+
control_type: proportional
66+
use_biased_controller: False # See default_joint_angles
67+
map_actions_to_pd_range: True
68+
# PD Drive parameters:
69+
stiffness: # [N*m/rad]
70+
hip_yaw: 100
71+
hip_roll: 100
72+
hip_pitch: 100
73+
knee: 200
74+
ankle_pitch: 20
75+
ankle_roll: 20
76+
waist_yaw: 400
77+
waist_roll: 400
78+
waist_pitch: 400
79+
shoulder_pitch: 90
80+
shoulder_roll: 60
81+
shoulder_yaw: 20
82+
elbow: 60
83+
wrist_roll: 4.0
84+
wrist_pitch: 4.0
85+
wrist_yaw: 4.0
86+
damping: # [N*m/rad] # [N*m*s/rad]
87+
hip_yaw: 2.5
88+
hip_roll: 2.5
89+
hip_pitch: 2.5
90+
knee: 5.0
91+
ankle_pitch: 0.2
92+
ankle_roll: 0.1
93+
waist_yaw: 5.0
94+
waist_roll: 5.0
95+
waist_pitch: 5.0
96+
shoulder_pitch: 2.0
97+
shoulder_roll: 1.0
98+
shoulder_yaw: 0.4
99+
elbow: 1.0
100+
wrist_roll: 0.2
101+
wrist_pitch: 0.2
102+
wrist_yaw: 0.2
103+
104+
asset:
105+
collapse_fixed_joints: True # merge bodies connected by fixed joints. Specific fixed joints can be kept by adding " <... dont_collapse="true">
106+
replace_cylinder_with_capsule: True
107+
flip_visual_attachments: False
108+
armature: 0.001
109+
thickness: 0.01
110+
max_angular_velocity: 1000.
111+
max_linear_velocity: 1000.
112+
density: 0.001
113+
angular_damping: 0.
114+
linear_damping: 0.
115+
116+
asset_file_name: "urdf/g1.urdf"
117+
usd_asset_file_name: "usd/g1/g1.usd"
118+
robot_type: g1
119+
self_collisions: False
120+
default_dof_drive_mode: 3
121+
122+
sim:
123+
isaacgym:
124+
fps: 200
125+
decimation: 4
126+
substeps: 1
127+
isaaclab:
128+
fps: 200
129+
decimation: 4
130+
genesis:
131+
fps: 200
132+
decimation: 4
133+
substeps: 1
134+
135+
136+
# Override motion lib default to use the adapted H1 variant
137+
motion_lib:
138+
_target_: protomotions.utils.motion_lib_h1.H1_MotionLib
139+
140+
# Override simulation config to use the adapted H1 variant
141+
env:
142+
config:
143+
mimic_reset_track:
144+
grace_period: 10
Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
Copyright (c) 2016-2023 HangZhou YuShu TECHNOLOGY CO.,LTD. ("Unitree Robotics")
2+
All rights reserved.
3+
4+
Redistribution and use in source and binary forms, with or without
5+
modification, are permitted provided that the following conditions are met:
6+
7+
* Redistributions of source code must retain the above copyright notice, this
8+
list of conditions and the following disclaimer.
9+
10+
* Redistributions in binary form must reproduce the above copyright notice,
11+
this list of conditions and the following disclaimer in the documentation
12+
and/or other materials provided with the distribution.
13+
14+
* Neither the name of the copyright holder nor the names of its
15+
contributors may be used to endorse or promote products derived from
16+
this software without specific prior written permission.
17+
18+
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19+
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20+
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21+
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22+
FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23+
DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24+
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25+
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26+
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27+
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
Lines changed: 13 additions & 0 deletions
911 KB

0 commit comments

Comments
 (0)