Skip to content
Open
Show file tree
Hide file tree
Changes from all 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
Binary file added robotiq_2f140/2f140.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
170 changes: 170 additions & 0 deletions robotiq_2f140/2f140.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,170 @@
<mujoco model="robotiq_2f140">
<compiler angle="radian" meshdir="assets" autolimits="true"/>

<option cone="elliptic" impratio="10"/>

<asset>
<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="black" rgba="0.149 0.149 0.149 1"/>

<mesh class="2f140" scale="0.001 0.001 0.001" file="base_mount.stl"/>
<mesh class="2f140" file="base.stl"/>
<mesh class="2f140" file="driver.stl"/>
<mesh class="2f140" file="follower.stl"/>
<mesh class="2f140" file="coupler.stl"/>
<mesh class="2f140" scale="0.001 0.001 0.001" file="pad.stl"/>
<mesh class="2f140" file="spring_link.stl"/>
</asset>

<default>
<default class="2f140">
<general biastype="affine"/>
<joint axis="1 0 0"/>
<default class="driver">
<joint range="-0.8 0" armature="0.005" damping="0.1" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/>
</default>
<default class="follower">
<joint range="-0.8757 0.8757" armature="0.001" solimplimit="0.95 0.99 0.001" pos="0 0.005 -0.0175" solreflimit="0.005 1"/>
</default>
<default class="spring_link">
<joint range="-0.8 0.29670597283" armature="0.001" stiffness="0.05" springref="-2.62" damping="0.00125"/>
</default>
<default class="coupler">
<joint range="0 1.57" armature="0.001" solimplimit="0.95 0.99 0.001" 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 mass="0" type="box" pos="0 0.0457554 -0.0272203" size="0.0135 0.0325 0.00375" friction="0.7"
solimp="0.95 0.99 0.001" solref="0.004 1" priority="1" rgba="0.55 0.55 0.55 1"/>
</default>
</default>
</default>
</default>
<worldbody>
<body name="base_mount" pos="0 0 0.007" childclass="2f140">
<geom class="visual" mesh="base_mount" material="black"/>
<geom class="collision" mesh="base_mount"/>
<body name="base" pos="0 0 0.0038" quat="1 0 0 -1">
<inertial mass="0.777441" pos="0 -2.70394e-05 0.0354675" quat="1 -0.00152849 0 0"
diaginertia="0.000260285 0.000225381 0.000152708"/>
<geom class="visual" mesh="base" material="black"/>
<geom class="collision" mesh="base"/>
<!-- Right-hand side 4-bar linkage -->
<body name="right_driver" pos="0 0.030601 0.054905" quat="0 0 0.911903 0.410405">
<joint name="right_driver_joint" class="driver"/>
<geom class="visual" mesh="driver" material="gray"/>
<geom class="collision" mesh="driver"/>
<body name="right_coupler" pos="0 0.01822 0.026001" quat="1 0 0 0">
<inertial pos="0.000163875 0.0458404 -0.0117804" quat="0.881368 0.472423 -0.0024451 -0.000996122" mass="0.0311462" diaginertia="2.96023e-05 2.79814e-05 4.39017e-06"/>
<joint name="right_coupler_joint" class="coupler"/>
<geom class="visual" mesh="coupler" material="black"/>
<geom class="collision" mesh="coupler"/>
</body>
</body>
<body name="right_spring_link" pos="0 0.0127 0.06142" quat="0 0 -0.9135455 -0.406736">
<inertial mass="0.0271177" pos="0.000123012 0.0507851 0.00103969" quat="0.497203 0.502496 -0.507943 0.492221"
diaginertia="2.83809e-05 2.61936e-05 2.81319e-06"/>
<joint name="right_spring_link_joint" class="spring_link"/>
<geom class="visual" mesh="spring_link" material="black"/>
<geom class="collision" mesh="spring_link"/>
<body name="right_follower" pos="0 0.107454 0.01451853" quat="0.935013 -0.354613 0 0">
<inertial mass="0.0261503" pos="0.000119314 0.0339244 -0.021841" quat="0.545437 0.430197 -0.442938 0.566776"
diaginertia="1.62408e-05 1.59131e-05 2.38936e-06"/>
<joint name="right_follower_joint" class="follower"/>
<geom class="visual" mesh="follower" material="black"/>
<geom class="collision" mesh="follower"/>
<body name="right_pad" pos="0 0.012 -0.0276" quat="0.707107 -0.707107 0 0">
<inertial mass="0.0035" pos="0 -0.0025 0.0185" quat="0.707107 0 0 0.707107"
diaginertia="4.73958e-07 3.64583e-07 1.23958e-07"/>
<geom class="visual" mesh="pad"/>
</body>
<geom class="pad_box1" name="right_pad1"/>
</body>
</body>
<!-- Left-hand side 4-bar linkage -->
<body name="left_driver" pos="0 -0.0306011 0.054904" quat="0.410405 0.911903 0 0">
<joint name="left_driver_joint" class="driver"/>
<geom class="visual" mesh="driver" material="gray"/>
<geom class="collision" mesh="driver"/>
<body name="left_coupler" pos="0 0.01822 0.026001" quat="1 0 0 0">
<inertial pos="0.000163875 0.0458404 -0.0117804" quat="0.881368 0.472423 -0.0024451 -0.000996122" mass="0.0311462" diaginertia="2.96023e-05 2.79814e-05 4.39017e-06"/>
<joint name="left_coupler_joint" class="coupler"/>
<geom class="visual" mesh="coupler" material="black"/>
<geom class="collision" mesh="coupler"/>
</body>
</body>
<body name="left_spring_link" pos="0 -0.0127 0.06142" quat="0.410405 0.911903 0 0">
<inertial mass="0.0271177" pos="0.000123012 0.0507851 0.00103969" quat="0.497203 0.502496 -0.507943 0.492221"
diaginertia="2.83809e-05 2.61936e-05 2.81319e-06"/>
<joint name="left_spring_link_joint" class="spring_link"/>
<geom class="visual" mesh="spring_link" material="black"/>
<geom class="collision" mesh="spring_link"/>
<body name="left_follower" pos="0 0.107454 0.01451853" quat="0.935013 -0.354613 0 0">
<inertial mass="0.0261503" pos="0.000119314 0.0339244 -0.021841" quat="0.545437 0.430197 -0.442938 0.566776"
diaginertia="1.62408e-05 1.59131e-05 2.38936e-06"/>
<joint name="left_follower_joint" class="follower"/>
<geom class="visual" mesh="follower" material="black"/>
<geom class="collision" mesh="follower"/>
<body name="left_pad" pos="0 0.012 -0.0276" quat="0.707107 -0.707107 0 0">
<inertial mass="0.0035" pos="0 -0.0025 0.0185" quat="1 0 0 1"
diaginertia="4.73958e-07 3.64583e-07 1.23958e-07"/>
<geom class="visual" mesh="pad"/>
</body>
<geom class="pad_box1" name="left_pad1"/>
</body>
</body>
</body>
</body>
</worldbody>

