Implementation of vacuum suction using vacuum gripper
Hello. I'm in the process of implementing vacuum suction by referring to some of the open sources here. I referenced a lot in urdf, gazebo's xacro, and node files, but the object should stick to the wall, but it keeps falling off. I'll give you the attached file, can you take a look? Source code is here.
python code of vacuum suction
#!/usr/bin/env python3
import rospy
from geometry_msgs.msg import Twist
import moveit_msgs.msg
from std_msgs.msg import Header
from std_msgs.msg import Bool
from std_srvs.srv import Empty
def gripper_status(msg):
if msg.data:
return True
def gripper1():
rospy.wait_for_service('/wallclimb/vacuum1/on')
try:
turn_on = rospy.ServiceProxy('/wallclimb/vacuum1/on', Empty)
resp = turn_on()
return resp
except rospy.ServiceException as e:
print("Service call failed : %s" % e)
def gripper2():
rospy.wait_for_service('/wallclimb/vacuum2/on')
try:
turn_on = rospy.ServiceProxy('/wallclimb/vacuum2/on', Empty)
resp = turn_on()
return resp
except rospy.ServiceException as e
print("Service call failed : %s" % e)
rospy.init_node('climbbot_gripper', anonymous=False)
gripper_sub = rospy.Subscriber('/wallclimb/vacuum/grip', Bool, gripper_status,queue_size=1)
gripper1()
gripper2()
rospy.spin()
urdf.xacro of vacuum suction part
<joint name="vacuum_front_joint" type="revolute">
<parent link="base_link"/>
<child link="vacuum_front_link"/>
<origin xyz="0.0625 0 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="5000" velocity="50" lower="0" upper="0"/>
<dynamics damping="0.0" friction="10"/>
</joint>
<link name="vacuum_front_link">
<gravity>0</gravity>
<visual>
<geometry>
<mesh filename="package://wallclimb/mesh/wall_climb_prototype_vacuum_front.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.0625 0 0"/>
<material name="yellow">
<color rgba="1 1 0 1"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://wallclimb/mesh/wall_climb_prototype_vacuum_front.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.0625 0 0"/>
</collision>
<xacro:vacuum_front_inertia m="${vacuum_M}" r="${vacuum_R}" h="${vacuum_H}"/>
</link>
<joint name="vacuum_back_joint" type="fixed">
<parent link="base_link"/>
<child link="vacuum_back_link"/>
<origin xyz="-0.0625 0 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="5000" velocity="50" lower="0" upper="0"/>
<dynamics damping="0.0" friction="10"/>
</joint>
<link name="vacuum_back_link">
<gravity>0</gravity>
<visual>
<geometry>
<mesh filename="package://wallclimb/mesh/wall_climb_prototype_vacuum_back.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin rpy="0 0 0" xyz="0.0625 0 0"/>
<material name="yellow">
<color rgba="1 1 0 1"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://wallclimb/mesh/wall_climb_prototype_vacuum_back.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin rpy="0 0 0" xyz="0.0625 0 0"/>
</collision>
<xacro:vacuum_back_inertia m="${vacuum_M}" r="${vacuum_R}" h="${vacuum_H}"/>
</link>
gazebo.xacro of vauum suction part
<gazebo>
<plugin name="gazebo_ros_vacuum_gripper1" filename="libgazebo_ros_vacuum_gripper.so">
<robotNamespace>/wallclimb/vacuum1</robotNamespace>
<bodyName>vacuum_front_link</bodyName>
<topicName>grip1</topicName>
<maxForce>5000</maxForce>
<maxDistance>0 ...
Maybe the discussion in question #q243080 will help you. From that discussion, it seems that the plugin assumes the "object" the vacuum is trying to grip is a link, and that the link is moveable within the world. If those assumptions do not apply to your simulation, I don't see how you can use this plugin.
Thank you I implemented the code based on the document, so it became a lot of good material. But what I don't understand is why the plug-in doesn't work properly when the wall created through Gazebo's model editor is also a link. When I run py, the gripper goes from off to on without a problem.