$search
00001 #!/usr/bin/python 00002 00003 import roslib 00004 roslib.load_manifest('srs_grasping') 00005 import rospy 00006 import grasping_functions 00007 from shared_state_information import * 00008 00009 00010 from simple_script_server import * 00011 sss = simple_script_server() 00012 00013 from srs_grasping.srv import * 00014 00015 class select_grasp(smach.State): 00016 00017 def __init__(self): 00018 smach.State.__init__( 00019 self, 00020 outcomes=['succeeded', 'failed', 'preempted'], 00021 input_keys=['object'], 00022 output_keys=['grasp_configuration']) 00023 00024 #default grasp categorisation 00025 #self.grasp_configuration = "" 00026 self.object_id=9 00027 00028 def execute(self, userdata): 00029 00030 global listener 00031 try: 00032 # transform object_pose into base_link 00033 object_pose_in = userdata.object.pose 00034 print object_pose_in 00035 object_pose_in.header.stamp = listener.getLatestCommonTime("/base_link",object_pose_in.header.frame_id) 00036 object_pose_bl = listener.transformPose("/base_link", object_pose_in) 00037 except rospy.ROSException, e: 00038 print "Transformation not possible: %s"%e 00039 return 'failed' 00040 00041 get_grasps_from_position = rospy.ServiceProxy('get_grasps_from_position', GetGraspsFromPosition) 00042 req = GetGraspsFromPositionRequest(self.object_id, object_pose_bl.pose) 00043 grasp_configuration = (get_grasps_from_position(req)).grasp_configuration 00044 00045 userdata.grasp_configuration = grasp_configuration[1] 00046 00047 return 'succeeded' 00048 00049 00050 00051 class grasp(smach.State): 00052 def __init__(self): 00053 smach.State.__init__(self, outcomes=['succeeded','not_completed','retry' ,'failed', 'preempted'], input_keys=['grasp_configuration']) 00054 00055 def get_joint_state(self, msg): 00056 global current_joint_configuration 00057 current_joint_configuration = list(msg.desired.positions) 00058 rospy.spin() 00059 00060 def execute(self, userdata): 00061 rospy.loginfo('Executing state GRASP') 00062 00063 #Open SDH at the pre-grasp position ----------------------------------------------- 00064 sss.move("sdh", "cylopen") 00065 00066 #Get the current arm joint states. 00067 sub = rospy.Subscriber("/arm_controller/state", JointTrajectoryControllerState, self.get_joint_state) 00068 while sub.get_num_connections() == 0: 00069 time.sleep(0.3) 00070 continue 00071 00072 #Move to grasp position with SDH open --------------------------------------------- 00073 #pregrasp 00074 pre_grasp_stamped = PoseStamped(); 00075 pre_grasp_stamped.header.frame_id = "/base_link"; 00076 pre_grasp_stamped.pose = userdata.grasp_configuration.pre_grasp; 00077 00078 #grasp 00079 grasp_stamped = PoseStamped(); 00080 grasp_stamped.header.frame_id = "/base_link"; 00081 grasp_stamped.pose = userdata.grasp_configuration.grasp; 00082 00083 #offset 00084 """ 00085 offset_x = 0#(userdata.grasp_configuration.grasp.position.x - userdata.grasp_configuration.pre_grasp.position.x)/3 00086 offset_y = 0#(userdata.grasp_configuration.grasp.position.y - userdata.grasp_configuration.pre_grasp.position.y)/3 00087 offset_z = 0#(userdata.grasp_configuration.grasp.position.z - userdata.grasp_configuration.pre_grasp.position.z)/3 00088 00089 pre_grasp_stamped.pose.position.x += offset_x 00090 pre_grasp_stamped.pose.position.y += offset_y 00091 pre_grasp_stamped.pose.position.z -= offset_z 00092 grasp_stamped.pose.position.x += offset_x 00093 grasp_stamped.pose.position.y += offset_y 00094 grasp_stamped.pose.position.z -= offset_z 00095 """ 00096 00097 00098 sol = False 00099 for i in range(0,10): 00100 (pre_grasp_conf, error_code) = grasping_functions.callIKSolver(current_joint_configuration, pre_grasp_stamped) 00101 if(error_code.val == error_code.SUCCESS): 00102 for j in range(0,10): 00103 (grasp_conf, error_code) = grasping_functions.callIKSolver(pre_grasp_conf, grasp_stamped) 00104 sol = True 00105 break 00106 if sol: 00107 break; 00108 00109 00110 if not sol: 00111 return 'failed'; 00112 else: 00113 arm_handle = sss.move("arm", [pre_grasp_conf], False) 00114 arm_handle.wait(); 00115 rospy.sleep(2); 00116 arm_handle = sss.move("arm", [grasp_conf], False) 00117 arm_handle.wait(); 00118 rospy.sleep(2); 00119 00120 #Close SDH based on the grasp configuration to grasp. 00121 arm_handle = sss.move("sdh", [list(userdata.grasp_configuration.sdh_joint_values)], False) 00122 arm_handle.wait(); 00123 rospy.sleep(2); 00124 00125 #TODO: Confirm the grasp based on force feedback 00126 successful_grasp = grasping_functions.sdh_tactil_sensor_result(); 00127 00128 if successful_grasp: 00129 return 'succeeded' 00130 else: 00131 #TODO: Regrasp (close MORE the fingers) 00132 regrasp = list(userdata.grasp_configuration.sdh_joint_values) 00133 regrasp[2] -= 0.1 00134 regrasp[4] -= 0.1 00135 regrasp[6] -= 0.1 00136 arm_handle = sss.move("sdh", [regrasp], False) 00137 arm_handle.wait(); 00138 00139 successful_regrasp = grasping_functions.sdh_tactil_sensor_result(); 00140 if successful_regrasp: 00141 return 'succeeded' 00142 else: 00143 return 'failed' 00144 #return 'failed'