Gazebo | Ignition | Community
Ask Your Question
1

I cannot make gazebo_ros_vacuum_gripper plugin or ARIAC's vacuum gripper plugin to work. Please help

asked 2018-12-09 09:29:10 -0600

zoid gravatar image

updated 2018-12-12 13:18:03 -0600

Hello,

I have a vacuum gripper and I am trying to attach the gazebo_ros_vacuum_gripper plugin to make it work but without any success so far.

My .xacro configuration is as follows:

<joint name="${prefix}rotary_to_carriage_joint" type="prismatic">
  <parent link="${prefix}rotary"/>
  <child link="${prefix}carriage"/>
  <origin rpy="0 1.5708 0" xyz="-0.685 0 0.064"/>

  <limit effort="30" velocity="1" lower="0.0" upper="0.75" />
</joint>

<link name="${prefix}carriage">
  <gravity>0</gravity>
  <inertial>
    <mass value="2.524"/>
    <origin rpy="0 0 0" xyz="-0.1832 0.0 0.813"/>
    <inertia ixx="0.024" ixy="0.0" ixz="0.083" iyy="0.569" iyz="0.0" izz="0.555"/>
  </inertial>
  <collision>
<origin rpy="0 0 0" xyz="-0.65 0 0.75"/>
    <geometry>
      <mesh filename="package://meshes/carriage.stl" scale="0.001 0.001 0.001"/>
    </geometry>
  </collision>
  <visual>
    <origin rpy="0 0 0" xyz="-0.65 0 0.75"/>
    <geometry>
      <mesh filename="package://meshes/carriage.stl" scale="0.001 0.001 0.001"/>
    </geometry>
    <material name="Blue">
      <color rgba="0.0 0.0 0.4 1.0"/>
    </material>
  </visual>
</link>

<gazebo>
  <plugin name="gazebo_ros_vacuum_gripper" filename="libgazebo_ros_vacuum_gripper.so">
    <robotNamespace>/</robotNamespace>
    <bodyName>${prefix}carriage</bodyName>
    <topicName>grasping</topicName>
    <maxForce>20</maxForce>
    <maxDistance>0.10</maxDistance>
<minDistance>0.01</minDistance>
  </plugin>
</gazebo>

So with that configuration and by using rosservice call /on "{}" and rosservice call /off "{}" to activate deactivate suction, nothing happens and a target item (box) is not gripped. Does this plugin supports "prismatic" joints or is it made only for "revolute" joints?

Any help would be greatly appreciate it! Thank you.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2020-05-30 10:07:18 -0600

Hello I managed to use libgazebo_ros_vacuum_gripper with my robot after a few hours of trying. First Change the joint to revolute. Remove the collision from the vacuum gripper (carriage in your robot). Let it go through the object. Then turn on the gripper using grasping service.

Set mu1 and mu2 for the grasping surfaces. In your case the parent link of the gripper(the link which the object will touch when suction is happening) and the grasping object. If you are using PositionJointInterface for your robot, then add kp and kd values for both touching surfaces.

Ex:

<gazebo reference="box">
    <material>Gazebo/Blue</material>
    <mu1>10</mu1>
    <mu2>10</mu2>
    <minDepth>0.003</minDepth>
    <maxVel>0</maxVel>
    <kp>1000000.0</kp>
    <kd>1.0</kd>
</gazebo>

Check these answers- PositionJointInterface issue when gripping Use this as a guideline when using vacuum gripper - ur5 with vacuum gripper

edit flag offensive delete link more
0

answered 2018-12-12 13:16:37 -0600

zoid gravatar image

Hi again,

I have compiled separately the ARIAC competition vacuum gripper plugin and I am using the following .xacro configuration:

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="create_vacuum_gripper" params="wrist_link link_no *origin">


  <joint name="vacuum_gripper_joint_${link_no}" type="revolute">
    <xacro:insert_block name="origin" />

    <axis xyz="0 0 1" />
    <limit lower="0" upper="0" effort="0" velocity="0" />
    <parent link="${wrist_link}" />
    <child link="vacuum_gripper_link_${link_no}" />

    <dynamics damping="0.0" friction="0.0"/>
  </joint>


  <link name="vacuum_gripper_link_${link_no}">
    <inertial>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <inertia ixx="0.0000063" ixy="0" ixz="0"
               iyy="0.0000063" iyz="0"
               izz="0.000025" />
      <mass value="0.01" />
    </inertial>

    <visual>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <cylinder radius="0.05" length="0.01" />
      </geometry>
      <material name="SomeColor">
        <color rgba="1.0 0.0 0.0 1.0"/>
      </material>
    </visual>

    <collision>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.05" length="0.01"/>
      </geometry>
    </collision>
  </link>



  <gazebo reference="vacuum_gripper_link_${link_no}">
    <material>Gazebo/Black</material>
  </gazebo>

  <gazebo>
    <plugin name="ros_vacuum_gripper" filename="libROSVacuumGripperPlugin.so">
      <grasp_check>
        <detach_steps>40</detach_steps>
        <attach_steps>1</attach_steps>
        <min_contact_count>1</min_contact_count>
      </grasp_check>

      <suction_cup_link>vacuum_gripper_link_${link_no}</suction_cup_link>

      <robot_namespace>/trs/${link_no}</robot_namespace>
      <control_topic>gripper/control</control_topic>
      <state_topic>gripper/state</state_topic>
    </plugin>

    <!--plugin name="gazebo_ros_vacuum_gripper" filename="libgazebo_ros_vacuum_gripper.so">
      <robotNamespace>/trs/${link_no}</robotNamespace>
      <bodyName>vacuum_gripper_link_${link_no}</bodyName>
      <topicName>grasping</topicName>
      <maxForce>20</maxForce>
      <maxDistance>0.10</maxDistance>
      <minDistance>0.01</minDistance>
    </plugin-->
  </gazebo>

</xacro:macro>

</robot>

and then to use the above, I am using the following lines in my main .xacro

<xacro:create_vacuum_gripper wrist_link="${prefix}carriage" link_no="1">
    <origin xyz="-0.001 0 0.9" rpy="${90 * 0.0174533} 0 1.5708" />
</xacro:create_vacuum_gripper>

Whichever plugin I use (gazebo_ros_vacuum_gripper or ros_vacuum_gripper), I cannot secure a box object... :( Please if you have any ideas how these plugins work let me know.

Thank you!

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2018-12-09 09:29:10 -0600

Seen: 2,536 times

Last updated: May 30 '20