mani-skill-nightly 2025.10.21.2002__py3-none-any.whl → 2025.10.21.2011__py3-none-any.whl

This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.

Potentially problematic release.


This version of mani-skill-nightly might be problematic. Click here for more details.

@@ -0,0 +1,554 @@
1
+ <robot name="ability_hand">
2
+ <link name="root">
3
+ <inertial>
4
+ <mass value="0"/>
5
+ <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
6
+ </inertial>
7
+ </link>
8
+ <link name="root_arm_1_link_1">
9
+ <inertial>
10
+ <mass value="0"/>
11
+ <inertia ixx="0.00" ixy="0.00" ixz="0.00" iyy="0.00" iyz="0.00" izz="0.00"/>
12
+ </inertial>
13
+ </link>
14
+ <link name="root_arm_1_link_2">
15
+ <inertial>
16
+ <mass value="0"/>
17
+ <inertia ixx="0.00" ixy="0.00" ixz="0.00" iyy="0.00" iyz="0.00" izz="0.00"/>
18
+ </inertial>
19
+ </link>
20
+ <link name="root_arm_1_link_3">
21
+ <inertial>
22
+ <mass value="0"/>
23
+ <inertia ixx="0.00" ixy="0.00" ixz="0.00" iyy="0.00" iyz="0.00" izz="0.00"/>
24
+ </inertial>
25
+ </link>
26
+ <link name="root_arm_1_link_4">
27
+ <inertial>
28
+ <mass value="0"/>
29
+ <inertia ixx="0.00" ixy="0.00" ixz="0.00" iyy="0.00" iyz="0.00" izz="0.00"/>
30
+ </inertial>
31
+ </link>
32
+ <link name="root_arm_1_link_5">
33
+ <inertial>
34
+ <mass value="0"/>
35
+ <inertia ixx="0.00" ixy="0.00" ixz="0.00" iyy="0.00" iyz="0.00" izz="0.00"/>
36
+ </inertial>
37
+ </link>
38
+ <joint name="root_x_axis_joint" type="prismatic">
39
+ <parent link="root" />
40
+ <child link="root_arm_1_link_1" />
41
+ <axis xyz="1 0 0" />
42
+ <limit effort="100" lower="-20" upper="20" velocity="0.5" />
43
+ <dynamics damping="10.0" friction="10" />
44
+ </joint>
45
+ <joint name="root_y_axis_joint" type="prismatic">
46
+ <parent link="root_arm_1_link_1" />
47
+ <child link="root_arm_1_link_2" />
48
+ <axis xyz="0 1 0" />
49
+ <limit effort="100" lower="-20" upper="20" velocity="0.5" />
50
+ <dynamics damping="10" friction="10" />
51
+ </joint>
52
+ <joint name="root_z_axis_joint" type="prismatic">
53
+ <parent link="root_arm_1_link_2" />
54
+ <child link="root_arm_1_link_3" />
55
+ <axis xyz="0 0 1" />
56
+ <limit effort="100" lower="-20" upper="20" velocity="0.5" />
57
+ <dynamics damping="10" friction="10" />
58
+ </joint>
59
+ <joint name="root_x_rot_joint" type="revolute">
60
+ <parent link="root_arm_1_link_3" />
61
+ <child link="root_arm_1_link_4" />
62
+ <axis xyz="1 0 0" />
63
+ <limit effort="100" lower="-20" upper="20" velocity="0.5" />
64
+ <dynamics damping="10" friction="10" />
65
+ </joint>
66
+ <joint name="root_y_rot_joint" type="revolute">
67
+ <parent link="root_arm_1_link_4" />
68
+ <child link="root_arm_1_link_5" />
69
+ <axis xyz="0 1 0" />
70
+ <limit effort="100" lower="-20" upper="20" velocity="0.5" />
71
+ <dynamics damping="10" friction="10" />
72
+ </joint>
73
+ <joint name="root_z_rot_joint" type="revolute">
74
+ <parent link="root_arm_1_link_5" />
75
+ <child link="base_link" />
76
+ <axis xyz="0 0 1" />
77
+ <limit effort="100" lower="-20" upper="20" velocity="0.5" />
78
+ <dynamics damping="10" friction="10" />
79
+ </joint>
80
+
81
+ <link name="base_link"/>
82
+ <joint name="base_joint" type="fixed">
83
+ <parent link="base_link"/>
84
+ <child link="base"/>
85
+ <origin xyz="0 0 0" rpy="0 0 -1.57079"/>
86
+ </joint>
87
+ <link name="base">
88
+ <visual name="wrist_mesh">
89
+ <origin rpy="0 0 0" xyz="0 0 0"/>
90
+ <geometry>
91
+ <mesh filename="meshes/visual/wristmesh.obj"/>
92
+ </geometry>
93
+ </visual>
94
+ <collision>
95
+ <origin xyz="0 0 0" rpy="0 0 0"/>
96
+ <geometry>
97
+ <mesh filename="meshes/collision/wristmesh_C.obj"/>
98
+ </geometry>
99
+ </collision>
100
+ <inertial> <!-- the mass and inertia here are NOT correct -->
101
+ <mass value="0.200"/>
102
+ <inertia ixx="978.26e-6" ixy="87.34e-6" ixz="322.99e-6" iyy="1244.78e-6" iyz="244.74e-6" izz="456.22e-6"/>
103
+ <origin xyz="22.41911e-3 -0.15798201e-3 -0.01319866e-3" rpy="0 0 0"/>
104
+ </inertial>
105
+ </link>
106
+ <joint name="wrist2thumb" type="fixed">
107
+ <parent link="base"/>
108
+ <child link="thumb_base"/>
109
+ <origin xyz="24.0476665e-3 3.78124745e-3 32.32964923e-3" rpy="3.14148426 0.08848813 3.14036612"/>
110
+ </joint>
111
+ <link name="thumb_base">
112
+ <inertial>
113
+ <mass value="0.400"/>
114
+ <inertia ixx="978.26e-6" ixy="87.34e-6" ixz="322.99e-6" iyy="1244.78e-6" iyz="244.74e-6" izz="456.22e-6"/>
115
+ <origin xyz="22.41911e-3 -0.15798201e-3 -0.01319866e-3" rpy="0 0 0"/>
116
+ </inertial>
117
+ <visual name="palm_mesh">
118
+ <origin rpy="0 0 0" xyz="0 0 0"/>
119
+ <geometry>
120
+ <mesh filename="meshes/visual/FB_palm_ref.obj"/>
121
+ </geometry>
122
+ </visual>
123
+ <collision> <!-- thumb_base -->
124
+ <origin xyz="0 0 0" rpy="0 0 0"/>
125
+ <geometry>
126
+ <mesh filename="meshes/collision/FB_palm_ref.obj"/>
127
+ </geometry>
128
+ </collision>
129
+ </link>
130
+ <link name="thumb_L1">
131
+ <inertial>
132
+ <mass value="0.00268342"/>
133
+ <inertia ixx="0.16931e-4" ixy="-0.076214e-4" ixz="-0.16959148e-4" iyy="0.77769934e-4" iyz="0.0156622e-4" izz="0.7249122e-4"/>
134
+ <origin rpy="0 0 0" xyz="14.606e-3 -1.890854e-3 -3.1155356e-3"/>
135
+ </inertial>
136
+ <visual name="thumb_mesh_1">
137
+ <origin xyz="27.8283501e-3 0 -14.7507000e-3" rpy="4.450589592585541 0 0"/>
138
+ <geometry>
139
+ <mesh filename="meshes/visual/thumb-F1.obj"/>
140
+ </geometry>
141
+ </visual>
142
+ <collision> <!-- thumb_L1 -->
143
+ <origin xyz="27.8283501e-3 0 -14.7507000e-3" rpy="4.450589592585541 0 0"/>
144
+ <geometry>
145
+ <mesh filename="meshes/collision/thumb-F1_C.obj"/>
146
+ </geometry>
147
+ </collision>
148
+ </link>
149
+ <link name="thumb_L2">
150
+ <inertial>
151
+ <mass value="0.0055"/>
152
+ <inertia ixx="4.4789082e-4" ixy="4.4789082e-4" ixz="-0.62144934e-4" iyy="15.600996e-4" iyz="-0.07466143e-4" izz="17.908554e-4"/>
153
+ <origin rpy="0 0 0" xyz="30.020522e-3 5.59476e-3 -4.1504356e-3"/>
154
+ </inertial>
155
+ <visual name="thumb_mesh_2">
156
+ <origin xyz="65.18669e-3 23.34021e-3 -3.93483e-3" rpy="3.141592 0 0.343830"/>
157
+ <geometry>
158
+ <mesh filename="meshes/visual/thumb-F2.obj"/>
159
+ </geometry>
160
+ </visual>
161
+ <collision> <!-- thumb_L2 -->
162
+ <origin xyz="65.18669e-3 23.34021e-3 -3.93483e-3" rpy="3.141592 0 0.343830"/>
163
+ <geometry>
164
+ <mesh filename="meshes/collision/thumb-F2_C.obj"/>
165
+ </geometry>
166
+ </collision>
167
+ </link>
168
+ <joint name="thumb_q1" type="revolute">
169
+ <parent link="thumb_base"/>
170
+ <child link="thumb_L1"/>
171
+ <origin xyz="0 0 0" rpy="0 0 3.330437"/>
172
+ <axis xyz="0 0 1"/>
173
+ <limit lower="-2.0943951" upper="0" effort="1.2" velocity="40.338888721"/> <!-- angles in rad, efforts in N-m, velocity in rad/s -->
174
+ <dynamics damping="0.001" friction="0.001"/> <!-- Friction coefficient is not from quantitative measurement -->
175
+ </joint>
176
+ <joint name="thumb_q2" type="revolute">
177
+ <parent link="thumb_L1"/>
178
+ <child link="thumb_L2"/>
179
+ <origin xyz="27.8283501e-3 0 -14.7507000e-3" rpy="4.450589592585541 0 0"/>
180
+ <axis xyz="0 0 1"/>
181
+ <limit lower="0" upper="2.0943951" effort="6.0" velocity="8.0677777442"/> <!-- angles in rad, efforts in N-m, velocity in rad/s -->
182
+ <dynamics damping="0.001" friction="0.001"/> <!-- Friction coefficient is not from quantitative measurement -->
183
+ </joint>
184
+ <link name="thumb_tip"/>
185
+ <joint name="thumb_tip_joint" type="fixed">
186
+ <parent link="thumb_L2"/>
187
+ <child link="thumb_tip"/>
188
+ <origin rpy="0 0 0" xyz="0.065 0.016 0"/>
189
+ </joint>
190
+ <link name="index_L1">
191
+ <inertial>
192
+ <mass value="0.00635888"/>
193
+ <inertia ixx="0.29766e-4" ixy="-0.06447133e-4" ixz="-0.00423315e-4" iyy="3.6947967e-4" iyz="0.00083028e-4" izz="3.8176336e-4"/>
194
+ <origin xyz="22.41911e-3 -0.15798201e-3 -0.01319866e-3" rpy="0 0 0"/>
195
+ </inertial>
196
+ <visual name="index_mesh_1">
197
+ <origin xyz="38.472723e-3 3.257695e-3 0.000000" rpy="0 0 0.084474"/>
198
+ <geometry>
199
+ <mesh filename="meshes/visual/idx-F1.obj"/>
200
+ </geometry>
201
+ </visual>
202
+ <collision> <!-- index_L1 -->
203
+ <origin xyz="0.036 -0.00175 0" rpy="0 0 0"/>
204
+ <geometry>
205
+ <sphere radius="0.0085"/>
206
+ </geometry>
207
+ </collision>
208
+ <collision>
209
+ <origin xyz="0.019 -0.0045 0" rpy="0 0 0.0845"/>
210
+ <geometry>
211
+ <box size="0.028 0.012 0.016"/>
212
+ </geometry>
213
+ </collision>
214
+ <collision>
215
+ <origin xyz="0.018 0.006 0" rpy="0 0 0.0845"/>
216
+ <geometry>
217
+ <box size="0.02 0.01 0.016"/>
218
+ </geometry>
219
+ </collision>
220
+ <collision>
221
+ <origin xyz="-0.001 0 0.007" rpy="0 0 0.0845"/>
222
+ <geometry>
223
+ <box size="0.012 0.012 0.002"/>
224
+ </geometry>
225
+ </collision>
226
+ <collision>
227
+ <origin xyz="-0.001 0 -0.007" rpy="0 0 0.0845"/>
228
+ <geometry>
229
+ <box size="0.012 0.012 0.002"/>
230
+ </geometry>
231
+ </collision>
232
+ </link>
233
+ <link name="index_L2">
234
+ <inertial>
235
+ <mass value="0.00645"/>
236
+ <inertia ixx="0.82671e-4" ixy="-1.08876e-4" ixz="-0.00037e-4" iyy="1.98028e-4" iyz="0.00081e-4" izz="2.64638e-4"/>
237
+ <origin rpy="0 0 0" xyz="13.36818e-3 -8.75392e-3 -0.02886e-3"/>
238
+ </inertial>
239
+ <visual name="index_mesh_2">
240
+ <origin rpy="0 0 0" xyz="9.1241e-3 0 0"/>
241
+ <geometry>
242
+ <mesh filename="meshes/visual/idx-F2.obj"/>
243
+ </geometry>
244
+ </visual>
245
+ <collision> <!-- index_L2 -->
246
+ <origin xyz="0 0 0" rpy="0 0 0"/>
247
+ <geometry>
248
+ <mesh filename="meshes/collision/idx-F2_C.obj"/>
249
+ </geometry>
250
+ </collision>
251
+ <collision>
252
+ <origin xyz="0.03 -0.016 0" rpy="0 0 0"/>
253
+ <geometry>
254
+ <sphere radius="0.007"/>
255
+ </geometry>
256
+ </collision>
257
+ </link>
258
+ <joint name="index_q1" type="revolute">
259
+ <parent link="thumb_base"/>
260
+ <child link="index_L1"/>
261
+ <origin xyz="-9.49e-3 -13.04e-3 -62.95e-3" rpy="-1.982050 1.284473 -2.090591"/>
262
+ <axis xyz="0 0 1"/>
263
+ <limit lower="0" upper="2.0943951" effort="6.0" velocity="8.0677777442"/> <!-- angles in rad, efforts in N-m, velocity in rad/s -->
264
+ <dynamics damping="0.001" friction="0.001"/> <!-- Friction coefficient is not from quantitative measurement -->
265
+ </joint>
266
+ <joint name="index_q2" type="revolute">
267
+ <parent link="index_L1"/>
268
+ <child link="index_L2"/>
269
+ <origin xyz="38.472723e-3 3.257695e-3 0.000000e-3" rpy="0 0 0.084474"/>
270
+ <axis xyz="0 0 1"/>
271
+ <limit lower="0.0" upper="2.6586" effort="6.0" velocity="8.0677777442"/> <!-- angles in rad, efforts in N-m, velocity in rad/s -->
272
+ <dynamics damping="0.001" friction="0.001"/> <!-- Friction coefficient is not from quantitative measurement -->
273
+ <!-- <mimic joint="index_q1" multiplier="1.05851325" offset="0.72349796"/> -->
274
+ </joint>
275
+ <link name="index_tip"/>
276
+ <joint name="index_tip_joint" type="fixed">
277
+ <parent link="index_L2"/>
278
+ <child link="index_tip"/>
279
+ <origin rpy="0 0 0" xyz="0.035 -0.018 0"/>
280
+ </joint>
281
+ <link name="middle_L1">
282
+ <inertial>
283
+ <mass value="0.00635888"/>
284
+ <inertia ixx="0.29766e-4" ixy="-0.06447133e-4" ixz="-0.00423315e-4" iyy="3.6947967e-4" iyz="0.00083028e-4" izz="3.8176336e-4"/>
285
+ <origin xyz="22.41911e-3 -0.15798201e-3 -0.01319866e-3" rpy="0 0 0"/>
286
+ </inertial>
287
+ <visual name="middle_mesh_1">
288
+ <origin xyz="38.472723e-3 3.257695e-3 0.000000" rpy="0 0 0.084474"/>
289
+ <geometry>
290
+ <mesh filename="meshes/visual/idx-F1.obj"/>
291
+ </geometry>
292
+ </visual>
293
+ <collision> <!-- middle_L1 -->
294
+ <origin xyz="0.036 -0.00175 0" rpy="0 0 0"/>
295
+ <geometry>
296
+ <sphere radius="0.0085"/>
297
+ </geometry>
298
+ </collision>
299
+ <collision>
300
+ <origin xyz="0.019 -0.0045 0" rpy="0 0 0.0845"/>
301
+ <geometry>
302
+ <box size="0.028 0.012 0.016"/>
303
+ </geometry>
304
+ </collision>
305
+ <collision>
306
+ <origin xyz="0.018 0.006 0" rpy="0 0 0.0845"/>
307
+ <geometry>
308
+ <box size="0.02 0.01 0.016"/>
309
+ </geometry>
310
+ </collision>
311
+ <collision>
312
+ <origin xyz="-0.001 0 0.007" rpy="0 0 0.0845"/>
313
+ <geometry>
314
+ <box size="0.012 0.012 0.002"/>
315
+ </geometry>
316
+ </collision>
317
+ <collision>
318
+ <origin xyz="-0.001 0 -0.007" rpy="0 0 0.0845"/>
319
+ <geometry>
320
+ <box size="0.012 0.012 0.002"/>
321
+ </geometry>
322
+ </collision>
323
+ </link>
324
+ <link name="middle_L2">
325
+ <inertial>
326
+ <mass value="0.00645"/>
327
+ <inertia ixx="0.82671e-4" ixy="-1.08876e-4" ixz="-0.00037e-4" iyy="1.98028e-4" iyz="0.00081e-4" izz="2.64638e-4"/>
328
+ <origin rpy="0 0 0" xyz="13.36818e-3 -8.75392e-3 -0.02886e-3"/>
329
+ </inertial>
330
+ <visual name="middle_mesh_2">
331
+ <origin rpy="0 0 0" xyz="9.1241e-3 0 0"/>
332
+ <geometry>
333
+ <mesh filename="meshes/visual/idx-F2.obj"/>
334
+ </geometry>
335
+ </visual>
336
+ <collision> <!-- middle_L2 -->
337
+ <origin xyz="0 0 0" rpy="0 0 0"/>
338
+ <geometry>
339
+ <mesh filename="meshes/collision/idx-F2_C.obj"/>
340
+ </geometry>
341
+ </collision>
342
+ <collision>
343
+ <origin xyz="0.03 -0.016 0" rpy="0 0 0"/>
344
+ <geometry>
345
+ <sphere radius="0.007"/>
346
+ </geometry>
347
+ </collision>
348
+ </link>
349
+ <joint name="middle_q1" type="revolute">
350
+ <parent link="thumb_base"/>
351
+ <child link="middle_L1"/>
352
+ <origin xyz="9.653191e-3 -15.310271e-3 -67.853949e-3" rpy="-1.860531 1.308458 -1.896217"/>
353
+ <limit lower="0" upper="2.0943951" effort="6.0" velocity="8.0677777442"/> <!-- angles in rad, efforts in N-m, velocity in rad/s -->
354
+ <dynamics damping="0.001" friction="0.001"/> <!-- Friction coefficient is not from quantitative measurement -->
355
+ <axis xyz="0 0 1"/>
356
+ </joint>
357
+ <joint name="middle_q2" type="revolute">
358
+ <parent link="middle_L1"/>
359
+ <child link="middle_L2"/>
360
+ <origin xyz="38.472723e-3 3.257695e-3 0.000000" rpy="0 0 0.084474"/>
361
+ <axis xyz="0 0 1"/>
362
+ <limit lower="0.0" upper="2.6586" effort="6.0" velocity="8.0677777442"/> <!-- angles in rad, efforts in N-m, velocity in rad/s -->
363
+ <dynamics damping="0.001" friction="0.001"/> <!-- Friction coefficient is not from quantitative measurement -->
364
+ <!-- <mimic joint="middle_q1" multiplier="1.05851325" offset="0.72349796"/> -->
365
+ </joint>
366
+ <link name="middle_tip"/>
367
+ <joint name="middle_tip_joint" type="fixed">
368
+ <parent link="middle_L2"/>
369
+ <child link="middle_tip"/>
370
+ <origin rpy="0 0 0" xyz="0.035 -0.018 0"/>
371
+ </joint>
372
+ <link name="ring_L1">
373
+ <inertial>
374
+ <mass value="0.00635888"/>
375
+ <inertia ixx="0.29766e-4" ixy="-0.06447133e-4" ixz="-0.00423315e-4" iyy="3.6947967e-4" iyz="0.00083028e-4" izz="3.8176336e-4"/>
376
+ <origin xyz="22.41911e-3 -0.15798201e-3 -0.01319866e-3" rpy="0 0 0"/>
377
+ </inertial>
378
+ <visual name="ring_mesh_1">
379
+ <origin xyz="38.472723e-3 3.257695e-3 0.000000" rpy="0 0 0.084474"/>
380
+ <geometry>
381
+ <mesh filename="meshes/visual/idx-F1.obj"/>
382
+ </geometry>
383
+ </visual>
384
+ <collision> <!-- ring_L1 -->
385
+ <origin xyz="0.036 -0.00175 0" rpy="0 0 0"/>
386
+ <geometry>
387
+ <sphere radius="0.0085"/>
388
+ </geometry>
389
+ </collision>
390
+ <collision>
391
+ <origin xyz="0.019 -0.0045 0" rpy="0 0 0.0845"/>
392
+ <geometry>
393
+ <box size="0.028 0.012 0.016"/>
394
+ </geometry>
395
+ </collision>
396
+ <collision>
397
+ <origin xyz="0.018 0.006 0" rpy="0 0 0.0845"/>
398
+ <geometry>
399
+ <box size="0.02 0.01 0.016"/>
400
+ </geometry>
401
+ </collision>
402
+ <collision>
403
+ <origin xyz="-0.001 0 0.007" rpy="0 0 0.0845"/>
404
+ <geometry>
405
+ <box size="0.012 0.012 0.002"/>
406
+ </geometry>
407
+ </collision>
408
+ <collision>
409
+ <origin xyz="-0.001 0 -0.007" rpy="0 0 0.0845"/>
410
+ <geometry>
411
+ <box size="0.012 0.012 0.002"/>
412
+ </geometry>
413
+ </collision>
414
+ </link>
415
+ <link name="ring_L2">
416
+ <inertial>
417
+ <mass value="0.00645"/>
418
+ <inertia ixx="0.82671e-4" ixy="-1.08876e-4" ixz="-0.00037e-4" iyy="1.98028e-4" iyz="0.00081e-4" izz="2.64638e-4"/>
419
+ <origin rpy="0 0 0" xyz="13.36818e-3 -8.75392e-3 -0.02886e-3"/>
420
+ </inertial>
421
+ <visual name="ring_mesh_2">
422
+ <origin rpy="0 0 0" xyz="9.1241e-3 0 0"/>
423
+ <geometry>
424
+ <mesh filename="meshes/visual/idx-F2.obj"/>
425
+ </geometry>
426
+ </visual>
427
+ <collision> <!-- ring_L2 -->
428
+ <origin xyz="0 0 0" rpy="0 0 0"/>
429
+ <geometry>
430
+ <mesh filename="meshes/collision/idx-F2_C.obj"/>
431
+ </geometry>
432
+ </collision>
433
+ <collision>
434
+ <origin xyz="0.03 -0.016 0" rpy="0 0 0"/>
435
+ <geometry>
436
+ <sphere radius="0.007"/>
437
+ </geometry>
438
+ </collision>
439
+ </link>
440
+ <joint name="ring_q1" type="revolute">
441
+ <parent link="thumb_base"/>
442
+ <child link="ring_L1"/>
443
+ <origin xyz="29.954260e-3 -14.212492e-3 -67.286105e-3" rpy="-1.716598 1.321452 -1.675862"/>
444
+ <limit lower="0" upper="2.0943951" effort="6.0" velocity="8.0677777442"/> <!-- angles in rad, efforts in N-m, velocity in rad/s -->
445
+ <dynamics damping="0.001" friction="0.001"/> <!-- Friction coefficient is not from quantitative measurement -->
446
+ <axis xyz="0 0 1"/>
447
+ </joint>
448
+ <joint name="ring_q2" type="revolute">
449
+ <parent link="ring_L1"/>
450
+ <child link="ring_L2"/>
451
+ <origin xyz="38.472723e-3 3.257695e-3 0.000000" rpy="0 0 0.084474"/>
452
+ <axis xyz="0 0 1"/>
453
+ <limit lower="0.0" upper="2.6586" effort="6.0" velocity="8.0677777442"/> <!-- angles in rad, efforts in N-m, velocity in rad/s -->
454
+ <dynamics damping="0.001" friction="0.001"/> <!-- Friction coefficient is not from quantitative measurement -->
455
+ <!-- <mimic joint="ring_q1" multiplier="1.05851325" offset="0.72349796"/> -->
456
+ </joint>
457
+ <link name="ring_tip"/>
458
+ <joint name="ring_tip_joint" type="fixed">
459
+ <parent link="ring_L2"/>
460
+ <child link="ring_tip"/>
461
+ <origin rpy="0 0 0" xyz="0.035 -0.018 0"/>
462
+ </joint>
463
+ <link name="pinky_L1">
464
+ <inertial>
465
+ <mass value="0.00635888"/>
466
+ <inertia ixx="0.29766e-4" ixy="-0.06447133e-4" ixz="-0.00423315e-4" iyy="3.6947967e-4" iyz="0.00083028e-4" izz="3.8176336e-4"/>
467
+ <origin xyz="22.41911e-3 -0.15798201e-3 -0.01319866e-3" rpy="0 0 0"/>
468
+ </inertial>
469
+ <visual name="pinky_mesh_1">
470
+ <origin xyz="38.472723e-3 3.257695e-3 0.000000" rpy="0 0 0.084474"/>
471
+ <geometry>
472
+ <mesh filename="meshes/visual/idx-F1.obj"/>
473
+ </geometry>
474
+ </visual>
475
+ <collision> <!-- pinky_L1 -->
476
+ <origin xyz="0.036 -0.00175 0" rpy="0 0 0"/>
477
+ <geometry>
478
+ <sphere radius="0.0085"/>
479
+ </geometry>
480
+ </collision>
481
+ <collision>
482
+ <origin xyz="0.019 -0.0045 0" rpy="0 0 0.0845"/>
483
+ <geometry>
484
+ <box size="0.028 0.012 0.016"/>
485
+ </geometry>
486
+ </collision>
487
+ <collision>
488
+ <origin xyz="0.018 0.006 0" rpy="0 0 0.0845"/>
489
+ <geometry>
490
+ <box size="0.02 0.01 0.016"/>
491
+ </geometry>
492
+ </collision>
493
+ <collision>
494
+ <origin xyz="-0.001 0 0.007" rpy="0 0 0.0845"/>
495
+ <geometry>
496
+ <box size="0.012 0.012 0.002"/>
497
+ </geometry>
498
+ </collision>
499
+ <collision>
500
+ <origin xyz="-0.001 0 -0.007" rpy="0 0 0.0845"/>
501
+ <geometry>
502
+ <box size="0.012 0.012 0.002"/>
503
+ </geometry>
504
+ </collision>
505
+ </link>
506
+ <link name="pinky_L2">
507
+ <inertial>
508
+ <mass value="0.00645"/>
509
+ <inertia ixx="0.82671e-4" ixy="-1.08876e-4" ixz="-0.00037e-4" iyy="1.98028e-4" iyz="0.00081e-4" izz="2.64638e-4"/>
510
+ <origin rpy="0 0 0" xyz="13.36818e-3 -8.75392e-3 -0.02886e-3"/>
511
+ </inertial>
512
+ <visual name="pinky_mesh_2">
513
+ <origin rpy="0 0 0" xyz="9.1241e-3 0 0"/>
514
+ <geometry>
515
+ <mesh filename="meshes/visual/idx-F2.obj"/>
516
+ </geometry>
517
+ </visual>
518
+ <collision> <!-- pinky_L2 -->
519
+ <origin xyz="0 0 0" rpy="0 0 0"/>
520
+ <geometry>
521
+ <mesh filename="meshes/collision/idx-F2_C.obj"/>
522
+ </geometry>
523
+ </collision>
524
+ <collision>
525
+ <origin xyz="0.03 -0.016 0" rpy="0 0 0"/>
526
+ <geometry>
527
+ <sphere radius="0.007"/>
528
+ </geometry>
529
+ </collision>
530
+ </link>
531
+ <joint name="pinky_q1" type="revolute">
532
+ <parent link="thumb_base"/>
533
+ <child link="pinky_L1"/>
534
+ <origin xyz="49.521293e-3 -11.004583e-3 -63.029065e-3" rpy="-1.765110 1.322220 -1.658383"/>
535
+ <limit lower="0" upper="2.0943951" effort="6.0" velocity="8.0677777442"/> <!-- angles in rad, efforts in N-m, velocity in rad/s -->
536
+ <dynamics damping="0.001" friction="0.001"/> <!-- Friction coefficient is not from quantitative measurement -->
537
+ <axis xyz="0 0 1"/>
538
+ </joint>
539
+ <joint name="pinky_q2" type="revolute">
540
+ <parent link="pinky_L1"/>
541
+ <child link="pinky_L2"/>
542
+ <origin xyz="38.472723e-3 3.257695e-3 0.000000" rpy="0 0 0.084474"/>
543
+ <limit lower="0.0" upper="2.6586" effort="6.0" velocity="8.0677777442"/> <!-- angles in rad, efforts in N-m, velocity in rad/s -->
544
+ <dynamics damping="0.001" friction="0.001"/> <!-- Friction coefficient is not from quantitative measurement -->
545
+ <axis xyz="0 0 1"/>
546
+ <!-- <mimic joint="pinky_q1" multiplier="1.05851325" offset="0.72349796"/> -->
547
+ </joint>
548
+ <link name="pinky_tip"/>
549
+ <joint name="pinky_tip_joint" type="fixed">
550
+ <parent link="pinky_L2"/>
551
+ <child link="pinky_tip"/>
552
+ <origin rpy="0 0 0" xyz="0.035 -0.018 0"/>
553
+ </joint>
554
+ </robot>