How do I adapt gripper simulation in Gazebo?
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.
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?