-
Notifications
You must be signed in to change notification settings - Fork 239
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
PiperOrigin-RevId: 715743887 Change-Id: I266295a795e8d2706362253e77bade7660583cee
- Loading branch information
1 parent
832d908
commit 680740f
Showing
1 changed file
with
211 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,211 @@ | ||
<mujoco model="panda"> | ||
<compiler angle="radian" meshdir="assets" autolimits="true"/> | ||
|
||
<default> | ||
<default class="panda"> | ||
<material specular="0.5" shininess="0.25"/> | ||
<joint armature="0.1" damping="1" axis="0 0 1" range="-2.8973 2.8973"/> | ||
<general dyntype="none" biastype="affine" ctrlrange="-2.8973 2.8973" forcerange="-87 87"/> | ||
<position forcerange="-100 100"/> | ||
<default class="finger"> | ||
<joint axis="0 1 0" type="slide" range="0 0.04"/> | ||
</default> | ||
|
||
<default class="visual"> | ||
<geom type="mesh" contype="0" conaffinity="0" group="2"/> | ||
</default> | ||
<default class="collision"> | ||
<geom group="3" type="mesh" contype="0" conaffinity="0"/> | ||
</default> | ||
</default> | ||
</default> | ||
|
||
<asset> | ||
<material class="panda" name="white" rgba="1 1 1 1"/> | ||
<material class="panda" name="off_white" rgba="0.901961 0.921569 0.929412 1"/> | ||
<material class="panda" name="black" rgba="0.25 0.25 0.25 1"/> | ||
<material class="panda" name="green" rgba="0 1 0 1"/> | ||
<material class="panda" name="light_blue" rgba="0.039216 0.541176 0.780392 1"/> | ||
|
||
<!-- Collision meshes --> | ||
<mesh name="link0_c" file="link0.stl"/> | ||
<mesh name="link1_c" file="link1.stl"/> | ||
<mesh name="link2_c" file="link2.stl"/> | ||
<mesh name="link3_c" file="link3.stl"/> | ||
<mesh name="link4_c" file="link4.stl"/> | ||
<mesh name="link5_c0" file="link5_collision_0.obj"/> | ||
<mesh name="link5_c1" file="link5_collision_1.obj"/> | ||
<mesh name="link5_c2" file="link5_collision_2.obj"/> | ||
<mesh name="link6_c" file="link6.stl"/> | ||
<mesh name="link7_c" file="link7.stl"/> | ||
|
||
<!-- Visual meshes --> | ||
<mesh file="link0_0.obj"/> | ||
<mesh file="link0_1.obj"/> | ||
<mesh file="link0_2.obj"/> | ||
<mesh file="link0_3.obj"/> | ||
<mesh file="link0_4.obj"/> | ||
<mesh file="link0_5.obj"/> | ||
<mesh file="link0_7.obj"/> | ||
<mesh file="link0_8.obj"/> | ||
<mesh file="link0_9.obj"/> | ||
<mesh file="link0_10.obj"/> | ||
<mesh file="link0_11.obj"/> | ||
<mesh file="link1.obj"/> | ||
<mesh file="link2.obj"/> | ||
<mesh file="link3_0.obj"/> | ||
<mesh file="link3_1.obj"/> | ||
<mesh file="link3_2.obj"/> | ||
<mesh file="link3_3.obj"/> | ||
<mesh file="link4_0.obj"/> | ||
<mesh file="link4_1.obj"/> | ||
<mesh file="link4_2.obj"/> | ||
<mesh file="link4_3.obj"/> | ||
<mesh file="link5_0.obj"/> | ||
<mesh file="link5_1.obj"/> | ||
<mesh file="link5_2.obj"/> | ||
<mesh file="link6_0.obj"/> | ||
<mesh file="link6_1.obj"/> | ||
<mesh file="link6_2.obj"/> | ||
<mesh file="link6_3.obj"/> | ||
<mesh file="link6_4.obj"/> | ||
<mesh file="link6_5.obj"/> | ||
<mesh file="link6_6.obj"/> | ||
<mesh file="link6_7.obj"/> | ||
<mesh file="link6_8.obj"/> | ||
<mesh file="link6_9.obj"/> | ||
<mesh file="link6_10.obj"/> | ||
<mesh file="link6_11.obj"/> | ||
<mesh file="link6_12.obj"/> | ||
<mesh file="link6_13.obj"/> | ||
<mesh file="link6_14.obj"/> | ||
<mesh file="link6_15.obj"/> | ||
<mesh file="link6_16.obj"/> | ||
<mesh file="link7_0.obj"/> | ||
<mesh file="link7_1.obj"/> | ||
<mesh file="link7_2.obj"/> | ||
<mesh file="link7_3.obj"/> | ||
<mesh file="link7_4.obj"/> | ||
<mesh file="link7_5.obj"/> | ||
<mesh file="link7_6.obj"/> | ||
<mesh file="link7_7.obj"/> | ||
</asset> | ||
|
||
<worldbody> | ||
<light name="top" pos="0 0 2" mode="trackcom"/> | ||
<body name="link0" childclass="panda"> | ||
<inertial mass="0.629769" pos="-0.041018 -0.00014 0.049974" | ||
fullinertia="0.00315 0.00388 0.004285 8.2904e-7 0.00015 8.2299e-6"/> | ||
<geom mesh="link0_0" material="off_white" class="visual"/> | ||
<geom mesh="link0_1" material="black" class="visual"/> | ||
<geom mesh="link0_2" material="off_white" class="visual"/> | ||
<geom mesh="link0_3" material="black" class="visual"/> | ||
<geom mesh="link0_4" material="off_white" class="visual"/> | ||
<geom mesh="link0_5" material="black" class="visual"/> | ||
<geom mesh="link0_7" material="white" class="visual"/> | ||
<geom mesh="link0_8" material="white" class="visual"/> | ||
<geom mesh="link0_9" material="black" class="visual"/> | ||
<geom mesh="link0_10" material="off_white" class="visual"/> | ||
<geom mesh="link0_11" material="white" class="visual"/> | ||
<geom mesh="link0_c" class="collision"/> | ||
<body name="link1" pos="0 0 0.333"> | ||
<inertial mass="4.970684" pos="0.003875 0.002081 -0.04762" | ||
fullinertia="0.70337 0.70661 0.0091170 -0.00013900 0.0067720 0.019169"/> | ||
<joint name="joint1" damping="40"/> | ||
<geom material="white" mesh="link1" class="visual"/> | ||
<geom mesh="link1_c" class="collision"/> | ||
<body name="link2" quat="1 -1 0 0"> | ||
<inertial mass="0.646926" pos="-0.003141 -0.02872 0.003495" | ||
fullinertia="0.0079620 2.8110e-2 2.5995e-2 -3.925e-3 1.0254e-2 7.04e-4"/> | ||
<joint name="joint2" range="-1.7628 1.7628" damping="40"/> | ||
<geom material="white" mesh="link2" class="visual"/> | ||
<geom mesh="link2_c" class="collision"/> | ||
<body name="link3" pos="0 -0.316 0" quat="1 1 0 0"> | ||
<joint name="joint3" damping="40"/> | ||
<inertial mass="3.228604" pos="2.7518e-2 3.9252e-2 -6.6502e-2" | ||
fullinertia="3.7242e-2 3.6155e-2 1.083e-2 -4.761e-3 -1.1396e-2 -1.2805e-2"/> | ||
<geom mesh="link3_0" material="white" class="visual"/> | ||
<geom mesh="link3_1" material="white" class="visual"/> | ||
<geom mesh="link3_2" material="white" class="visual"/> | ||
<geom mesh="link3_3" material="black" class="visual"/> | ||
<geom mesh="link3_c" class="collision"/> | ||
<body name="link4" pos="0.0825 0 0" quat="1 1 0 0"> | ||
<inertial mass="3.587895" pos="-5.317e-2 1.04419e-1 2.7454e-2" | ||
fullinertia="2.5853e-2 1.9552e-2 2.8323e-2 7.796e-3 -1.332e-3 8.641e-3"/> | ||
<joint name="joint4" range="-3.0718 -0.0698" damping="40"/> | ||
<geom mesh="link4_0" material="white" class="visual"/> | ||
<geom mesh="link4_1" material="white" class="visual"/> | ||
<geom mesh="link4_2" material="black" class="visual"/> | ||
<geom mesh="link4_3" material="white" class="visual"/> | ||
<geom mesh="link4_c" class="collision"/> | ||
<body name="link5" pos="-0.0825 0.384 0" quat="1 -1 0 0"> | ||
<inertial mass="1.225946" pos="-1.1953e-2 4.1065e-2 -3.8437e-2" | ||
fullinertia="3.5549e-2 2.9474e-2 8.627e-3 -2.117e-3 -4.037e-3 2.29e-4"/> | ||
<joint name="joint5" damping="2"/> | ||
<geom mesh="link5_0" material="black" class="visual"/> | ||
<geom mesh="link5_1" material="white" class="visual"/> | ||
<geom mesh="link5_2" material="white" class="visual"/> | ||
<geom mesh="link5_c0" class="collision"/> | ||
<geom mesh="link5_c1" class="collision"/> | ||
<geom mesh="link5_c2" class="collision"/> | ||
<body name="link6" quat="1 1 0 0"> | ||
<inertial mass="1.666555" pos="6.0149e-2 -1.4117e-2 -1.0517e-2" | ||
fullinertia="1.964e-3 4.354e-3 5.433e-3 1.09e-4 -1.158e-3 3.41e-4"/> | ||
<joint name="joint6" range="-0.0175 3.7525" damping="2"/> | ||
<geom mesh="link6_0" material="off_white" class="visual"/> | ||
<geom mesh="link6_1" material="white" class="visual"/> | ||
<geom mesh="link6_2" material="black" class="visual"/> | ||
<geom mesh="link6_3" material="white" class="visual"/> | ||
<geom mesh="link6_4" material="white" class="visual"/> | ||
<geom mesh="link6_5" material="white" class="visual"/> | ||
<geom mesh="link6_6" material="white" class="visual"/> | ||
<geom mesh="link6_7" material="light_blue" class="visual"/> | ||
<geom mesh="link6_8" material="light_blue" class="visual"/> | ||
<geom mesh="link6_9" material="black" class="visual"/> | ||
<geom mesh="link6_10" material="black" class="visual"/> | ||
<geom mesh="link6_11" material="white" class="visual"/> | ||
<geom mesh="link6_12" material="green" class="visual"/> | ||
<geom mesh="link6_13" material="white" class="visual"/> | ||
<geom mesh="link6_14" material="black" class="visual"/> | ||
<geom mesh="link6_15" material="black" class="visual"/> | ||
<geom mesh="link6_16" material="white" class="visual"/> | ||
<geom mesh="link6_c" class="collision"/> | ||
<body name="link7" pos="0.088 0 0" quat="1 1 0 0"> | ||
<inertial mass="7.35522e-01" pos="1.0517e-2 -4.252e-3 6.1597e-2" | ||
fullinertia="1.2516e-2 1.0027e-2 4.815e-3 -4.28e-4 -1.196e-3 -7.41e-4"/> | ||
<joint name="joint7" damping="2"/> | ||
<geom mesh="link7_0" material="white" class="visual"/> | ||
<geom mesh="link7_1" material="black" class="visual"/> | ||
<geom mesh="link7_2" material="black" class="visual"/> | ||
<geom mesh="link7_3" material="black" class="visual"/> | ||
<geom mesh="link7_4" material="black" class="visual"/> | ||
<geom mesh="link7_5" material="black" class="visual"/> | ||
<geom mesh="link7_6" material="black" class="visual"/> | ||
<geom mesh="link7_7" material="white" class="visual"/> | ||
<geom mesh="link7_c" class="collision"/> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
</worldbody> | ||
|
||
<actuator> | ||
<position class="panda" name="actuator1" joint="joint1" kp="1000" kv="20" | ||
ctrlrange="-2.8973 2.8973"/> | ||
<position class="panda" name="actuator2" joint="joint2" kp="1000" kv="20" | ||
ctrlrange="-1.7628 1.7628"/> | ||
<position class="panda" name="actuator3" joint="joint3" kp="750" kv="4" | ||
ctrlrange="-2.8973 2.8973"/> | ||
<position class="panda" name="actuator4" joint="joint4" kp="750" kv="4" | ||
ctrlrange="-3.0718 -0.0698"/> | ||
<position class="panda" name="actuator5" joint="joint5" kp="300" kv="2" | ||
forcerange="-12 12" ctrlrange="-2.8973 2.8973"/> | ||
<position class="panda" name="actuator6" joint="joint6" kp="300" kv="2" forcerange="-12 12" | ||
ctrlrange="-0.0175 3.7525"/> | ||
<position class="panda" name="actuator7" joint="joint7" kp="300" kv="2" forcerange="-12 12"/> | ||
</actuator> | ||
</mujoco> |