00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 import csv, os
00021
00022
00023 import rospy, roslib
00024 from moveit_msgs.msg import *
00025 from geometry_msgs.msg import *
00026 from trajectory_msgs.msg import *
00027
00028
00029
00030 def check_database(object_name, gripper_type):
00031
00032 path_in = roslib.packages.get_pkg_dir('cob_grasp_generation')+'/files/database/'+object_name+'/'+gripper_type+'_'+object_name+'.csv'
00033
00034
00035 if os.path.exists(path_in):
00036 return True
00037 else:
00038 return False
00039
00040 def get_grasp_list(object_name, gripper_type, sort_by_quality=False):
00041
00042 path_in = roslib.packages.get_pkg_dir('cob_grasp_generation')+'/files/database/'+object_name+'/'+gripper_type+'_'+object_name+'.csv'
00043
00044
00045 try:
00046 with open(path_in) as f: pass
00047 except IOError as e:
00048 rospy.logerr("The path or file does not exist: "+path_in)
00049
00050
00051 reader = csv.DictReader( open(path_in, "rb"), delimiter=',')
00052
00053 if sort_by_quality:
00054
00055 return sorted(reader, key=lambda d: float(d['eps_l1']), reverse=True)
00056 else:
00057 return sorted(reader, key=lambda d: float(d['id']), reverse=False)
00058
00059
00060 def get_grasps(object_name, gripper_type, gripper_side="", grasp_id=0, num_grasps=0, threshold=0):
00061
00062 grasp_list = get_grasp_list(object_name, gripper_type)
00063
00064
00065 if grasp_id > 0:
00066 if grasp_id < len(grasp_list):
00067
00068 return [_fill_grasp_msg(gripper_type, gripper_side, grasp_list[grasp_id])]
00069 else:
00070 print "Grasp not available"
00071 return []
00072
00073
00074 sorted_list = sorted(grasp_list, key=lambda d: float(d['eps_l1']), reverse=True)
00075
00076
00077 if num_grasps > 0:
00078 max_grasps=min(len(sorted_list),num_grasps)
00079 else:
00080 max_grasps=len(sorted_list)
00081
00082
00083 selected_grasp_list = []
00084 for i in range(0,max_grasps):
00085 if threshold > 0 and float(sorted_list[i]['eps_l1']) >= threshold:
00086 selected_grasp_list.append(_fill_grasp_msg(gripper_type, gripper_side, sorted_list[i]))
00087 elif threshold == 0:
00088 selected_grasp_list.append(_fill_grasp_msg(gripper_type, gripper_side, sorted_list[i]))
00089 else:
00090 pass
00091
00092
00093 return selected_grasp_list
00094
00095
00096 def _fill_grasp_msg(gripper_type, gripper_side, grasp):
00097
00098
00099 joint_config = JointTrajectory()
00100
00101
00102
00103
00104 if gripper_type == "sdh":
00105 joint_config.joint_names = ['sdh_knuckle_joint', 'sdh_finger_12_joint', 'sdh_finger_13_joint', 'sdh_finger_22_joint', 'sdh_finger_23_joint', 'sdh_thumb_2_joint', 'sdh_thumb_3_joint']
00106 elif gripper_type == "sdhx":
00107 joint_config.joint_names = ['gripper_finger_1_joint', 'gripper_finger_2_joint']
00108 else:
00109 rospy.logerr("Gripper not supported")
00110 return Grasp()
00111
00112
00113 point = JointTrajectoryPoint()
00114 for joint_name in joint_config.joint_names:
00115 point.positions.append(float(grasp[joint_name]))
00116 point.velocities.append(0.0)
00117 point.accelerations.append(0.0)
00118 point.effort.append(0.0)
00119 point.time_from_start = rospy.Duration(3.0)
00120 joint_config.points.append(point)
00121
00122
00123
00124 if gripper_type == "sdh":
00125 if gripper_side == "left":
00126 joint_config.joint_names = ['sdh_left_knuckle_joint', 'sdh_left_finger_12_joint', 'sdh_left_finger_13_joint', 'sdh_left_finger_22_joint', 'sdh_left_finger_23_joint', 'sdh_left_thumb_2_joint', 'sdh_left_thumb_3_joint']
00127 elif gripper_side == "right":
00128 joint_config.joint_names = ['sdh_right_knuckle_joint', 'sdh_right_finger_12_joint', 'sdh_right_finger_13_joint', 'sdh_right_finger_22_joint', 'sdh_right_finger_23_joint', 'sdh_right_thumb_2_joint', 'sdh_right_thumb_3_joint']
00129 else:
00130 joint_config.joint_names = ['sdh_knuckle_joint', 'sdh_finger_12_joint', 'sdh_finger_13_joint', 'sdh_finger_22_joint', 'sdh_finger_23_joint', 'sdh_thumb_2_joint', 'sdh_thumb_3_joint']
00131 elif gripper_type == "sdhx":
00132 if gripper_side == "left":
00133 joint_config.joint_names = ['gripper_left_finger_1_joint', 'gripper_left_finger_2_joint']
00134 elif gripper_side == "right":
00135 joint_config.joint_names = ['gripper_right_finger_1_joint', 'gripper_right_finger_2_joint']
00136 else:
00137 joint_config.joint_names = ['gripper_finger_1_joint', 'gripper_finger_2_joint']
00138 else:
00139 rospy.logerr("Gripper not supported")
00140 return Grasp()
00141
00142
00143
00144
00145 pre_joint_config = JointTrajectory()
00146
00147
00148
00149
00150 if gripper_type == "sdh":
00151 if gripper_side == "left":
00152 pre_joint_config.joint_names = ['sdh_left_knuckle_joint', 'sdh_left_finger_12_joint', 'sdh_left_finger_13_joint', 'sdh_left_finger_22_joint', 'sdh_left_finger_23_joint', 'sdh_left_thumb_2_joint', 'sdh_left_thumb_3_joint']
00153 elif gripper_side == "right":
00154 pre_joint_config.joint_names = ['sdh_right_knuckle_joint', 'sdh_right_finger_12_joint', 'sdh_right_finger_13_joint', 'sdh_right_finger_22_joint', 'sdh_right_finger_23_joint', 'sdh_right_thumb_2_joint', 'sdh_right_thumb_3_joint']
00155 else:
00156 pre_joint_config.joint_names = ['sdh_knuckle_joint', 'sdh_finger_12_joint', 'sdh_finger_13_joint', 'sdh_finger_22_joint', 'sdh_finger_23_joint', 'sdh_thumb_2_joint', 'sdh_thumb_3_joint']
00157 open_config = [0.0, -0.9854, 0.9472, -0.9854, 0.9472, -0.9854, 0.9472]
00158 elif gripper_type == "sdhx":
00159 if gripper_side == "left":
00160 pre_joint_config.joint_names = ['gripper_left_finger_1_joint', 'gripper_left_finger_2_joint']
00161 elif gripper_side == "right":
00162 pre_joint_config.joint_names = ['gripper_right_finger_1_joint', 'gripper_right_finger_2_joint']
00163 else:
00164 pre_joint_config.joint_names = ['gripper_finger_1_joint', 'gripper_finger_2_joint']
00165 open_config = [-0.85, -0.5]
00166
00167 else:
00168 rospy.logerr("Gripper not supported")
00169 return Grasp()
00170
00171 point = JointTrajectoryPoint()
00172 for i in range(len(pre_joint_config.joint_names)):
00173 point.positions.append(open_config[i])
00174 point.velocities.append(0.0)
00175 point.accelerations.append(0.0)
00176 point.effort.append(0.0)
00177 point.time_from_start = rospy.Duration(3.0)
00178 pre_joint_config.points.append(point)
00179
00180
00181
00182 grasp_pose = PoseStamped()
00183 grasp_pose.header.stamp = rospy.Time.now()
00184
00185 grasp_pose.pose.position.x = float(grasp['pos-x'])*0.001
00186 grasp_pose.pose.position.y = float(grasp['pos-y'])*0.001
00187 grasp_pose.pose.position.z = float(grasp['pos-z'])*0.001
00188 grasp_pose.pose.orientation.x = float(grasp['qx'])
00189 grasp_pose.pose.orientation.y = float(grasp['qy'])
00190 grasp_pose.pose.orientation.z = float(grasp['qz'])
00191 grasp_pose.pose.orientation.w = float(grasp['qw'])
00192
00193
00194 grasp_out = Grasp()
00195 grasp_out.id = grasp['id']
00196 grasp_out.pre_grasp_posture = pre_joint_config
00197 grasp_out.grasp_posture = joint_config
00198 grasp_out.grasp_pose = grasp_pose
00199 grasp_out.grasp_quality = float(grasp['eps_l1'])
00200 grasp_out.max_contact_force = 0
00201
00202 return grasp_out