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)
Esempio n. 2
0
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 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)
Esempio n. 4
0
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
    pose = get_obj_capsentf(obj_id) # x,y,z,qx,qy,qz,qw
    if len(pose) <7:
        pose = [0,0,0,0,0,0,1]
    
    #pdb.set_trace()
    # create an interactive marker server on the topic namespace simple_marker
    server = InteractiveMarkerServer("affordance_marker")
    int_marker = createInteractiveMarker('Object',*pose)
    
    pointmarker = createPointMarker(colors=colors, points=points, offset=tuple(pose[0:3]), orientation=tuple(pose[3:7]))
    int_marker.controls.append(pointmarker)    
    
    int_marker.controls.extend(createMoveControls(fixed=True))
    
    #### create a static marker
    dim = get_obj_dim(obj_id)
    for i in range(5):
        vizCubeMarker(size=dim, rgba=(0,1,0,0.3))
    
    server.insert(int_marker, processFeedback)

    rospy.Timer(rospy.Duration(0.01), frameCallback)


    server.applyChanges()
    
    # ros services
    #startPoseService()
    
    rospy.spin()
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 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)
Esempio n. 8
0
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)
Esempio n. 9
0
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)
Esempio n. 10
0
        pose = [0, 0, 0, 0, 0, 0, 1]

    #pdb.set_trace()
    # create an interactive marker server on the topic namespace simple_marker
    server = InteractiveMarkerServer("affordance_marker")
    int_marker = createInteractiveMarker('Object', *pose)

    pointmarker = createPointMarker(colors=colors,
                                    points=points,
                                    offset=tuple(pose[0:3]),
                                    orientation=tuple(pose[3:7]))
    int_marker.controls.append(pointmarker)

    int_marker.controls.extend(createMoveControls(fixed=True))

    #### create a static marker
    dim = get_obj_dim(obj_id)
    for i in range(5):
        vizCubeMarker(size=dim, rgba=(0, 1, 0, 0.3))

    server.insert(int_marker, processFeedback)

    rospy.Timer(rospy.Duration(0.01), frameCallback)

    server.applyChanges()

    # ros services
    #startPoseService()

    rospy.spin()
Esempio n. 11
0
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)