Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Better grasping for xArm7 #131

Open
wants to merge 4 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions ufactory_xarm7/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,14 @@

Requires MuJoCo 2.3.3 or later.

## Changelog

- **17/12/2024**: Improved object grasping by:
- Adding two collision box meshes as pads for each finger.
- Setting `armature=0.1` for the joints.

These changes resolve [issue #83](https://github.com/google-deepmind/mujoco_menagerie/issues/83) and are implemented in [PR #131](https://github.com/google-deepmind/mujoco_menagerie/pull/131).
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'd prefer removing this part if possible (the issue/PR part).

BTW, feel free to add your name next to "Improved object grasping" --> (thanks to @s1lent4gnt)

Copy link
Author

@s1lent4gnt s1lent4gnt Dec 18, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I've corrected it. Thanks!


## Overview

This package contains a simplified robot description (MJCF) of the [xArm7
Expand Down
22 changes: 19 additions & 3 deletions ufactory_xarm7/hand.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
<default>
<default class="xarm7_hand">
<geom type="mesh" material="black"/>
<joint range="0 0.85" axis="1 0 0" frictionloss="1"/>
<joint range="0 0.85" axis="1 0 0" armature="0.1" frictionloss="1"/>
<site size="0.001" rgba="1 0 0 1" group="4"/>
<general biastype="affine" forcerange="-50 50" ctrlrange="0 255" gainprm="0.333" biasprm="0 -100 -10"/>
<default class="spring_link">
Expand All @@ -31,6 +31,18 @@
<default class="follower">
<joint solreflimit="0.005 1"/>
</default>
<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
</default>
<default class="collision">
<geom type="mesh" group="3"/>
<default class="pad_box1">
<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"/>
</default>
<default class="pad_box2">
<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"/>
</default>
</default>
</default>
</default>

Expand All @@ -48,7 +60,9 @@
<inertial pos="0 -0.016413 0.029258" quat="0.697634 0.115353 -0.115353 0.697634" mass="0.048304"
diaginertia="1.88037e-05 1.7493e-05 3.56792e-06"/>
<joint name="left_finger_joint" axis="-1 0 0" class="follower"/>
<geom material="black" mesh="left_finger"/>
<geom class="visual" material="black" mesh="left_finger"/>
<geom class="pad_box1" name="left_finger_pad_1" pos="0 -0.024003 0.032"/>
<geom class="pad_box2" name="left_finger_pad_2" pos="0 -0.024003 0.050"/>
</body>
</body>
<body name="left_inner_knuckle" pos="0 0.02 0.074098">
Expand All @@ -66,7 +80,9 @@
<inertial pos="0 0.016413 0.029258" quat="0.697634 -0.115356 0.115356 0.697634" mass="0.048304"
diaginertia="1.88038e-05 1.7493e-05 3.56779e-06"/>
<joint name="right_finger_joint" class="follower"/>
<geom material="black" mesh="right_finger"/>
<geom class="visual" material="black" mesh="right_finger"/>
<geom class="pad_box1" name="right_finger_pad_1" pos="0 0.024003 0.032"/>
<geom class="pad_box2" name="right_finger_pad_2" pos="0 0.024003 0.050"/>
</body>
</body>
<body name="right_inner_knuckle" pos="0 -0.02 0.074098">
Expand Down
22 changes: 19 additions & 3 deletions ufactory_xarm7/xarm7.xml
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
<default>
<default class="xarm7">
<geom type="mesh" material="white"/>
<joint axis="0 0 1" range="-6.28319 6.28319" frictionloss="1"/>
<joint axis="0 0 1" armature="0.1" range="-6.28319 6.28319" frictionloss="1"/>
<general biastype="affine" ctrlrange="-6.28319 6.28319"/>
<default class="size1">
<joint damping="10"/>
Expand All @@ -52,6 +52,18 @@
<default class="follower">
<joint range="0 0.85" solreflimit="0.005 1"/>
</default>
<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
</default>
<default class="collision">
<geom type="mesh" group="3"/>
<default class="pad_box1">
<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"/>
</default>
<default class="pad_box2">
<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"/>
</default>
</default>
<site size="0.001" rgba="1 0 0 1" group="4"/>
</default>
</default>
Expand Down Expand Up @@ -109,7 +121,9 @@
<inertial pos="0 -0.016413 0.029258" quat="0.697634 0.115353 -0.115353 0.697634"
mass="0.048304" diaginertia="1.88037e-05 1.7493e-05 3.56792e-06"/>
<joint name="left_finger_joint" axis="-1 0 0" class="follower"/>
<geom material="black" mesh="left_finger"/>
<geom class="visual" material="black" mesh="left_finger"/>
<geom class="pad_box1" name="left_finger_pad_1" pos="0 -0.024003 0.032"/>
<geom class="pad_box2" name="left_finger_pad_2" pos="0 -0.024003 0.050"/>
</body>
</body>
<body name="left_inner_knuckle" pos="0 0.02 0.074098">
Expand All @@ -127,7 +141,9 @@
<inertial pos="0 0.016413 0.029258" quat="0.697634 -0.115356 0.115356 0.697634"
mass="0.048304" diaginertia="1.88038e-05 1.7493e-05 3.56779e-06"/>
<joint name="right_finger_joint" axis="1 0 0" class="follower"/>
<geom material="black" mesh="right_finger"/>
<geom class="visual" material="black" mesh="right_finger"/>
<geom class="pad_box1" name="right_finger_pad_1" pos="0 0.024003 0.032"/>
<geom class="pad_box2" name="right_finger_pad_2" pos="0 0.024003 0.050"/>
</body>
</body>
<body name="right_inner_knuckle" pos="0 -0.02 0.074098">
Expand Down
2 changes: 1 addition & 1 deletion ufactory_xarm7/xarm7_nohand.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
<default>
<default class="xarm7">
<geom type="mesh" material="white"/>
<joint axis="0 0 1" range="-6.28319 6.28319" frictionloss="1"/>
<joint axis="0 0 1" armature="0.1" range="-6.28319 6.28319" frictionloss="1"/>
<general biastype="affine" ctrlrange="-6.28319 6.28319"/>
<default class="size1">
<joint damping="10"/>
Expand Down