Skip to content

Commit 680740f

Browse files
DeepMindcopybara-github
authored andcommitted
Add mjx_panda_nohand.xml.
PiperOrigin-RevId: 715743887 Change-Id: I266295a795e8d2706362253e77bade7660583cee
1 parent 832d908 commit 680740f

File tree

1 file changed

+211
-0
lines changed

1 file changed

+211
-0
lines changed
Lines changed: 211 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,211 @@
1+
<mujoco model="panda">
2+
<compiler angle="radian" meshdir="assets" autolimits="true"/>
3+
4+
<default>
5+
<default class="panda">
6+
<material specular="0.5" shininess="0.25"/>
7+
<joint armature="0.1" damping="1" axis="0 0 1" range="-2.8973 2.8973"/>
8+
<general dyntype="none" biastype="affine" ctrlrange="-2.8973 2.8973" forcerange="-87 87"/>
9+
<position forcerange="-100 100"/>
10+
<default class="finger">
11+
<joint axis="0 1 0" type="slide" range="0 0.04"/>
12+
</default>
13+
14+
<default class="visual">
15+
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
16+
</default>
17+
<default class="collision">
18+
<geom group="3" type="mesh" contype="0" conaffinity="0"/>
19+
</default>
20+
</default>
21+
</default>
22+
23+
<asset>
24+
<material class="panda" name="white" rgba="1 1 1 1"/>
25+
<material class="panda" name="off_white" rgba="0.901961 0.921569 0.929412 1"/>
26+
<material class="panda" name="black" rgba="0.25 0.25 0.25 1"/>
27+
<material class="panda" name="green" rgba="0 1 0 1"/>
28+
<material class="panda" name="light_blue" rgba="0.039216 0.541176 0.780392 1"/>
29+
30+
<!-- Collision meshes -->
31+
<mesh name="link0_c" file="link0.stl"/>
32+
<mesh name="link1_c" file="link1.stl"/>
33+
<mesh name="link2_c" file="link2.stl"/>
34+
<mesh name="link3_c" file="link3.stl"/>
35+
<mesh name="link4_c" file="link4.stl"/>
36+
<mesh name="link5_c0" file="link5_collision_0.obj"/>
37+
<mesh name="link5_c1" file="link5_collision_1.obj"/>
38+
<mesh name="link5_c2" file="link5_collision_2.obj"/>
39+
<mesh name="link6_c" file="link6.stl"/>
40+
<mesh name="link7_c" file="link7.stl"/>
41+
42+
<!-- Visual meshes -->
43+
<mesh file="link0_0.obj"/>
44+
<mesh file="link0_1.obj"/>
45+
<mesh file="link0_2.obj"/>
46+
<mesh file="link0_3.obj"/>
47+
<mesh file="link0_4.obj"/>
48+
<mesh file="link0_5.obj"/>
49+
<mesh file="link0_7.obj"/>
50+
<mesh file="link0_8.obj"/>
51+
<mesh file="link0_9.obj"/>
52+
<mesh file="link0_10.obj"/>
53+
<mesh file="link0_11.obj"/>
54+
<mesh file="link1.obj"/>
55+
<mesh file="link2.obj"/>
56+
<mesh file="link3_0.obj"/>
57+
<mesh file="link3_1.obj"/>
58+
<mesh file="link3_2.obj"/>
59+
<mesh file="link3_3.obj"/>
60+
<mesh file="link4_0.obj"/>
61+
<mesh file="link4_1.obj"/>
62+
<mesh file="link4_2.obj"/>
63+
<mesh file="link4_3.obj"/>
64+
<mesh file="link5_0.obj"/>
65+
<mesh file="link5_1.obj"/>
66+
<mesh file="link5_2.obj"/>
67+
<mesh file="link6_0.obj"/>
68+
<mesh file="link6_1.obj"/>
69+
<mesh file="link6_2.obj"/>
70+
<mesh file="link6_3.obj"/>
71+
<mesh file="link6_4.obj"/>
72+
<mesh file="link6_5.obj"/>
73+
<mesh file="link6_6.obj"/>
74+
<mesh file="link6_7.obj"/>
75+
<mesh file="link6_8.obj"/>
76+
<mesh file="link6_9.obj"/>
77+
<mesh file="link6_10.obj"/>
78+
<mesh file="link6_11.obj"/>
79+
<mesh file="link6_12.obj"/>
80+
<mesh file="link6_13.obj"/>
81+
<mesh file="link6_14.obj"/>
82+
<mesh file="link6_15.obj"/>
83+
<mesh file="link6_16.obj"/>
84+
<mesh file="link7_0.obj"/>
85+
<mesh file="link7_1.obj"/>
86+
<mesh file="link7_2.obj"/>
87+
<mesh file="link7_3.obj"/>
88+
<mesh file="link7_4.obj"/>
89+
<mesh file="link7_5.obj"/>
90+
<mesh file="link7_6.obj"/>
91+
<mesh file="link7_7.obj"/>
92+
</asset>
93+
94+
<worldbody>
95+
<light name="top" pos="0 0 2" mode="trackcom"/>
96+
<body name="link0" childclass="panda">
97+
<inertial mass="0.629769" pos="-0.041018 -0.00014 0.049974"
98+
fullinertia="0.00315 0.00388 0.004285 8.2904e-7 0.00015 8.2299e-6"/>
99+
<geom mesh="link0_0" material="off_white" class="visual"/>
100+
<geom mesh="link0_1" material="black" class="visual"/>
101+
<geom mesh="link0_2" material="off_white" class="visual"/>
102+
<geom mesh="link0_3" material="black" class="visual"/>
103+
<geom mesh="link0_4" material="off_white" class="visual"/>
104+
<geom mesh="link0_5" material="black" class="visual"/>
105+
<geom mesh="link0_7" material="white" class="visual"/>
106+
<geom mesh="link0_8" material="white" class="visual"/>
107+
<geom mesh="link0_9" material="black" class="visual"/>
108+
<geom mesh="link0_10" material="off_white" class="visual"/>
109+
<geom mesh="link0_11" material="white" class="visual"/>
110+
<geom mesh="link0_c" class="collision"/>
111+
<body name="link1" pos="0 0 0.333">
112+
<inertial mass="4.970684" pos="0.003875 0.002081 -0.04762"
113+
fullinertia="0.70337 0.70661 0.0091170 -0.00013900 0.0067720 0.019169"/>
114+
<joint name="joint1" damping="40"/>
115+
<geom material="white" mesh="link1" class="visual"/>
116+
<geom mesh="link1_c" class="collision"/>
117+
<body name="link2" quat="1 -1 0 0">
118+
<inertial mass="0.646926" pos="-0.003141 -0.02872 0.003495"
119+
fullinertia="0.0079620 2.8110e-2 2.5995e-2 -3.925e-3 1.0254e-2 7.04e-4"/>
120+
<joint name="joint2" range="-1.7628 1.7628" damping="40"/>
121+
<geom material="white" mesh="link2" class="visual"/>
122+
<geom mesh="link2_c" class="collision"/>
123+
<body name="link3" pos="0 -0.316 0" quat="1 1 0 0">
124+
<joint name="joint3" damping="40"/>
125+
<inertial mass="3.228604" pos="2.7518e-2 3.9252e-2 -6.6502e-2"
126+
fullinertia="3.7242e-2 3.6155e-2 1.083e-2 -4.761e-3 -1.1396e-2 -1.2805e-2"/>
127+
<geom mesh="link3_0" material="white" class="visual"/>
128+
<geom mesh="link3_1" material="white" class="visual"/>
129+
<geom mesh="link3_2" material="white" class="visual"/>
130+
<geom mesh="link3_3" material="black" class="visual"/>
131+
<geom mesh="link3_c" class="collision"/>
132+
<body name="link4" pos="0.0825 0 0" quat="1 1 0 0">
133+
<inertial mass="3.587895" pos="-5.317e-2 1.04419e-1 2.7454e-2"
134+
fullinertia="2.5853e-2 1.9552e-2 2.8323e-2 7.796e-3 -1.332e-3 8.641e-3"/>
135+
<joint name="joint4" range="-3.0718 -0.0698" damping="40"/>
136+
<geom mesh="link4_0" material="white" class="visual"/>
137+
<geom mesh="link4_1" material="white" class="visual"/>
138+
<geom mesh="link4_2" material="black" class="visual"/>
139+
<geom mesh="link4_3" material="white" class="visual"/>
140+
<geom mesh="link4_c" class="collision"/>
141+
<body name="link5" pos="-0.0825 0.384 0" quat="1 -1 0 0">
142+
<inertial mass="1.225946" pos="-1.1953e-2 4.1065e-2 -3.8437e-2"
143+
fullinertia="3.5549e-2 2.9474e-2 8.627e-3 -2.117e-3 -4.037e-3 2.29e-4"/>
144+
<joint name="joint5" damping="2"/>
145+
<geom mesh="link5_0" material="black" class="visual"/>
146+
<geom mesh="link5_1" material="white" class="visual"/>
147+
<geom mesh="link5_2" material="white" class="visual"/>
148+
<geom mesh="link5_c0" class="collision"/>
149+
<geom mesh="link5_c1" class="collision"/>
150+
<geom mesh="link5_c2" class="collision"/>
151+
<body name="link6" quat="1 1 0 0">
152+
<inertial mass="1.666555" pos="6.0149e-2 -1.4117e-2 -1.0517e-2"
153+
fullinertia="1.964e-3 4.354e-3 5.433e-3 1.09e-4 -1.158e-3 3.41e-4"/>
154+
<joint name="joint6" range="-0.0175 3.7525" damping="2"/>
155+
<geom mesh="link6_0" material="off_white" class="visual"/>
156+
<geom mesh="link6_1" material="white" class="visual"/>
157+
<geom mesh="link6_2" material="black" class="visual"/>
158+
<geom mesh="link6_3" material="white" class="visual"/>
159+
<geom mesh="link6_4" material="white" class="visual"/>
160+
<geom mesh="link6_5" material="white" class="visual"/>
161+
<geom mesh="link6_6" material="white" class="visual"/>
162+
<geom mesh="link6_7" material="light_blue" class="visual"/>
163+
<geom mesh="link6_8" material="light_blue" class="visual"/>
164+
<geom mesh="link6_9" material="black" class="visual"/>
165+
<geom mesh="link6_10" material="black" class="visual"/>
166+
<geom mesh="link6_11" material="white" class="visual"/>
167+
<geom mesh="link6_12" material="green" class="visual"/>
168+
<geom mesh="link6_13" material="white" class="visual"/>
169+
<geom mesh="link6_14" material="black" class="visual"/>
170+
<geom mesh="link6_15" material="black" class="visual"/>
171+
<geom mesh="link6_16" material="white" class="visual"/>
172+
<geom mesh="link6_c" class="collision"/>
173+
<body name="link7" pos="0.088 0 0" quat="1 1 0 0">
174+
<inertial mass="7.35522e-01" pos="1.0517e-2 -4.252e-3 6.1597e-2"
175+
fullinertia="1.2516e-2 1.0027e-2 4.815e-3 -4.28e-4 -1.196e-3 -7.41e-4"/>
176+
<joint name="joint7" damping="2"/>
177+
<geom mesh="link7_0" material="white" class="visual"/>
178+
<geom mesh="link7_1" material="black" class="visual"/>
179+
<geom mesh="link7_2" material="black" class="visual"/>
180+
<geom mesh="link7_3" material="black" class="visual"/>
181+
<geom mesh="link7_4" material="black" class="visual"/>
182+
<geom mesh="link7_5" material="black" class="visual"/>
183+
<geom mesh="link7_6" material="black" class="visual"/>
184+
<geom mesh="link7_7" material="white" class="visual"/>
185+
<geom mesh="link7_c" class="collision"/>
186+
</body>
187+
</body>
188+
</body>
189+
</body>
190+
</body>
191+
</body>
192+
</body>
193+
</body>
194+
</worldbody>
195+
196+
<actuator>
197+
<position class="panda" name="actuator1" joint="joint1" kp="1000" kv="20"
198+
ctrlrange="-2.8973 2.8973"/>
199+
<position class="panda" name="actuator2" joint="joint2" kp="1000" kv="20"
200+
ctrlrange="-1.7628 1.7628"/>
201+
<position class="panda" name="actuator3" joint="joint3" kp="750" kv="4"
202+
ctrlrange="-2.8973 2.8973"/>
203+
<position class="panda" name="actuator4" joint="joint4" kp="750" kv="4"
204+
ctrlrange="-3.0718 -0.0698"/>
205+
<position class="panda" name="actuator5" joint="joint5" kp="300" kv="2"
206+
forcerange="-12 12" ctrlrange="-2.8973 2.8973"/>
207+
<position class="panda" name="actuator6" joint="joint6" kp="300" kv="2" forcerange="-12 12"
208+
ctrlrange="-0.0175 3.7525"/>
209+
<position class="panda" name="actuator7" joint="joint7" kp="300" kv="2" forcerange="-12 12"/>
210+
</actuator>
211+
</mujoco>

0 commit comments

Comments
 (0)