<contact>
<exclude body1="base" body2="left_driver"/>
<exclude body1="base" body2="right_driver"/>
<exclude body1="base" body2="left_spring_link"/>
<exclude body1="base" body2="right_spring_link"/>
<exclude body1="left_driver" body2="left_spring_link"/>
<exclude body1="right_driver" body2="right_spring_link"/>
<exclude body1="right_coupler" body2="right_follower"/>
<exclude body1="left_coupler" body2="left_follower"/>
</contact>

<!--
This adds stability to the model by having a tendon that distributes the forces between both
joints, such that the equality constraint doesn't have to do that much work in order to equalize
both joints. Since both joints share the same sign, we split the force between both equally by
setting coef=0.5
-->
<tendon>
<fixed name="split">
<joint joint="right_driver_joint" coef="-0.5"/>
<joint joint="left_driver_joint" coef="-0.5"/>
</fixed>
</tendon>

<equality>
<connect anchor="0 0 0" body1="right_follower" body2="right_coupler" solimp="0.95 0.99 0.001" solref="0.005 1"/>
<connect anchor="0 0 0" body1="left_follower" body2="left_coupler" solimp="0.95 0.99 0.001" solref="0.005 1"/>
<joint joint1="right_driver_joint" joint2="left_driver_joint" polycoef="0 1 0 0 0" solimp="0.95 0.99 0.001"
solref="0.005 1"/>
</equality>

