More merge conflicts. Taking main changes then will integrate mine.
213 lines
11 KiB
XML
213 lines
11 KiB
XML
<mujoco model="berkeley_humanoid">
|
|
<compiler angle="radian" meshdir="assets"/>
|
|
|
|
<default>
|
|
<default class="berkeley_humanoid">
|
|
<joint axis="0 0 1"/>
|
|
<position inheritrange="1"/>
|
|
<default class="hxx">
|
|
<joint armature="0.0056" frictionloss="0.3" actuatorfrcrange="-20 20" range="-0.610865 0.610865"/>
|
|
<position kp="10" kv="1.5"/>
|
|
</default>
|
|
<default class="hfe">
|
|
<joint armature="0.007614" frictionloss="0.3" actuatorfrcrange="-30 30" range="-1.74533 0.523599"/>
|
|
<position kp="15" kv="1.5"/>
|
|
</default>
|
|
<default class="kfe">
|
|
<joint armature="0.0056" frictionloss="1.0" actuatorfrcrange="-30 30" range="0 2.0944"/>
|
|
<position kp="1" kv=".1"/>
|
|
</default>
|
|
<default class="ffe">
|
|
<joint armature="0.0056" frictionloss="1.0" actuatorfrcrange="-20 20" range="-0.523599 0.698132"/>
|
|
<position kp="1" kv=".1"/>
|
|
</default>
|
|
<default class="faa">
|
|
<joint armature="0.0004941" frictionloss=".1" actuatorfrcrange="-5 5" range="-0.523599 0.523599"/>
|
|
<position kp="1" kv=".1"/>
|
|
</default>
|
|
<default class="visual">
|
|
<geom type="mesh" contype="0" conaffinity="0" density="0" group="2" material="metal"/>
|
|
</default>
|
|
<default class="collision">
|
|
<geom group="3"/>
|
|
<default class="foot1">
|
|
<geom friction="0.8 0.02 0.01" size="0.08 0.0275 0.006" pos="0 -0.0429038 0.0133277" type="box"/>
|
|
</default>
|
|
<default class="foot2">
|
|
<geom size="0.027 0.0325" pos="0 9.61687e-05 0.0388277" type="cylinder"/>
|
|
</default>
|
|
</default>
|
|
<site size="0.01" rgba="1 0 0 1" group="4"/>
|
|
</default>
|
|
</default>
|
|
|
|
<asset>
|
|
<material name="metal" rgba=".3 .3 .3 1"/>
|
|
|
|
<mesh file="torso.stl"/>
|
|
<mesh file="ll_hr.stl"/>
|
|
<mesh file="ll_haa.stl"/>
|
|
<mesh file="ll_hfe.stl"/>
|
|
<mesh file="ll_kfe.stl"/>
|
|
<mesh file="ll_ffe.stl"/>
|
|
<mesh file="ll_faa.stl"/>
|
|
<mesh file="lr_hr.stl"/>
|
|
<mesh file="lr_haa.stl"/>
|
|
<mesh file="lr_hfe.stl"/>
|
|
<mesh file="lr_kfe.stl"/>
|
|
<mesh file="lr_ffe.stl"/>
|
|
<mesh file="lr_faa.stl"/>
|
|
</asset>
|
|
|
|
<worldbody>
|
|
<light name="spotlight" mode="targetbodycom" target="torso" pos="0 -1 2"/>
|
|
<body name="torso" childclass="berkeley_humanoid" pos="0 0 0.6">
|
|
<freejoint/>
|
|
<site name="imu"/>
|
|
<camera name="track" pos="1.210 -0.435 0.32" xyaxes="0.342 0.940 0.000 -0.321 0.117 0.940" mode="trackcom"/>
|
|
<inertial pos="0.0123294 -0.0023557 0.114047" quat="0.997324 0.0100377 0.00560983 -0.0721951" mass="5.37812"
|
|
diaginertia="0.0900564 0.0815619 0.0530251"/>
|
|
<geom class="visual" mesh="torso"/>
|
|
<geom class="collision" size="0.09 0.125 0.125" pos="0.02 0 0.12" type="box"/>
|
|
<body name="ll_hr" pos="0 0.07 0" quat="0.92388 0 0.382683 0">
|
|
<inertial pos="-0.00717501 0.000638 -0.0603296" quat="0.997785 0.00699266 0.066053 0.00374607" mass="0.797"
|
|
diaginertia="0.00165598 0.00124847 0.000774206"/>
|
|
<joint name="LL_HR" class="hxx"/>
|
|
<geom pos="0 -0.07 0" quat="0.92388 0 -0.382683 0" class="visual" mesh="ll_hr"/>
|
|
<body name="ll_haa" pos="0.0158 0 -0.065" quat="1 0 -1 0">
|
|
<inertial pos="0.000606614 -0.009735 -0.0611092" quat="0.702991 -0.06137 0.0554512 0.706373" mass="0.897"
|
|
diaginertia="0.0018904 0.0014613 0.000923049"/>
|
|
<joint name="LL_HAA" class="hxx"/>
|
|
<geom pos="0.065 -0.07 0.0158" quat="0.92388 0 0.382683 0" class="visual" mesh="ll_haa"/>
|
|
<geom class="collision" size="0.055 0.025" pos="6.77985e-05 -0.015 -0.0649318"
|
|
quat="0.653281 0.653281 0.270598 -0.270598" type="cylinder"/>
|
|
<body name="ll_hfe" pos="0 0.0158 -0.065" quat="0.653281 -0.653281 -0.270598 -0.270598">
|
|
<inertial pos="-0.0596998 -0.000999287 0.045473" quat="-0.00572221 0.744789 -0.0182535 0.667026"
|
|
mass="2.689" diaginertia="0.0191406 0.0181903 0.00583016"/>
|
|
<joint name="LL_HFE" class="hfe"/>
|
|
<geom pos="0.103096 -0.0111723 -0.0858" quat="0.5 0.5 0.5 0.5" class="visual" mesh="ll_hfe"/>
|
|
<geom class="collision" size="0.0615 0.045" pos="9.61687e-05 -2.87143e-07 0.0542" quat="0 -1 -1 0"
|
|
type="cylinder"/>
|
|
<geom class="collision" size="0.052 0.04" pos="-0.114904 -2.87143e-07 0.0592" quat="0 -1 -1 0"
|
|
type="cylinder"/>
|
|
<body name="ll_kfe" pos="-0.22 0 0.0742" quat="1 0 0 0">
|
|
<inertial pos="-0.0856948 -0.00928029 -0.002232" quat="-0.11773 0.702823 -0.0559586 0.69932" mass="0.35"
|
|
diaginertia="0.00161117 0.00159463 9.70556e-05"/>
|
|
<joint name="LL_KFE" class="kfe"/>
|
|
<geom pos="0.323096 -0.0111723 -0.16" quat="0.5 0.5 0.5 0.5" class="visual" mesh="ll_kfe"/>
|
|
<geom class="collision" size="0.015 0.02 0.08" pos="-0.0569038 -0.00117229 0" quat="0.5 0.5 0.5 0.5"
|
|
type="box"/>
|
|
<body name="ll_ffe" pos="-0.18 0 0">
|
|
<inertial pos="-0.00107817 0.0237707 6.8e-05" quat="0.553259 0.458091 -0.532546 0.447717"
|
|
mass="0.0993228" diaginertia="8.20308e-05 7.84322e-05 9.34827e-06"/>
|
|
<joint name="LL_FFE" class="ffe"/>
|
|
<geom pos="0.503096 -0.0111723 -0.16" quat="0.5 0.5 0.5 0.5" class="visual" mesh="ll_ffe"/>
|
|
<body name="ll_faa" pos="0 0.0175 0" quat="0.5 -0.5 -0.5 -0.5">
|
|
<inertial pos="-2.9e-05 -0.0163978 0.0153387" quat="0.985258 -0.171058 -0.00255986 0.000455342"
|
|
mass="0.507" diaginertia="0.00109422 0.000978734 0.000375399"/>
|
|
<joint name="LL_FAA" class="faa"/>
|
|
<geom pos="-0.16 0.503096 -0.0286723" quat="0.5 -0.5 -0.5 -0.5" class="visual" mesh="ll_faa"/>
|
|
<geom class="foot1" quat="0.45452 -0.541675 -0.541675 -0.45452"/>
|
|
<geom class="foot2" quat="0 -1 -1 0"/>
|
|
<site name="LL_FOOT" pos="0 -0.048689 0.014485" quat="-0.454519 0.541675 0.541675 0.454519"/>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
<body name="lr_hr" pos="0 -0.07 0" quat="0.92388 0 0.382683 0">
|
|
<inertial pos="-0.00717501 -0.000638 -0.0603296" quat="0.997804 -0.00433689 0.066057 0.0019766" mass="0.797"
|
|
diaginertia="0.00165632 0.00124845 0.000774613"/>
|
|
<joint name="LR_HR" class="hxx"/>
|
|
<geom pos="0 0.07 0" quat="0.92388 0 -0.382683 0" class="visual" mesh="lr_hr"/>
|
|
<body name="lr_haa" pos="0.0158 0 -0.065" quat="1 0 -1 0">
|
|
<inertial pos="0.000606614 0.009735 -0.0611092" quat="0.704792 0.0582267 -0.0597566 0.704491" mass="0.897"
|
|
diaginertia="0.00189204 0.00146613 0.000918492"/>
|
|
<joint name="LR_HAA" class="hxx"/>
|
|
<geom pos="0.065 0.07 0.0158" quat="0.92388 0 0.382683 0" class="visual" mesh="lr_haa"/>
|
|
<geom class="collision" size="0.055 0.025" pos="6.77985e-05 0.015 -0.0649318"
|
|
quat="0.653281 0.653281 0.270598 -0.270598" type="cylinder"/>
|
|
<body name="lr_hfe" pos="0 -0.0158 -0.065" quat="0.653281 -0.653281 -0.270598 -0.270598">
|
|
<inertial pos="-0.0596998 -0.000999287 -0.045473" quat="0.018407 0.667006 0.00579507 0.744802" mass="2.689"
|
|
diaginertia="0.0191386 0.0181883 0.00582996"/>
|
|
<joint name="LR_HFE" class="hfe"/>
|
|
<geom pos="0.103096 -0.0111723 0.0858" quat="0.5 0.5 0.5 0.5" class="visual" mesh="lr_hfe"/>
|
|
<geom class="collision" size="0.0615 0.045" pos="9.61687e-05 -2.87143e-07 -0.0542" quat="0 -1 -1 0"
|
|
type="cylinder"/>
|
|
<geom class="collision" size="0.052 0.04" pos="-0.114904 -2.87143e-07 -0.0592" quat="0 -1 -1 0"
|
|
type="cylinder"/>
|
|
<body name="lr_kfe" pos="-0.22 0 -0.0742" quat="1 0 0 0">
|
|
<inertial pos="-0.0856948 -0.00928029 0.002232" quat="0.055958 0.69932 0.11773 0.702823" mass="0.35"
|
|
diaginertia="0.00161117 0.00159463 9.70556e-05"/>
|
|
<joint name="LR_KFE" class="kfe"/>
|
|
<geom pos="0.323096 -0.0111723 0.16" quat="0.5 0.5 0.5 0.5" class="visual" mesh="lr_kfe"/>
|
|
<geom class="collision" size="0.015 0.02 0.08" pos="-0.0569038 -0.00117229 0" quat="0.5 0.5 0.5 0.5"
|
|
type="box"/>
|
|
<body name="lr_ffe" pos="-0.18 0 0" quat="1 0 0 0">
|
|
<inertial pos="-0.00107817 0.0237707 -6.8e-05" quat="0.532548 0.447721 -0.553256 0.45809"
|
|
mass="0.0993223" diaginertia="8.20306e-05 7.84321e-05 9.34825e-06"/>
|
|
<joint name="LR_FFE" class="ffe"/>
|
|
<geom pos="0.503096 -0.0111723 0.16" quat="0.5 0.5 0.5 0.5" class="visual" mesh="lr_ffe"/>
|
|
<body name="lr_faa" pos="0 0.0175 0" quat="0.5 -0.5 -0.5 -0.5">
|
|
<inertial pos="2.9e-05 -0.0163368 0.0153387" quat="0.985231 -0.171209 0.00251902 -0.000808065"
|
|
mass="0.507" diaginertia="0.00109488 0.000978788 0.000376011"/>
|
|
<joint name="LR_FAA" class="faa"/>
|
|
<geom pos="0.16 0.503096 -0.0286723" quat="0.5 -0.5 -0.5 -0.5" class="visual" mesh="lr_faa"/>
|
|
<geom class="foot1" quat="-0.45452 0.541675 0.541675 0.45452"/>
|
|
<geom class="foot2" quat="0 1 1 0"/>
|
|
<site name="LR_FOOT" pos="0 -0.048689 0.014485" quat="0.454519 -0.541675 -0.541675 -0.454519"/>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</worldbody>
|
|
|
|
<actuator>
|
|
<position class="hxx" name="LL_HR" joint="LL_HR"/>
|
|
<position class="hxx" name="LL_HAA" joint="LL_HAA"/>
|
|
<position class="hfe" name="LL_HFE" joint="LL_HFE"/>
|
|
<position class="kfe" name="LL_KFE" joint="LL_KFE"/>
|
|
<position class="ffe" name="LL_FFE" joint="LL_FFE"/>
|
|
<position class="faa" name="LL_FAA" joint="LL_FAA"/>
|
|
|
|
<position class="hxx" name="LR_HR" joint="LR_HR"/>
|
|
<position class="hxx" name="LR_HAA" joint="LR_HAA"/>
|
|
<position class="hfe" name="LR_HFE" joint="LR_HFE"/>
|
|
<position class="kfe" name="LR_KFE" joint="LR_KFE"/>
|
|
<position class="ffe" name="LR_FFE" joint="LR_FFE"/>
|
|
<position class="faa" name="LR_FAA" joint="LR_FAA"/>
|
|
</actuator>
|
|
|
|
<sensor>
|
|
<gyro site="imu" name="local_rpyrate"/>
|
|
<velocimeter site="imu" name="local_linvel"/>
|
|
<accelerometer site="imu" name="accelerometer"/>
|
|
<framepos objtype="site" objname="imu" name="position"/>
|
|
<framezaxis objtype="site" objname="imu" name="upvector"/>
|
|
<framexaxis objtype="site" objname="imu" name="forwardvector"/>
|
|
<framelinvel objtype="site" objname="imu" name="global_linvel"/>
|
|
<frameangvel objtype="site" objname="imu" name="global_angvel"/>
|
|
<framequat objtype="site" objname="imu" name="orientation"/>
|
|
<framelinvel objtype="site" objname="LL_FOOT" name="left_foot_global_linvel"/>
|
|
<framelinvel objtype="site" objname="LR_FOOT" name="right_foot_global_linvel"/>
|
|
<force site="LL_FOOT" name="left_foot_force"/>
|
|
<force site="LR_FOOT" name="right_foot_force"/>
|
|
</sensor>
|
|
|
|
<keyframe>
|
|
<key name="home"
|
|
qpos="
|
|
0 0 0.515
|
|
1 0 0 0
|
|
-0.071 0.103 -0.463 0.983 -0.350 0.126
|
|
0.071 -0.103 -0.463 0.983 -0.350 -0.126"
|
|
ctrl="
|
|
-0.071 0.103 -0.463 0.983 -0.350 0.126
|
|
0.071 -0.103 -0.463 0.983 -0.350 -0.126"/>
|
|
</keyframe>
|
|
</mujoco>
|