def scoop(objPose=[1.95, 0.25, 1.4], objId=0, binNum=3, robotConfig=[0, 0, 0, 0, 0, 0], shelfPosition=[1.91, 0, -0.50], forceThreshold=1, isExecute=False): ## objPose: world position and orientation frame attached to com of object in quaternion form. XYZ. This is a list, not a matrix ## objId: object identifier ## robotConfig: current time robot configuration. List of joint angles, in radians ## shelfPosition: shelf position in world frame. This is a list. ## force threshold: amount of force needed to say we have a grasp ## initialize listener rospy ## Copy pasta hasta la pasta rospy.init_node('listener', anonymous=True) listener = tf.TransformListener() rospy.sleep(0.1) br = tf.TransformBroadcaster() rospy.sleep(0.1) ##hasta la copy la patio ## stop pasta # shelf variables pretensionDelta = 0.00 #how far we push nail down lipHeight = 0.035 #height of the lip of the bin # plan store plans = [] #list of plans generated each plan is an object ## get object position (world frame) objPosition = getObjCOM(objPose, objId) # ## move gripper to object com outside bin along world y direction and ## move the gripper over the lip of the bin # set tcp. this is the XYZ roll-pitch-yaw of middle of the wrist with respect to link 6 l2 = 0.45 #how far tcp is away from link 6 tip_hand_transform = [ 0, 0, l2, 0, 0, 0 ] #something used for planning in drake, I don't get it # to be updated when we have a hand design finalized # broadcast frame attached to tcp rospy.sleep(0.1) #.1 second delay so broadcasting works. syncing with ROS #broadcasting transformation between tcp and link 6 on ROS br.sendTransform(tuple(tip_hand_transform[0:3]), tfm.quaternion_from_euler(*tip_hand_transform[3:6]), rospy.Time.now(), 'tip', "link_6") rospy.sleep(0.1) # get position of the tcp in world frame pose_world = coordinateFrameTransform(tip_hand_transform[0:3], 'link_6', 'map', listener) #tcp position as a list tcpPos = [ pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z ] tcpPosHome = tcpPos # set scoop orientation (rotate wrist) scoopOrientation = [0, 0.7071, 0, 0.7071] # set first target to move gripper in front of the object and adjust height to middle of bin distFromShelf = 0.05 wristWidth = 0.0725 # this is actually half the wrist width (binMouth, binFloorHeight) = getBinMouthAndFloor(distFromShelf, binNum) pose_world = coordinateFrameTransform(binMouth[0:3], 'shelf', 'map', listener) binMouth = [ pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z ] targetPosition = [ binMouth[0], objPosition[1], binMouth[2] ] #align the position of the tcp relative to the object before the scoop frontOfObjectPtOutOfBin = targetPosition q_initial = robotConfig #q0 is initial configuration #target_tip_pos is where we want the tcp to be #target_tip_ori is the tip orientation #tip hand transform is see above planner = IK(q0=q_initial, target_tip_pos=targetPosition, target_tip_ori=scoopOrientation, tip_hand_transform=tip_hand_transform) plan = planner.plan() s = plan.success() #true if successful if s: print 'move to COM in y successful' print 'tcp at:' print(targetPosition) plan.visualize() #display in arvix plans.append(plan) if isExecute: plan.execute() #this executes the plan for reals else: print 'move to COM in y fail' #after this point, it's just a sequence of points for the plan qf = plan.q_traj[-1] #this is the final configuration of the object # set second target, go over the lip of the bin interiorLipBin = [0, 0.37, 0] # define over the lip distance in shelf frame interiorLipBin = coordinateFrameTransform(interiorLipBin, 'shelf', 'map', listener) deltaX = np.add(-targetPosition[0], interiorLipBin.pose.position.x) targetPosition = np.add(targetPosition, [deltaX, 0, 0]) q_initial = qf planner = IK(q0=q_initial, target_tip_pos=targetPosition, target_tip_ori=scoopOrientation, tip_hand_transform=tip_hand_transform) plan = planner.plan() s = plan.success() if s: print 'move to inside the lip success' print 'tcp at:' print(targetPosition) plans.append(plan) plan.visualize() if isExecute: plan.execute() else: print 'move to inside the lip fail' qf = plan.q_traj[-1] ## open gripper fully openGripper() ## push spatula against base of bin (pre-tension) binFloorHeight = coordinateFrameTransform([0, 0, binFloorHeight], 'shelf', 'map', listener) q_initial = qf deltaH = targetPosition[ 2] - binFloorHeight.pose.position.z - pretensionDelta - lipHeight targetPosition = np.add(targetPosition, [0, 0, -deltaH + wristWidth]) scoopOrientation = [0, 0.7071 + 0.11 / 2, 0, 0.7071 - 0.11 / 2] planner = IK(q0=q_initial, target_tip_pos=targetPosition, target_tip_ori=scoopOrientation, tip_hand_transform=tip_hand_transform) plan = planner.plan() s = plan.success() if s: print 'push finger against floor of bin success' print 'tcp at:' print(targetPosition) plans.append(plan) plan.visualize() if isExecute: plan.execute() else: print 'push finger against floor of bin fail' qf = plan.q_traj[-1] ## perform bin length stroke to middle q_initial = qf targetPosition = np.add(targetPosition, [0.20, 0, -lipHeight]) planner = IK(q0=q_initial, target_tip_pos=targetPosition, target_tip_ori=scoopOrientation, tip_hand_transform=tip_hand_transform) plan = planner.plan() s = plan.success() if s: print 'stroke middle of bin success' print 'tcp at:' print(targetPosition) plans.append(plan) plan.visualize() if isExecute: plan.execute() else: print 'stroke middle of bin fail' qf = plan.q_traj[-1] plans.append(plan) ## perform bin length stroke to end q_initial = qf targetPosition = np.add(targetPosition, [0.20, 0, 0]) scoopOrientation = [0, 0.7071 + 0.11 / 4, 0, 0.7071 - 0.11 / 4] planner = IK(q0=q_initial, target_tip_pos=targetPosition, target_tip_ori=scoopOrientation, tip_hand_transform=tip_hand_transform) plan = planner.plan() s = plan.success() if s: print 'stroke middle to end of bin success' print 'tcp at:' print(targetPosition) plans.append(plan) plan.visualize() if isExecute: plan.execute() else: print 'stroke middle to end of bin fail' qf = plan.q_traj[-1] plans.append(plan) ## close gripper closeGripper(forceThreshold) ## retreat #pdb.set_trace() #TRACEEEEE #this does each plan backwards so that the hand can leave the bin #VERY IMPORTANT for numOfPlan in range(0, len(plans)): plans[len(plans) - numOfPlan - 1].visualizeBackward() if isExecute: for numOfPlan in range(0, len(plans)): plans[len(plans) - numOfPlan - 1].executeBackward()
def flush_grasp(objPose = [1.95,1.25,1.4,0,0,0,1], binNum=4, objId = 0, bin_contents = None, robotConfig = None, forceThreshold = 1, isExecute = True, withPause = False): ## objPose: world position and orientation frame attached to com of object in quaternion form. XYZ ## objId: object identifier ## robotConfig: current time robot configuration ## shelfPosition: shelf position in world frame ## force threshold: amount fo force needed to say we have a grasp joint_topic = '/joint_states' ## initialize listener rospy listener = tf.TransformListener() br = tf.TransformBroadcaster() rospy.sleep(0.1) # shelf variables pretensionDelta = 0.00 lipHeight = 0.035 #tcp_offset_variables #set robot speed setSpeedByName(speedName = 'fast') # plan store plans = [] ## get object position (world frame) objPosition = getObjCOM(objPose[0:3], objId) 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] vertical_index=np.argmax(np.fabs(obj_pose_orient[2,0:3])) object_dim=get_obj_dim(objId) vertical_dim=object_dim[vertical_index] s1=np.fabs(obj_pose_orient[1,0])*object_dim[0] s2=np.fabs(obj_pose_orient[1,1])*object_dim[1] s3=np.fabs(obj_pose_orient[1,2])*object_dim[2] s4=np.fabs(obj_pose_orient[1,vertical_index])*object_dim[vertical_index] horizontal_dim=s1+s2+s3-s4 hand_gap=0 gripper.close() while True: APCrobotjoints = ROS_Wait_For_Msg(joint_topic, sensor_msgs.msg.JointState).getmsg() q0 = APCrobotjoints.position if len(q0) < 6: continue else: break ## move gripper to object com outside bin along world y direction and ## move the gripper over the lip of the bin # set tcp vert_offset=.035 l2 = 0.43 #change this to edit where you think the cup is l2 =.44 tip_hand_transform = [-vert_offset, 0, l2, 0,0,0] # to be updated when we have a hand design finalized # broadcast frame attached to tcp # for i in range(5): # rospy.sleep(0.1) # br.sendTransform(tuple(tip_hand_transform[0:3]), tfm.quaternion_from_euler(*tip_hand_transform[3:6]), rospy.Time.now(), 'tip', "link_6") # rospy.sleep(0.1) pubFrame(br, pose=tip_hand_transform, frame_id='tip', parent_frame_id='link_6', npub=5) # get position of the tcp in world frame pose_world = coordinateFrameTransform(tip_hand_transform[0:3], 'link_6', 'map', listener) tcpPos=[pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z] #this may cause issues!!! tcpPosHome = tcpPos # set scoop orientation (rotate wrist) distFromShelf = 0.05 wristWidth = 0.0725 # this is actually half the wrist width (binMouth,bin_height,bin_width) = getBinMouth(distFromShelf, binNum) pose_world = coordinateFrameTransform(binMouth[0:3], 'shelf', 'map', listener) binMouth=[pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z] object_depth=objPosition[0]-binMouth[0] finger_length=.23 finger_width=.06 up_offset=.05 down_offset=0.005 cup_to_spatula=.08 hand_width=.15 max_gripper_width=.110 hand_top_offset=hand_width/2+vert_offset+.03 hand_bot_offset=hand_width/2-vert_offset+.015 side_offset=.03 binFloorHeight=binMouth[2]-bin_height/2 binCeilHeight=binMouth[2]+bin_height/2 min_height=binFloorHeight+lipHeight+finger_width/2+down_offset desired_height=objPosition[2] max_height=binCeilHeight-lipHeight-finger_width/2-down_offset target_height=desired_height if target_height<min_height: target_height=min_height if target_height>max_height: target_height=max_height bin_sideways=binMouth[1] sidepos=objPosition[1] horz_offset=0.015 #this determines bin sides based on bin input binSmall=binMouth[1]-bin_width/2 binLarge=binMouth[1]+bin_width/2 #this determines bin sides based on object #(binSmall,binLarge)=getSides(objPosition[1],listener) binRight=binSmall binLeft=binLarge final_hand_gap=110 if sidepos>bin_sideways: #this stuff is what happens if the object is to the left print 'Object is to the left' if binNum==0 or binNum==3 or binNum==6 or binNum==9: print 'Object is in that weird rail corner' return False #turn the suction cup so that it is sideways left #scoopOrientation = [.5,-.5,.5,-.5] scoopOrientation = [0.5,.5,.5,.5] #side_waypoint1=binRight+cup_to_spatula+.01 #side_waypoint2=sidepos+horizontal_dim-side_offset #side_waypoint2=binLeft-horizontal_dim-horz_offset side_waypoint1=binLeft-hand_top_offset+horz_offset if sidepos-horizontal_dim<binLeft-final_hand_gap: print 'this is not a flush object' return False else: #this stuff is what happens if the object is to the right print 'Object is to the right' if binNum==2 or binNum==5 or binNum==8 or binNum==11: print 'Object is in that weird rail corner' return False #turn the suction cup so that it is sideways right #scoopOrientation = [0.5,.5,.5,.5] scoopOrientation = [.5,-.5,.5,-.5] #side_waypoint1=binLeft-cup_to_spatula-.01 #side_waypoint2=sidepos-horizontal_dim+side_offset #side_waypoint2=binRight+horizontal_dim+horz_offset side_waypoint1=binRight+hand_top_offset-horz_offset if sidepos+horizontal_dim>binRight+final_hand_gap: print 'this is not a flush object' return False targetPositionList=[ [binMouth[0]-.15, side_waypoint1, min_height], [binMouth[0]+.04, side_waypoint1, min_height], [binMouth[0]+.3, side_waypoint1, min_height], [binMouth[0]+.3, side_waypoint1, min_height+.03], [binMouth[0]-.1, side_waypoint1, min_height+.03]] qf=q0 for tp_index in range(0, len(targetPositionList)): targetPosition = targetPositionList[tp_index] frontOfObjectPtOutOfBin = targetPosition q_initial = qf planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = scoopOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() if s: print 'move to COM in y successful' print 'tcp at:' print(targetPosition) #plan.visualize(hand_param=hand_gap) plans.append(plan) #if isExecute: # pauseFunc(withPause) # plan.execute() else: print 'move to COM in y fail' return False #print plan.q_traj qf = plan.q_traj[-1] print qf for numOfPlan in range(0, 2): if isExecute: plans[numOfPlan].visualize(hand_param=final_hand_gap) pauseFunc(withPause) plans[numOfPlan].execute() #time.sleep(2.5) #suction.start() final_hand_gap=110 gripper.set_force(20) gripper.grasp(move_pos=final_hand_gap) for numOfPlan in range(2, 3): if isExecute: plans[numOfPlan].visualize(hand_param=hand_gap) pauseFunc(withPause) plans[numOfPlan].execute() gripper.set_force(50) rospy.sleep(0.1) gripper.move(move_pos=0) hand_gap=final_hand_gap print hand_gap ## retreat #for numOfPlan in range(0, len(plans)-1): # plans[len(plans)-numOfPlan-1].visualizeBackward(hand_param=hand_gap) # if isExecute: # pauseFunc(withPause) # plans[len(plans)-numOfPlan-1].executeBackward() # suction.stop() for numOfPlan in range(3, len(plans)): if isExecute: plans[numOfPlan].visualize(hand_param=hand_gap) pauseFunc(withPause) plans[numOfPlan].execute() return True
def suction_down(objPose = [1.95,1.25,1.4,0,0,0,1], binNum=4, objId = 0, bin_contents = None, robotConfig = None, shelfPosition = [1.9019,0.00030975,-0.503], forceThreshold = 1, isExecute = True, withPause = False): ## objPose: world position and orientation frame attached to com of object in quaternion form. XYZ ## objId: object identifier ## robotConfig: current time robot configuration ## shelfPosition: shelf position in world frame ## force threshold: amount fo force needed to say we have a grasp joint_topic = '/joint_states' ## initialize listener rospy listener = tf.TransformListener() rospy.sleep(0.1) br = tf.TransformBroadcaster() rospy.sleep(0.1) # shelf variables pretensionDelta = 0.00 lipHeight = 0.035 ## get object position (world frame) objPosition = getObjCOM(objPose[0:3], objId) 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] vertical_index=np.argmax(np.fabs(obj_pose_orient[2,0:3])) object_dim=get_obj_dim(objId) object_dim=adjust_obj_dim(objId,object_dim) vertical_dim=object_dim[vertical_index] while True: APCrobotjoints = ROS_Wait_For_Msg(joint_topic, sensor_msgs.msg.JointState).getmsg() q0 = APCrobotjoints.position if len(q0) < 6: continue else: break ## move gripper to object com outside bin along world y direction and ## move the gripper over the lip of the bin # set tcp vert_offset=.035 l2 =.44 tip_hand_transform = [-vert_offset, 0, l2, 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) # get position of the tcp in world frame pose_world = coordinateFrameTransform(tip_hand_transform[0:3], 'link_6', 'map', listener) tcpPos=[pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z] #this may cause issues!!! tcpPosHome = tcpPos # set scoop orientation (rotate wrist) scoopOrientation = [0.7071, 0, 0.7071,0] distFromShelf = 0.05 wristWidth = 0.0725 # this is actually half the wrist width (binMouth,bin_height,bin_width) = getBinMouth(distFromShelf, binNum) pose_world = coordinateFrameTransform(binMouth[0:3], 'shelf', 'map', listener) binMouth=[pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z] finger_length=.23 finger_width=.08 up_offset=.05 down_offset=-.025 cup_to_spatula=.08 hand_width=.15 max_gripper_width=110 hand_top_offset=hand_width/2+vert_offset+.01 hand_bot_offset=hand_width/2-vert_offset #this determines bin stuff based on bin input binFloorHeight=binMouth[2]-bin_height/2 binCeilHeight=binMouth[2]+bin_height/2 #this determines bin sides based on object (binSmall,binLarge)=getSides(objPosition[1],listener) horz_offset=0 small_limit=binSmall+finger_width/2+horz_offset large_limit=binLarge-finger_width/2-horz_offset plans = [] plan = Plan() if objPosition[1]<0: link6_angle=(q0[5]-math.pi) possible_start_config=[0.007996209289, -0.6193283503, 0.5283758664, -0.1974229539, 0.09102420595, 3.33888627518-2*math.pi] else: link6_angle=(q0[5]+math.pi) possible_start_config=[0.007996209289, -0.6193283503, 0.5283758664, -0.1974229539, 0.09102420595, 3.33888627518] #start_config=possible_start_config start_config=[q0[0],q0[1],q0[2],q0[3],q0[4],link6_angle]; plan.q_traj=[q0,start_config] plans.append(plan) qf=plan.q_traj[-1] def try_suction(target_x,target_y,qf,num_iter): object_depth=target_x-binMouth[0] sidepos=min(max(target_y,small_limit),large_limit) if object_depth<finger_length: print 'shallow suction' h1=binCeilHeight-lipHeight-cup_to_spatula h2=binFloorHeight+vertical_dim-down_offset else: print 'deep suction' h1=binCeilHeight-lipHeight-hand_top_offset h2a=binFloorHeight+vertical_dim-down_offset h2b=binFloorHeight+hand_bot_offset+lipHeight h2=max(h2a,h2b) h2=max(h2,binFloorHeight) if h2>h1: print 'cant go in' return False, False final_hand_gap=max_gripper_width targetPositionList=[ [binMouth[0]-.15, sidepos, h1], [target_x, sidepos, h1], [target_x, sidepos, h2]] for tp_index in range(0, len(targetPositionList)): targetPosition = targetPositionList[tp_index] planner = IK(q0 = qf, target_tip_pos = targetPosition, target_tip_ori = scoopOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() print 'Plan number:',tp_index+1 if s: print 'Plan calculated successfully' plans.append(plan) else: print 'Plan calulation failed' return (False, False) qf = plan.q_traj[-1] #set robot speed setSpeedByName(speedName = 'faster') hand_gap=0 gripper.close() for numOfPlan in range(0, len(plans)): if isExecute: plans[numOfPlan].visualize(hand_param=hand_gap) pauseFunc(withPause) plans[numOfPlan].execute() suction.start() gripper.set_force(10) gripper.grasp(move_pos=max_gripper_width) gripper.close() hand_gap=max_gripper_width print hand_gap ## retreat if num_iter==0: plan_offset=2 else: plan_offset=0 for numOfPlan in range(0, len(plans)-plan_offset): plans[len(plans)-numOfPlan-1].visualizeBackward(hand_param=hand_gap) if isExecute: #backward_plan=plans[len(plans)-numOfPlan-1] #q_first=backward_plan[0] #q_last=backward_plan[len(backward_plan)-1] #if(abs(q_first[5]-q_last[5])>math.pi/2): # print 'something weird is going on with joint 5 rotation' # break pauseFunc(withPause) plans[len(plans)-numOfPlan-1].executeBackward() time.sleep(4) my_return=suction.check() or suction_override(objId) if my_return==True: #set robot speed setSpeedByName(speedName = 'fast') return (True, True) else: suction.stop() return (True, False) target_offset=get_test_offset(objId) target_x_list=[objPosition[0],objPosition[0]-target_offset,objPosition[0],objPosition[0],objPosition[0]+target_offset] target_y_list=[objPosition[1],objPosition[1],objPosition[1]+target_offset,objPosition[1]-target_offset,objPosition[1]] count=0 suction_succeed=False overall_plan_succeed=False for count in range(0,len(target_x_list)): (plan_succeed,suction_succeed)=try_suction(target_x=target_x_list[count],target_y=target_y_list[count],qf=qf,num_iter=count) if suction_succeed: return (plan_succeed,suction_succeed) if plan_succeed==True: overall_plan_succeed=True while True: APCrobotjoints = ROS_Wait_For_Msg(joint_topic, sensor_msgs.msg.JointState).getmsg() qf = APCrobotjoints.position if len(qf) < 6: continue else: break print qf plans=[] count=count+1 return (overall_plan_succeed,suction_succeed)
def suction_side(objPose = [1.95,1.25,1.4,0,0,0,1], binNum=4, objId = 0, bin_contents = None, robotConfig = None, shelfPosition = [1.9019,0.00030975,-0.503], forceThreshold = 1, isExecute = True, withPause = False): ## objPose: world position and orientation frame attached to com of object in quaternion form. XYZ ## objId: object identifier ## robotConfig: current time robot configuration ## shelfPosition: shelf position in world frame ## force threshold: amount fo force needed to say we have a grasp joint_topic = '/joint_states' ## initialize listener rospy listener = tf.TransformListener() #rospy.sleep(0.1) br = tf.TransformBroadcaster() rospy.sleep(0.1) # shelf variables pretensionDelta = 0.00 lipHeight = 0.035 #tcp_offset_variables # plan store plans = [] ## get object position (world frame) objPosition = getObjCOM(objPose[0:3], objId) 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] vertical_index=np.argmax(np.fabs(obj_pose_orient[2,0:3])) object_dim=get_obj_dim(objId) vertical_dim=object_dim[vertical_index] s1=np.fabs(obj_pose_orient[1,0])*object_dim[0] s2=np.fabs(obj_pose_orient[1,1])*object_dim[1] s3=np.fabs(obj_pose_orient[1,2])*object_dim[2] s4=np.fabs(obj_pose_orient[1,vertical_index])*object_dim[vertical_index] horizontal_dim=s1+s2+s3-s4 hand_gap=0 gripper.close() while True: APCrobotjoints = ROS_Wait_For_Msg(joint_topic, sensor_msgs.msg.JointState).getmsg() q0 = APCrobotjoints.position if len(q0) < 6: continue else: break ## move gripper to object com outside bin along world y direction and ## move the gripper over the lip of the bin # set tcp vert_offset=.035 l2 = 0.43 #change this to edit where you think the cup is l2 =.44 tip_hand_transform = [-vert_offset, 0, l2, 0,0,0] # to be updated when we have a hand design finalized # broadcast frame attached to tcp # for i in range(5): # rospy.sleep(0.1) # br.sendTransform(tuple(tip_hand_transform[0:3]), tfm.quaternion_from_euler(*tip_hand_transform[3:6]), rospy.Time.now(), 'tip', "link_6") # rospy.sleep(0.1) pubFrame(br, pose=tip_hand_transform, frame_id='target_pose', parent_frame_id='tip', npub=1) # get position of the tcp in world frame pose_world = coordinateFrameTransform(tip_hand_transform[0:3], 'link_6', 'map', listener) tcpPos=[pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z] #this may cause issues!!! tcpPosHome = tcpPos # set scoop orientation (rotate wrist) distFromShelf = 0.05 wristWidth = 0.0725 # this is actually half the wrist width (binMouth,bin_height,bin_width) = getBinMouth(distFromShelf, binNum) pose_world = coordinateFrameTransform(binMouth[0:3], 'shelf', 'map', listener) binMouth=[pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z] object_depth=objPosition[0]-binMouth[0] finger_length=.23 finger_width=.08 up_offset=.05 down_offset=.01 cup_to_spatula=.08 hand_width=.15 max_gripper_width=.110 hand_top_offset=hand_width/2+vert_offset+.015 hand_bot_offset=hand_width/2-vert_offset+.015 up_down_adjust=.025 side_offset=.03 binFloorHeight=binMouth[2]-bin_height/2 binCeilHeight=binMouth[2]+bin_height/2 min_height=binFloorHeight+lipHeight+finger_width/2+down_offset desired_height=objPosition[2] max_height=binCeilHeight-lipHeight-finger_width/2-down_offset-up_down_adjust target_height=desired_height if target_height<min_height: target_height=min_height if target_height>max_height: target_height=max_height bin_sideways=binMouth[1] sidepos=objPosition[1] horz_offset=0.01 #this determines bin sides based on object #(binSmall,binLarge)=getSides(objPosition[1],listener) (binSmall,binLarge)=getSides(binNum,listener) binRight=binSmall binLeft=binLarge if sidepos>bin_sideways: #this stuff is what happens if the object is to the left print '[SucSide] Object is to the left' #turn the suction cup so that it is sideways left scoopOrientation = [.5,-.5,.5,-.5] side_waypoint1a=binRight+cup_to_spatula+.01 side_waypoint1b=sidepos-horizontal_dim/2-2*horz_offset if side_waypoint1a>side_waypoint1b: side_waypoint1=side_waypoint1a print '[SucSide] side waypoint A' else: side_waypoint1=side_waypoint1b print '[SucSide] side waypoint B' #side_waypoint2=sidepos+horizontal_dim-side_offset side_waypoint2=binLeft-horizontal_dim-horz_offset if side_waypoint2<side_waypoint1: if side_waypoint2<side_waypoint1a: print '[SucSide] Not enought gap' return (False, False) else: side_waypoint1=side_waypoint2 else: #this stuff is what happens if the object is to the right print '[SucSide] Object is to the right' #turn the suction cup so that it is sideways right scoopOrientation = [0.5,.5,.5,.5] side_waypoint1a=binLeft-cup_to_spatula-.01 side_waypoint1b=sidepos+horizontal_dim/2+2*horz_offset if side_waypoint1a<side_waypoint1b: side_waypoint1=side_waypoint1a print '[SucSide] side waypoint A' else: side_waypoint1=side_waypoint1b print '[SucSide] side waypoint B' #side_waypoint2=sidepos-horizontal_dim+side_offset side_waypoint2=binRight+horizontal_dim+horz_offset if side_waypoint2>side_waypoint1: if side_waypoint2>side_waypoint1a: print '[SucSide] Not enought gap' return (False, False) else: side_waypoint1=side_waypoint2 targetPositionList=[ [binMouth[0]-.15, side_waypoint1, target_height+up_down_adjust], [objPosition[0], side_waypoint1, target_height+up_down_adjust], [objPosition[0], side_waypoint2, target_height+up_down_adjust], [objPosition[0], side_waypoint2, target_height]] qf=q0 for tp_index in range(0, len(targetPositionList)): targetPosition = targetPositionList[tp_index] frontOfObjectPtOutOfBin = targetPosition q_initial = qf planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = scoopOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() if s: print '[SucSide] move to COM in y successful' print '[SucSide] tcp at:', targetPosition plan.visualize(hand_param=hand_gap) plans.append(plan) #if isExecute: # pauseFunc(withPause) # plan.execute() else: print '[SucSide] move to COM in y fail' return (False, False) #print plan.q_traj qf = plan.q_traj[-1] print '[SucSide] qf:', qf #set robot speed setSpeedByName(speedName = 'faster') for numOfPlan in range(0, len(plans)): if numOfPlan >=len(plans)-2: setSpeedByName(speedName = 'fast') if isExecute: plans[numOfPlan].visualize(hand_param=hand_gap) pauseFunc(withPause) plans[numOfPlan].execute() suction.start() final_hand_gap=110 gripper.set_force(12) gripper.grasp(move_pos=final_hand_gap) gripper.close() hand_gap=final_hand_gap print '[SucSide] hand_gap:', hand_gap continue_suction=suction_items(objId) if continue_suction: print '[SucSide] object is of type that suction side will try to remove from bin' else: print '[SucSide] object is to big to remove from bin' ## retreat for numOfPlan in range(0, len(plans)-1): plans[len(plans)-numOfPlan-1].visualizeBackward(hand_param=hand_gap) if isExecute: pauseFunc(withPause) plans[len(plans)-numOfPlan-1].executeBackward() if not continue_suction: suction.stop() rospy.sleep(3) print '[SucSide] Is suction in contact still? Lets see:' print '[SucSide] suction.check(): ', suction.check() print '[SucSide] suction.check(): ', suction.check() if suction.check(): #set robot speed print '[SucSide] got item. continuing. suction' setSpeedByName(speedName = 'fast') return (True, True) else: print '[SucSide] did not get item. Stopping suction' suction.stop() return (True, False)
def scoop(objPose=[1.95, 0.25, 1.4, 0, 0, 0, 1], binNum=3, objId=0, bin_contents=None, robotConfig=None, shelfPosition=[1.9116, -0.012498, -0.4971], forceThreshold=1, isExecute=True, withPause=True, withVisualize=False): ## objPose: world position and orientation frame attached to com of object in quaternion form. XYZ ## objId: object identifier ## robotConfig: current time robot configuration ## shelfPosition: shelf position in world frame ## force threshold: amount fo force needed to say we have a grasp setSpeedByName(speedName='faster') joint_topic = '/joint_states' planSuccess = True ## initialize listener rospy listener = tf.TransformListener() rospy.sleep(0.1) br = tf.TransformBroadcaster() rospy.sleep(0.1) # shelf variables if binNum < 3: pretensionDelta = 0.03 if binNum > 2 and binNum < 6: pretensionDelta = 0.009 if binNum > 5 and binNum < 9: pretensionDelta = 0.009 if binNum > 8: pretensionDelta = 0.03 #pretensionDelta = 0.00 lipHeight = 0.025 # plan store plans = [] ## get object position (world frame) objPosition = getObjCOM(objPose[0:3], objId) ## move gripper to object com outside bin along world y direction and ## move the gripper over the lip of the bin # set tcp tcpXOffset = 0.018 l2 = 0.47 tip_hand_transform = [ tcpXOffset, 0, l2, 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) # get position of the tcp in world frame pose_world = coordinateFrameTransform(tip_hand_transform[0:3], 'link_6', 'map', listener) tcpPos = [ pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z ] tcpPosHome = tcpPos # set scoop orientation (rotate wrist) scoopOrientation = [0, 0.7071, 0, 0.7071] # set first target to move gripper in front of the object and adjust height to middle of bin distFromShelf = 0.05 wristWidth = 0.0725 # this is actually half the wrist width (binMouth, binFloorHeight) = getBinMouthAndFloor(distFromShelf, binNum) pose_world = coordinateFrameTransform(binMouth[0:3], 'shelf', 'map', listener) binMouth = [ pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z ] verticalOffsetLip = 0.00 # we need this so we don't damage the sucker wH = 0.075 targetPosition = [ binMouth[0], objPosition[1], binMouth[2] + tcpXOffset - wH + lipHeight - pretensionDelta ] ## check to make sure we are inside the bin and not colliding with sides: minHeight, maxHeight, leftWall, rightWall = BinBBDims(binNum) leftWall = coordinateFrameTransform([leftWall, 0, 0], 'shelf', 'map', listener) leftWall = leftWall.pose.position.y rightWall = coordinateFrameTransform([rightWall, 0, 0], 'shelf', 'map', listener) rightWall = rightWall.pose.position.y interiorLipBin = [0, 0.40, 0] # define over the lip distance in shelf frame interiorLipBin = coordinateFrameTransform(interiorLipBin, 'shelf', 'map', listener) stepOverLip = interiorLipBin.pose.position.x fStroke = 0.20 sStroke = 0.19 binLengthSafety = 0.015 if targetPosition[1] + 0.04 > leftWall: interiorLipBin = [0, 0.36, 0] # define over the lip distance in shelf frame interiorLipBin = coordinateFrameTransform(interiorLipBin, 'shelf', 'map', listener) stepOverLip = interiorLipBin.pose.position.x fStroke = 0.17 if targetPosition[1] - 0.04 < leftWall: interiorLipBin = [0, 0.36, 0] # define over the lip distance in shelf frame interiorLipBin = coordinateFrameTransform(interiorLipBin, 'shelf', 'map', listener) stepOverLip = interiorLipBin.pose.position.x fStroke = 0.17 if targetPosition[1] + binLengthSafety > leftWall: targetPosition[1] = leftWall if targetPosition[1] - binLengthSafety < rightWall: targetPosition[1] = rightWall frontOfObjectPtOutOfBin = targetPosition q_initial = robotConfig planner = IK(q0=q_initial, target_tip_pos=targetPosition, target_tip_ori=scoopOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() # Plan 0 if s: print '[Scoop] move to COM in y successful' #~ print '[Scoop] tcp at:' #~ print(targetPosition) visualizeFunc(withVisualize, plan) plans.append(plan) else: print '[Scoop] move to COM in y fail' return (False, False) qf = plan.q_traj[-1] ## push spatula against base of bin (pre-tension) binFloorHeight = coordinateFrameTransform([0, 0, binFloorHeight], 'shelf', 'map', listener) q_initial = qf percentTilt = 0.1 # 10 percent scoopOrientation = [ 0, 0.7071 * (1 + percentTilt), 0, 0.7071 * (1 - percentTilt) ] planner = IK(q0=q_initial, target_tip_pos=targetPosition, target_tip_ori=scoopOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() # Plan 1 if s: print '[Scoop] reorient the hand' #~ print '[Scoop] tcp at:' #~ print(targetPosition) plans.append(plan) visualizeFunc(withVisualize, plan) else: print '[Scoop] reorient the hand fail' return (False, False) qf = plan.q_traj[-1] # set second target, go over the lip of the bin deltaX = np.add(-targetPosition[0], stepOverLip) targetPosition = np.add(targetPosition, [deltaX, 0, 0]) q_initial = qf planner = IK(q0=q_initial, target_tip_pos=targetPosition, target_tip_ori=scoopOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() # Plan 2 if s: print '[Scoop] move to inside the lip success' #~ print '[Scoop] tcp at:' #~ print(targetPosition) plans.append(plan) visualizeFunc(withVisualize, plan) else: print '[Scoop] move to inside the lip fail' return (False, False) qf = plan.q_traj[-1] ## perform bin length stroke to middle q_initial = qf targetPosition = np.add(targetPosition, [fStroke, 0, -lipHeight]) planner = IK(q0=q_initial, target_tip_pos=targetPosition, target_tip_ori=scoopOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() # Plan 3 if s: print '[Scoop] stroke middle of bin success' #~ print '[Scoop] tcp at:' #~ print(targetPosition) plans.append(plan) visualizeFunc(withVisualize, plan) else: print '[Scoop] stroke middle of bin fail' return (False, False) qf = plan.q_traj[-1] ## perform bin length stroke to end q_initial = qf targetPosition = np.add(targetPosition, [sStroke, 0, 0]) scoopOrientation = [0, 0.7071 + 0.11 / 4, 0, 0.7071 - 0.11 / 4] planner = IK(q0=q_initial, target_tip_pos=targetPosition, target_tip_ori=scoopOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() # Plan 4 if s: print '[Scoop] stroke middle to end of bin success' #~ print '[Scoop] tcp at:' #~ print(targetPosition) plans.append(plan) visualizeFunc(withVisualize, plan) else: print '[Scoop] stroke middle to end of bin fail' return (False, False) qf = plan.q_traj[-1] ## close gripper #~ closeGripper(forceThreshold) closeGripper(forceThreshold) execution_possible = True ## execute isNotInCollision = True for numOfPlan in range(0, len(plans)): plans[numOfPlan].visualize() if isExecute: if numOfPlan == 3: openGripper() pauseFunc(withPause) isNotInCollision = plans[numOfPlan].execute() if numOfPlan == 3: closeGripper(forceThreshold) plans[numOfPlan].executeBackward() openGripper() plans[numOfPlan].execute() if not isNotInCollision: planFailNum = numOfPlan print '[Scoop] collision detected' break if numOfPlan == 4: closeGripper(forceThreshold) rospy.sleep(0.5) while True: APCrobotjoints = ROS_Wait_For_Msg( joint_topic, sensor_msgs.msg.JointState).getmsg() q0 = APCrobotjoints.position if len(q0) == 2 or len(q0) == 8: q0 = q0[-2:] # get last 2 break gripper_q0 = np.fabs(q0) drop_thick = 0.000001 # finger gap =0.002m = .5 mm if gripper_q0[0] < drop_thick: print '[Scoop] ***************' print '[Scoop] Could not grasp' print '[Scoop] ***************' execution_possible = False else: print '[Scoop] ***************' print '[Scoop] Grasp Successful' print '[Scoop] ***************' execution_possible = True if not isNotInCollision: for numOfPlan in range(0, len(planFailNum)): plans[planFailNum - numOfPlan].executeBackward() ## retreat for numOfPlan in range(0, len(plans)): if withVisualize: plans[len(plans) - numOfPlan - 1].visualizeBackward() if isExecute: pauseFunc(withPause) plans[len(plans) - numOfPlan - 1].executeBackward() return True, execution_possible
def scoop(objPose = [1.95,0.25,1.4], objId = 0, binNum=3, robotConfig=[0,0,0,0,0,0], shelfPosition = [1.91,0,-0.50], forceThreshold = 1, isExecute = False): ## objPose: world position and orientation frame attached to com of object in quaternion form. XYZ. This is a list, not a matrix ## objId: object identifier ## robotConfig: current time robot configuration. List of joint angles, in radians ## shelfPosition: shelf position in world frame. This is a list. ## force threshold: amount of force needed to say we have a grasp ## initialize listener rospy ## Copy pasta hasta la pasta rospy.init_node('listener', anonymous=True) listener = tf.TransformListener() rospy.sleep(0.1) br = tf.TransformBroadcaster() rospy.sleep(0.1) ##hasta la copy la patio ## stop pasta # shelf variables pretensionDelta = 0.00 #how far we push nail down lipHeight = 0.035 #height of the lip of the bin # plan store plans = [] #list of plans generated each plan is an object ## get object position (world frame) objPosition = getObjCOM(objPose, objId) # ## move gripper to object com outside bin along world y direction and ## move the gripper over the lip of the bin # set tcp. this is the XYZ roll-pitch-yaw of middle of the wrist with respect to link 6 l2 = 0.45 #how far tcp is away from link 6 tip_hand_transform = [0, 0, l2, 0,0,0] #something used for planning in drake, I don't get it # to be updated when we have a hand design finalized # broadcast frame attached to tcp rospy.sleep(0.1) #.1 second delay so broadcasting works. syncing with ROS #broadcasting transformation between tcp and link 6 on ROS br.sendTransform(tuple(tip_hand_transform[0:3]), tfm.quaternion_from_euler(*tip_hand_transform[3:6]), rospy.Time.now(), 'tip', "link_6") rospy.sleep(0.1) # get position of the tcp in world frame pose_world = coordinateFrameTransform(tip_hand_transform[0:3], 'link_6', 'map', listener) #tcp position as a list tcpPos=[pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z] tcpPosHome = tcpPos # set scoop orientation (rotate wrist) scoopOrientation = [0, 0.7071, 0, 0.7071] # set first target to move gripper in front of the object and adjust height to middle of bin distFromShelf = 0.05 wristWidth = 0.0725 # this is actually half the wrist width (binMouth, binFloorHeight) = getBinMouthAndFloor(distFromShelf, binNum) pose_world = coordinateFrameTransform(binMouth[0:3], 'shelf', 'map', listener) binMouth=[pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z] targetPosition = [binMouth[0], objPosition[1], binMouth[2]] #align the position of the tcp relative to the object before the scoop frontOfObjectPtOutOfBin = targetPosition q_initial = robotConfig #q0 is initial configuration #target_tip_pos is where we want the tcp to be #target_tip_ori is the tip orientation #tip hand transform is see above planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = scoopOrientation, tip_hand_transform=tip_hand_transform) plan = planner.plan() s = plan.success() #true if successful if s: print 'move to COM in y successful' print 'tcp at:' print(targetPosition) plan.visualize() #display in arvix plans.append(plan) if isExecute: plan.execute() #this executes the plan for reals else: print 'move to COM in y fail' #after this point, it's just a sequence of points for the plan qf = plan.q_traj[-1] #this is the final configuration of the object # set second target, go over the lip of the bin interiorLipBin = [0,0.37,0] # define over the lip distance in shelf frame interiorLipBin = coordinateFrameTransform(interiorLipBin, 'shelf', 'map', listener) deltaX = np.add(-targetPosition[0],interiorLipBin.pose.position.x) targetPosition = np.add(targetPosition, [deltaX,0,0]) q_initial = qf planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = scoopOrientation, tip_hand_transform=tip_hand_transform) plan = planner.plan() s = plan.success() if s: print 'move to inside the lip success' print 'tcp at:' print(targetPosition) plans.append(plan) plan.visualize() if isExecute: plan.execute() else: print 'move to inside the lip fail' qf = plan.q_traj[-1] ## open gripper fully openGripper() ## push spatula against base of bin (pre-tension) binFloorHeight = coordinateFrameTransform([0,0,binFloorHeight], 'shelf', 'map', listener) q_initial = qf deltaH = targetPosition[2] - binFloorHeight.pose.position.z - pretensionDelta - lipHeight targetPosition = np.add(targetPosition, [0,0,-deltaH+wristWidth]) scoopOrientation = [0, 0.7071+0.11/2, 0, 0.7071-0.11/2] planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = scoopOrientation, tip_hand_transform=tip_hand_transform) plan = planner.plan() s = plan.success() if s: print 'push finger against floor of bin success' print 'tcp at:' print(targetPosition) plans.append(plan) plan.visualize() if isExecute: plan.execute() else: print 'push finger against floor of bin fail' qf = plan.q_traj[-1] ## perform bin length stroke to middle q_initial = qf targetPosition = np.add(targetPosition, [0.20,0,-lipHeight]) planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = scoopOrientation, tip_hand_transform=tip_hand_transform) plan = planner.plan() s = plan.success() if s: print 'stroke middle of bin success' print 'tcp at:' print(targetPosition) plans.append(plan) plan.visualize() if isExecute: plan.execute() else: print 'stroke middle of bin fail' qf = plan.q_traj[-1] plans.append(plan) ## perform bin length stroke to end q_initial = qf targetPosition = np.add(targetPosition, [0.20,0,0]) scoopOrientation = [0, 0.7071+0.11/4, 0, 0.7071-0.11/4] planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = scoopOrientation, tip_hand_transform=tip_hand_transform) plan = planner.plan() s = plan.success() if s: print 'stroke middle to end of bin success' print 'tcp at:' print(targetPosition) plans.append(plan) plan.visualize() if isExecute: plan.execute() else: print 'stroke middle to end of bin fail' qf = plan.q_traj[-1] plans.append(plan) ## close gripper closeGripper(forceThreshold) ## retreat #pdb.set_trace() #TRACEEEEE #this does each plan backwards so that the hand can leave the bin #VERY IMPORTANT for numOfPlan in range(0, len(plans)): plans[len(plans)-numOfPlan-1].visualizeBackward() if isExecute: for numOfPlan in range(0, len(plans)): plans[len(plans)-numOfPlan-1].executeBackward()
def push(objPose = [1.55,0.25,1.1,0,0,0,0], binNum=0, objId = 0, bin_contents = None, robotConfig=None, shelfPosition = [1.9116,-0.012498,-0.4971], forceThreshold = 1, binDepthReach = 0.40, isExecute = True, withPause = False): ## objPose: world position and orientation frame attached to com of object ## objId: object identifier ## robotConfig: current time robot configuration ## shelfPosition: shelf position in world frame ## force threshold: amount fo force needed to say we have a grasp ## initialize listener rospy rospy.init_node('listener', anonymous=True) listener = tf.TransformListener() rospy.sleep(0.1) br = tf.TransformBroadcaster() rospy.sleep(0.1) joint_topic = '/joint_states' # shelf variables pretensionDelta = 0.00 lipHeight = 0.035 ## get object position (world frame) objPosition = getObjCOM(objPose[0:3], objId) ## move gripper to object com outside bin along world y direction and ## move the gripper over the lip of the bin # set tcp l2 = 0.47 tip_hand_transform = [0, 0, l2, 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) # get position of the tcp in world frame pose_world = coordinateFrameTransform(tip_hand_transform[0:3], 'link_6', 'map', listener) tcpPos=[pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z] tcpPosHome = tcpPos # set topple orientation (rotate wrist) toppleOrientation = [0.0, 0.7071, 0.0, 0.7071] #[0, 0.7071, 0, 0.7071] # if gripper open close it closeGripper(forceThreshold) # set first target to move gripper in front of the object and adjust height to middle of bin distFromShelf = 0.05 wristWidth = 0.0725 # this is actually half the wrist width (binMouth, binFloorHeight) = getBinMouthAndFloor(distFromShelf, binNum) pose_world = coordinateFrameTransform(binMouth[0:3], 'shelf', 'map', listener) binFloorHeight = coordinateFrameTransform([0,0,binFloorHeight], 'shelf', 'map', listener) binFloorHeight = binFloorHeight.pose.position.z binMouth=[pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z] # set offset past COM # offset is 1/4 of object's height + half finger width # note: (COM height - bin floor height) is half of the object's height #pdb.set_trace() #TRACEEEEE fingerWidth = 0.06 offsetFinger = fingerWidth/2 targetHeight = (objPosition[2] - binFloorHeight)*2 effect = 'slide' if effect == 'topple': offsetEffect = targetHeight*3/4 elif effect == 'slide': offsetEffect = targetHeight*1/4 else: offsetEffect = targetHeight*1/4 #Default is slide, made three cases for flexibility offset = offsetFinger + offsetEffect targetPosition = [binMouth[0], objPosition[1], binFloorHeight+offset] frontOfObjectPtOutOfBin = targetPosition q_initial = robotConfig planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = toppleOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() if s and effect == 'topple': print 'move to COM in y and above COM in z successful' elif s and effect == 'slide': print 'move to COM in y and below COM in z successful' else: print 'move to COM in y and below COM in z successful' #Default is slide, made three cases for flexibility if s: print 'tcp at:' print(targetPosition) plan.visualize() if isExecute: pauseFunc(withPause) plan.execute() else: print 'move to COM in y and above COM in z fail' qf = plan.q_traj[-1] # set second target, go over the lip of the bin #interiorLipBin = [0,0.39,0] # define over the lip distance in shelf frame #interiorLipBin = coordinateFrameTransform(interiorLipBin, 'shelf', 'map', listener) #deltaX = np.add(-targetPosition[0],interiorLipBin.pose.position.x) #targetPosition = np.add(targetPosition, [deltaX,0,0]) #q_initial = qf #planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = toppleOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) #plan = planner.plan() #s = plan.success() #if s: # print 'move to inside the lip success' # print 'tcp at:' # print(targetPosition) # plan.visualize() # if isExecute: # pauseFunc(withPause) # plan.execute() #else: # print 'move to inside the lip fail' #qf = plan.q_traj[-1] ## close gripper fully (Do we wish to topple with gripper slightly open?) closeGripper(forceThreshold) ## perform bin length stroke to end q_initial = qf targetPosition = np.add(targetPosition, [binDepthReach,0,0]) planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = toppleOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() if s: print 'stroke to end of bin success' print 'tcp at:' print(targetPosition) plan.visualize() if isExecute: pauseFunc(withPause) plan.execute() else: print 'stroke to end of bin fail' qf = plan.q_traj[-1] ## close gripper closeGripper(forceThreshold) ## retreat # go back along stroke q_initial = qf targetPosition = frontOfObjectPtOutOfBin planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = toppleOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() if s: print 'stroke to bin start success' print 'tcp at:' print(targetPosition) plan.visualize() if isExecute: pauseFunc(withPause) plan.execute() else: print 'stroke to bin start fail' qf = plan.q_traj[-1] # go back to initial tcp position q_initial = qf targetPosition = frontOfObjectPtOutOfBin planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = toppleOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() if s: print 'return to mouth success' plan.visualize() if isExecute: pauseFunc(withPause) plan.execute() else: print 'return to mouth fail' return False
def suction_down(objPose=[1.95, 1.25, 1.4, 0, 0, 0, 1], binNum=4, objId=0, bin_contents=None, robotConfig=None, shelfPosition=[1.9019, 0.00030975, -0.503], forceThreshold=1, isExecute=True, withPause=True): ## objPose: world position and orientation frame attached to com of object in quaternion form. XYZ ## objId: object identifier ## robotConfig: current time robot configuration ## shelfPosition: shelf position in world frame ## force threshold: amount fo force needed to say we have a grasp joint_topic = '/joint_states' ## initialize listener rospy listener = tf.TransformListener() rospy.sleep(0.1) br = tf.TransformBroadcaster() rospy.sleep(0.1) # shelf variables pretensionDelta = 0.00 lipHeight = 0.035 ## get object position (world frame) objPosition = getObjCOM(objPose[0:3], objId) 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] vertical_index = np.argmax(np.fabs(obj_pose_orient[2, 0:3])) object_dim = get_obj_dim(objId) object_dim = adjust_obj_dim(objId, object_dim) vertical_dim = object_dim[vertical_index] while True: APCrobotjoints = ROS_Wait_For_Msg(joint_topic, sensor_msgs.msg.JointState).getmsg() q0 = APCrobotjoints.position if len(q0) >= 6: q0 = q0[ 0: 6] # take first 6, because in virtual environmet there will be additional 2 hand joint break ## move gripper to object com outside bin along world y direction and ## move the gripper over the lip of the bin # set tcp vert_offset = .035 l2 = .44 tip_hand_transform = [ -vert_offset, 0, l2, 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) # get position of the tcp in world frame pose_world = coordinateFrameTransform(tip_hand_transform[0:3], 'link_6', 'map', listener) tcpPos = [ pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z ] #this may cause issues!!! tcpPosHome = tcpPos # set scoop orientation (rotate wrist) scoopOrientation = [0.7071, 0, 0.7071, 0] distFromShelf = 0.05 wristWidth = 0.0725 # this is actually half the wrist width (binMouth, bin_height, bin_width) = getBinMouth(distFromShelf, binNum) pose_world = coordinateFrameTransform(binMouth[0:3], 'shelf', 'map', listener) binMouth = [ pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z ] hand_gap = 0 gripper.close() finger_length = .23 finger_width = .08 up_offset = .05 down_offset = -.025 cup_to_spatula = .08 hand_width = .15 max_gripper_width = 110 hand_top_offset = hand_width / 2 + vert_offset + .01 hand_bot_offset = hand_width / 2 - vert_offset #this determines bin stuff based on bin input binFloorHeight = binMouth[2] - bin_height / 2 binCeilHeight = binMouth[2] + bin_height / 2 #this determines bin sides based on object #(binSmall,binLarge)=getSides(objPosition[1],listener) (binSmall, binLarge) = getSides(binNum, listener) horz_offset = 0 small_limit = binSmall + finger_width / 2 + horz_offset large_limit = binLarge - finger_width / 2 - horz_offset plans = [] plan = Plan() if objPosition[1] < 0: link6_angle = (q0[5] - math.pi) possible_start_config = [ 0.007996209289, -0.6193283503, 0.5283758664, -0.1974229539, 0.09102420595, 3.33888627518 - 2 * math.pi ] else: link6_angle = (q0[5] + math.pi) possible_start_config = [ 0.007996209289, -0.6193283503, 0.5283758664, -0.1974229539, 0.09102420595, 3.33888627518 ] #start_config=possible_start_config start_config = [q0[0], q0[1], q0[2], q0[3], q0[4], link6_angle] planner = IKJoint(q0=q0, target_joint_pos=start_config) plan = planner.plan() #plan.q_traj=[q0,start_config] plans.append(plan) qf = plan.q_traj[-1] def get_motion_param(target_x, target_y): object_depth = target_x - binMouth[0] sidepos = min(max(target_y, small_limit), large_limit) if object_depth < finger_length: print '[SucDown] shallow suction' h1 = binCeilHeight - lipHeight - cup_to_spatula h2 = binFloorHeight + vertical_dim - down_offset else: print '[SucDown] deep suction, quitting' h1 = binCeilHeight - lipHeight - hand_top_offset h2a = binFloorHeight + vertical_dim - down_offset h2b = binFloorHeight + hand_bot_offset + lipHeight h2 = max(h2a, h2b) return False, h1, h2, sidepos h2 = max(h2, binFloorHeight) if h2 > h1: print '[SucDown] cant go in' return False, h1, h2, sidepos return True, h1, h2, sidepos def generate_plan(targetPositionList, plans, qf): for tp_index in range(0, len(targetPositionList)): targetPosition = targetPositionList[tp_index] planner = IK(q0=qf, target_tip_pos=targetPosition, target_tip_ori=scoopOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() print '[SucDown] Plan number:', tp_index + 1 if s: print '[SucDown] Plan calculated successfully' plans.append(plan) else: print '[SucDown] Plan calulation failed' return (False, plans, qf) qf = plan.q_traj[-1] return (True, plans, qf) def execute_forward(plans, hand_gap): for numOfPlan in range(0, len(plans)): if isExecute: plans[numOfPlan].visualize(hand_param=hand_gap) pauseFunc(withPause) plans[numOfPlan].execute() def execute_backward(plans, hand_gap, plan_offset): for numOfPlan in range(0, len(plans) - plan_offset): plans[len(plans) - numOfPlan - 1].visualizeBackward(hand_param=hand_gap) if isExecute: pauseFunc(withPause) plans[len(plans) - numOfPlan - 1].executeBackward() def try_suction(target_x, target_y, plans, qf, num_iter): (continue_val, h1, h2, sidepos) = get_motion_param(target_x, target_y) if continue_val == False: return False, False final_hand_gap = max_gripper_width targetPositionList = [[target_x, sidepos, h1], [target_x, sidepos, h2]] (continue_val, plans, throwaway) = generate_plan(targetPositionList, plans, qf) if continue_val == False: return False, False #set robot speed setSpeedByName(speedName='faster') hand_gap = 0 gripper.close() execute_forward(plans, hand_gap) #suction.start() gripper.set_force(10) gripper.grasp(move_pos=max_gripper_width) gripper.close() hand_gap = max_gripper_width print '[SucDown] hand_gap:', hand_gap execute_backward(plans, hand_gap, 0) #time.sleep(4) my_return = suction.check() or suction_override(objId) if my_return == True: #set robot speed setSpeedByName(speedName='fast') return (True, True) else: #suction.stop() return (True, False) target_offset = get_test_offset(objId) target_x_list = [ objPosition[0], objPosition[0] - target_offset, objPosition[0], objPosition[0], objPosition[0] + target_offset ] target_y_list = [ objPosition[1], objPosition[1], objPosition[1] + target_offset, objPosition[1] - target_offset, objPosition[1] ] count = 0 suction_succeed = False overall_plan_succeed = False (continue_val, h1, h2, sidepos) = get_motion_param(target_x=target_x_list[0], target_y=target_y_list[0]) if continue_val == False: return False, False #targetPositionList=[ #[binMouth[0]-.15, sidepos, h1], #[binMouth[0]-.15, sidepos, h1], #[target_x_list[0], sidepos, h1]] targetPositionListA = [[binMouth[0] - .15, sidepos, h1], [binMouth[0] - .15, sidepos, h1]] targetPositionListB = [[target_x_list[0], sidepos, h1]] (continue_val, plans1, qf) = generate_plan(targetPositionListA, plans, qf) if continue_val == False: return False, False (continue_val, plans2, qf) = generate_plan(targetPositionListB, [], qf) if continue_val == False: return False, False setSpeedByName(speedName='yolo') execute_forward(plans1, 0) setSpeedByName(speedName='faster') execute_forward(plans2, 0) suction.start() #time.sleep(6) #plans_store=plans plans = [] for count in range(0, len(target_x_list)): (plan_succeed, suction_succeed) = try_suction(target_x=target_x_list[count], target_y=target_y_list[count], plans=plans, qf=qf, num_iter=count) if suction_succeed: overall_plan_succeed = True break #return (plan_succeed,suction_succeed) if plan_succeed == True: overall_plan_succeed = True while True: APCrobotjoints = ROS_Wait_For_Msg( joint_topic, sensor_msgs.msg.JointState).getmsg() qf = APCrobotjoints.position if len(qf) < 6: continue else: break print '[SucDown] qf:', hand_gap plans = [] count = count + 1 execute_backward(plans2, 0, 0) if not suction_succeed: suction.stop() return (overall_plan_succeed, suction_succeed)
def topple(objPose = [1.55,0.25,1.1,0,0,0,0], binNum=0, objId = 0, bin_contents = None, robotConfig = None, shelfPosition = [1.9116,-0.012498,-0.4971], forceThreshold = 1, binDepthReach = 0.40, isExecute = True, withPause = True, withVisualize = True): ## objPose: world position and orientation frame attached to com of object ## objId: object identifier ## robotConfig: current time robot configuration ## shelfPosition: shelf position in world frame ## force threshold: amount fo force needed to say we have a grasp planSuccess = True ## initialize listener rospy listener = tf.TransformListener() rospy.sleep(0.1) br = tf.TransformBroadcaster() rospy.sleep(0.1) setSpeedByName(speedName = 'faster') joint_topic = '/joint_states' # shelf variables pretensionDelta = 0.00 lipHeight = 0.035 temp_bias = 0.00 # TO-DO remove this: # plan store plans = [] ## get object position (world frame) objPosition = getObjCOM(objPose[0:3], objId) ## move gripper to object com outside bin along world y direction and ## move the gripper over the lip of the bin # set tcp l1 = 0.018 l2 = 0.470 tip_hand_transform = [l1, 0, l2, 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) # get position of the tcp in world frame pose_world = coordinateFrameTransform(tip_hand_transform[0:3], 'link_6', 'map', listener) tcpPos=[pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z] tcpPosHome = tcpPos toppleOrientation = [0.0, 0.7071, 0.0, 0.7071] # set topple orientation (rotate wrist) closeGripper(forceThreshold) # if gripper open close it # set first target to move gripper in front of the object and adjust height to middle of bin distFromShelf = 0.05 wristWidth = 0.0725 # this is actually half the wrist width (binMouth, binFloorHeight) = getBinMouthAndFloor(distFromShelf, binNum) pose_world = coordinateFrameTransform(binMouth[0:3], 'shelf', 'map', listener) binFloorHeight = coordinateFrameTransform([0,0,binFloorHeight], 'shelf', 'map', listener) binFloorHeight = binFloorHeight.pose.position.z binMouth = [pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z] # set offset past COM # offset is 1/4 of object's height + half finger width # note: (COM height - bin floor height) is half of the object's height fingerWidth = 0.06 offsetFinger = fingerWidth/2 targetHeight = (objPosition[2] - binFloorHeight)*2 # to be changed to be from an object offsetEffect = targetHeight*3/4 offset = offsetEffect vertToppleHeight = binFloorHeight+offset-temp_bias ## bounding box constraint minHeight, maxHeight, leftWall, rightWall = BinBBDims(binNum) # shelf frame # trying to topple an object that is too tall? maxHeight = coordinateFrameTransform([0,0,maxHeight], 'shelf', 'map', listener) #pdb.set_trace() targetPosition = [binMouth[0], objPosition[1], vertToppleHeight] binDepthReach = 0.3 binHeightSaftey = 0.01 if vertToppleHeight + binHeightSaftey > maxHeight.pose.position.z: fingerLength = 0.26 binDepth = 0.42 binDepthReach = binDepth - fingerLength + 0.08 toppleHeightWhenTall = binMouth[2] + 0.03 targetPosition = [binMouth[0], objPosition[1], toppleHeightWhenTall] print '[Topple] Object too tall, topple will not go all the way in' # trying to topple an object that is too short? minHeight = coordinateFrameTransform([0,0,minHeight], 'shelf', 'map', listener) closeGripper(forceThreshold) if vertToppleHeight - binHeightSaftey < minHeight.pose.position.z: print '[Topple] Object too short, resetting topple height' toppleHeightWhenShort = minHeight.pose.position.z + binHeightSaftey targetPosition = [binMouth[0], objPosition[1], toppleHeightWhenShort] gripper.move(80,100) # too far left or right? leftWall = coordinateFrameTransform([leftWall,0,0], 'shelf', 'map', listener) leftWall = leftWall.pose.position.y rightWall = coordinateFrameTransform([rightWall,0,0], 'shelf', 'map', listener) rightWall = rightWall.pose.position.y binLengthSafety = 0.02 horizontalSaftey = 0.01 if targetPosition[1] + binLengthSafety > leftWall: targetPosition[1] = leftWall - horizontalSaftey if targetPosition[1] - binLengthSafety < rightWall: targetPosition[1] = rightWall + horizontalSaftey frontOfObjectPtOutOfBin = targetPosition q_initial = robotConfig planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = toppleOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() effect = 'topple' if s and effect == 'topple': print '[Topple] move to COM in y and above COM in z successful' elif s and effect == 'slide': print '[Topple] move to COM in y and below COM in z successful' else: print '[Topple] move to COM in y and below COM in z successful' #Default is slide, made three cases for flexibility if s: visualizeFunc(withVisualize, plan) plans.append(plan) else: print '[Topple] move to COM in y and above COM in z fail' planSuccess = False qf = plan.q_traj[-1] ## perform bin length stroke to end q_initial = qf targetPosition = np.add(targetPosition, [binDepthReach,0,0]) planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = toppleOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() if s: print '[Topple] stroke to end of bin success' visualizeFunc(withVisualize, plan) plans.append(plan) else: print '[Topple] stroke to end of bin fail' planSuccess = False qf = plan.q_traj[-1] ## close gripper closeGripper(forceThreshold) ## retreat # go back along stroke q_initial = qf targetPosition = frontOfObjectPtOutOfBin planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = toppleOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() if s: print '[Topple] stroke to bin start success' visualizeFunc(withVisualize, plan) plans.append(plan) else: print '[Topple] stroke to bin start fail' planSuccess = False qf = plan.q_traj[-1] # go back to initial tcp position q_initial = qf targetPosition = frontOfObjectPtOutOfBin planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = toppleOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() if s: print '[Topple] return to mouth success' visualizeFunc(withVisualize, plan) plans.append(plan) else: print '[Topple] return to mouth fail' planSuccess = False if not planSuccess: return False, False ## execute #~ for numOfPlan in range(0, len(plans)): #~ plans[numOfPlan].visualize() #~ if isExecute: #~ pauseFunc(withPause) #~ plans[numOfPlan].execute() ## execute isNotInCollision = True for numOfPlan in range(0, len(plans)): plans[numOfPlan].visualize() if isExecute: pauseFunc(withPause) isNotInCollision = plans[numOfPlan].execute() if not isNotInCollision: print '[Topple] collision detected' planFailNum = numOfPlan break if not isNotInCollision: for numOfPlan in range(0, len(planFailNum)): plans[planFailNum-numOfPlan].executeBackward() ## retreat for numOfPlan in range(0, len(plans)): if withVisualize: plans[len(plans)-numOfPlan-1].visualizeBackward() if isExecute: pauseFunc(withPause) plans[len(plans)-numOfPlan-1].executeBackward() return True, False
def suction_side(objPose=[1.95, 1.25, 1.4, 0, 0, 0, 1], binNum=4, objId=0, bin_contents=None, robotConfig=None, shelfPosition=[1.9019, 0.00030975, -0.503], forceThreshold=1, isExecute=True, withPause=False): ## objPose: world position and orientation frame attached to com of object in quaternion form. XYZ ## objId: object identifier ## robotConfig: current time robot configuration ## shelfPosition: shelf position in world frame ## force threshold: amount fo force needed to say we have a grasp joint_topic = '/joint_states' ## initialize listener rospy listener = tf.TransformListener() #rospy.sleep(0.1) br = tf.TransformBroadcaster() rospy.sleep(0.1) # shelf variables pretensionDelta = 0.00 lipHeight = 0.035 #tcp_offset_variables # plan store plans = [] ## get object position (world frame) objPosition = getObjCOM(objPose[0:3], objId) 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] vertical_index = np.argmax(np.fabs(obj_pose_orient[2, 0:3])) object_dim = get_obj_dim(objId) vertical_dim = object_dim[vertical_index] s1 = np.fabs(obj_pose_orient[1, 0]) * object_dim[0] s2 = np.fabs(obj_pose_orient[1, 1]) * object_dim[1] s3 = np.fabs(obj_pose_orient[1, 2]) * object_dim[2] s4 = np.fabs(obj_pose_orient[1, vertical_index]) * object_dim[vertical_index] horizontal_dim = s1 + s2 + s3 - s4 hand_gap = 0 gripper.close() while True: APCrobotjoints = ROS_Wait_For_Msg(joint_topic, sensor_msgs.msg.JointState).getmsg() q0 = APCrobotjoints.position if len(q0) < 6: continue else: break ## move gripper to object com outside bin along world y direction and ## move the gripper over the lip of the bin # set tcp vert_offset = .035 l2 = 0.43 #change this to edit where you think the cup is l2 = .44 tip_hand_transform = [ -vert_offset, 0, l2, 0, 0, 0 ] # to be updated when we have a hand design finalized # broadcast frame attached to tcp # for i in range(5): # rospy.sleep(0.1) # br.sendTransform(tuple(tip_hand_transform[0:3]), tfm.quaternion_from_euler(*tip_hand_transform[3:6]), rospy.Time.now(), 'tip', "link_6") # rospy.sleep(0.1) pubFrame(br, pose=tip_hand_transform, frame_id='target_pose', parent_frame_id='tip', npub=1) # get position of the tcp in world frame pose_world = coordinateFrameTransform(tip_hand_transform[0:3], 'link_6', 'map', listener) tcpPos = [ pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z ] #this may cause issues!!! tcpPosHome = tcpPos # set scoop orientation (rotate wrist) distFromShelf = 0.05 wristWidth = 0.0725 # this is actually half the wrist width (binMouth, bin_height, bin_width) = getBinMouth(distFromShelf, binNum) pose_world = coordinateFrameTransform(binMouth[0:3], 'shelf', 'map', listener) binMouth = [ pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z ] object_depth = objPosition[0] - binMouth[0] finger_length = .23 finger_width = .08 up_offset = .05 down_offset = .01 cup_to_spatula = .08 hand_width = .15 max_gripper_width = .110 hand_top_offset = hand_width / 2 + vert_offset + .015 hand_bot_offset = hand_width / 2 - vert_offset + .015 up_down_adjust = .025 side_offset = .03 binFloorHeight = binMouth[2] - bin_height / 2 binCeilHeight = binMouth[2] + bin_height / 2 min_height = binFloorHeight + lipHeight + finger_width / 2 + down_offset desired_height = objPosition[2] max_height = binCeilHeight - lipHeight - finger_width / 2 - down_offset - up_down_adjust target_height = desired_height if target_height < min_height: target_height = min_height if target_height > max_height: target_height = max_height bin_sideways = binMouth[1] sidepos = objPosition[1] horz_offset = 0.01 #this determines bin sides based on object #(binSmall,binLarge)=getSides(objPosition[1],listener) (binSmall, binLarge) = getSides(binNum, listener) binRight = binSmall binLeft = binLarge if sidepos > bin_sideways: #this stuff is what happens if the object is to the left print '[SucSide] Object is to the left' #turn the suction cup so that it is sideways left scoopOrientation = [.5, -.5, .5, -.5] side_waypoint1a = binRight + cup_to_spatula + .01 side_waypoint1b = sidepos - horizontal_dim / 2 - 2 * horz_offset if side_waypoint1a > side_waypoint1b: side_waypoint1 = side_waypoint1a print '[SucSide] side waypoint A' else: side_waypoint1 = side_waypoint1b print '[SucSide] side waypoint B' #side_waypoint2=sidepos+horizontal_dim-side_offset side_waypoint2 = binLeft - horizontal_dim - horz_offset if side_waypoint2 < side_waypoint1: if side_waypoint2 < side_waypoint1a: print '[SucSide] Not enought gap' return (False, False) else: side_waypoint1 = side_waypoint2 else: #this stuff is what happens if the object is to the right print '[SucSide] Object is to the right' #turn the suction cup so that it is sideways right scoopOrientation = [0.5, .5, .5, .5] side_waypoint1a = binLeft - cup_to_spatula - .01 side_waypoint1b = sidepos + horizontal_dim / 2 + 2 * horz_offset if side_waypoint1a < side_waypoint1b: side_waypoint1 = side_waypoint1a print '[SucSide] side waypoint A' else: side_waypoint1 = side_waypoint1b print '[SucSide] side waypoint B' #side_waypoint2=sidepos-horizontal_dim+side_offset side_waypoint2 = binRight + horizontal_dim + horz_offset if side_waypoint2 > side_waypoint1: if side_waypoint2 > side_waypoint1a: print '[SucSide] Not enought gap' return (False, False) else: side_waypoint1 = side_waypoint2 targetPositionList = [ [binMouth[0] - .15, side_waypoint1, target_height + up_down_adjust], [objPosition[0], side_waypoint1, target_height + up_down_adjust], [objPosition[0], side_waypoint2, target_height + up_down_adjust], [objPosition[0], side_waypoint2, target_height] ] qf = q0 for tp_index in range(0, len(targetPositionList)): targetPosition = targetPositionList[tp_index] frontOfObjectPtOutOfBin = targetPosition q_initial = qf planner = IK(q0=q_initial, target_tip_pos=targetPosition, target_tip_ori=scoopOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() if s: print '[SucSide] move to COM in y successful' print '[SucSide] tcp at:', targetPosition plan.visualize(hand_param=hand_gap) plans.append(plan) #if isExecute: # pauseFunc(withPause) # plan.execute() else: print '[SucSide] move to COM in y fail' return (False, False) #print plan.q_traj qf = plan.q_traj[-1] print '[SucSide] qf:', qf #set robot speed setSpeedByName(speedName='faster') for numOfPlan in range(0, len(plans)): if numOfPlan >= len(plans) - 2: setSpeedByName(speedName='fast') if isExecute: plans[numOfPlan].visualize(hand_param=hand_gap) pauseFunc(withPause) plans[numOfPlan].execute() suction.start() final_hand_gap = 110 gripper.set_force(12) gripper.grasp(move_pos=final_hand_gap) gripper.close() hand_gap = final_hand_gap print '[SucSide] hand_gap:', hand_gap continue_suction = suction_items(objId) if continue_suction: print '[SucSide] object is of type that suction side will try to remove from bin' else: print '[SucSide] object is to big to remove from bin' ## retreat for numOfPlan in range(0, len(plans) - 1): plans[len(plans) - numOfPlan - 1].visualizeBackward(hand_param=hand_gap) if isExecute: pauseFunc(withPause) plans[len(plans) - numOfPlan - 1].executeBackward() if not continue_suction: suction.stop() rospy.sleep(3) print '[SucSide] Is suction in contact still? Lets see:' print '[SucSide] suction.check(): ', suction.check() print '[SucSide] suction.check(): ', suction.check() if suction.check(): #set robot speed print '[SucSide] got item. continuing. suction' setSpeedByName(speedName='fast') return (True, True) else: print '[SucSide] did not get item. Stopping suction' suction.stop() return (True, False)
def scoop(objPose = [1.95,0.25,1.4,0,0,0,1], binNum=3, objId = 0, bin_contents = None, robotConfig = None, shelfPosition = [1.9116,-0.012498,-0.4971], forceThreshold = 1, isExecute = True, withPause = True, withVisualize = False): ## objPose: world position and orientation frame attached to com of object in quaternion form. XYZ ## objId: object identifier ## robotConfig: current time robot configuration ## shelfPosition: shelf position in world frame ## force threshold: amount fo force needed to say we have a grasp setSpeedByName(speedName = 'faster') joint_topic = '/joint_states' planSuccess = True ## initialize listener rospy listener = tf.TransformListener() rospy.sleep(0.1) br = tf.TransformBroadcaster() rospy.sleep(0.1) # shelf variables if binNum <3: pretensionDelta = 0.03 if binNum > 2 and binNum < 6: pretensionDelta = 0.009 if binNum > 5 and binNum < 9: pretensionDelta = 0.009 if binNum > 8: pretensionDelta = 0.03 #pretensionDelta = 0.00 lipHeight = 0.025 # plan store plans = [] ## get object position (world frame) objPosition = getObjCOM(objPose[0:3], objId) ## move gripper to object com outside bin along world y direction and ## move the gripper over the lip of the bin # set tcp tcpXOffset = 0.018 l2 = 0.47 tip_hand_transform = [tcpXOffset, 0, l2, 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) # get position of the tcp in world frame pose_world = coordinateFrameTransform(tip_hand_transform[0:3], 'link_6', 'map', listener) tcpPos=[pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z] tcpPosHome = tcpPos # set scoop orientation (rotate wrist) scoopOrientation = [0, 0.7071, 0, 0.7071] # set first target to move gripper in front of the object and adjust height to middle of bin distFromShelf = 0.05 wristWidth = 0.0725 # this is actually half the wrist width (binMouth, binFloorHeight) = getBinMouthAndFloor(distFromShelf, binNum) pose_world = coordinateFrameTransform(binMouth[0:3], 'shelf', 'map', listener) binMouth=[pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z] verticalOffsetLip = 0.00 # we need this so we don't damage the sucker wH = 0.075 targetPosition = [binMouth[0], objPosition[1], binMouth[2]+tcpXOffset-wH+lipHeight-pretensionDelta] ## check to make sure we are inside the bin and not colliding with sides: minHeight, maxHeight, leftWall, rightWall = BinBBDims(binNum) leftWall = coordinateFrameTransform([leftWall,0,0], 'shelf', 'map', listener) leftWall = leftWall.pose.position.y rightWall = coordinateFrameTransform([rightWall,0,0], 'shelf', 'map', listener) rightWall = rightWall.pose.position.y interiorLipBin = [0,0.40,0] # define over the lip distance in shelf frame interiorLipBin = coordinateFrameTransform(interiorLipBin, 'shelf', 'map', listener) stepOverLip = interiorLipBin.pose.position.x fStroke = 0.20 sStroke = 0.19 binLengthSafety = 0.015 if targetPosition[1] + 0.04 > leftWall: interiorLipBin = [0,0.36,0] # define over the lip distance in shelf frame interiorLipBin = coordinateFrameTransform(interiorLipBin, 'shelf', 'map', listener) stepOverLip = interiorLipBin.pose.position.x fStroke = 0.17 if targetPosition[1] - 0.04 < leftWall: interiorLipBin = [0,0.36,0] # define over the lip distance in shelf frame interiorLipBin = coordinateFrameTransform(interiorLipBin, 'shelf', 'map', listener) stepOverLip = interiorLipBin.pose.position.x fStroke = 0.17 if targetPosition[1] + binLengthSafety > leftWall: targetPosition[1] = leftWall if targetPosition[1] - binLengthSafety < rightWall: targetPosition[1] = rightWall frontOfObjectPtOutOfBin = targetPosition q_initial = robotConfig planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = scoopOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() # Plan 0 if s: print '[Scoop] move to COM in y successful' #~ print '[Scoop] tcp at:' #~ print(targetPosition) visualizeFunc(withVisualize, plan) plans.append(plan) else: print '[Scoop] move to COM in y fail' return (False, False) qf = plan.q_traj[-1] ## push spatula against base of bin (pre-tension) binFloorHeight = coordinateFrameTransform([0,0,binFloorHeight], 'shelf', 'map', listener) q_initial = qf percentTilt = 0.1 # 10 percent scoopOrientation = [0, 0.7071*(1+percentTilt), 0, 0.7071*(1-percentTilt)] planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = scoopOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() # Plan 1 if s: print '[Scoop] reorient the hand' #~ print '[Scoop] tcp at:' #~ print(targetPosition) plans.append(plan) visualizeFunc(withVisualize, plan) else: print '[Scoop] reorient the hand fail' return (False, False) qf = plan.q_traj[-1] # set second target, go over the lip of the bin deltaX = np.add(-targetPosition[0],stepOverLip) targetPosition = np.add(targetPosition, [deltaX,0,0]) q_initial = qf planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = scoopOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() # Plan 2 if s: print '[Scoop] move to inside the lip success' #~ print '[Scoop] tcp at:' #~ print(targetPosition) plans.append(plan) visualizeFunc(withVisualize, plan) else: print '[Scoop] move to inside the lip fail' return (False, False) qf = plan.q_traj[-1] ## perform bin length stroke to middle q_initial = qf targetPosition = np.add(targetPosition, [fStroke,0,-lipHeight]) planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = scoopOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() # Plan 3 if s: print '[Scoop] stroke middle of bin success' #~ print '[Scoop] tcp at:' #~ print(targetPosition) plans.append(plan) visualizeFunc(withVisualize, plan) else: print '[Scoop] stroke middle of bin fail' return (False, False) qf = plan.q_traj[-1] ## perform bin length stroke to end q_initial = qf targetPosition = np.add(targetPosition, [sStroke,0,0]) scoopOrientation = [0, 0.7071+0.11/4, 0, 0.7071-0.11/4] planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = scoopOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic) plan = planner.plan() s = plan.success() # Plan 4 if s: print '[Scoop] stroke middle to end of bin success' #~ print '[Scoop] tcp at:' #~ print(targetPosition) plans.append(plan) visualizeFunc(withVisualize, plan) else: print '[Scoop] stroke middle to end of bin fail' return (False, False) qf = plan.q_traj[-1] ## close gripper #~ closeGripper(forceThreshold) closeGripper(forceThreshold) execution_possible = True ## execute isNotInCollision = True for numOfPlan in range(0, len(plans)): plans[numOfPlan].visualize() if isExecute: if numOfPlan == 3: openGripper() pauseFunc(withPause) isNotInCollision = plans[numOfPlan].execute() if numOfPlan == 3: closeGripper(forceThreshold) plans[numOfPlan].executeBackward() openGripper() plans[numOfPlan].execute() if not isNotInCollision: planFailNum = numOfPlan print '[Scoop] collision detected' break if numOfPlan == 4: closeGripper(forceThreshold) rospy.sleep(0.5) while True: APCrobotjoints = ROS_Wait_For_Msg(joint_topic, sensor_msgs.msg.JointState).getmsg() q0 = APCrobotjoints.position if len(q0) == 2 or len(q0) == 8: q0 = q0[-2:] # get last 2 break gripper_q0=np.fabs(q0) drop_thick=0.000001 # finger gap =0.002m = .5 mm if gripper_q0[0] < drop_thick: print '[Scoop] ***************' print '[Scoop] Could not grasp' print '[Scoop] ***************' execution_possible = False else: print '[Scoop] ***************' print '[Scoop] Grasp Successful' print '[Scoop] ***************' execution_possible = True if not isNotInCollision: for numOfPlan in range(0, len(planFailNum)): plans[planFailNum-numOfPlan].executeBackward() ## retreat for numOfPlan in range(0, len(plans)): if withVisualize: plans[len(plans)-numOfPlan-1].visualizeBackward() if isExecute: pauseFunc(withPause) plans[len(plans)-numOfPlan-1].executeBackward() return True, execution_possible