Gazebo Vacuum Plugin grabbing the center of object

asked 2020-03-23 07:23:19 -0500

Obeseturtle gravatar image

updated 2020-03-23 08:35:14 -0500

gvdhoorn gravatar image

HI guys,

I am trying to utilize the Gazebo Vacuum plugin and I am almost 100% there. I am just having a minor issue where the plugin grabs the center of the object not the limits of it.

I followed the ROS Answer here .

And the crucial thing for this plugin is the distance between the object link and gripper one (currently the plugin does not compute the distance between the collisions of gripper and the object), so in most cases you need to add another link to the robot to use this gripper.

I do not fully understand what it means to add another link to the robot to use this gripper.

Only in the on state will the 'gripper' exert a force on any other links that are close to it (see these lines that calculate the force).

Forgive me if my question does not make sense but is there a way to mimic the limits of the object so that the vacuum sees it as a link?

Thank you in advance.

C:\fakepath\Object.png

<robot xmlns:xacro="http://wiki.ros.org/xacro"
       name="ur5" >

  <xacro:arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface"/>

  <!-- common stuff -->
  <xacro:include filename="$(find ur_description)/urdf/common.gazebo.xacro" />

  <!-- ur5 -->
  <xacro:include filename="$(find ur_description)/urdf/ur5.urdf.xacro" />

  <!-- arm -->
  <xacro:ur5_robot prefix="" joint_limited="false"
    transmission_hw_interface="$(arg transmission_hw_interface)"  />
  <joint name="world_joint" type="fixed">
   <parent link="world" />
   <child link = "base_link" />
   <origin xyz="0.0 0.0 1.273" rpy="3.141 0.0 0.0" />
   </joint>
   <link name="Stick">    
   <gravity>0</gravity>
   <visual>
   <origin rpy="0 0 0" xyz="0 0 0"/>
   <geometry>
   <box size="0.03 0.30 0.03"/>
   </geometry>
   <material name="transparent">
   <color rgba="0 0 0 0"/>
    </material>
   </visual>
   <inertial>
   <origin rpy="0 0 0" xyz="0.000000 0.000000 0.000000"/>
   <mass value="0.0001"/>
   <inertia ixx="1e-08" ixy="0" ixz="0" iyy="1e-08" iyz="0" izz="1e-08"/>
   </inertial>
  </link>
  <joint name="gripper_joint_stick" type="revolute">
   <axis xyz="1 0 0" />
   <parent link="wrist_3_link" />
   <child link="Stick" />
   <origin rpy="0 0 0" xyz="0.0 0.24 0.00" />
   <limit effort="50" velocity="50" lower="0" upper="0" />
   <dynamics damping="0.0" friction="10"/>
  </joint>

  <link name="vacuum_gripper1">
   <gravity>0</gravity>
   <visual>
   <origin rpy="0 0 0" xyz="0 0 0"/>
   <geometry>
   <cylinder radius="0.005" length="0.001"/>
   </geometry>
   <material name="transparent">
   <color rgba="0 0 0 0"/>
   </material>
   </visual>
   <inertial>
   <origin rpy="0 0 0" xyz="0 0 0"/>
   <mass value="0.0001"/>
   <inertia ixx="1e-08" ixy="0" ixz="0" iyy="1e-08" iyz="0" izz="1e-08"/>
   </inertial>
   </link>
   <joint name="gripper_joint1" type="revolute">
   <axis xyz="1 0 0" />
   <parent link="Stick" />
   <child link="vacuum_gripper1" />
   <origin rpy=" -1.5708 0  0 ...
(more)
edit retag flag offensive close merge delete

Comments

1

I am learning this plugin as well, but I am having issues with the force being too small. Could you kindly share how heavy is your object? were you able to get actual 50N from one vaccum gripper?

hwan30 gravatar image hwan30  ( 2022-05-05 00:46:49 -0500 )edit

Unfortunately this tag creates a link to the object, like it will lock to the object origin. What I did was that I edited the c++ plugin to link to the first collision instead of the origin. But this will grab the item and will never let go unless you turn the service from on to off. "As commented by gvdhorn, you can turn on/off the vacuum gripper with on, off ros service with std_srvs/Empty message.". So it will not accurately simulate an actual gripper. Instead I used friction for this project. Where instead of using plugins, I used friction but this is a huge task and I no longer have the code. But I can certainly point you to the right direction if you need assistance . @hwan30

Obeseturtle gravatar image Obeseturtle  ( 2022-05-24 19:37:29 -0500 )edit