def push_back(objPose=[1.95, 0.25, 1.4, 0, 0, 0, 1], binNum=4, objId='crayola_64_ct', bin_contents=[ 'paper_mate_12_count_mirado_black_warrior', 'crayola_64_ct', 'expo_dry_erase_board_eraser' ], robotConfig=None, grasp_range_lim=0.11, fing_width=0.06, isExecute=True, withPause=True): #~ ***************************************************************** obj_dim = get_obj_dim(objId) obj_dim = np.array(obj_dim) #~ ***************************************************************** # # DEFINE HAND WIDTH######################### hand_width = 0.186 #~ ***************************************************************** ## initialize listener rospy listener = tf.TransformListener() rospy.sleep(0.1) br = tf.TransformBroadcaster() rospy.sleep(0.1) (shelf_position, shelf_quaternion) = lookupTransform("map", "shelf", listener) # print shelf_position, shelf_quaternion #~ ***************************************************************** # Convert xyx quat to tranformation matrix for Shelf frame #~ shelf_pose_tfm_list=matrix_from_xyzquat(shelfPose[0:3], shelfPose[3:7]) shelf_pose_tfm_list = matrix_from_xyzquat(shelf_position, shelf_quaternion) shelf_pose_tfm = np.array(shelf_pose_tfm_list) shelf_pose_orient = shelf_pose_tfm[0:3, 0:3] #~ print '[PushBack] shelf_pose_orient' #~ print shelf_pose_orient shelf_pose_pos = shelf_pose_tfm[0:3, 3] #~ print '[PushBack] shelf_pose_pos' #~ print shelf_pose_pos #Normalized axes of the shelf frame shelf_X = shelf_pose_orient[:, 0] / la.norm(shelf_pose_orient[:, 0]) shelf_Y = shelf_pose_orient[:, 1] / la.norm(shelf_pose_orient[:, 1]) shelf_Z = shelf_pose_orient[:, 2] / la.norm(shelf_pose_orient[:, 2]) #~ ***************************************************************** # Convert xyx quat to tranformaation matrix for Object frame obj_pose_tfm_list = matrix_from_xyzquat(objPose[0:3], objPose[3:7]) obj_pose_tfm = np.array(obj_pose_tfm_list) obj_pose_orient = obj_pose_tfm[0:3, 0:3] obj_pose_pos = obj_pose_tfm[0:3, 3] #~ print '[PushBack] obj_pose_orient' #~ print obj_pose_orient #Normalized axes of the object frame obj_X = obj_pose_orient[:, 0] / la.norm(obj_pose_orient[:, 0]) #~ print '[PushBack] obj_X' #~ print obj_X obj_Y = obj_pose_orient[:, 1] / la.norm(obj_pose_orient[:, 1]) #~ print '[PushBack] obj_Y' #~ print obj_Y obj_Z = obj_pose_orient[:, 2] / la.norm(obj_pose_orient[:, 2]) #~ print '[PushBack] obj_Z' #~ print obj_Z #Normalized object frame obj_pose_orient_norm = np.vstack((obj_X, obj_Y, obj_Z)) obj_pose_orient_norm = obj_pose_orient_norm.transpose() #~ print '[PushBack] obj_pose_orient_norm' #~ print obj_pose_orient_norm #~ ***************************************************************** # We will assume that hand normal tries to move along object dimension along the Y axis of the shelf (along the lenght of the bin) # Find projection of object axes on Y axis of the shelf frame proj_vecY = np.dot(shelf_Y, obj_pose_orient_norm) #~ print '[PushBack] proj' #~ print proj_vecY max_proj_valY, hand_norm_dir = np.max(np.fabs(proj_vecY)), np.argmax( np.fabs(proj_vecY)) if proj_vecY[hand_norm_dir] > 0: hand_norm_vec = -obj_pose_orient_norm[:, hand_norm_dir] else: hand_norm_vec = obj_pose_orient_norm[:, hand_norm_dir] #~ print '[PushBack] hand_norm_vec' #~ print hand_norm_vec #Find angle of the edge of the object Cos_angle_made_with_shelf_Y = max_proj_valY / (la.norm(shelf_Y) * la.norm(hand_norm_vec)) angle_to_shelfY = np.arccos(Cos_angle_made_with_shelf_Y) * 180 / np.pi #~ print'angle_to_shelfY' #~ print angle_to_shelfY #Find object dimension along hand normal axis obj_dim_along_hand_norm = obj_dim[hand_norm_dir] # print '[PushBack] dim along hand norm' # print obj_dim_along_hand_norm #~ ***************************************************************** #Find projection of object axes on X axis of the shelf frame #To find out which object frame is lying closer to the X axis of the shelf proj_vecX = np.dot(shelf_X, obj_pose_orient_norm) max_proj_valX, fing_axis_dir = np.max(np.fabs(proj_vecX)), np.argmax( np.fabs(proj_vecX)) if proj_vecX[fing_axis_dir] > 0: fing_axis_vec = obj_pose_orient_norm[:, fing_axis_dir] else: fing_axis_vec = -obj_pose_orient_norm[:, fing_axis_dir] #~ print '[PushBack] fing_axis_vec' #~ print fing_axis_vec #Find object dimension along the finger axis obj_dim_along_fingAxis = obj_dim[fing_axis_dir] # print '[PushBack] obj_dim_along_fingAxis' # print obj_dim_along_fingAxis #~ ***************************************************************** #Find projection of object axes on Z axis of the shelf frame #To find out which object frame is lying closer to the Z axis of the shelf proj_vecZ = np.dot(shelf_Z, obj_pose_orient_norm) max_proj_valZ, Zaxis_dir = np.max(np.fabs(proj_vecZ)), np.argmax( np.fabs(proj_vecZ)) Zaxis_vec = obj_pose_orient_norm[:, Zaxis_dir] #~ print '[PushBack] Zaxis_vec' #~ print Zaxis_vec #Find object dimension along the finger axis, shelf Z obj_dim_along_ZAxis = obj_dim[Zaxis_dir] hand_Y = np.cross(hand_norm_vec, fing_axis_vec) diag_dist = la.norm( np.array([obj_dim_along_hand_norm, obj_dim_along_fingAxis])) # print'req obj diag dist=', diag_dist #~ ***************************************************************** # Find the maximum distance to which we will push other_diag = np.zeros(len(bin_contents)) for num_bin_contents in range(0, len(bin_contents)): if bin_contents[num_bin_contents] != objId: temp_obj_dim = get_obj_dim(objId) other_diag[num_bin_contents] = la.norm( np.array([temp_obj_dim[0], temp_obj_dim[1]])) max_diag, max_obj_ID = np.max(np.fabs(other_diag)), np.argmax( np.fabs(other_diag)) # print '[PushBack] max_obj_ID',max_diag # print '[PushBack] max_obj_ID', bin_contents[max_obj_ID] #******************************************************************* bin_inner_cnstr = get_bin_inner_cnstr() #******************************************************************* #Check if we can do left push diag_factor = 0.75 obj_left_edge = obj_pose_pos[1] + diag_factor * diag_dist / 2.0 binLeftWall = bin_inner_cnstr[binNum][1] binLeftWall_world = coordinateFrameTransform([binLeftWall, 0, 0], 'shelf', 'map', listener) binRightWall = bin_inner_cnstr[binNum][0] binRightWall_world = coordinateFrameTransform([binRightWall, 0, 0], 'shelf', 'map', listener) left_gap = binLeftWall_world.pose.position.y - obj_left_edge # print '[PushBack] left_gap=', left_gap fing_clearance = 0.010 # It's like 5 mm on both sides of finger bin_width = binLeftWall_world.pose.position.y - binRightWall_world.pose.position.y tolerance_in_push = 0.020 if left_gap + diag_dist / 2.0 - tolerance_in_push > bin_width: print '[PushBack] looks like vision has messed up. the object does not seem to be in the appropriate bin' return (False, False) if left_gap > fing_width + fing_clearance: left_push = True print '[PushBack] left push is possible' else: left_push = False print '[PushBack] left push is NOT possible' # check if we can do right push obj_right_edge = obj_pose_pos[1] - diag_factor * diag_dist / 2.0 right_gap = obj_right_edge - binRightWall_world.pose.position.y # print '[PushBack] right_gap', right_gap fing_clearance = 0.010 # It's like 5 mm on both sides of finger if right_gap + diag_dist / 2.0 - tolerance_in_push > bin_width: print '[PushBack] looks like vision has messed up. the object does not seem to be in the appropriate bin' return (False, False) if right_gap > fing_width + fing_clearance: right_push = True print '[PushBack] right push is possible' else: right_push = False print '[PushBack] right push is NOT possible' #******************************************************************* #Find Push Points for left push bin_face_pos, binFloorHeight = getBinMouthAndFloor(0.0, binNum) bin_face_pos_world = coordinateFrameTransform(bin_face_pos, 'shelf', 'map', listener) tcp_Z_off = 0.005 #lower down from center of the bin push_tcp_Z_shelfFrame = ( (bin_inner_cnstr[binNum][4] + bin_inner_cnstr[binNum][5]) / 2.0) - tcp_Z_off push_tcp_Z_WorldFrame = coordinateFrameTransform( [0, 0, push_tcp_Z_shelfFrame], 'shelf', 'map', listener) push_tcp_Z = push_tcp_Z_WorldFrame.pose.position.z push_side_off = 1.0 if left_push: left_pushPt_X = bin_face_pos_world.pose.position.x + 0.05 left_pushPt_Y = binLeftWall_world.pose.position.y - push_side_off * left_gap # left_Y_lim=binLeftWall_world.pose.position.y- left_pushPt_Z = deepcopy(push_tcp_Z) left_push_Pt = np.array([left_pushPt_X, left_pushPt_Y, left_pushPt_Z]) print '[PushBack] expected left push clearance=', binLeftWall_world.pose.position.y - left_pushPt_Y - fing_width / 2.0 #Find Push Points for right push if right_push: right_pushPt_X = bin_face_pos_world.pose.position.x + 0.05 right_pushPt_Y = binRightWall_world.pose.position.y + push_side_off * right_gap right_pushPt_Z = deepcopy(push_tcp_Z) right_push_Pt = np.array( [right_pushPt_X, right_pushPt_Y, right_pushPt_Z]) print '[PushBack] expected right push clearance=', right_pushPt_Y - binRightWall_world.pose.position.y - fing_width / 2.0 #Execute push trajectories #~ ************************************************************* # set spatual down orientation (rotate wrist) spatula_down_orient = [0, 0.7071, 0, 0.7071] push_orient = spatula_down_orient push_hand_opening = 0.100 joint_topic = '/joint_states' #~ ************************************************************* #Execure left push trajectory if left_push: # plan store left_plans = [] # set tcp (same as that set in generate dictionary) l1 = 0.0 l2 = 0.0 l3 = 0.47 tip_hand_transform = [ l1, l2, l3, 0, 0, 0 ] # to be updated when we have a hand design finalized # broadcast frame attached to tcp pubFrame(br, pose=tip_hand_transform, frame_id='tip', parent_frame_id='link_6', npub=5) #~ ************************************************************* # GO TO MOUTH OF THE BIN q_initial = robotConfig # move to bin mouth distFromShelf = 0.1 mouthPt, temp = getBinMouthAndFloor(distFromShelf, binNum) mouthPt = coordinateFrameTransform(mouthPt, 'shelf', 'map', listener) targetPosition = [ mouthPt.pose.position.x, mouthPt.pose.position.y, mouthPt.pose.position.z ] gripperOri = [0, 0.7071, 0, 0.7071] pubFrame(br, pose=targetPosition + gripperOri, frame_id='target_pose', parent_frame_id='link_6', npub=5) planner = IK(q0=q_initial, target_tip_pos=targetPosition, target_tip_ori=gripperOri, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() plan.setSpeedByName('faster') s = plan.success() if s: print '[PushBack] move to bin mouth in push-back code successful (left push)' left_plans.append(plan) # Plan 0 else: print '[PushBack] move to bin mouth in push-back code fail (left push)' return (False, False) qf = plan.q_traj[-1] q_initial = qf #################### CLOSE THE GRIPPER GRASP ################# grasp_plan = EvalPlan('moveGripper(%f, 100)' % (0.0)) left_plans.append(grasp_plan) #~ ************************************************************* ###### MOVE THE ROBOT INSIDE THE BIN WITH PUSH ORIENTATION ###### # set push_tcp push_l1 = 0.0 push_l2 = 0.0 push_l3 = 0.47 push_tip_hand_transform = [ l1, l2, l3, 0, 0, 0 ] # to be updated when we have a hand design finalized # broadcast frame attached to grasp_tcp pubFrame(br, pose=push_tip_hand_transform, frame_id='push_tip', parent_frame_id='link_6', npub=10) distFromShelf = -0.015 InbinPt, temp = getBinMouthAndFloor(distFromShelf, binNum) InbinPt = coordinateFrameTransform(InbinPt, 'shelf', 'map', listener) prepush_targetPosition = [ InbinPt.pose.position.x, left_push_Pt[1], InbinPt.pose.position.z ] #matching world_Y of first push pt pubFrame(br, pose=prepush_targetPosition + push_orient, frame_id='target_pose', parent_frame_id='map', npub=10) planner = IK(q0=q_initial, target_tip_pos=prepush_targetPosition, target_tip_ori=push_orient, tip_hand_transform=push_tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() plan.setSpeedByName('fast') s = plan.success() if s: print '[PushBack] move inside bin in push orient successful' #~ print '[PushBack] tcp at:' #~ print(pregrasp_targetPosition) #~ plan.visualize() left_plans.append(plan) # Plan 1 #~ if isExecute: #~ pauseFunc(withPause) #~ plan.execute() else: print '[PushBack] move inside bin in push orient fail' return (False, False) qf = plan.q_traj[-1] q_initial = qf #~ ************************************************************* ############## OPEN THE GRIPPER To PUSH############### # Open the gripper to dim calculated for pushing print '[PushBack] hand opening to' print push_hand_opening * 1000.0 grasp_plan = EvalPlan('moveGripper(%f, 100)' % (push_hand_opening)) left_plans.append(grasp_plan) #~ ************************************************************* ############ Execute the push trajectory ############## back_bin_X = bin_face_pos_world.pose.position.x + 0.43 push_stop_worldX = back_bin_X - max_diag - 0.010 left_pushStop_Pt_pos = deepcopy(left_push_Pt) left_pushStop_Pt_pos[0] = push_stop_worldX #Push until the end planner = IK(q0=q_initial, target_tip_pos=left_pushStop_Pt_pos, target_tip_ori=push_orient, joint_topic=joint_topic, tip_hand_transform=push_tip_hand_transform) plan = planner.plan() plan.setSpeedByName('fast') s = plan.success() if s: print '[PushBack] start point push traj successful' left_plans.append(plan) # Plan 1 else: print '[PushBack] start point push traj fail' return (False, False) qf = plan.q_traj[-1] q_initial = qf #################### CLOSE THE GRIPPER GRASP ################# grasp_plan = EvalPlan('moveGripper(%f, 100)' % (0.0)) left_plans.append(grasp_plan) #~ ************************************************************* # #################### EXECUTE FORWARD #################### for numOfPlan in range(0, len(left_plans)): if isExecute: left_plans[numOfPlan].visualize() pauseFunc(withPause) left_plans[numOfPlan].execute() # #################### RETREAT #################### for numOfPlan in range(0, len(left_plans)): if isExecute: left_plans[numOfPlan].visualizeBackward() pauseFunc(withPause) left_plans[len(left_plans) - numOfPlan - 1].executeBackward() #******************************************************************* if right_push: # plan store right_plans = [] # set tcp (same as that set in generate dictionary) l1 = 0.0 l2 = 0.0 l3 = 0.47 tip_hand_transform = [ l1, l2, l3, 0, 0, 0 ] # to be updated when we have a hand design finalized # broadcast frame attached to tcp pubFrame(br, pose=tip_hand_transform, frame_id='tip', parent_frame_id='link_6', npub=5) #~ ************************************************************* # GO TO MOUTH OF THE BIN q_initial = robotConfig # move to bin mouth distFromShelf = 0.1 mouthPt, temp = getBinMouthAndFloor(distFromShelf, binNum) mouthPt = coordinateFrameTransform(mouthPt, 'shelf', 'map', listener) targetPosition = [ mouthPt.pose.position.x, mouthPt.pose.position.y, mouthPt.pose.position.z ] gripperOri = [0, 0.7071, 0, 0.7071] pubFrame(br, pose=targetPosition + gripperOri, frame_id='target_pose', parent_frame_id='link_6', npub=5) planner = IK(q0=q_initial, target_tip_pos=targetPosition, target_tip_ori=gripperOri, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() plan.setSpeedByName('faster') s = plan.success() if s: print '[PushBack] move to bin mouth in push-back code successful (right push)' right_plans.append(plan) # Plan 0 else: print '[PushBack] move to bin mouth in push-back code fail (right push)' return (False, False) qf = plan.q_traj[-1] q_initial = qf #################### CLOSE THE GRIPPER GRASP ################# grasp_plan = EvalPlan('moveGripper(%f, 100)' % (0.0)) right_plans.append(grasp_plan) #~ ************************************************************* ###### MOVE THE ROBOT INSIDE THE BIN WITH PUSH ORIENTATION ###### # set push_tcp push_l1 = 0.0 push_l2 = 0.0 push_l3 = 0.47 push_tip_hand_transform = [ l1, l2, l3, 0, 0, 0 ] # to be updated when we have a hand design finalized # broadcast frame attached to grasp_tcp pubFrame(br, pose=push_tip_hand_transform, frame_id='push_tip', parent_frame_id='link_6', npub=10) distFromShelf = -0.015 InbinPt, temp = getBinMouthAndFloor(distFromShelf, binNum) InbinPt = coordinateFrameTransform(InbinPt, 'shelf', 'map', listener) prepush_targetPosition = [ InbinPt.pose.position.x, right_push_Pt[1], InbinPt.pose.position.z ] #matching world_Y of first push pt pubFrame(br, pose=prepush_targetPosition + push_orient, frame_id='target_pose', parent_frame_id='map', npub=10) planner = IK(q0=q_initial, target_tip_pos=prepush_targetPosition, target_tip_ori=push_orient, tip_hand_transform=push_tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() plan.setSpeedByName('fast') s = plan.success() if s: print '[PushBack] move inside bin in push orient successful' #~ print '[PushBack] tcp at:' #~ print(pregrasp_targetPosition) #~ plan.visualize() right_plans.append(plan) # Plan 1 #~ if isExecute: #~ pauseFunc(withPause) #~ plan.execute() else: print '[PushBack] move inside bin in push orient fail' return (False, False) qf = plan.q_traj[-1] q_initial = qf #~ ************************************************************* ############## OPEN THE GRIPPER To PUSH############### # Open the gripper to dim calculated for pushing print '[PushBack] hand opening to' print push_hand_opening * 1000.0 grasp_plan = EvalPlan('moveGripper(%f, 100)' % (push_hand_opening)) right_plans.append(grasp_plan) #~ ************************************************************* ############ Execute the push trajectory ############## back_bin_X = bin_face_pos_world.pose.position.x + 0.42 push_stop_worldX = back_bin_X - max_diag - 0.010 right_pushStop_Pt_pos = deepcopy(right_push_Pt) right_pushStop_Pt_pos[0] = push_stop_worldX #Push until the end planner = IK(q0=q_initial, target_tip_pos=right_pushStop_Pt_pos, target_tip_ori=push_orient, joint_topic=joint_topic, tip_hand_transform=push_tip_hand_transform) plan = planner.plan() plan.setSpeedByName('fast') s = plan.success() if s: print '[PushBack] start point push traj successful' right_plans.append(plan) # Plan 1 else: print '[PushBack] start point push traj fail' return (False, False) qf = plan.q_traj[-1] q_initial = qf #################### CLOSE THE GRIPPER GRASP ################# grasp_plan = EvalPlan('moveGripper(%f, 100)' % (0.0)) right_plans.append(grasp_plan) #~ ************************************************************* # #################### EXECUTE FORWARD #################### for numOfPlan in range(0, len(right_plans)): if isExecute: right_plans[numOfPlan].visualize() pauseFunc(withPause) right_plans[numOfPlan].execute() # #################### RETREAT #################### for numOfPlan in range(0, len(right_plans)): if isExecute: right_plans[numOfPlan].visualizeBackward() pauseFunc(withPause) right_plans[len(right_plans) - numOfPlan - 1].executeBackward() if right_push or left_push: push_possible = True else: push_possible = False return (push_possible, False)
def push_rotate(objPose=[1.95,0.25,1.4,0,0,0,1], binNum=4, objId = 'crayola_64_ct', bin_contents = None, robotConfig = None, grasp_range_lim=0.11, fing_width=0.06, isExecute = True, withPause = True): #~ ***************************************************************** obj_dim=get_obj_dim(objId) obj_dim=np.array(obj_dim) #~ ***************************************************************** # # DEFINE HAND WIDTH######################### hand_width=0.186 #~ ***************************************************************** ## initialize listener rospy listener = tf.TransformListener() br = tf.TransformBroadcaster() rospy.sleep(0.2) (shelf_position, shelf_quaternion) = lookupTransform("map", "shelf", listener) # print shelf_position, shelf_quaternion #~ ***************************************************************** # Convert xyx quat to tranformation matrix for Shelf frame #~ shelf_pose_tfm_list=matrix_from_xyzquat(shelfPose[0:3], shelfPose[3:7]) shelf_pose_tfm_list=matrix_from_xyzquat(shelf_position,shelf_quaternion) shelf_pose_tfm=np.array(shelf_pose_tfm_list) shelf_pose_orient=shelf_pose_tfm[0:3,0:3] #~ print 'shelf_pose_orient' #~ print shelf_pose_orient shelf_pose_pos=shelf_pose_tfm[0:3,3] #~ print 'shelf_pose_pos' #~ print shelf_pose_pos #Normalized axes of the shelf frame shelf_X=shelf_pose_orient[:,0]/la.norm(shelf_pose_orient[:,0]) shelf_Y=shelf_pose_orient[:,1]/la.norm(shelf_pose_orient[:,1]) shelf_Z=shelf_pose_orient[:,2]/la.norm(shelf_pose_orient[:,2]) #~ ***************************************************************** # Convert xyx quat to tranformaation matrix for Object frame obj_pose_tfm_list=matrix_from_xyzquat(objPose[0:3], objPose[3:7]) obj_pose_tfm=np.array(obj_pose_tfm_list) obj_pose_orient=obj_pose_tfm[0:3,0:3] obj_pose_pos=obj_pose_tfm[0:3,3] #~ print 'obj_pose_orient' #~ print obj_pose_orient #Normalized axes of the object frame obj_X=obj_pose_orient[:,0]/la.norm(obj_pose_orient[:,0]) #~ print 'obj_X' #~ print obj_X obj_Y=obj_pose_orient[:,1]/la.norm(obj_pose_orient[:,1]) #~ print 'obj_Y' #~ print obj_Y obj_Z=obj_pose_orient[:,2]/la.norm(obj_pose_orient[:,2]) #~ print 'obj_Z' #~ print obj_Z #Normalized object frame obj_pose_orient_norm=np.vstack((obj_X,obj_Y,obj_Z)) obj_pose_orient_norm=obj_pose_orient_norm.transpose() #~ print 'obj_pose_orient_norm' #~ print obj_pose_orient_norm #~ ***************************************************************** # We will assume that hand normal tries to move along object dimension along the Y axis of the shelf (along the lenght of the bin) # Find projection of object axes on Y axis of the shelf frame proj_vecY=np.dot(shelf_Y,obj_pose_orient_norm) #~ print 'proj' #~ print proj_vecY max_proj_valY,hand_norm_dir=np.max(np.fabs(proj_vecY)), np.argmax(np.fabs(proj_vecY)) if proj_vecY[hand_norm_dir]>0: hand_norm_vec=-obj_pose_orient_norm[:,hand_norm_dir] else: hand_norm_vec=obj_pose_orient_norm[:,hand_norm_dir] #~ print 'hand_norm_vec' #~ print hand_norm_vec #Find angle of the edge of the object Cos_angle_made_with_shelf_Y=max_proj_valY/(la.norm(shelf_Y)*la.norm(hand_norm_vec)); angle_to_shelfY=np.arccos(Cos_angle_made_with_shelf_Y)*180.0/np.pi #~ print'angle_to_shelfY' #~ print angle_to_shelfY #Find object dimension along hand normal axis obj_dim_along_hand_norm=obj_dim[hand_norm_dir] print '[PushRotate] dim along hand norm', obj_dim_along_hand_norm #~ ***************************************************************** #Find projection of object axes on X axis of the shelf frame #To find out which object frame is lying closer to the X axis of the shelf proj_vecX=np.dot(shelf_X,obj_pose_orient_norm) max_proj_valX,fing_axis_dir=np.max(np.fabs(proj_vecX)), np.argmax(np.fabs(proj_vecX)) if proj_vecX[fing_axis_dir]>0: fing_axis_vec=obj_pose_orient_norm[:,fing_axis_dir] else: fing_axis_vec=-obj_pose_orient_norm[:,fing_axis_dir] #~ print 'fing_axis_vec' #~ print fing_axis_vec #Find object dimension along the finger axis obj_dim_along_fingAxis=obj_dim[fing_axis_dir] print '[PushRotate] obj_dim_along_fingAxis:', obj_dim_along_fingAxis #~ ***************************************************************** #Find projection of object axes on Z axis of the shelf frame #To find out which object frame is lying closer to the Z axis of the shelf proj_vecZ=np.dot(shelf_Z,obj_pose_orient_norm) max_proj_valZ,Zaxis_dir=np.max(np.fabs(proj_vecZ)), np.argmax(np.fabs(proj_vecZ)) Zaxis_vec=obj_pose_orient_norm[:,Zaxis_dir] #~ print 'Zaxis_vec' #~ print Zaxis_vec #Find object dimension along the finger axis, shelf Z obj_dim_along_ZAxis=obj_dim[Zaxis_dir] hand_Y=np.cross(hand_norm_vec,fing_axis_vec) #~ ***************************************************************** #################### DECISION STRATEGIES ######################### bin_inner_cnstr=get_bin_inner_cnstr() proj_handNorm_ShelfX=np.dot(hand_norm_vec,shelf_X) right_push=False left_push=False # print 'obj_dim_along_hand_norm', obj_dim_along_hand_norm # print 'obj_dim_along_fingAxis', obj_dim_along_fingAxis # # print 'proj_handNorm_ShelfX' # print proj_handNorm_ShelfX if obj_dim_along_hand_norm>obj_dim_along_fingAxis: #~ print 'proj_vecY' #~ print proj_vecY #~ print proj_vecY[hand_norm_dir] #~ #~ print 'proj_vecX' #~ print proj_vecX #~ print proj_vecX[fing_axis_dir] #~ if proj_vecY[hand_norm_dir]*proj_vecX[fing_axis_dir]<0: #~ #Do left push #~ Ypush_mult=1 #~ print 'Left Push' #~ else: #~ #Do right push #~ Ypush_mult=-1 #~ print 'right Push' if proj_handNorm_ShelfX>0: #Do left push Ypush_mult=1 left_push=True print '[PushRotate] Left Push' else: #Do right push Ypush_mult=-1 print '[PushRotate] right Push' right_push=True push_offset=(obj_dim_along_hand_norm/2.0) #(Instead pf pushing on edge we will push 5 mm inside) else: #~ if proj_vecY[hand_norm_dir]*proj_vecX[fing_axis_dir]<0: #~ #Do right push #~ Ypush_mult=-1 #~ print 'right Push' #~ else: #~ #Do left push #~ Ypush_mult=1 #~ print 'Left Push' if proj_handNorm_ShelfX>0: #Do right push Ypush_mult=-1 print '[PushRotate] right Push' right_push=True else: #Do left push Ypush_mult=1 print '[PushRotate] Left Push' left_push=True push_offset=(obj_dim_along_fingAxis/2.0) num_intm_points=5 push_x_intm=np.zeros(num_intm_points+1) push_y_intm=np.zeros(num_intm_points+1) backWall_shelf=bin_inner_cnstr[binNum][1] backWall_world = coordinateFrameTransform([0,backWall_shelf,0], 'shelf', 'map', listener) back_check=backWall_world.pose.position.x-obj_dim_along_hand_norm/2.0 binRightWall=bin_inner_cnstr[binNum][0] binLeftWall=bin_inner_cnstr[binNum][1] binRightWall_world = coordinateFrameTransform([binRightWall,0,0], 'shelf', 'map', listener) binLeftWall_world = coordinateFrameTransform([binLeftWall,0,0], 'shelf', 'map', listener) if left_push: sideWall_check=binRightWall_world.pose.position.y+(fing_width/2.0)+(obj_dim_along_fingAxis) if right_push: sideWall_check=binLeftWall_world.pose.position.y-(fing_width/2.0)-(obj_dim_along_fingAxis) for i in range(num_intm_points+1): push_x_intm[i]=obj_pose_pos[0]+(push_offset)*np.sin(((90/num_intm_points)*i*np.pi)/180.0) if push_x_intm[i]>back_check: push_x_intm[i]=back_check push_y_intm[i]=obj_pose_pos[1]+(Ypush_mult*push_offset)*np.cos(((90/num_intm_points)*i*np.pi)/180.0) if left_push: if push_y_intm[i]<sideWall_check: push_y_intm[i]=sideWall_check print '[PushRotate] push Y reduced, I do not want to crush the obj and gripper' if right_push: if push_y_intm[i]>sideWall_check: push_y_intm[i]=sideWall_check print '[PushRotate] push Y reduced, I do not want to crush the obj and gripper' push_x_intm=np.array(push_x_intm) #~ print'push_x_intm' #~ print push_x_intm push_y_intm=np.array(push_y_intm) #******************************************************************* #Move the hand to the center of the bin and open the hand based on the height of the object bin_mid_pos,binFloorHeight=getBinMouthAndFloor(0.0, binNum) binFloorHeight_world = coordinateFrameTransform([0,0,binFloorHeight], 'shelf', 'map', listener) bin_mid_pos_world = coordinateFrameTransform(bin_mid_pos, 'shelf', 'map', listener) #******************************************************************* tcp_Z_off=0.005 push_tcp_Z_shelfFrame=((bin_inner_cnstr[binNum][4]+bin_inner_cnstr[binNum][5])/2.0)-tcp_Z_off push_tcp_Z_WorldFrame = coordinateFrameTransform([0,0,push_tcp_Z_shelfFrame], 'shelf', 'map', listener) push_tcp_Z=push_tcp_Z_WorldFrame.pose.position.z push_z_intm=(push_tcp_Z)*np.ones(push_x_intm.size) push_series_pos=np.vstack((push_x_intm,push_y_intm,push_z_intm)) push_series_pos=push_series_pos.transpose() #~ print 'push_series_pos' #~ print push_series_pos #~ print push_series_pos[0,:] #~ print push_series_pos[-1,:] push_possible=True #****************************************************************** fing_push_pt=0.2*obj_dim_along_ZAxis+binFloorHeight_world.pose.position.z blade_tip_TCP_off=0.038 # dist between finger inner end and spatual edge push_hand_opening=2*(push_tcp_Z-blade_tip_TCP_off-fing_push_pt) if push_hand_opening>grasp_range_lim: push_hand_opening=grasp_range_lim # Spatula finger should not hit the lip of the bin while pushing lip_Z_shelf=bin_inner_cnstr[binNum][4] lip_Z_world=coordinateFrameTransform([0,0,lip_Z_shelf], 'shelf', 'map', listener) #~ lip_off=.025 #~ bin_lip_Z=binFloorHeight_world.pose.position.z+lip_off max_allowed_hand_opening_out=2*(push_tcp_Z-lip_Z_world.pose.position.z) max_allowed_hand_opening=max_allowed_hand_opening_out-0.036 # 0.036 is diff between inside and outside of the finger/finger mount surface if push_hand_opening>max_allowed_hand_opening: print '[PushRotate] reducing hand opening bcaz it may hit the lip of the bin' push_hand_opening=max_allowed_hand_opening #~ print 'push_hand_opening' #~ print push_hand_opening #~ #hand should not hit the side walls #~ binRightWall,binLeftWall=find_shelf_walls(binNum) #~ #~ binRightWall_world = coordinateFrameTransform([binRightWall,0,0], 'shelf', 'map', listener) #~ binLeftWall_world = coordinateFrameTransform([binLeftWall,0,0], 'shelf', 'map', listener) side_wall_clearance=0.0 print '[PushRotate] binRightWall_world.pose.position.y', binRightWall_world.pose.position.y print '[PushRotate] right_hand_edge=', (push_y_intm[0]-fing_width-side_wall_clearance) print '[PushRotate] binLeftWall_world.pose.position.y', binLeftWall_world.pose.position.y print '[PushRotate] left_hand_edge=', (push_y_intm[0]+fing_width+side_wall_clearance) if push_y_intm[0]-fing_width-side_wall_clearance<binRightWall_world.pose.position.y: print '[PushRotate] Hand will hit the right wall, Push rotate not possible' push_possible=False if push_y_intm[0]+fing_width+side_wall_clearance>binLeftWall_world.pose.position.y: print '[PushRotate] Hand will hit the left wall, push rotate not possible' push_possible=False #~ ************************************************************* # set spatual down orientation (rotate wrist) spatula_down_orient = [0, 0.7071, 0, 0.7071] push_orient=deepcopy(spatula_down_orient) #~ ************************************************************* if push_possible==True: #Now we know where we wan to move TCP #Let's do robot motion planning now joint_topic = '/joint_states' # plan store plans = [] # set tcp (same as that set in generate dictionary) l1=0.0 l2=0.0 l3 = 0.47 tip_hand_transform = [l1, l2, l3, 0,0,0] # to be updated when we have a hand design finalized # broadcast frame attached to tcp pubFrame(br, pose=tip_hand_transform, frame_id='tip', parent_frame_id='link_6', npub=5) #~ ************************************************************* # GO TO MOUTH OF THE BIN q_initial = robotConfig # move to bin mouth distFromShelf = 0.1 mouthPt,temp = getBinMouthAndFloor(distFromShelf, binNum) mouthPt = coordinateFrameTransform(mouthPt, 'shelf', 'map', listener) targetPosition = [mouthPt.pose.position.x, mouthPt.pose.position.y, mouthPt.pose.position.z] gripperOri=[0, 0.7071, 0, 0.7071] pubFrame(br, pose = targetPosition+gripperOri, frame_id='target_pose', parent_frame_id='link_6', npub=5) planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = gripperOri, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() plan.setSpeedByName('faster') s = plan.success() if s: print '[PushRotate] move to bin mouth in push-rotate code successful' #plan.visualize() plans.append(plan) # Plan 0 #if isExecute: # pauseFunc(withPause) # plan.execute() else: print '[PushRotate] move to bin mouth in push-rotate code fail' return False qf = plan.q_traj[-1] q_initial = qf #################### CLOSE THE GRIPPER GRASP ################# grasp_plan = EvalPlan('moveGripper(%f, 100)' % (0.0)) plans.append(grasp_plan) #~ moveGripper(0.1,100) #~ ************************************************************* ###### MOVE THE ROBOT INSIDE THE BIN WITH PUSH ORIENTATION ###### # set push_tcp push_l1=0.0 #0.035 push_l2=-Ypush_mult*(fing_width/2.0) # This should depend on the righ or left push conditions push_l3 = 0.47 push_tip_hand_transform = [l1, l2, l3, 0,0,0] # to be updated when we have a hand design finalized # broadcast frame attached to grasp_tcp pubFrame(br, pose=push_tip_hand_transform, frame_id='push_tip', parent_frame_id='link_6', npub=10) #~ q_initial = robotConfig # move just inside the bin with push orientation and open the hand suitable to push distFromShelf = -0.01 InbinPt,temp = getBinMouthAndFloor(distFromShelf, binNum) InbinPt = coordinateFrameTransform(InbinPt, 'shelf', 'map', listener) prepush_targetPosition = [InbinPt.pose.position.x, push_series_pos[0,1] , InbinPt.pose.position.z] #matching world_Y of first push pt print '[PushRotate] prepush_targetPosition=', prepush_targetPosition pubFrame(br, pose=prepush_targetPosition+push_orient, frame_id='target_pose', parent_frame_id='map', npub=10) planner = IK(q0 = q_initial, target_tip_pos = prepush_targetPosition, target_tip_ori = push_orient, tip_hand_transform=push_tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() plan.setSpeedByName('slow') s = plan.success() if s: print '[PushRotate] move inside bin in push orient successful' #~ print 'tcp at:' #~ print(pregrasp_targetPosition) #~ plan.visualize() plans.append(plan) # Plan 1 #~ if isExecute: #~ pauseFunc(withPause) #~ plan.execute() else: print '[PushRotate] move inside bin in push orient fail' return False qf = plan.q_traj[-1] q_initial = qf #~ ************************************************************* ############## OPEN THE GRIPPER To PUSH ############### # Open the gripper to dim calculated for pushing print '[PushRotate] hand opening to' print push_hand_opening*1000.0 #~ moveGripper(push_hand_opening,100) grasp_plan = EvalPlan('moveGripper(%f, 100)' % (push_hand_opening)) plans.append(grasp_plan) #~ ************************************************************* ############ Execute the push trajectory ############## #~ push_rotate_traj = Plan() #~ push_rotate_traj.q_traj = qf for i in range(0,push_x_intm.size): pushpt_pos=push_series_pos[i,:].transpose() pubFrame(br, pose=pushpt_pos.tolist()+push_orient, frame_id='target_pose', parent_frame_id='map', npub=10) #~ pdb.set_trace() # planner = IK(q0 = q_initial, target_tip_pos = graspPT_pose_pos, target_tip_ori = push_orient, # joint_topic=joint_topic, tip_hand_transform=tip_hand_transform, straightness = 0.3, inframebb = inframebb) planner = IK(q0 = q_initial, target_tip_pos = pushpt_pos, target_tip_ori = push_orient, joint_topic=joint_topic, tip_hand_transform=push_tip_hand_transform) plan = planner.plan() plan.setSpeedByName('slow') s = plan.success() if s: print '[PushRotate] point inside push traj successful' #~ print 'tcp at:' #~ print(pregrasp_targetPosition) #~ plan.visualize() plans.append(plan) # Plan 1 #~ if isExecute: #~ pauseFunc(withPause) #~ plan.execute() else: print '[PushRotate] point inside push traj fail' return False qf = plan.q_traj[-1] q_initial = qf #~ ************************************************************* #~ if isExecute: #~ pauseFunc(withPause) #~ push_rotate_traj.execute() #################### CLOSE THE GRIPPER GRASP ################# #~ moveGripper(0.0,100) grasp_plan = EvalPlan('moveGripper(%f, 100)' % (0.0)) plans.append(grasp_plan) #~ ************************************************************* # #################### EXECUTE FORWARD #################### for numOfPlan in range(0, len(plans)): if isExecute: plans[numOfPlan].visualize() pauseFunc(withPause) plans[numOfPlan].execute() # #################### RETREAT #################### for numOfPlan in range(0, len(plans)): if isExecute: plans[len(plans)-numOfPlan-1].visualizeBackward() pauseFunc(withPause) plans[len(plans)-numOfPlan-1].executeBackward() #******************************************************************* print '[PushRotate] push_successful' return (push_possible,False)
# bin_1 # 1.1069; -0.018219; 1.3762 -0.54475; 0.075625; 0.20345; 0.81003 #-0.035814156250925766, 0.5470560007467684, -0.8243085337401062, -2.70526034059, 0.8721846604532582, -0.3148573970598978 rospy.init_node('listener', anonymous=True) #desired_joint_pose = [-0.0087, 0.6423, -0.1222, 1.4731, 1.4643, 1.2] # for bin 7 home_joint_pose = [0, -0.2, 0.2, 0.01, 1, 1.4] plan = Plan() plan.q_traj = [home_joint_pose] plan.visualize() plan.execute() br = tf.TransformBroadcaster() # generate targets for horizontal scan #bin_cnstr = get_bin_cnstr() bin_cnstr = get_bin_inner_cnstr() target_poses = [] refind = 7 for i in range(12): #target_pose_7_vert = [1.1756, 0, 0.79966, 0.69537, 0.11132, 0.049168, 0.70827] # for bin 7 vertical #target_pose_7_hori = [1.1756, -0.0080496, 0.79966, 0.96262, -0.039399, -0.25934, 0.06743] # for bin 7 horizontal target_pose_7_vert = [1.1756, 0, 0.79966] + tfm.quaternion_from_euler( math.pi, 1.4, math.pi).tolist() # for bin 7 vertical target_pose_7_hori = [1.1756, 0, 0.79966] + tfm.quaternion_from_euler( 2.2, 0, math.pi / 2).tolist() target_pose_7_invhori = [1.1756, 0, 0.79966] + tfm.quaternion_from_euler( -math.pi / 2, 0, -math.pi / 2).tolist() if i < 3: target_pose = target_pose_7_invhori
def push_back(objPose=[1.95,0.25,1.4,0,0,0,1], binNum=4, objId = 'crayola_64_ct', bin_contents = ['paper_mate_12_count_mirado_black_warrior','crayola_64_ct','expo_dry_erase_board_eraser'], robotConfig = None, grasp_range_lim=0.11, fing_width=0.06, isExecute = True, withPause = True): #~ ***************************************************************** obj_dim=get_obj_dim(objId) obj_dim=np.array(obj_dim) #~ ***************************************************************** # # DEFINE HAND WIDTH######################### hand_width=0.186 #~ ***************************************************************** ## initialize listener rospy listener = tf.TransformListener() rospy.sleep(0.1) br = tf.TransformBroadcaster() rospy.sleep(0.1) (shelf_position, shelf_quaternion) = lookupTransform("map", "shelf", listener) # print shelf_position, shelf_quaternion #~ ***************************************************************** # Convert xyx quat to tranformation matrix for Shelf frame #~ shelf_pose_tfm_list=matrix_from_xyzquat(shelfPose[0:3], shelfPose[3:7]) shelf_pose_tfm_list=matrix_from_xyzquat(shelf_position,shelf_quaternion) shelf_pose_tfm=np.array(shelf_pose_tfm_list) shelf_pose_orient=shelf_pose_tfm[0:3,0:3] #~ print '[PushBack] shelf_pose_orient' #~ print shelf_pose_orient shelf_pose_pos=shelf_pose_tfm[0:3,3] #~ print '[PushBack] shelf_pose_pos' #~ print shelf_pose_pos #Normalized axes of the shelf frame shelf_X=shelf_pose_orient[:,0]/la.norm(shelf_pose_orient[:,0]) shelf_Y=shelf_pose_orient[:,1]/la.norm(shelf_pose_orient[:,1]) shelf_Z=shelf_pose_orient[:,2]/la.norm(shelf_pose_orient[:,2]) #~ ***************************************************************** # Convert xyx quat to tranformaation matrix for Object frame obj_pose_tfm_list=matrix_from_xyzquat(objPose[0:3], objPose[3:7]) obj_pose_tfm=np.array(obj_pose_tfm_list) obj_pose_orient=obj_pose_tfm[0:3,0:3] obj_pose_pos=obj_pose_tfm[0:3,3] #~ print '[PushBack] obj_pose_orient' #~ print obj_pose_orient #Normalized axes of the object frame obj_X=obj_pose_orient[:,0]/la.norm(obj_pose_orient[:,0]) #~ print '[PushBack] obj_X' #~ print obj_X obj_Y=obj_pose_orient[:,1]/la.norm(obj_pose_orient[:,1]) #~ print '[PushBack] obj_Y' #~ print obj_Y obj_Z=obj_pose_orient[:,2]/la.norm(obj_pose_orient[:,2]) #~ print '[PushBack] obj_Z' #~ print obj_Z #Normalized object frame obj_pose_orient_norm=np.vstack((obj_X,obj_Y,obj_Z)) obj_pose_orient_norm=obj_pose_orient_norm.transpose() #~ print '[PushBack] obj_pose_orient_norm' #~ print obj_pose_orient_norm #~ ***************************************************************** # We will assume that hand normal tries to move along object dimension along the Y axis of the shelf (along the lenght of the bin) # Find projection of object axes on Y axis of the shelf frame proj_vecY=np.dot(shelf_Y,obj_pose_orient_norm) #~ print '[PushBack] proj' #~ print proj_vecY max_proj_valY,hand_norm_dir=np.max(np.fabs(proj_vecY)), np.argmax(np.fabs(proj_vecY)) if proj_vecY[hand_norm_dir]>0: hand_norm_vec=-obj_pose_orient_norm[:,hand_norm_dir] else: hand_norm_vec=obj_pose_orient_norm[:,hand_norm_dir] #~ print '[PushBack] hand_norm_vec' #~ print hand_norm_vec #Find angle of the edge of the object Cos_angle_made_with_shelf_Y=max_proj_valY/(la.norm(shelf_Y)*la.norm(hand_norm_vec)); angle_to_shelfY=np.arccos(Cos_angle_made_with_shelf_Y)*180/np.pi #~ print'angle_to_shelfY' #~ print angle_to_shelfY #Find object dimension along hand normal axis obj_dim_along_hand_norm=obj_dim[hand_norm_dir] # print '[PushBack] dim along hand norm' # print obj_dim_along_hand_norm #~ ***************************************************************** #Find projection of object axes on X axis of the shelf frame #To find out which object frame is lying closer to the X axis of the shelf proj_vecX=np.dot(shelf_X,obj_pose_orient_norm) max_proj_valX,fing_axis_dir=np.max(np.fabs(proj_vecX)), np.argmax(np.fabs(proj_vecX)) if proj_vecX[fing_axis_dir]>0: fing_axis_vec=obj_pose_orient_norm[:,fing_axis_dir] else: fing_axis_vec=-obj_pose_orient_norm[:,fing_axis_dir] #~ print '[PushBack] fing_axis_vec' #~ print fing_axis_vec #Find object dimension along the finger axis obj_dim_along_fingAxis=obj_dim[fing_axis_dir] # print '[PushBack] obj_dim_along_fingAxis' # print obj_dim_along_fingAxis #~ ***************************************************************** #Find projection of object axes on Z axis of the shelf frame #To find out which object frame is lying closer to the Z axis of the shelf proj_vecZ=np.dot(shelf_Z,obj_pose_orient_norm) max_proj_valZ,Zaxis_dir=np.max(np.fabs(proj_vecZ)), np.argmax(np.fabs(proj_vecZ)) Zaxis_vec=obj_pose_orient_norm[:,Zaxis_dir] #~ print '[PushBack] Zaxis_vec' #~ print Zaxis_vec #Find object dimension along the finger axis, shelf Z obj_dim_along_ZAxis=obj_dim[Zaxis_dir] hand_Y=np.cross(hand_norm_vec,fing_axis_vec) diag_dist=la.norm(np.array([obj_dim_along_hand_norm,obj_dim_along_fingAxis])) # print'req obj diag dist=', diag_dist #~ ***************************************************************** # Find the maximum distance to which we will push other_diag=np.zeros(len(bin_contents)) for num_bin_contents in range(0, len(bin_contents)): if bin_contents[num_bin_contents] != objId: temp_obj_dim=get_obj_dim(objId) other_diag[num_bin_contents]=la.norm(np.array([temp_obj_dim[0],temp_obj_dim[1]])) max_diag,max_obj_ID=np.max(np.fabs(other_diag)), np.argmax(np.fabs(other_diag)) # print '[PushBack] max_obj_ID',max_diag # print '[PushBack] max_obj_ID', bin_contents[max_obj_ID] #******************************************************************* bin_inner_cnstr=get_bin_inner_cnstr() #******************************************************************* #Check if we can do left push diag_factor=0.75 obj_left_edge=obj_pose_pos[1]+diag_factor*diag_dist/2.0 binLeftWall=bin_inner_cnstr[binNum][1] binLeftWall_world = coordinateFrameTransform([binLeftWall,0,0], 'shelf', 'map', listener) binRightWall=bin_inner_cnstr[binNum][0] binRightWall_world = coordinateFrameTransform([binRightWall,0,0], 'shelf', 'map', listener) left_gap=binLeftWall_world.pose.position.y-obj_left_edge # print '[PushBack] left_gap=', left_gap fing_clearance=0.010 # It's like 5 mm on both sides of finger bin_width=binLeftWall_world.pose.position.y-binRightWall_world.pose.position.y tolerance_in_push=0.020 if left_gap+diag_dist/2.0-tolerance_in_push>bin_width: print '[PushBack] looks like vision has messed up. the object does not seem to be in the appropriate bin' return (False,False) if left_gap > fing_width+fing_clearance: left_push=True print '[PushBack] left push is possible' else: left_push=False print '[PushBack] left push is NOT possible' # check if we can do right push obj_right_edge=obj_pose_pos[1]-diag_factor*diag_dist/2.0 right_gap=obj_right_edge-binRightWall_world.pose.position.y # print '[PushBack] right_gap', right_gap fing_clearance=0.010 # It's like 5 mm on both sides of finger if right_gap+diag_dist/2.0-tolerance_in_push>bin_width: print '[PushBack] looks like vision has messed up. the object does not seem to be in the appropriate bin' return (False,False) if right_gap > fing_width+fing_clearance: right_push=True print '[PushBack] right push is possible' else: right_push=False print '[PushBack] right push is NOT possible' #******************************************************************* #Find Push Points for left push bin_face_pos,binFloorHeight=getBinMouthAndFloor(0.0, binNum) bin_face_pos_world = coordinateFrameTransform(bin_face_pos, 'shelf', 'map', listener) tcp_Z_off=0.005 #lower down from center of the bin push_tcp_Z_shelfFrame=((bin_inner_cnstr[binNum][4]+bin_inner_cnstr[binNum][5])/2.0)-tcp_Z_off push_tcp_Z_WorldFrame = coordinateFrameTransform([0,0,push_tcp_Z_shelfFrame], 'shelf', 'map', listener) push_tcp_Z=push_tcp_Z_WorldFrame.pose.position.z push_side_off=1.0 if left_push: left_pushPt_X=bin_face_pos_world.pose.position.x+0.05 left_pushPt_Y=binLeftWall_world.pose.position.y-push_side_off*left_gap # left_Y_lim=binLeftWall_world.pose.position.y- left_pushPt_Z=deepcopy(push_tcp_Z) left_push_Pt=np.array([left_pushPt_X,left_pushPt_Y,left_pushPt_Z]) print '[PushBack] expected left push clearance=',binLeftWall_world.pose.position.y-left_pushPt_Y-fing_width/2.0 #Find Push Points for right push if right_push: right_pushPt_X=bin_face_pos_world.pose.position.x+0.05 right_pushPt_Y=binRightWall_world.pose.position.y+push_side_off*right_gap right_pushPt_Z=deepcopy(push_tcp_Z) right_push_Pt=np.array([right_pushPt_X,right_pushPt_Y,right_pushPt_Z]) print '[PushBack] expected right push clearance=',right_pushPt_Y-binRightWall_world.pose.position.y-fing_width/2.0 #Execute push trajectories #~ ************************************************************* # set spatual down orientation (rotate wrist) spatula_down_orient = [0, 0.7071, 0, 0.7071] push_orient=spatula_down_orient push_hand_opening=0.100 joint_topic = '/joint_states' #~ ************************************************************* #Execure left push trajectory if left_push: # plan store left_plans = [] # set tcp (same as that set in generate dictionary) l1=0.0 l2=0.0 l3 = 0.47 tip_hand_transform = [l1, l2, l3, 0,0,0] # to be updated when we have a hand design finalized # broadcast frame attached to tcp pubFrame(br, pose=tip_hand_transform, frame_id='tip', parent_frame_id='link_6', npub=5) #~ ************************************************************* # GO TO MOUTH OF THE BIN q_initial = robotConfig # move to bin mouth distFromShelf = 0.1 mouthPt,temp = getBinMouthAndFloor(distFromShelf, binNum) mouthPt = coordinateFrameTransform(mouthPt, 'shelf', 'map', listener) targetPosition = [mouthPt.pose.position.x, mouthPt.pose.position.y, mouthPt.pose.position.z] gripperOri=[0, 0.7071, 0, 0.7071] pubFrame(br, pose = targetPosition+gripperOri, frame_id='target_pose', parent_frame_id='link_6', npub=5) planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = gripperOri, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() plan.setSpeedByName('faster') s = plan.success() if s: print '[PushBack] move to bin mouth in push-back code successful (left push)' left_plans.append(plan) # Plan 0 else: print '[PushBack] move to bin mouth in push-back code fail (left push)' return (False,False) qf = plan.q_traj[-1] q_initial = qf #################### CLOSE THE GRIPPER GRASP ################# grasp_plan = EvalPlan('moveGripper(%f, 100)' % (0.0)) left_plans.append(grasp_plan) #~ ************************************************************* ###### MOVE THE ROBOT INSIDE THE BIN WITH PUSH ORIENTATION ###### # set push_tcp push_l1=0.0 push_l2=0.0 push_l3 = 0.47 push_tip_hand_transform = [l1, l2, l3, 0,0,0] # to be updated when we have a hand design finalized # broadcast frame attached to grasp_tcp pubFrame(br, pose=push_tip_hand_transform, frame_id='push_tip', parent_frame_id='link_6', npub=10) distFromShelf = -0.015 InbinPt,temp = getBinMouthAndFloor(distFromShelf, binNum) InbinPt = coordinateFrameTransform(InbinPt, 'shelf', 'map', listener) prepush_targetPosition = [InbinPt.pose.position.x, left_push_Pt[1] , InbinPt.pose.position.z] #matching world_Y of first push pt pubFrame(br, pose=prepush_targetPosition+push_orient, frame_id='target_pose', parent_frame_id='map', npub=10) planner = IK(q0 = q_initial, target_tip_pos = prepush_targetPosition, target_tip_ori = push_orient, tip_hand_transform=push_tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() plan.setSpeedByName('fast') s = plan.success() if s: print '[PushBack] move inside bin in push orient successful' #~ print '[PushBack] tcp at:' #~ print(pregrasp_targetPosition) #~ plan.visualize() left_plans.append(plan) # Plan 1 #~ if isExecute: #~ pauseFunc(withPause) #~ plan.execute() else: print '[PushBack] move inside bin in push orient fail' return (False,False) qf = plan.q_traj[-1] q_initial = qf #~ ************************************************************* ############## OPEN THE GRIPPER To PUSH############### # Open the gripper to dim calculated for pushing print '[PushBack] hand opening to' print push_hand_opening*1000.0 grasp_plan = EvalPlan('moveGripper(%f, 100)' % (push_hand_opening)) left_plans.append(grasp_plan) #~ ************************************************************* ############ Execute the push trajectory ############## back_bin_X=bin_face_pos_world.pose.position.x+0.43 push_stop_worldX=back_bin_X-max_diag-0.010 left_pushStop_Pt_pos=deepcopy(left_push_Pt) left_pushStop_Pt_pos[0]=push_stop_worldX #Push until the end planner = IK(q0 = q_initial, target_tip_pos = left_pushStop_Pt_pos, target_tip_ori = push_orient, joint_topic=joint_topic, tip_hand_transform=push_tip_hand_transform) plan = planner.plan() plan.setSpeedByName('fast') s = plan.success() if s: print '[PushBack] start point push traj successful' left_plans.append(plan) # Plan 1 else: print '[PushBack] start point push traj fail' return (False,False) qf = plan.q_traj[-1] q_initial = qf #################### CLOSE THE GRIPPER GRASP ################# grasp_plan = EvalPlan('moveGripper(%f, 100)' % (0.0)) left_plans.append(grasp_plan) #~ ************************************************************* # #################### EXECUTE FORWARD #################### for numOfPlan in range(0, len(left_plans)): if isExecute: left_plans[numOfPlan].visualize() pauseFunc(withPause) left_plans[numOfPlan].execute() # #################### RETREAT #################### for numOfPlan in range(0, len(left_plans)): if isExecute: left_plans[numOfPlan].visualizeBackward() pauseFunc(withPause) left_plans[len(left_plans)-numOfPlan-1].executeBackward() #******************************************************************* if right_push: # plan store right_plans = [] # set tcp (same as that set in generate dictionary) l1=0.0 l2=0.0 l3 = 0.47 tip_hand_transform = [l1, l2, l3, 0,0,0] # to be updated when we have a hand design finalized # broadcast frame attached to tcp pubFrame(br, pose=tip_hand_transform, frame_id='tip', parent_frame_id='link_6', npub=5) #~ ************************************************************* # GO TO MOUTH OF THE BIN q_initial = robotConfig # move to bin mouth distFromShelf = 0.1 mouthPt,temp = getBinMouthAndFloor(distFromShelf, binNum) mouthPt = coordinateFrameTransform(mouthPt, 'shelf', 'map', listener) targetPosition = [mouthPt.pose.position.x, mouthPt.pose.position.y, mouthPt.pose.position.z] gripperOri=[0, 0.7071, 0, 0.7071] pubFrame(br, pose = targetPosition+gripperOri, frame_id='target_pose', parent_frame_id='link_6', npub=5) planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = gripperOri, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() plan.setSpeedByName('faster') s = plan.success() if s: print '[PushBack] move to bin mouth in push-back code successful (right push)' right_plans.append(plan) # Plan 0 else: print '[PushBack] move to bin mouth in push-back code fail (right push)' return (False,False) qf = plan.q_traj[-1] q_initial = qf #################### CLOSE THE GRIPPER GRASP ################# grasp_plan = EvalPlan('moveGripper(%f, 100)' % (0.0)) right_plans.append(grasp_plan) #~ ************************************************************* ###### MOVE THE ROBOT INSIDE THE BIN WITH PUSH ORIENTATION ###### # set push_tcp push_l1=0.0 push_l2=0.0 push_l3 = 0.47 push_tip_hand_transform = [l1, l2, l3, 0,0,0] # to be updated when we have a hand design finalized # broadcast frame attached to grasp_tcp pubFrame(br, pose=push_tip_hand_transform, frame_id='push_tip', parent_frame_id='link_6', npub=10) distFromShelf = -0.015 InbinPt,temp = getBinMouthAndFloor(distFromShelf, binNum) InbinPt = coordinateFrameTransform(InbinPt, 'shelf', 'map', listener) prepush_targetPosition = [InbinPt.pose.position.x, right_push_Pt[1] , InbinPt.pose.position.z] #matching world_Y of first push pt pubFrame(br, pose=prepush_targetPosition+push_orient, frame_id='target_pose', parent_frame_id='map', npub=10) planner = IK(q0 = q_initial, target_tip_pos = prepush_targetPosition, target_tip_ori = push_orient, tip_hand_transform=push_tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() plan.setSpeedByName('fast') s = plan.success() if s: print '[PushBack] move inside bin in push orient successful' #~ print '[PushBack] tcp at:' #~ print(pregrasp_targetPosition) #~ plan.visualize() right_plans.append(plan) # Plan 1 #~ if isExecute: #~ pauseFunc(withPause) #~ plan.execute() else: print '[PushBack] move inside bin in push orient fail' return (False,False) qf = plan.q_traj[-1] q_initial = qf #~ ************************************************************* ############## OPEN THE GRIPPER To PUSH############### # Open the gripper to dim calculated for pushing print '[PushBack] hand opening to' print push_hand_opening*1000.0 grasp_plan = EvalPlan('moveGripper(%f, 100)' % (push_hand_opening)) right_plans.append(grasp_plan) #~ ************************************************************* ############ Execute the push trajectory ############## back_bin_X=bin_face_pos_world.pose.position.x+0.42 push_stop_worldX=back_bin_X-max_diag-0.010 right_pushStop_Pt_pos=deepcopy(right_push_Pt) right_pushStop_Pt_pos[0]=push_stop_worldX #Push until the end planner = IK(q0 = q_initial, target_tip_pos = right_pushStop_Pt_pos, target_tip_ori = push_orient, joint_topic=joint_topic, tip_hand_transform=push_tip_hand_transform) plan = planner.plan() plan.setSpeedByName('fast') s = plan.success() if s: print '[PushBack] start point push traj successful' right_plans.append(plan) # Plan 1 else: print '[PushBack] start point push traj fail' return (False,False) qf = plan.q_traj[-1] q_initial = qf #################### CLOSE THE GRIPPER GRASP ################# grasp_plan = EvalPlan('moveGripper(%f, 100)' % (0.0)) right_plans.append(grasp_plan) #~ ************************************************************* # #################### EXECUTE FORWARD #################### for numOfPlan in range(0, len(right_plans)): if isExecute: right_plans[numOfPlan].visualize() pauseFunc(withPause) right_plans[numOfPlan].execute() # #################### RETREAT #################### for numOfPlan in range(0, len(right_plans)): if isExecute: right_plans[numOfPlan].visualizeBackward() pauseFunc(withPause) right_plans[len(right_plans)-numOfPlan-1].executeBackward() if right_push or left_push: push_possible=True else: push_possible=False return(push_possible, False)
import capsen.capsen from ik.roshelper import pubFrame # bin_1 # 1.1069; -0.018219; 1.3762 -0.54475; 0.075625; 0.20345; 0.81003 #-0.035814156250925766, 0.5470560007467684, -0.8243085337401062, -2.70526034059, 0.8721846604532582, -0.3148573970598978 rospy.init_node('listener', anonymous=True) #desired_joint_pose = [-0.0087, 0.6423, -0.1222, 1.4731, 1.4643, 1.2] # for bin 7 home_joint_pose = [0, -0.2, 0.2, 0.01, 1, 1.4] plan = Plan(); plan.q_traj = [home_joint_pose]; plan.visualize(); plan.execute() br = tf.TransformBroadcaster() # generate targets for horizontal scan #bin_cnstr = get_bin_cnstr() bin_cnstr = get_bin_inner_cnstr() target_poses = [] refind = 7 for i in range(12): #target_pose_7_vert = [1.1756, 0, 0.79966, 0.69537, 0.11132, 0.049168, 0.70827] # for bin 7 vertical #target_pose_7_hori = [1.1756, -0.0080496, 0.79966, 0.96262, -0.039399, -0.25934, 0.06743] # for bin 7 horizontal target_pose_7_vert = [1.1756, 0, 0.79966] + tfm.quaternion_from_euler(math.pi, 1.4, math.pi).tolist() # for bin 7 vertical target_pose_7_hori = [1.1756, 0, 0.79966] + tfm.quaternion_from_euler(2.2, 0, math.pi/2).tolist() target_pose_7_invhori = [1.1756, 0, 0.79966] + tfm.quaternion_from_euler(-math.pi/2, 0, -math.pi/2).tolist() if i < 3: target_pose = target_pose_7_invhori if i == 0: target_pose[1] -= 0.06
def push_rotate(objPose=[1.95, 0.25, 1.4, 0, 0, 0, 1], binNum=4, objId='crayola_64_ct', bin_contents=None, robotConfig=None, grasp_range_lim=0.11, fing_width=0.06, isExecute=True, withPause=True): #~ ***************************************************************** obj_dim = get_obj_dim(objId) obj_dim = np.array(obj_dim) #~ ***************************************************************** # # DEFINE HAND WIDTH######################### hand_width = 0.186 #~ ***************************************************************** ## initialize listener rospy listener = tf.TransformListener() br = tf.TransformBroadcaster() rospy.sleep(0.2) (shelf_position, shelf_quaternion) = lookupTransform("map", "shelf", listener) # print shelf_position, shelf_quaternion #~ ***************************************************************** # Convert xyx quat to tranformation matrix for Shelf frame #~ shelf_pose_tfm_list=matrix_from_xyzquat(shelfPose[0:3], shelfPose[3:7]) shelf_pose_tfm_list = matrix_from_xyzquat(shelf_position, shelf_quaternion) shelf_pose_tfm = np.array(shelf_pose_tfm_list) shelf_pose_orient = shelf_pose_tfm[0:3, 0:3] #~ print 'shelf_pose_orient' #~ print shelf_pose_orient shelf_pose_pos = shelf_pose_tfm[0:3, 3] #~ print 'shelf_pose_pos' #~ print shelf_pose_pos #Normalized axes of the shelf frame shelf_X = shelf_pose_orient[:, 0] / la.norm(shelf_pose_orient[:, 0]) shelf_Y = shelf_pose_orient[:, 1] / la.norm(shelf_pose_orient[:, 1]) shelf_Z = shelf_pose_orient[:, 2] / la.norm(shelf_pose_orient[:, 2]) #~ ***************************************************************** # Convert xyx quat to tranformaation matrix for Object frame obj_pose_tfm_list = matrix_from_xyzquat(objPose[0:3], objPose[3:7]) obj_pose_tfm = np.array(obj_pose_tfm_list) obj_pose_orient = obj_pose_tfm[0:3, 0:3] obj_pose_pos = obj_pose_tfm[0:3, 3] #~ print 'obj_pose_orient' #~ print obj_pose_orient #Normalized axes of the object frame obj_X = obj_pose_orient[:, 0] / la.norm(obj_pose_orient[:, 0]) #~ print 'obj_X' #~ print obj_X obj_Y = obj_pose_orient[:, 1] / la.norm(obj_pose_orient[:, 1]) #~ print 'obj_Y' #~ print obj_Y obj_Z = obj_pose_orient[:, 2] / la.norm(obj_pose_orient[:, 2]) #~ print 'obj_Z' #~ print obj_Z #Normalized object frame obj_pose_orient_norm = np.vstack((obj_X, obj_Y, obj_Z)) obj_pose_orient_norm = obj_pose_orient_norm.transpose() #~ print 'obj_pose_orient_norm' #~ print obj_pose_orient_norm #~ ***************************************************************** # We will assume that hand normal tries to move along object dimension along the Y axis of the shelf (along the lenght of the bin) # Find projection of object axes on Y axis of the shelf frame proj_vecY = np.dot(shelf_Y, obj_pose_orient_norm) #~ print 'proj' #~ print proj_vecY max_proj_valY, hand_norm_dir = np.max(np.fabs(proj_vecY)), np.argmax( np.fabs(proj_vecY)) if proj_vecY[hand_norm_dir] > 0: hand_norm_vec = -obj_pose_orient_norm[:, hand_norm_dir] else: hand_norm_vec = obj_pose_orient_norm[:, hand_norm_dir] #~ print 'hand_norm_vec' #~ print hand_norm_vec #Find angle of the edge of the object Cos_angle_made_with_shelf_Y = max_proj_valY / (la.norm(shelf_Y) * la.norm(hand_norm_vec)) angle_to_shelfY = np.arccos(Cos_angle_made_with_shelf_Y) * 180.0 / np.pi #~ print'angle_to_shelfY' #~ print angle_to_shelfY #Find object dimension along hand normal axis obj_dim_along_hand_norm = obj_dim[hand_norm_dir] print '[PushRotate] dim along hand norm', obj_dim_along_hand_norm #~ ***************************************************************** #Find projection of object axes on X axis of the shelf frame #To find out which object frame is lying closer to the X axis of the shelf proj_vecX = np.dot(shelf_X, obj_pose_orient_norm) max_proj_valX, fing_axis_dir = np.max(np.fabs(proj_vecX)), np.argmax( np.fabs(proj_vecX)) if proj_vecX[fing_axis_dir] > 0: fing_axis_vec = obj_pose_orient_norm[:, fing_axis_dir] else: fing_axis_vec = -obj_pose_orient_norm[:, fing_axis_dir] #~ print 'fing_axis_vec' #~ print fing_axis_vec #Find object dimension along the finger axis obj_dim_along_fingAxis = obj_dim[fing_axis_dir] print '[PushRotate] obj_dim_along_fingAxis:', obj_dim_along_fingAxis #~ ***************************************************************** #Find projection of object axes on Z axis of the shelf frame #To find out which object frame is lying closer to the Z axis of the shelf proj_vecZ = np.dot(shelf_Z, obj_pose_orient_norm) max_proj_valZ, Zaxis_dir = np.max(np.fabs(proj_vecZ)), np.argmax( np.fabs(proj_vecZ)) Zaxis_vec = obj_pose_orient_norm[:, Zaxis_dir] #~ print 'Zaxis_vec' #~ print Zaxis_vec #Find object dimension along the finger axis, shelf Z obj_dim_along_ZAxis = obj_dim[Zaxis_dir] hand_Y = np.cross(hand_norm_vec, fing_axis_vec) #~ ***************************************************************** #################### DECISION STRATEGIES ######################### bin_inner_cnstr = get_bin_inner_cnstr() proj_handNorm_ShelfX = np.dot(hand_norm_vec, shelf_X) right_push = False left_push = False # print 'obj_dim_along_hand_norm', obj_dim_along_hand_norm # print 'obj_dim_along_fingAxis', obj_dim_along_fingAxis # # print 'proj_handNorm_ShelfX' # print proj_handNorm_ShelfX if obj_dim_along_hand_norm > obj_dim_along_fingAxis: #~ print 'proj_vecY' #~ print proj_vecY #~ print proj_vecY[hand_norm_dir] #~ #~ print 'proj_vecX' #~ print proj_vecX #~ print proj_vecX[fing_axis_dir] #~ if proj_vecY[hand_norm_dir]*proj_vecX[fing_axis_dir]<0: #~ #Do left push #~ Ypush_mult=1 #~ print 'Left Push' #~ else: #~ #Do right push #~ Ypush_mult=-1 #~ print 'right Push' if proj_handNorm_ShelfX > 0: #Do left push Ypush_mult = 1 left_push = True print '[PushRotate] Left Push' else: #Do right push Ypush_mult = -1 print '[PushRotate] right Push' right_push = True push_offset = ( obj_dim_along_hand_norm / 2.0 ) #(Instead pf pushing on edge we will push 5 mm inside) else: #~ if proj_vecY[hand_norm_dir]*proj_vecX[fing_axis_dir]<0: #~ #Do right push #~ Ypush_mult=-1 #~ print 'right Push' #~ else: #~ #Do left push #~ Ypush_mult=1 #~ print 'Left Push' if proj_handNorm_ShelfX > 0: #Do right push Ypush_mult = -1 print '[PushRotate] right Push' right_push = True else: #Do left push Ypush_mult = 1 print '[PushRotate] Left Push' left_push = True push_offset = (obj_dim_along_fingAxis / 2.0) num_intm_points = 5 push_x_intm = np.zeros(num_intm_points + 1) push_y_intm = np.zeros(num_intm_points + 1) backWall_shelf = bin_inner_cnstr[binNum][1] backWall_world = coordinateFrameTransform([0, backWall_shelf, 0], 'shelf', 'map', listener) back_check = backWall_world.pose.position.x - obj_dim_along_hand_norm / 2.0 binRightWall = bin_inner_cnstr[binNum][0] binLeftWall = bin_inner_cnstr[binNum][1] binRightWall_world = coordinateFrameTransform([binRightWall, 0, 0], 'shelf', 'map', listener) binLeftWall_world = coordinateFrameTransform([binLeftWall, 0, 0], 'shelf', 'map', listener) if left_push: sideWall_check = binRightWall_world.pose.position.y + ( fing_width / 2.0) + (obj_dim_along_fingAxis) if right_push: sideWall_check = binLeftWall_world.pose.position.y - ( fing_width / 2.0) - (obj_dim_along_fingAxis) for i in range(num_intm_points + 1): push_x_intm[i] = obj_pose_pos[0] + (push_offset) * np.sin( ((90 / num_intm_points) * i * np.pi) / 180.0) if push_x_intm[i] > back_check: push_x_intm[i] = back_check push_y_intm[i] = obj_pose_pos[1] + (Ypush_mult * push_offset) * np.cos( ((90 / num_intm_points) * i * np.pi) / 180.0) if left_push: if push_y_intm[i] < sideWall_check: push_y_intm[i] = sideWall_check print '[PushRotate] push Y reduced, I do not want to crush the obj and gripper' if right_push: if push_y_intm[i] > sideWall_check: push_y_intm[i] = sideWall_check print '[PushRotate] push Y reduced, I do not want to crush the obj and gripper' push_x_intm = np.array(push_x_intm) #~ print'push_x_intm' #~ print push_x_intm push_y_intm = np.array(push_y_intm) #******************************************************************* #Move the hand to the center of the bin and open the hand based on the height of the object bin_mid_pos, binFloorHeight = getBinMouthAndFloor(0.0, binNum) binFloorHeight_world = coordinateFrameTransform([0, 0, binFloorHeight], 'shelf', 'map', listener) bin_mid_pos_world = coordinateFrameTransform(bin_mid_pos, 'shelf', 'map', listener) #******************************************************************* tcp_Z_off = 0.005 push_tcp_Z_shelfFrame = ( (bin_inner_cnstr[binNum][4] + bin_inner_cnstr[binNum][5]) / 2.0) - tcp_Z_off push_tcp_Z_WorldFrame = coordinateFrameTransform( [0, 0, push_tcp_Z_shelfFrame], 'shelf', 'map', listener) push_tcp_Z = push_tcp_Z_WorldFrame.pose.position.z push_z_intm = (push_tcp_Z) * np.ones(push_x_intm.size) push_series_pos = np.vstack((push_x_intm, push_y_intm, push_z_intm)) push_series_pos = push_series_pos.transpose() #~ print 'push_series_pos' #~ print push_series_pos #~ print push_series_pos[0,:] #~ print push_series_pos[-1,:] push_possible = True #****************************************************************** fing_push_pt = 0.2 * obj_dim_along_ZAxis + binFloorHeight_world.pose.position.z blade_tip_TCP_off = 0.038 # dist between finger inner end and spatual edge push_hand_opening = 2 * (push_tcp_Z - blade_tip_TCP_off - fing_push_pt) if push_hand_opening > grasp_range_lim: push_hand_opening = grasp_range_lim # Spatula finger should not hit the lip of the bin while pushing lip_Z_shelf = bin_inner_cnstr[binNum][4] lip_Z_world = coordinateFrameTransform([0, 0, lip_Z_shelf], 'shelf', 'map', listener) #~ lip_off=.025 #~ bin_lip_Z=binFloorHeight_world.pose.position.z+lip_off max_allowed_hand_opening_out = 2 * (push_tcp_Z - lip_Z_world.pose.position.z) max_allowed_hand_opening = max_allowed_hand_opening_out - 0.036 # 0.036 is diff between inside and outside of the finger/finger mount surface if push_hand_opening > max_allowed_hand_opening: print '[PushRotate] reducing hand opening bcaz it may hit the lip of the bin' push_hand_opening = max_allowed_hand_opening #~ print 'push_hand_opening' #~ print push_hand_opening #~ #hand should not hit the side walls #~ binRightWall,binLeftWall=find_shelf_walls(binNum) #~ #~ binRightWall_world = coordinateFrameTransform([binRightWall,0,0], 'shelf', 'map', listener) #~ binLeftWall_world = coordinateFrameTransform([binLeftWall,0,0], 'shelf', 'map', listener) side_wall_clearance = 0.0 print '[PushRotate] binRightWall_world.pose.position.y', binRightWall_world.pose.position.y print '[PushRotate] right_hand_edge=', (push_y_intm[0] - fing_width - side_wall_clearance) print '[PushRotate] binLeftWall_world.pose.position.y', binLeftWall_world.pose.position.y print '[PushRotate] left_hand_edge=', (push_y_intm[0] + fing_width + side_wall_clearance) if push_y_intm[ 0] - fing_width - side_wall_clearance < binRightWall_world.pose.position.y: print '[PushRotate] Hand will hit the right wall, Push rotate not possible' push_possible = False if push_y_intm[ 0] + fing_width + side_wall_clearance > binLeftWall_world.pose.position.y: print '[PushRotate] Hand will hit the left wall, push rotate not possible' push_possible = False #~ ************************************************************* # set spatual down orientation (rotate wrist) spatula_down_orient = [0, 0.7071, 0, 0.7071] push_orient = deepcopy(spatula_down_orient) #~ ************************************************************* if push_possible == True: #Now we know where we wan to move TCP #Let's do robot motion planning now joint_topic = '/joint_states' # plan store plans = [] # set tcp (same as that set in generate dictionary) l1 = 0.0 l2 = 0.0 l3 = 0.47 tip_hand_transform = [ l1, l2, l3, 0, 0, 0 ] # to be updated when we have a hand design finalized # broadcast frame attached to tcp pubFrame(br, pose=tip_hand_transform, frame_id='tip', parent_frame_id='link_6', npub=5) #~ ************************************************************* # GO TO MOUTH OF THE BIN q_initial = robotConfig # move to bin mouth distFromShelf = 0.1 mouthPt, temp = getBinMouthAndFloor(distFromShelf, binNum) mouthPt = coordinateFrameTransform(mouthPt, 'shelf', 'map', listener) targetPosition = [ mouthPt.pose.position.x, mouthPt.pose.position.y, mouthPt.pose.position.z ] gripperOri = [0, 0.7071, 0, 0.7071] pubFrame(br, pose=targetPosition + gripperOri, frame_id='target_pose', parent_frame_id='link_6', npub=5) planner = IK(q0=q_initial, target_tip_pos=targetPosition, target_tip_ori=gripperOri, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() plan.setSpeedByName('faster') s = plan.success() if s: print '[PushRotate] move to bin mouth in push-rotate code successful' #plan.visualize() plans.append(plan) # Plan 0 #if isExecute: # pauseFunc(withPause) # plan.execute() else: print '[PushRotate] move to bin mouth in push-rotate code fail' return False qf = plan.q_traj[-1] q_initial = qf #################### CLOSE THE GRIPPER GRASP ################# grasp_plan = EvalPlan('moveGripper(%f, 100)' % (0.0)) plans.append(grasp_plan) #~ moveGripper(0.1,100) #~ ************************************************************* ###### MOVE THE ROBOT INSIDE THE BIN WITH PUSH ORIENTATION ###### # set push_tcp push_l1 = 0.0 #0.035 push_l2 = -Ypush_mult * ( fing_width / 2.0 ) # This should depend on the righ or left push conditions push_l3 = 0.47 push_tip_hand_transform = [ l1, l2, l3, 0, 0, 0 ] # to be updated when we have a hand design finalized # broadcast frame attached to grasp_tcp pubFrame(br, pose=push_tip_hand_transform, frame_id='push_tip', parent_frame_id='link_6', npub=10) #~ q_initial = robotConfig # move just inside the bin with push orientation and open the hand suitable to push distFromShelf = -0.01 InbinPt, temp = getBinMouthAndFloor(distFromShelf, binNum) InbinPt = coordinateFrameTransform(InbinPt, 'shelf', 'map', listener) prepush_targetPosition = [ InbinPt.pose.position.x, push_series_pos[0, 1], InbinPt.pose.position.z ] #matching world_Y of first push pt print '[PushRotate] prepush_targetPosition=', prepush_targetPosition pubFrame(br, pose=prepush_targetPosition + push_orient, frame_id='target_pose', parent_frame_id='map', npub=10) planner = IK(q0=q_initial, target_tip_pos=prepush_targetPosition, target_tip_ori=push_orient, tip_hand_transform=push_tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() plan.setSpeedByName('slow') s = plan.success() if s: print '[PushRotate] move inside bin in push orient successful' #~ print 'tcp at:' #~ print(pregrasp_targetPosition) #~ plan.visualize() plans.append(plan) # Plan 1 #~ if isExecute: #~ pauseFunc(withPause) #~ plan.execute() else: print '[PushRotate] move inside bin in push orient fail' return False qf = plan.q_traj[-1] q_initial = qf #~ ************************************************************* ############## OPEN THE GRIPPER To PUSH ############### # Open the gripper to dim calculated for pushing print '[PushRotate] hand opening to' print push_hand_opening * 1000.0 #~ moveGripper(push_hand_opening,100) grasp_plan = EvalPlan('moveGripper(%f, 100)' % (push_hand_opening)) plans.append(grasp_plan) #~ ************************************************************* ############ Execute the push trajectory ############## #~ push_rotate_traj = Plan() #~ push_rotate_traj.q_traj = qf for i in range(0, push_x_intm.size): pushpt_pos = push_series_pos[i, :].transpose() pubFrame(br, pose=pushpt_pos.tolist() + push_orient, frame_id='target_pose', parent_frame_id='map', npub=10) #~ pdb.set_trace() # planner = IK(q0 = q_initial, target_tip_pos = graspPT_pose_pos, target_tip_ori = push_orient, # joint_topic=joint_topic, tip_hand_transform=tip_hand_transform, straightness = 0.3, inframebb = inframebb) planner = IK(q0=q_initial, target_tip_pos=pushpt_pos, target_tip_ori=push_orient, joint_topic=joint_topic, tip_hand_transform=push_tip_hand_transform) plan = planner.plan() plan.setSpeedByName('slow') s = plan.success() if s: print '[PushRotate] point inside push traj successful' #~ print 'tcp at:' #~ print(pregrasp_targetPosition) #~ plan.visualize() plans.append(plan) # Plan 1 #~ if isExecute: #~ pauseFunc(withPause) #~ plan.execute() else: print '[PushRotate] point inside push traj fail' return False qf = plan.q_traj[-1] q_initial = qf #~ ************************************************************* #~ if isExecute: #~ pauseFunc(withPause) #~ push_rotate_traj.execute() #################### CLOSE THE GRIPPER GRASP ################# #~ moveGripper(0.0,100) grasp_plan = EvalPlan('moveGripper(%f, 100)' % (0.0)) plans.append(grasp_plan) #~ ************************************************************* # #################### EXECUTE FORWARD #################### for numOfPlan in range(0, len(plans)): if isExecute: plans[numOfPlan].visualize() pauseFunc(withPause) plans[numOfPlan].execute() # #################### RETREAT #################### for numOfPlan in range(0, len(plans)): if isExecute: plans[len(plans) - numOfPlan - 1].visualizeBackward() pauseFunc(withPause) plans[len(plans) - numOfPlan - 1].executeBackward() #******************************************************************* print '[PushRotate] push_successful' return (push_possible, False)
def percept_hand(obj_pose = None, binNum = 0, obj_id = None, bin_contents = None, isExecute = True, withPause = True): capsen.capsen.init() home_joint_pose = [0, -0.2, 0.2, 0.01, 1, 1.4] planner = IKJoint(target_joint_pos=home_joint_pose); #plan = Plan() #plan.q_traj = [home_joint_pose]; plan = planner.plan() plan.visualize(); plan.setSpeedByName('yolo'); if withPause: print '[Percept] Going back to percept_hand home' pause() plan.execute() bin_cnstr = get_bin_inner_cnstr() # 1. init target poses target_poses = [] refind = 7 for i in range(12): target_pose_7_vert = [1.1756, 0, 0.79966] + tfm.quaternion_from_euler(math.pi, 1.4, math.pi).tolist() # for bin 7 vertical target_pose_7_hori = [1.1756, 0, 0.79966] + tfm.quaternion_from_euler(2.2, 0, math.pi/2).tolist() target_pose_7_invhori = [1.1756, 0, 0.79966] + tfm.quaternion_from_euler(-math.pi/2, 0, -math.pi/2).tolist() if i < 3: target_pose = copy.deepcopy(target_pose_7_invhori) if i == 0: target_pose[1] -= 0.06 target_pose[2] -= 0.08 # z elif i<6: target_pose = copy.deepcopy(target_pose_7_hori) target_pose[0] += 0.03 # x target_pose[2] -= 0.04 # z elif i<9: target_pose = copy.deepcopy(target_pose_7_hori) else: target_pose = copy.deepcopy(target_pose_7_hori) target_pose[2] += 0.1 # z target_pose[1] += (bin_cnstr[i][0]+bin_cnstr[i][1])/2 - (bin_cnstr[refind][0]+bin_cnstr[refind][1])/2 # y target_pose[2] += (bin_cnstr[i][4]+bin_cnstr[i][5])/2 - (bin_cnstr[refind][4]+bin_cnstr[refind][5])/2 # z target_poses.append(target_pose) y_deltas = [0.08, -0.08] caption = ['left', 'right'] max_score = -100 max_obj_pose = None for i in range(len(y_deltas)): # 2. plan to target tip_hand_transform = xyzrpy_from_xyzquat([-0.067, 0.027, -0.012, -0.007, 0.704, 0.710, -0.002]) # need to be updated target_pose = copy.deepcopy(target_poses[binNum]) target_pose[1] += y_deltas[i] plan = None planner = IK(target_tip_pos = target_pose[0:3], target_tip_ori = target_pose[3:7], tip_hand_transform=tip_hand_transform, target_link='link_5', target_joint_bb=[[6, 1.2, 1.2]]) for j in range(15): planner.ori_tol = 0.5*j/10.0 planner.pos_tol = 0.01*j/10.0 newplan = planner.plan() if newplan.success(): plan = newplan print '[Percept] hand planning success at the trial %d' % j break if plan: plan.setSpeedByName('fastest') plan.visualize() if withPause: print '[Percept] Going to percept_hand %s ' % caption[i] pause() plan.execute() else: print '[Percept] hand planning failed' continue # 3. percept rospy.sleep(0.8) # wait for new pointcloud obj_pose, score = capsen.capsen.detectOneObject(obj_id, bin_contents, binNum, mode = 1, withScore = True) if score > max_score: max_obj_pose = obj_pose max_score = score # 4. move back to percept home planner = IKJoint(target_joint_pos=home_joint_pose) plan = planner.plan() plan.visualize(); plan.setSpeedByName('yolo'); if withPause: print '[Percept] Going back to percept_hand home' pause() plan.execute() goToHome.goToHome(robotConfig=None, homePos = [1,0,1.2], isExecute = isExecute, withPause = withPause) if max_obj_pose is None: return None, None, None pose_type = find_object_pose_type(obj_id, max_obj_pose) return max_obj_pose, pose_type, max_score
def percept_hand(obj_pose=None, binNum=0, obj_id=None, bin_contents=None, isExecute=True, withPause=True): capsen.capsen.init() home_joint_pose = [0, -0.2, 0.2, 0.01, 1, 1.4] planner = IKJoint(target_joint_pos=home_joint_pose) #plan = Plan() #plan.q_traj = [home_joint_pose]; plan = planner.plan() plan.visualize() plan.setSpeedByName('yolo') if withPause: print '[Percept] Going back to percept_hand home' pause() plan.execute() bin_cnstr = get_bin_inner_cnstr() # 1. init target poses target_poses = [] refind = 7 for i in range(12): target_pose_7_vert = [1.1756, 0, 0.79966] + tfm.quaternion_from_euler( math.pi, 1.4, math.pi).tolist() # for bin 7 vertical target_pose_7_hori = [1.1756, 0, 0.79966] + tfm.quaternion_from_euler( 2.2, 0, math.pi / 2).tolist() target_pose_7_invhori = [1.1756, 0, 0.79966 ] + tfm.quaternion_from_euler( -math.pi / 2, 0, -math.pi / 2).tolist() if i < 3: target_pose = copy.deepcopy(target_pose_7_invhori) if i == 0: target_pose[1] -= 0.06 target_pose[2] -= 0.08 # z elif i < 6: target_pose = copy.deepcopy(target_pose_7_hori) target_pose[0] += 0.03 # x target_pose[2] -= 0.04 # z elif i < 9: target_pose = copy.deepcopy(target_pose_7_hori) else: target_pose = copy.deepcopy(target_pose_7_hori) target_pose[2] += 0.1 # z target_pose[1] += (bin_cnstr[i][0] + bin_cnstr[i][1]) / 2 - ( bin_cnstr[refind][0] + bin_cnstr[refind][1]) / 2 # y target_pose[2] += (bin_cnstr[i][4] + bin_cnstr[i][5]) / 2 - ( bin_cnstr[refind][4] + bin_cnstr[refind][5]) / 2 # z target_poses.append(target_pose) y_deltas = [0.08, -0.08] caption = ['left', 'right'] max_score = -100 max_obj_pose = None for i in range(len(y_deltas)): # 2. plan to target tip_hand_transform = xyzrpy_from_xyzquat( [-0.067, 0.027, -0.012, -0.007, 0.704, 0.710, -0.002]) # need to be updated target_pose = copy.deepcopy(target_poses[binNum]) target_pose[1] += y_deltas[i] plan = None planner = IK(target_tip_pos=target_pose[0:3], target_tip_ori=target_pose[3:7], tip_hand_transform=tip_hand_transform, target_link='link_5', target_joint_bb=[[6, 1.2, 1.2]]) for j in range(15): planner.ori_tol = 0.5 * j / 10.0 planner.pos_tol = 0.01 * j / 10.0 newplan = planner.plan() if newplan.success(): plan = newplan print '[Percept] hand planning success at the trial %d' % j break if plan: plan.setSpeedByName('fastest') plan.visualize() if withPause: print '[Percept] Going to percept_hand %s ' % caption[i] pause() plan.execute() else: print '[Percept] hand planning failed' continue # 3. percept rospy.sleep(0.8) # wait for new pointcloud obj_pose, score = capsen.capsen.detectOneObject(obj_id, bin_contents, binNum, mode=1, withScore=True) if score > max_score: max_obj_pose = obj_pose max_score = score # 4. move back to percept home planner = IKJoint(target_joint_pos=home_joint_pose) plan = planner.plan() plan.visualize() plan.setSpeedByName('yolo') if withPause: print '[Percept] Going back to percept_hand home' pause() plan.execute() goToHome.goToHome(robotConfig=None, homePos=[1, 0, 1.2], isExecute=isExecute, withPause=withPause) if max_obj_pose is None: return None, None, None pose_type = find_object_pose_type(obj_id, max_obj_pose) return max_obj_pose, pose_type, max_score