forked from Farama-Foundation/Gymnasium-Robotics
-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathmjmodel.xml
295 lines (295 loc) · 18.8 KB
/
mjmodel.xml
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
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
<mujoco model="scene">
<compiler angle="radian" meshdir="../objs_stls/ur10e_2f85/" autolimits="true"/>
<option impratio="10" integrator="RK4"/>
<visual>
<global azimuth="120" elevation="-20"/>
<headlight diffuse="0.6 0.6 0.6" specular="0 0 0"/>
<rgba haze="0.15 0.25 0.35 1"/>
</visual>
<statistic extent="1" center="0.4 0 0.4"/>
<default class="main">
<default class="ur10e">
<material shininess="0.25"/>
<joint range="-6.28319 6.28319" armature="0.1"/>
<general ctrlrange="-6.2831 6.2831" biastype="affine" gainprm="5000 0 0 0 0 0 0 0 0 0" biasprm="0 -5000 -500 0 0 0 0 0 0 0"/>
<default class="size4">
<joint damping="10"/>
<general forcerange="-330 330"/>
</default>
<default class="size3">
<joint damping="5"/>
<general forcerange="-150 150"/>
<default class="size3_limited">
<joint range="-3.1415 3.1415"/>
<general ctrlrange="-3.1415 3.1415"/>
</default>
</default>
<default class="size2">
<joint damping="2"/>
<general forcerange="-56 56"/>
</default>
<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
</default>
<default class="collision">
<geom type="capsule" group="3"/>
<default class="eef_collision">
<geom type="cylinder"/>
</default>
</default>
</default>
<default class="2f85">
<mesh scale="0.001 0.001 0.001"/>
<general biastype="affine"/>
<default class="driver">
<joint solreflimit="0.005 1" solimplimit="0.95 0.99 0.001 0.5 2" range="0 0.8" armature="0.005" damping="0.1"/>
</default>
<default class="follower">
<joint solreflimit="0.005 1" solimplimit="0.95 0.99 0.001 0.5 2" range="-0.872664 0.872664"/>
</default>
<default class="spring_link">
<joint springref="2.62" stiffness="0.05" range="-0.296706 0.8" damping="0.00125"/>
</default>
<default class="coupler">
<joint solreflimit="0.005 1" solimplimit="0.95 0.99 0.001 0.5 2" range="-1.57 0"/>
</default>
<default class="visual2">
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
</default>
<default class="collision2">
<geom type="mesh" group="3"/>
<default class="pad_box1">
<geom size="0.011 0.004 0.009375" type="box" priority="1" friction="0.7 0.005 0.0001" solref="0.004 1" solimp="0.95 0.99 0.001 0.5 2" rgba="0.55 0.55 0.55 1"/>
</default>
<default class="pad_box2">
<geom size="0.011 0.004 0.009375" type="box" priority="1" friction="0.6 0.005 0.0001" solref="0.004 1" solimp="0.95 0.99 0.001 0.5 2" rgba="0.45 0.45 0.45 1"/>
</default>
</default>
</default>
</default>
<asset>
<texture type="skybox" builtin="gradient" rgb1="0.3 0.5 0.7" rgb2="0 0 0" width="512" height="3072"/>
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
<material name="black" class="ur10e" rgba="0.033 0.033 0.033 1"/>
<material name="jointgray" class="ur10e" rgba="0.278 0.278 0.278 1"/>
<material name="linkgray" class="ur10e" rgba="0.82 0.82 0.82 1"/>
<material name="urblue" class="ur10e" rgba="0.49 0.678 0.8 1"/>
<material name="metal" rgba="0.58 0.58 0.58 1"/>
<material name="silicone" rgba="0.1882 0.1882 0.1882 1"/>
<material name="gray" rgba="0.4627 0.4627 0.4627 1"/>
<material name="black2" rgba="0.149 0.149 0.149 1"/>
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
<material name="MatTable" rgba="0.6 0.4 0.2 1"/>
<mesh name="base_0" file="base_0.obj"/>
<mesh name="base_1" file="base_1.obj"/>
<mesh name="shoulder_0" file="shoulder_0.obj"/>
<mesh name="shoulder_1" file="shoulder_1.obj"/>
<mesh name="shoulder_2" file="shoulder_2.obj"/>
<mesh name="upperarm_0" file="upperarm_0.obj"/>
<mesh name="upperarm_1" file="upperarm_1.obj"/>
<mesh name="upperarm_2" file="upperarm_2.obj"/>
<mesh name="upperarm_3" file="upperarm_3.obj"/>
<mesh name="forearm_0" file="forearm_0.obj"/>
<mesh name="forearm_1" file="forearm_1.obj"/>
<mesh name="forearm_2" file="forearm_2.obj"/>
<mesh name="forearm_3" file="forearm_3.obj"/>
<mesh name="wrist1_0" file="wrist1_0.obj"/>
<mesh name="wrist1_1" file="wrist1_1.obj"/>
<mesh name="wrist1_2" file="wrist1_2.obj"/>
<mesh name="wrist2_0" file="wrist2_0.obj"/>
<mesh name="wrist2_1" file="wrist2_1.obj"/>
<mesh name="wrist2_2" file="wrist2_2.obj"/>
<mesh name="wrist3" file="wrist3.obj"/>
<mesh name="base_mount" class="2f85" file="base_mount.stl"/>
<mesh name="base" class="2f85" file="base.stl"/>
<mesh name="driver" class="2f85" file="driver.stl"/>
<mesh name="coupler" class="2f85" file="coupler.stl"/>
<mesh name="follower" class="2f85" file="follower.stl"/>
<mesh name="pad" class="2f85" file="pad.stl"/>
<mesh name="silicone_pad" class="2f85" file="silicone_pad.stl"/>
<mesh name="spring_link" class="2f85" file="spring_link.stl"/>
</asset>
<worldbody>
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
<light name="spotlight" target="wrist_2_link" pos="0 -1 2" dir="0 0 -1" mode="targetbodycom"/>
<light pos="0 0 1.5" dir="0 0 -1" directional="true"/>
<body name="robot0:mocap" pos="0 0 0" mocap="true" gravcomp="0">
<geom size="0.005 0.005 0.005" type="box" contype="0" conaffinity="0" rgba="255 0.5 0 0.7"/>
<geom size="1 0.005 0.005" type="box" contype="0" conaffinity="0" rgba="255 0.5 0 0.1"/>
<geom size="0.005 1 0.001" type="box" contype="0" conaffinity="0" rgba="255 0.5 0 0.1"/>
<geom size="0.005 0.005 1" type="box" contype="0" conaffinity="0" rgba="255 0.5 0 0.1"/>
</body>
<body name="base" childclass="ur10e" pos="0 0 0" quat="0.707107 0 0 0.707107" gravcomp="0">
<inertial pos="0 0 0" mass="4" diaginertia="0.00610633 0.00610633 0.01125"/>
<geom class="visual" material="black" mesh="base_0"/>
<geom class="visual" material="jointgray" mesh="base_1"/>
<body name="shoulder_link" pos="0 0 0.181" gravcomp="0">
<inertial pos="0 0 0" mass="7.778" diaginertia="0.0314743 0.0314743 0.0218756"/>
<joint name="shoulder_pan_joint" class="size4" pos="0 0 0" axis="0 0 1"/>
<geom class="visual" material="urblue" mesh="shoulder_0"/>
<geom class="visual" material="black" mesh="shoulder_1"/>
<geom class="visual" material="jointgray" mesh="shoulder_2"/>
<geom class="collision" size="0.078 0.08" pos="0 0 -0.05"/>
<body name="upper_arm_link" pos="0 0.176 0" quat="0.707107 0 0.707107 0" gravcomp="0">
<inertial pos="0 0 0.3065" mass="12.93" diaginertia="0.423074 0.423074 0.0363656"/>
<joint name="shoulder_lift_joint" class="size4" pos="0 0 0" axis="0 1 0"/>
<geom class="visual" material="black" mesh="upperarm_0"/>
<geom class="visual" material="jointgray" mesh="upperarm_1"/>
<geom class="visual" material="urblue" mesh="upperarm_2"/>
<geom class="visual" material="linkgray" mesh="upperarm_3"/>
<geom class="collision" size="0.078 0.08" pos="0 -0.05 0" quat="0.707107 0.707107 0 0"/>
<geom class="collision" size="0.06 0.3" pos="0 0 0.3"/>
<body name="forearm_link" pos="0 -0.137 0.613" gravcomp="0">
<inertial pos="0 0 0.2855" mass="3.87" diaginertia="0.11059 0.11059 0.0108844"/>
<joint name="elbow_joint" class="size3_limited" pos="0 0 0" axis="0 1 0"/>
<geom class="visual" material="urblue" mesh="forearm_0"/>
<geom class="visual" material="black" mesh="forearm_1"/>
<geom class="visual" material="jointgray" mesh="forearm_2"/>
<geom class="visual" material="linkgray" mesh="forearm_3"/>
<geom class="collision" size="0.058 0.065" pos="0 0.08 0" quat="0.707107 0.707107 0 0"/>
<geom class="collision" size="0.043 0.28" pos="0 0 0.29"/>
<body name="wrist_1_link" pos="0 0 0.571" quat="0.707107 0 0.707107 0" gravcomp="0">
<inertial pos="0 0.135 0" quat="0.5 0.5 -0.5 0.5" mass="1.96" diaginertia="0.0055125 0.00510825 0.00510825"/>
<joint name="wrist_1_joint" class="size2" pos="0 0 0" axis="0 1 0"/>
<geom class="visual" material="black" mesh="wrist1_0"/>
<geom class="visual" material="urblue" mesh="wrist1_1"/>
<geom class="visual" material="jointgray" mesh="wrist1_2"/>
<geom class="collision" size="0.05 0.07" pos="0 0.06 0" quat="0.707107 0.707107 0 0"/>
<body name="wrist_2_link" pos="0 0.135 0" gravcomp="0">
<inertial pos="0 0 0.12" quat="0.5 0.5 -0.5 0.5" mass="1.96" diaginertia="0.0055125 0.00510825 0.00510825"/>
<joint name="wrist_2_joint" class="size2" pos="0 0 0" axis="0 0 1"/>
<geom class="visual" material="black" mesh="wrist2_0"/>
<geom class="visual" material="urblue" mesh="wrist2_1"/>
<geom class="visual" material="jointgray" mesh="wrist2_2"/>
<geom class="collision" size="0.046 0.065" pos="0 0 0.05"/>
<geom class="collision" size="0.046 0.043" pos="0 0.028 0.12" quat="0.707107 0.707107 0 0"/>
<body name="wrist_3_link" pos="0 0 0.12" gravcomp="0">
<inertial pos="0 0.092 0" quat="0 0.707107 -0.707107 0" mass="0.202" diaginertia="0.000204525 0.000144346 0.000144346"/>
<joint name="wrist_3_joint" class="size2" pos="0 0 0" axis="0 1 0"/>
<geom class="visual" material="linkgray" mesh="wrist3"/>
<geom class="eef_collision" size="0.046 0.02" pos="0 0.097 0" quat="0.707107 0.707107 0 0"/>
<site name="attachment_site" pos="0 0.1 0" quat="-0.707107 0.707107 0 0" size="0.001" group="4" rgba="255 0 0 1"/>
<body name="base_mount" childclass="2f85" pos="0 0.115 0" quat="-0.707107 0.707107 0 0" gravcomp="0">
<geom class="visual2" material="black2" mesh="base_mount"/>
<geom class="collision2" mesh="base_mount"/>
<body name="base2" pos="0 0 0.0038" quat="0.707107 0 0 -0.707107" gravcomp="0">
<inertial pos="0 -2.70394e-05 0.0354675" quat="0.999999 -0.00152849 0 0" mass="0.777441" diaginertia="0.000260285 0.000225381 0.000152708"/>
<geom class="visual2" material="black2" mesh="base"/>
<geom class="collision2" mesh="base"/>
<site name="pinch" pos="0 0 0.145" group="5" rgba="255 0.9 0.9 1"/>
<body name="right_driver" pos="0 0.0306011 0.054904" gravcomp="0">
<inertial pos="2.96931e-12 0.0177547 0.00107314" quat="0.681301 0.732003 0 0" mass="0.00899563" diaginertia="1.72352e-06 1.60906e-06 3.22006e-07"/>
<joint name="right_driver_joint" class="driver" pos="0 0 0" axis="1 0 0"/>
<geom class="visual2" material="gray" mesh="driver"/>
<geom class="collision2" mesh="driver"/>
<body name="right_coupler" pos="0 0.0315 -0.0041" gravcomp="0">
<inertial pos="0 0.00301209 0.0232175" quat="0.705636 -0.0455904 0.0455904 0.705636" mass="0.0140974" diaginertia="4.16206e-06 3.52216e-06 8.88131e-07"/>
<joint name="right_coupler_joint" class="coupler" pos="0 0 0" axis="1 0 0"/>
<geom class="visual2" material="black2" mesh="coupler"/>
<geom class="collision2" mesh="coupler"/>
</body>
</body>
<body name="right_spring_link" pos="0 0.0132 0.0609" gravcomp="0">
<inertial pos="-8.65005e-09 0.0181624 0.0212658" quat="0.663403 -0.244737 0.244737 0.663403" mass="0.0221642" diaginertia="8.96853e-06 6.71733e-06 2.63931e-06"/>
<joint name="right_spring_link_joint" class="spring_link" pos="0 0 0" axis="1 0 0" springref="2.62"/>
<geom class="visual2" material="black2" mesh="spring_link"/>
<geom class="collision2" mesh="spring_link"/>
<body name="right_follower" pos="0 0.055 0.0375" gravcomp="0">
<inertial pos="0 -0.011046 0.0124786" quat="0.986437 0.164143 0 0" mass="0.0125222" diaginertia="2.67415e-06 2.4559e-06 6.02031e-07"/>
<joint name="right_follower_joint" class="follower" pos="0 -0.018 0.0065" axis="1 0 0"/>
<geom class="visual2" material="black2" mesh="follower"/>
<geom class="collision2" mesh="follower"/>
<body name="right_pad" pos="0 -0.0189 0.01352" gravcomp="0">
<inertial pos="0 -0.0025 0.0185" quat="0.707107 0 0 0.707107" mass="0.0035" diaginertia="4.73958e-07 3.64583e-07 1.23958e-07"/>
<geom name="right_pad1" class="pad_box1" pos="0 -0.0026 0.028125" mass="0"/>
<geom name="right_pad2" class="pad_box2" pos="0 -0.0026 0.009375" mass="0"/>
<geom class="visual2" mesh="pad"/>
<body name="right_silicone_pad" pos="0 0 0" gravcomp="0">
<geom class="visual2" material="black2" mesh="silicone_pad"/>
</body>
</body>
</body>
</body>
<body name="left_driver" pos="0 -0.0306011 0.054904" quat="0 0 0 1" gravcomp="0">
<inertial pos="0 0.0177547 0.00107314" quat="0.681301 0.732003 0 0" mass="0.00899563" diaginertia="1.72352e-06 1.60906e-06 3.22006e-07"/>
<joint name="left_driver_joint" class="driver" pos="0 0 0" axis="1 0 0"/>
<geom class="visual2" material="gray" mesh="driver"/>
<geom class="collision2" mesh="driver"/>
<body name="left_coupler" pos="0 0.0315 -0.0041" gravcomp="0">
<inertial pos="0 0.00301209 0.0232175" quat="0.705636 -0.0455904 0.0455904 0.705636" mass="0.0140974" diaginertia="4.16206e-06 3.52216e-06 8.88131e-07"/>
<joint name="left_coupler_joint" class="coupler" pos="0 0 0" axis="1 0 0"/>
<geom class="visual2" material="black2" mesh="coupler"/>
<geom class="collision2" mesh="coupler"/>
</body>
</body>
<body name="left_spring_link" pos="0 -0.0132 0.0609" quat="0 0 0 1" gravcomp="0">
<inertial pos="-8.65005e-09 0.0181624 0.0212658" quat="0.663403 -0.244737 0.244737 0.663403" mass="0.0221642" diaginertia="8.96853e-06 6.71733e-06 2.63931e-06"/>
<joint name="left_spring_link_joint" class="spring_link" pos="0 0 0" axis="1 0 0" springref="2.62"/>
<geom class="visual2" material="black2" mesh="spring_link"/>
<geom class="collision2" mesh="spring_link"/>
<body name="left_follower" pos="0 0.055 0.0375" gravcomp="0">
<inertial pos="0 -0.011046 0.0124786" quat="0.986437 0.164143 0 0" mass="0.0125222" diaginertia="2.67415e-06 2.4559e-06 6.02031e-07"/>
<joint name="left_follower_joint" class="follower" pos="0 -0.018 0.0065" axis="1 0 0"/>
<geom class="visual2" material="black2" mesh="follower"/>
<geom class="collision2" mesh="follower"/>
<body name="left_pad" pos="0 -0.0189 0.01352" gravcomp="0">
<inertial pos="0 -0.0025 0.0185" quat="0.707107 0 0 0.707107" mass="0.0035" diaginertia="4.73958e-07 3.64583e-07 1.23958e-07"/>
<geom name="left_pad1" class="pad_box1" pos="0 -0.0026 0.028125" mass="0"/>
<geom name="left_pad2" class="pad_box2" pos="0 -0.0026 0.009375" mass="0"/>
<geom class="visual2" mesh="pad"/>
<body name="left_silicone_pad" pos="0 0 0" gravcomp="0">
<geom class="visual2" material="black2" mesh="silicone_pad"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
<body name="floor0" pos="0.8 0.75 0" gravcomp="0">
<site name="target0" pos="0 0 0.5" size="0.02" rgba="1 0 0 1"/>
</body>
</worldbody>
<contact>
<exclude body1="wrist_3_link" body2="right_driver"/>
<exclude body1="wrist_3_link" body2="right_coupler"/>
<exclude body1="wrist_3_link" body2="right_spring_link"/>
<exclude body1="wrist_3_link" body2="right_follower"/>
<exclude body1="wrist_3_link" body2="left_driver"/>
<exclude body1="wrist_3_link" body2="left_coupler"/>
<exclude body1="wrist_3_link" body2="left_spring_link"/>
<exclude body1="wrist_3_link" body2="left_follower"/>
<exclude body1="base2" body2="right_driver"/>
<exclude body1="base2" body2="right_spring_link"/>
<exclude body1="base2" body2="left_driver"/>
<exclude body1="base2" body2="left_spring_link"/>
<exclude body1="right_coupler" body2="right_follower"/>
<exclude body1="left_coupler" body2="left_follower"/>
</contact>
<equality>
<connect body1="right_follower" body2="right_coupler" anchor="0 0 0" solref="0.005 1" solimp="0.95 0.99 0.001 0.5 2"/>
<connect body1="left_follower" body2="left_coupler" anchor="0 0 0" solref="0.005 1" solimp="0.95 0.99 0.001 0.5 2"/>
<joint joint1="right_driver_joint" joint2="left_driver_joint" polycoef="0 1 0 0 0" solref="0.005 1" solimp="0.95 0.99 0.001 0.5 2"/>
</equality>
<tendon>
<fixed name="split">
<joint joint="right_driver_joint" coef="0.5"/>
<joint joint="left_driver_joint" coef="0.5"/>
</fixed>
</tendon>
<actuator>
<general name="shoulder_pan" class="size4" joint="shoulder_pan_joint" actdim="0"/>
<general name="shoulder_lift" class="size4" joint="shoulder_lift_joint" actdim="0"/>
<general name="elbow" class="size3_limited" joint="elbow_joint" actdim="0"/>
<general name="wrist_1" class="size2" joint="wrist_1_joint" actdim="0"/>
<general name="wrist_2" class="size2" joint="wrist_2_joint" actdim="0"/>
<general name="wrist_3" class="size2" joint="wrist_3_joint" actdim="0"/>
<general name="fingers_actuator" class="2f85" tendon="split" ctrlrange="0 255" forcerange="-5 5" actdim="0" gainprm="0.313725 0 0 0 0 0 0 0 0 0" biasprm="0 -100 -10 0 0 0 0 0 0 0"/>
</actuator>
</mujoco>