Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 import rospy
00037 from actionlib import SimpleActionClient
00038 from geometry_msgs.msg import PoseArray, Pose, Point
00039 from std_msgs.msg import Header
00040 from moveit_simple_grasps.msg import GenerateGraspsAction, GenerateGraspsGoal
00041 from moveit_msgs.msg import Grasp
00042 import geometry_msgs
00043
00044 grasp_publisher = None
00045 grasps_ac = None
00046
00047 def generate_grasps(pose, width):
00048
00049 grasps_ac.wait_for_server()
00050 rospy.loginfo("Successfully connected.")
00051 goal = GenerateGraspsGoal()
00052 goal.pose = pose.pose
00053 goal.width = width
00054 grasps_ac.send_goal(goal)
00055 rospy.loginfo("Sent goal, waiting:\n" + str(goal))
00056 t_start = rospy.Time.now()
00057 grasps_ac.wait_for_result()
00058 t_end = rospy.Time.now()
00059 t_total = t_end - t_start
00060 rospy.loginfo("Result received in " + str(t_total.to_sec()))
00061 grasp_list = grasps_ac.get_result().grasps
00062 return grasp_list
00063
00064 def publish_grasps_as_poses(grasps):
00065 rospy.loginfo("Publishing PoseArray on /grasp_pose_from_block_bla for grasp_pose")
00066 graspmsg = Grasp()
00067 grasp_PA = PoseArray()
00068 header = Header()
00069 header.frame_id = "base_link"
00070 header.stamp = rospy.Time.now()
00071 grasp_PA.header = header
00072 for graspmsg in grasps:
00073 p = Pose(graspmsg.grasp_pose.pose.position, graspmsg.grasp_pose.pose.orientation)
00074 grasp_PA.poses.append(p)
00075 grasp_publisher.publish(grasp_PA)
00076 rospy.loginfo('Published ' + str(len(grasp_PA.poses)) + ' poses')
00077 rospy.sleep(2)
00078
00079
00080 if __name__ == '__main__':
00081 name = 'grasp_object_server'
00082 rospy.init_node(name, anonymous=False)
00083 rospy.loginfo("Connecting to grasp generator AS")
00084 grasps_ac = SimpleActionClient('/moveit_simple_grasps_server/generate', GenerateGraspsAction)
00085 grasp_publisher = rospy.Publisher("generated_grasps", PoseArray)
00086 object_pose = geometry_msgs.msg.PoseStamped()
00087 object_pose.pose.position.x = 1.0
00088 object_pose.pose.position.y = 1.0
00089 object_pose.pose.position.z = 1.0
00090 object_pose.pose.orientation.w = 1.0
00091 object_pose.pose.orientation.x = 0.0
00092 object_pose.pose.orientation.y = 0.0
00093 object_pose.pose.orientation.z = 0.0
00094 grasp_list = generate_grasps(object_pose, 0.06)
00095 rospy.loginfo('Generated ' + str(len(grasp_list)) + ' grasps.')
00096 publish_grasps_as_poses(grasp_list)
00097 rospy.sleep(10.0)