|
| 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 |
0 commit comments