Skip to content

Commit

Permalink
Merge pull request google-deepmind#89 from eufrizz:ufactory_gripper
Browse files Browse the repository at this point in the history
PiperOrigin-RevId: 672505836
Change-Id: I78c0020af6bd9172155843875a13a84fa6b1b52c
  • Loading branch information
copybara-github committed Sep 9, 2024
2 parents f59b989 + a54fc22 commit 15b7a2b
Show file tree
Hide file tree
Showing 20 changed files with 338 additions and 19 deletions.
28 changes: 26 additions & 2 deletions ufactory_lite6/README.md
Original file line number Diff line number Diff line change
@@ -1,17 +1,30 @@
# Lite 6 Description (MJCF)

Requires MuJoCo 2.3.3 or later.
Requires MuJoCo 3.1.0 or later.

## Overview

This package contains a simplified robot description (MJCF) of the
[Lite 6](https://www.ufactory.cc/product-page/ufactory-lite-6) developed by
[UFactory](https://www.ufactory.cc/). It is derived from the [publicly available
URDF
description](https://github.com/xArm-Developer/xarm_ros2/tree/master/xarm_description/urdf/lite6).
description](https://github.com/xArm-Developer/xarm_ros2/tree/master/xarm_description/urdf/lite6). 3 versions are provided: no gripper, wide gripper, and narrow gripper. The gripper fingers can be attached in two orientations, narrrow (so that they close fully) or wide (so that wider objects can be gripped). This provides some flexibility with the limited range of the gripper.

<p float="left">
<img src="lite6.png" width="400">
<figcaption>No gripper</figcaption>
</p>

<p float="left">
<img src="lite6_gripper_wide_closed.png" width="200">
<img src="lite6_gripper_wide_open.png" width="200">
<figcaption>Wide gripper configuration, fully closed (initial position) and open</figcaption>
</p>

<p float="left">
<img src="lite6_gripper_narrow_closed.png" width="200">
<img src="lite6_gripper_narrow_open.png" width="200">
<figcaption>Narrow gripper confgiguration, fully closed (initial position) and open</figcaption>
</p>

## URDF → MJCF derivation steps
Expand All @@ -23,6 +36,17 @@ description](https://github.com/xArm-Developer/xarm_ros2/tree/master/xarm_descri
4. Added actuators.
5. Added `scene.xml` which includes the robot, with a textured groundplane, skybox, and haze.

### Gripper

The URDF only contains a gripper model for the Lite 6 with the fingers fused to the gripper body. To separate the fingers, the .step file of the fused body from the [Ufactory website](https://usa.ufactory.cc/download-lite6-robot) was loaded into Onshape ([file here](https://cad.onshape.com/documents/f60aac1c8ff6af8f490dc855/w/5c0df4bc7414802fc89a514e/e/7dc41825dd66894c14b085ca?renderMode=0&uiState=66bdfb41f48d6a182064f4a4)) and split along the tracks that the fingers run on. Because MuJoCo forms a convex hull for collision meshes, it was necessary to separate the wide fingers into the base and tip for realistic gripping.

Because they are actuated via an air compressor, a single `motor` actuator was used in the model, with an equality constraint to mimic the gearing mechanism that keeps them equidistant from the centre. There is no position control of the gripper.

The moments of inertia were estimated in Onshape due to not having any data from the manufacturer. This was done by choosing a density that matched the mass of the actual part, and assuming a uniform mass distribution (which is not the actual case but should be close enough).




## License

This model is released under a [BSD-3-Clause License](LICENSE).
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
34 changes: 17 additions & 17 deletions ufactory_lite6/lite6.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,15 +7,15 @@
<default class="lite6">
<geom type="mesh"/>
<joint axis="0 0 1" damping="1" armature="0.1"/>
<general gaintype="fixed" biastype="affine" gainprm="2000" biasprm="0 -2000 -200"/>
<position kp="2000" kv="200"/>
<default class="size1">
<general forcerange="-50 50"/>
<position forcerange="-50 50"/>
</default>
<default class="size2">
<general forcerange="-32 32"/>
<position forcerange="-32 32"/>
</default>
<default class="size3">
<general forcerange="-20 20"/>
<position forcerange="-20 20"/>
</default>
<default class="visual">
<geom contype="0" conaffinity="0" group="2" material="white"/>
Expand Down Expand Up @@ -51,43 +51,43 @@
<body name="link_base" childclass="lite6">
<inertial pos="-0.00829545 3.26357e-05 0.0631195" mass="1.65394" diaginertia="0 0 0"/>
<geom class="visual" mesh="link_base"/>
<geom class="collision" mesh="link_base_c"/>
<geom name="link_base_c" class="collision" mesh="link_base_c"/>
<body name="link1" pos="0 0 0.2435">
<inertial pos="-0.00036 0.04195 -0.0025" quat="0.608059 0.792349 -0.0438707 0.0228718" mass="1.411"
diaginertia="0.00145276 0.00135275 0.000853355"/>
<joint name="joint1" range="-6.28319 6.28319"/>
<geom class="visual" mesh="link1"/>
<geom class="collision" mesh="link1_c"/>
<geom name="link1_c" class="collision" mesh="link1_c"/>
<body name="link2" quat="-1 1 1 1">
<inertial pos="0.179 0 0.0584" quat="0.417561 0.571619 0.569585 0.417693" mass="1.34"
diaginertia="0.00560971 0.0052152 0.00122018"/>
<joint name="joint2" range="-2.61799 2.61799"/>
<geom class="visual" mesh="link2"/>
<geom class="collision" mesh="link2_c"/>
<geom name="link2_c" class="collision" mesh="link2_c"/>
<body name="link3" pos="0.2002 0 0" quat="-2.59734e-06 -0.707105 -0.707108 -2.59735e-06">
<inertial pos="0.072 -0.0357 -0.001" quat="0.128259 0.662963 -0.167256 0.71837" mass="0.953"
diaginertia="0.0018521 0.00175546 0.000703807"/>
<joint name="joint3" range="-0.061087 5.23599"/>
<geom class="visual" mesh="link3"/>
<geom class="collision" mesh="link3_c"/>
<geom name="link3_c" class="collision" mesh="link3_c"/>
<body name="link4" pos="0.087 -0.22761 0" quat="0.707105 0.707108 0 0">
<inertial pos="-0.002 -0.0285 -0.0813" quat="0.975248 0.22109 0.00203498 -0.00262178" mass="1.284"
diaginertia="0.00370503 0.00349091 0.00109586"/>
<joint name="joint4" range="-6.28319 6.28319"/>
<geom class="visual" mesh="link4"/>
<geom class="collision" mesh="link4_c"/>
<geom name="link4_c" class="collision" mesh="link4_c"/>
<body name="link5" quat="1 1 0 0">
<inertial pos="0 0.01 0.0019" quat="0.71423 0.696388 -0.0531933 0.0456997" mass="0.804"
diaginertia="0.000567553 0.000529266 0.000507681"/>
<joint name="joint5" range="-2.1642 2.1642"/>
<geom class="visual" mesh="link5"/>
<geom class="collision" mesh="link5_c"/>
<geom name="link5_c" class="collision" mesh="link5_c"/>
<body name="link6" pos="0 0.0625 0" quat="1 -1 0 0">
<inertial pos="0 -0.00194 -0.0102" quat="-0.0376023 0.704057 0.0446838 0.707738" mass="0.13"
diaginertia="0.000148148 8.57757e-05 7.71412e-05"/>
<joint name="joint6" range="-6.28319 6.28319"/>
<geom class="visual" mesh="link6" material="silver"/>
<geom class="collision" mesh="link6_c"/>
<geom name="link6_c" class="collision" mesh="link6_c"/>
<site name="attachment_site"/>
</body>
</body>
Expand All @@ -99,12 +99,12 @@
</worldbody>

<actuator>
<general joint="joint1" class="size1" ctrlrange="-6.28319 6.28319"/>
<general joint="joint2" class="size1" ctrlrange="-2.61799 2.61799"/>
<general joint="joint3" class="size2" ctrlrange="-0.061087 5.23599"/>
<general joint="joint4" class="size2" ctrlrange="-6.28319 6.28319"/>
<general joint="joint5" class="size2" ctrlrange="-2.1642 2.1642"/>
<general joint="joint6" class="size3" ctrlrange="-6.28319 6.28319"/>
<position joint="joint1" class="size1" ctrlrange="-6.28319 6.28319"/>
<position joint="joint2" class="size1" ctrlrange="-2.61799 2.61799"/>
<position joint="joint3" class="size2" ctrlrange="-0.061087 5.23599"/>
<position joint="joint4" class="size2" ctrlrange="-6.28319 6.28319"/>
<position joint="joint5" class="size2" ctrlrange="-2.1642 2.1642"/>
<position joint="joint6" class="size3" ctrlrange="-6.28319 6.28319"/>
</actuator>

<keyframe>
Expand Down
143 changes: 143 additions & 0 deletions ufactory_lite6/lite6_gripper_narrow.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,143 @@
<mujoco model="ufactory_lite6">
<compiler angle="radian" meshdir="assets" autolimits="true"/>

<option integrator="implicitfast"/>

<default>
<default class="lite6">
<geom type="mesh"/>
<joint axis="0 0 1" damping="1" armature="0.1"/>
<position kp="2000" kv="200"/>
<default class="size1">
<position forcerange="-50 50"/>
</default>
<default class="size2">
<position forcerange="-32 32"/>
</default>
<default class="size3">
<position forcerange="-20 20"/>
</default>
<default class="visual">
<geom contype="0" conaffinity="0" group="2" material="white"/>
</default>
<default class="collision">
<geom group="3" mass="0" density="0"/>
</default>
<site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/>
</default>
</default>

<asset>
<material name="white" rgba="1 1 1 1"/>
<material name="silver" rgba=".753 .753 .753 1"/>
<material name="black" rgba=".1 .1 .1 1"/>

<mesh file="visual/link_base.stl"/>
<mesh file="visual/link1.stl"/>
<mesh file="visual/link2.stl"/>
<mesh file="visual/link3.stl"/>
<mesh file="visual/link4.stl"/>
<mesh file="visual/link5.stl"/>
<mesh file="visual/link6.stl"/>
<mesh file="visual/gripper_lite_body.stl"/>
<mesh file="visual/gripper_lite_left_finger_narrow.stl"/>
<mesh file="visual/gripper_lite_right_finger_narrow.stl"/>
<mesh name="link_base_c" file="collision/link_base.stl"/>
<mesh name="link1_c" file="collision/link1.stl"/>
<mesh name="link2_c" file="collision/link2.stl"/>
<mesh name="link3_c" file="collision/link3.stl"/>
<mesh name="link4_c" file="collision/link4.stl"/>
<mesh name="link5_c" file="collision/link5.stl"/>
<mesh name="link6_c" file="collision/link6.stl"/>
<mesh name="gripper_lite_body_c" file="collision/gripper_lite_body.stl"/>
</asset>

<worldbody>
<body name="link_base" childclass="lite6">
<inertial pos="-0.00829545 3.26357e-05 0.0631195" mass="1.65394" diaginertia="0 0 0"/>
<geom class="visual" mesh="link_base"/>
<geom name="link_base_c" class="collision" mesh="link_base_c"/>
<body name="link1" pos="0 0 0.2435">
<inertial pos="-0.00036 0.04195 -0.0025" quat="0.608059 0.792349 -0.0438707 0.0228718" mass="1.411"
diaginertia="0.00145276 0.00135275 0.000853355"/>
<joint name="joint1" range="-6.28319 6.28319"/>
<geom class="visual" mesh="link1"/>
<geom name="link1_c" class="collision" mesh="link1_c"/>
<body name="link2" quat="-1 1 1 1">
<inertial pos="0.179 0 0.0584" quat="0.417561 0.571619 0.569585 0.417693" mass="1.34"
diaginertia="0.00560971 0.0052152 0.00122018"/>
<joint name="joint2" range="-2.61799 2.61799"/>
<geom class="visual" mesh="link2"/>
<geom name="link2_c" class="collision" mesh="link2_c"/>
<body name="link3" pos="0.2002 0 0" quat="-2.59734e-06 -0.707105 -0.707108 -2.59735e-06">
<inertial pos="0.072 -0.0357 -0.001" quat="0.128259 0.662963 -0.167256 0.71837" mass="0.953"
diaginertia="0.0018521 0.00175546 0.000703807"/>
<joint name="joint3" range="-0.061087 5.23599"/>
<geom class="visual" mesh="link3"/>
<geom name="link3_c" class="collision" mesh="link3_c"/>
<body name="link4" pos="0.087 -0.22761 0" quat="0.707105 0.707108 0 0">
<inertial pos="-0.002 -0.0285 -0.0813" quat="0.975248 0.22109 0.00203498 -0.00262178" mass="1.284"
diaginertia="0.00370503 0.00349091 0.00109586"/>
<joint name="joint4" range="-6.28319 6.28319"/>
<geom class="visual" mesh="link4"/>
<geom name="link4_c" class="collision" mesh="link4_c"/>
<body name="link5" quat="1 1 0 0">
<inertial pos="0 0.01 0.0019" quat="0.71423 0.696388 -0.0531933 0.0456997" mass="0.804"
diaginertia="0.000567553 0.000529266 0.000507681"/>
<joint name="joint5" range="-2.1642 2.1642"/>
<geom class="visual" mesh="link5"/>
<geom name="link5_c" class="collision" mesh="link5_c"/>
<body name="link6" pos="0 0.0625 0" quat="1 -1 0 0">
<inertial pos="0 -0.00194 -0.0102" quat="-0.0376023 0.704057 0.0446838 0.707738" mass="0.13"
diaginertia="0.000148148 8.57757e-05 7.71412e-05"/>
<joint name="joint6" range="-6.28319 6.28319"/>
<geom class="visual" mesh="link6" material="silver"/>
<geom name="link6_c" class="collision" mesh="link6_c"/>
<site name="attachment_site"/>
<body name="gripper_body" pos="0 0 0" quat="1 0 0 0">
<inertial pos="0.0 0.0 0.026" quat="1 0 0 0" mass="0.26"
diaginertia="0.00016117 0.000118 0.00014455" />
<geom name="gripper_lite_body" class="visual" mesh="gripper_lite_body" material="white"/>
<geom name="gripper_lite_body_c" class="collision" mesh="gripper_lite_body_c"/>
<body name="gripper_left_finger" pos="0 0 0.054" quat="1 0 0 0">
<inertial pos="0.0 -0.005 0.01" quat="1 0 0 0" mass="0.024"
diaginertia="1.961e-6 2.274e-6 1.238e-6" />
<geom name="gripper_left_finger" mesh="gripper_lite_left_finger_narrow" material="black" condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.005 0.0001"/>
<joint name="gripper_left_finger" pos="0 0 0" axis="0 1 0" type="slide" limited="true" range="-0.0081 -1e-5" frictionloss="1" />
</body>
<body name="gripper_right_finger" pos="0 0 0.054" quat="1 0 0 0">
<inertial pos="0.0 0.005 0.01" quat="1 0 0 0" mass="0.024"
diaginertia="1.961e-6 2.274e-6 1.238e-6" />
<geom name="gripper_right_finger" mesh="gripper_lite_right_finger_narrow" material="black" condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.005 0.0001"/>
<joint name="gripper_right_finger" pos="0 0 0" axis="0 1 0" type="slide" limited="true" range="1e-5 0.0081" frictionloss="1" />
</body>
<!-- End effector reference point is in the middle of the tips of the grippers -->
<site name="end_effector" pos="0 0 0.0811"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>

<actuator>
<position joint="joint1" class="size1" ctrlrange="-6.28319 6.28319"/>
<position joint="joint2" class="size1" ctrlrange="-2.61799 2.61799"/>
<position joint="joint3" class="size2" ctrlrange="-0.061087 5.23599"/>
<position joint="joint4" class="size2" ctrlrange="-6.28319 6.28319"/>
<position joint="joint5" class="size2" ctrlrange="-2.1642 2.1642"/>
<position joint="joint6" class="size3" ctrlrange="-6.28319 6.28319"/>
<motor name="gripper" joint="gripper_left_finger" forcerange="-10 10" ctrlrange="-10 10"/>
</actuator>

<equality>
<joint joint1="gripper_left_finger" joint2="gripper_right_finger" polycoef="0 -1 0 0 0"/>
</equality>

<keyframe>
<key name="home" qpos="0 0 1.57 0 1.57 0 0 0" ctrl="0 0 1.57 0 1.57 0 0"/>
</keyframe>
</mujoco>
Binary file added ufactory_lite6/lite6_gripper_narrow_closed.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added ufactory_lite6/lite6_gripper_narrow_open.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading

0 comments on commit 15b7a2b

Please sign in to comment.