<!--
The general actuator below is a customized position actuator (with some damping) where
gainprm[0] != kp (see http://mujoco.org/book/modeling.html#position).
The reason why gainprm[0] != kp is because the control input range has to be re-scaled to
[0, 255]. The joint range is currently set at [0, 0.8], the control range is [0, 255] and
kp = 100. Tau = Kp * scale * control_input - Kp * error, max(Kp * scale * control_input) = 0.8,
hence scale = 0.8 * 100 / 255
-->
<actuator>
<general class="2f140" name="fingers_actuator" tendon="split" forcerange="-5 5" ctrlrange="0 255"
gainprm="0.3137255 0 0" biasprm="0 -100 -10"/>
</actuator>
</mujoco>
23 changes: 23 additions & 0 deletions robotiq_2f140/LICENSE
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
Copyright (c) 2013, ROS-Industrial
All rights reserved.

Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:

Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.

Redistributions in binary form must reproduce the above copyright notice, this
list of conditions and the following disclaimer in the documentation and/or
other materials provided with the distribution.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
33 changes: 33 additions & 0 deletions robotiq_2f140/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
# Robotiq 2F-140 Description (MJCF)

Requires MuJoCo 2.2.2 or later.

## Overview

This package contains a simplified robot description (MJCF) of the [Robotiq 140mm
2-Finger Adaptive
Gripper](https://robotiq.com/products/2f85-140-adaptive-robot-gripper) developed
by [Robotiq](https://robotiq.com/). It is derived from the [publicly available
URDF
description](https://github.com/ros-industrial/robotiq/tree/kinetic-devel/robotiq_2f_140_gripper_visualization).

<p float="left">
<img src="2f140.png" width="400">
</p>

## URDF → MJCF derivation steps

1. Added `<mujoco> <compiler discardvisual="false"/> </mujoco>` to the URDF's
`<robot>` clause in order to preserve visual geometries.
2. Loaded the URDF into MuJoCo and saved a corresponding MJCF.
3. Manually edited the MJCF to extract common properties into the `<default>` section.
4. Added `<exclude>` clauses to prevent collisions between the linkage bodies.
5. Broke up collision pads into two pads for more contacts.
6. Increased pad friction and priority.
7. Added `impratio=10` for better noslip.
8. Added `scene.xml` which includes the robot, with a textured groundplane, skybox, and haze.
9. Added hanging box to `scene.xml`.

## License

This model is released under a [BSD-2-Clause License](LICENSE).
Binary file added robotiq_2f140/assets/base.stl
Binary file not shown.
Binary file added robotiq_2f140/assets/base_mount.stl
Binary file not shown.
Binary file added robotiq_2f140/assets/coupler.stl
Binary file not shown.
Binary file added robotiq_2f140/assets/driver.stl
Binary file not shown.
Binary file added robotiq_2f140/assets/follower.stl
Binary file not shown.
Binary file added robotiq_2f140/assets/pad.stl
Binary file not shown.
Binary file added robotiq_2f140/assets/spring_link.stl
Binary file not shown.
40 changes: 40 additions & 0 deletions robotiq_2f140/scene.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
<mujoco model="2f140 scene">
<include file="2f140.xml"/>

<!-- Add some fluid viscosity to prevent the hanging box from jiggling forever -->
<option viscosity="0.1"/>

<statistic center="0 0 0.05" extent="0.3"/>

<visual>
<headlight diffuse="0.6 0.6 0.6" ambient="0.3 0.3 0.3" specular="0 0 0"/>
<rgba haze="0.15 0.25 0.35 1"/>
<global azimuth="60" elevation="-20"/>
</visual>

<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="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
</asset>

<worldbody>
<light pos="0 0 1"/>
<light pos="0 -0.2 1" dir="0 0.2 -0.8" directional="true"/>
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
<site size="0.002" pos="0 0 0.27" name="anchor"/>
<body name="object" pos="0 0 0.26">
<freejoint/>
<geom type="box" size="0.015 0.015 0.015" rgba=".5 .7 .5 1" friction=".5" priority="1"/>
<site size="0.002" pos="0.015 0.015 0.015" name="hook"/>
</body>
</worldbody>

<tendon>
<spatial limited="true" range="0 0.02" width="0.001">
<site site="hook"/>
<site site="anchor"/>
</spatial>
</tendon>
</mujoco>