ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

How do I adapt gripper simulation in Gazebo?

asked 2019-01-08 16:07:34 -0500

ceres gravatar image

updated 2019-01-11 18:46:28 -0500

I am trying to create a Gazebo simulation for a Robotiq 2f-140 gripper with ROS kinetic, but the joints do not move as expected, and result in a gripper that appears broken when trying to move it (as shown in the image below).

I know there are some older answers and Github issues about using mimic joints to simulate grippers in Gazebo, but most of them appear to be outdated, and it seems like using this gripper in a simulation should be a simple task that does not require 3rd party plugins such as the one here. Is there a straightforward way to set this up?

I have found some examples of a 2f-85 gripper that are working in Gazebo, but they use modified packages such as this one instead of the urdf files in the ros industrial repo.

I've tried to replicate those approaches with the 2f-140 gripper, but so far without success. As you can seen in the image below, the finger joints do not move in coordination with each other.

image description

I am using the urdf files from the ROS-industrial robotiq package which specifies mimic joints, and have added the mimic joints to the transmission file robotiq_arg2f_transmission.xacro:

<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:macro name="robotiq_arg2f_transmission" params="prefix">
    <transmission name="${prefix}finger_joint_trans">
      <type>transmission_interface/SimpleTransmission</type>
      <joint name="${prefix}finger_joint">
        <hardwareInterface>PositionJointInterface</hardwareInterface>
      </joint>
      <actuator name="${prefix}finger_joint_motor">
        <mechanicalReduction>1</mechanicalReduction>
      </actuator>
    </transmission>
    <!-- Mimic joints -->
    <gazebo>
      <plugin filename="libgazebo_mimic_joint_plugin.so" name="${prefix}mimic_robotiq_140_1">
        <joint>${prefix}finger_joint</joint>
        <mimicJoint>${prefix}right_outer_knuckle_joint</mimicJoint>
      </plugin>
      <plugin filename="libgazebo_mimic_joint_plugin.so" name="${prefix}mimic_robotiq_140_2">
        <joint>${prefix}finger_joint</joint>
        <mimicJoint>${prefix}left_inner_knuckle_joint</mimicJoint>
      </plugin>
      <plugin filename="libgazebo_mimic_joint_plugin.so" name="${prefix}mimic_robotiq_140_3">
        <joint>${prefix}finger_joint</joint>
        <mimicJoint>${prefix}right_inner_knuckle_joint</mimicJoint>
      </plugin>
      <plugin filename="libgazebo_mimic_joint_plugin.so" name="${prefix}mimic_robotiq_140_4">
        <joint>${prefix}finger_joint</joint>
        <mimicJoint>${prefix}left_inner_finger_joint</mimicJoint>
      </plugin>
      <plugin filename="libgazebo_mimic_joint_plugin.so" name="${prefix}mimic_robotiq_140_5">
        <joint>${prefix}finger_joint</joint>
        <mimicJoint>${prefix}right_inner_finger_joint</mimicJoint>
      </plugin>
    </gazebo>
  </xacro:macro>
</robot>

The gripper still fails to move as expected though. How do I use the gripper in simulation?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2019-07-07 22:34:39 -0500

yepw gravatar image

Hi, please considering using roboticsgroup_gazebo_plugins and <multiplier>-1.0</multiplier>.

<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:macro name="robotiq_arg2f_transmission" params="prefix">
    <transmission name="${prefix}finger_joint_trans">
      <type>transmission_interface/SimpleTransmission</type>
      <joint name="${prefix}finger_joint">
        <hardwareInterface>PositionJointInterface</hardwareInterface>
      </joint>
      <actuator name="${prefix}finger_joint_motor">
        <mechanicalReduction>1</mechanicalReduction>
      </actuator>
    </transmission>
        <gazebo>
             <!-- loading plugin: mimic joints works in gazebo now-->
             <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="${prefix}mimic_robotiq_140_4">
                <joint>${prefix}finger_joint</joint>
                <mimicJoint>${prefix}right_outer_knuckle_joint</mimicJoint>
                <multiplier>-1.0</multiplier>
            </plugin>
            <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="${prefix}mimic_robotiq_140_2">
                <joint>${prefix}finger_joint</joint>
                <mimicJoint>${prefix}left_inner_finger_joint</mimicJoint>
                <multiplier>1.0</multiplier> 
            </plugin>
            <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="${prefix}mimic_robotiq_140_1">
                <joint>${prefix}finger_joint</joint>
                <mimicJoint>${prefix}right_inner_finger_joint</mimicJoint>
                <multiplier>1.0</multiplier>
            </plugin>
            <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="${prefix}mimic_robotiq_140_3">
                <joint>${prefix}finger_joint</joint>
                <mimicJoint>${prefix}left_inner_knuckle_joint</mimicJoint>
                <multiplier>-1.0</multiplier>
            </plugin>
            <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="${prefix}mimic_robotiq_140_5">
                <joint>${prefix}finger_joint</joint>
                <mimicJoint>${prefix}right_inner_knuckle_joint</mimicJoint>
                <multiplier>-1.0</multiplier>
            </plugin>
        </gazebo>
  </xacro:macro>
</robot>

At least this code works for me. The complete package is https://github.com/intuitivecomputing.... The package enables an ur5 and a Robotiq 140 gripper to be used with Moveit! and Gazebo. Hope it is helpful.

edit flag offensive delete link more

Comments

I can confirm too this package worked clone the repo in your catkin/src/ build the package and load it as the person above

MasterTsoutsos gravatar image MasterTsoutsos  ( 2019-10-29 03:40:13 -0500 )edit

when I git clone the repository, there are some errors with catkin_make.(ubuntu16.04)

hubery524 gravatar image hubery524  ( 2020-05-15 05:15:44 -0500 )edit

Question Tools

5 followers

Stats

Asked: 2019-01-08 16:07:34 -0500

Seen: 3,210 times

Last updated: Jan 11 '19