Skip to content

Commit 0620d7f

Browse files
Merge pull request google-deepmind#131 from s1lent4gnt:lilkm/collision-pads
PiperOrigin-RevId: 719391820 Change-Id: Icb0068bf3bb808dd82e0f71bdc6cb5d9aad24ae9
2 parents aaaeb28 + 3d45d12 commit 0620d7f

File tree

4 files changed

+45
-7
lines changed

4 files changed

+45
-7
lines changed

ufactory_xarm7/README.md

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,12 @@
22

33
Requires MuJoCo 2.3.3 or later.
44

5+
## Changelog
6+
7+
- **17/12/2024**: Improved object grasping (thanks to [@s1lent4gnt](https://github.com/s1lent4gnt)) by:
8+
- Adding two collision box meshes as pads for each finger.
9+
- Setting `armature=0.1` for the joints.
10+
511
## Overview
612

713
This package contains a simplified robot description (MJCF) of the [xArm7

ufactory_xarm7/hand.xml

Lines changed: 19 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919
<default>
2020
<default class="xarm7_hand">
2121
<geom type="mesh" material="black"/>
22-
<joint range="0 0.85" axis="1 0 0" frictionloss="1"/>
22+
<joint range="0 0.85" axis="1 0 0" armature="0.1" frictionloss="1"/>
2323
<site size="0.001" rgba="1 0 0 1" group="4"/>
2424
<general biastype="affine" forcerange="-50 50" ctrlrange="0 255" gainprm="0.333" biasprm="0 -100 -10"/>
2525
<default class="spring_link">
@@ -31,6 +31,18 @@
3131
<default class="follower">
3232
<joint solreflimit="0.005 1"/>
3333
</default>
34+
<default class="visual">
35+
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
36+
</default>
37+
<default class="collision">
38+
<geom type="mesh" group="3"/>
39+
<default class="pad_box1">
40+
<geom type="box" friction="0.7" solimp="0.95 0.99 0.001" solref="0.004 1" mass="0" priority="1" size="0.015 0.002 0.0095" rgba="0.0 0.1 0.7 1"/>
41+
</default>
42+
<default class="pad_box2">
43+
<geom type="box" friction="0.6" solimp="0.95 0.99 0.001" solref="0.004 1" mass="0" priority="1" size="0.015 0.002 0.0095" rgba="0.0 0.5 0.5 1"/>
44+
</default>
45+
</default>
3446
</default>
3547
</default>
3648

@@ -48,7 +60,9 @@
4860
<inertial pos="0 -0.016413 0.029258" quat="0.697634 0.115353 -0.115353 0.697634" mass="0.048304"
4961
diaginertia="1.88037e-05 1.7493e-05 3.56792e-06"/>
5062
<joint name="left_finger_joint" axis="-1 0 0" class="follower"/>
51-
<geom material="black" mesh="left_finger"/>
63+
<geom class="visual" material="black" mesh="left_finger"/>
64+
<geom class="pad_box1" name="left_finger_pad_1" pos="0 -0.024003 0.032"/>
65+
<geom class="pad_box2" name="left_finger_pad_2" pos="0 -0.024003 0.050"/>
5266
</body>
5367
</body>
5468
<body name="left_inner_knuckle" pos="0 0.02 0.074098">
@@ -66,7 +80,9 @@
6680
<inertial pos="0 0.016413 0.029258" quat="0.697634 -0.115356 0.115356 0.697634" mass="0.048304"
6781
diaginertia="1.88038e-05 1.7493e-05 3.56779e-06"/>
6882
<joint name="right_finger_joint" class="follower"/>
69-
<geom material="black" mesh="right_finger"/>
83+
<geom class="visual" material="black" mesh="right_finger"/>
84+
<geom class="pad_box1" name="right_finger_pad_1" pos="0 0.024003 0.032"/>
85+
<geom class="pad_box2" name="right_finger_pad_2" pos="0 0.024003 0.050"/>
7086
</body>
7187
</body>
7288
<body name="right_inner_knuckle" pos="0 -0.02 0.074098">

ufactory_xarm7/xarm7.xml

Lines changed: 19 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@
2929
<default>
3030
<default class="xarm7">
3131
<geom type="mesh" material="white"/>
32-
<joint axis="0 0 1" range="-6.28319 6.28319" frictionloss="1"/>
32+
<joint axis="0 0 1" armature="0.1" range="-6.28319 6.28319" frictionloss="1"/>
3333
<general biastype="affine" ctrlrange="-6.28319 6.28319"/>
3434
<default class="size1">
3535
<joint damping="10"/>
@@ -52,6 +52,18 @@
5252
<default class="follower">
5353
<joint range="0 0.85" solreflimit="0.005 1"/>
5454
</default>
55+
<default class="visual">
56+
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
57+
</default>
58+
<default class="collision">
59+
<geom type="mesh" group="3"/>
60+
<default class="pad_box1">
61+
<geom type="box" friction="0.7" solimp="0.95 0.99 0.001" solref="0.004 1" mass="0" priority="1" size="0.015 0.002 0.0095" rgba="0.0 0.1 0.7 1"/>
62+
</default>
63+
<default class="pad_box2">
64+
<geom type="box" friction="0.6" solimp="0.95 0.99 0.001" solref="0.004 1" mass="0" priority="1" size="0.015 0.002 0.0095" rgba="0.0 0.5 0.5 1"/>
65+
</default>
66+
</default>
5567
<site size="0.001" rgba="1 0 0 1" group="4"/>
5668
</default>
5769
</default>
@@ -109,7 +121,9 @@
109121
<inertial pos="0 -0.016413 0.029258" quat="0.697634 0.115353 -0.115353 0.697634"
110122
mass="0.048304" diaginertia="1.88037e-05 1.7493e-05 3.56792e-06"/>
111123
<joint name="left_finger_joint" axis="-1 0 0" class="follower"/>
112-
<geom material="black" mesh="left_finger"/>
124+
<geom class="visual" material="black" mesh="left_finger"/>
125+
<geom class="pad_box1" name="left_finger_pad_1" pos="0 -0.024003 0.032"/>
126+
<geom class="pad_box2" name="left_finger_pad_2" pos="0 -0.024003 0.050"/>
113127
</body>
114128
</body>
115129
<body name="left_inner_knuckle" pos="0 0.02 0.074098">
@@ -127,7 +141,9 @@
127141
<inertial pos="0 0.016413 0.029258" quat="0.697634 -0.115356 0.115356 0.697634"
128142
mass="0.048304" diaginertia="1.88038e-05 1.7493e-05 3.56779e-06"/>
129143
<joint name="right_finger_joint" axis="1 0 0" class="follower"/>
130-
<geom material="black" mesh="right_finger"/>
144+
<geom class="visual" material="black" mesh="right_finger"/>
145+
<geom class="pad_box1" name="right_finger_pad_1" pos="0 0.024003 0.032"/>
146+
<geom class="pad_box2" name="right_finger_pad_2" pos="0 0.024003 0.050"/>
131147
</body>
132148
</body>
133149
<body name="right_inner_knuckle" pos="0 -0.02 0.074098">

ufactory_xarm7/xarm7_nohand.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
<default>
2222
<default class="xarm7">
2323
<geom type="mesh" material="white"/>
24-
<joint axis="0 0 1" range="-6.28319 6.28319" frictionloss="1"/>
24+
<joint axis="0 0 1" armature="0.1" range="-6.28319 6.28319" frictionloss="1"/>
2525
<general biastype="affine" ctrlrange="-6.28319 6.28319"/>
2626
<default class="size1">
2727
<joint damping="10"/>

0 commit comments

Comments
 (0)