예제 #1
0
    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)
def suction_side(objPose = [1.95,1.25,1.4,0,0,0,1],
            binNum=4,
            objId = 0,
            bin_contents = None,
            robotConfig = None, 
            shelfPosition = [1.9019,0.00030975,-0.503], 
            forceThreshold = 1, 
            isExecute = True,
            withPause = False):
    ## objPose: world position and orientation frame attached to com of object in quaternion form. XYZ
    ## objId: object identifier
    ## robotConfig: current time robot configuration
    ## shelfPosition: shelf position in world frame
    ## force threshold: amount fo force needed to say we have a grasp
    joint_topic = '/joint_states'  
    ## initialize listener rospy
    listener = tf.TransformListener()
    #rospy.sleep(0.1)
    br = tf.TransformBroadcaster()
    rospy.sleep(0.1)
    
    # shelf variables
    pretensionDelta = 0.00
    lipHeight = 0.035
    
    #tcp_offset_variables
    
    

    
    # plan store
    plans = []
    ## get object position (world frame)
    objPosition = getObjCOM(objPose[0:3], objId)
    obj_pose_tfm_list=matrix_from_xyzquat(objPose[0:3], objPose[3:7])
    obj_pose_tfm=np.array(obj_pose_tfm_list)
    
    obj_pose_orient=obj_pose_tfm[0:3,0:3]
    vertical_index=np.argmax(np.fabs(obj_pose_orient[2,0:3]))
    
    object_dim=get_obj_dim(objId)
    vertical_dim=object_dim[vertical_index]
    
    
    s1=np.fabs(obj_pose_orient[1,0])*object_dim[0]
    s2=np.fabs(obj_pose_orient[1,1])*object_dim[1]
    s3=np.fabs(obj_pose_orient[1,2])*object_dim[2]
    s4=np.fabs(obj_pose_orient[1,vertical_index])*object_dim[vertical_index]
    
    horizontal_dim=s1+s2+s3-s4

    hand_gap=0
    gripper.close()
        
    while True:
        APCrobotjoints = ROS_Wait_For_Msg(joint_topic, sensor_msgs.msg.JointState).getmsg() 
        q0 = APCrobotjoints.position
        if len(q0) < 6:
            continue
        else:
            break
    
        
    ## move gripper to object com outside bin along world y direction and
    ## move the gripper over the lip of the bin    
    # set tcp
    vert_offset=.035
    l2 = 0.43  #change this to edit where you think the cup is
    l2 =.44
    
    tip_hand_transform = [-vert_offset, 0, l2, 0,0,0] # to be updated when we have a hand design finalized
    # broadcast frame attached to tcp
    # for i in range(5):
        # rospy.sleep(0.1)
        # br.sendTransform(tuple(tip_hand_transform[0:3]), tfm.quaternion_from_euler(*tip_hand_transform[3:6]), rospy.Time.now(), 'tip', "link_6")
    # rospy.sleep(0.1)
    
    pubFrame(br, pose=tip_hand_transform, frame_id='target_pose', parent_frame_id='tip', npub=1)
    
    # get position of the tcp in world frame
    pose_world = coordinateFrameTransform(tip_hand_transform[0:3], 'link_6', 'map', listener)
    tcpPos=[pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z]
    
    
    #this may cause issues!!!
    tcpPosHome = tcpPos
    
    
    # set scoop orientation (rotate wrist)
    
    
    
    
    
    distFromShelf = 0.05
    wristWidth = 0.0725 # this is actually half the wrist width
    (binMouth,bin_height,bin_width) = getBinMouth(distFromShelf, binNum)
    pose_world = coordinateFrameTransform(binMouth[0:3], 'shelf', 'map', listener)
    binMouth=[pose_world.pose.position.x, pose_world.pose.position.y, pose_world.pose.position.z]
    
    
    
    object_depth=objPosition[0]-binMouth[0]
    
    
    finger_length=.23     
    finger_width=.08
    
    up_offset=.05
    down_offset=.01
    cup_to_spatula=.08
    hand_width=.15
    max_gripper_width=.110
    hand_top_offset=hand_width/2+vert_offset+.015
    hand_bot_offset=hand_width/2-vert_offset+.015
    
    up_down_adjust=.025
    
    side_offset=.03
    
    binFloorHeight=binMouth[2]-bin_height/2
    binCeilHeight=binMouth[2]+bin_height/2
    
    
    min_height=binFloorHeight+lipHeight+finger_width/2+down_offset
    desired_height=objPosition[2]
    max_height=binCeilHeight-lipHeight-finger_width/2-down_offset-up_down_adjust
    
    target_height=desired_height
    if target_height<min_height:
        target_height=min_height
    if target_height>max_height:
        target_height=max_height
    
    bin_sideways=binMouth[1]
    sidepos=objPosition[1]
    
    horz_offset=0.01
    
    #this determines bin sides based on object
    #(binSmall,binLarge)=getSides(objPosition[1],listener)
    (binSmall,binLarge)=getSides(binNum,listener)
    binRight=binSmall
    binLeft=binLarge
    
 
    if sidepos>bin_sideways:
        #this stuff is what happens if the object is to the left
        print '[SucSide] Object is to the left'
        
        #turn the suction cup so that it is sideways left
        scoopOrientation = [.5,-.5,.5,-.5]
        side_waypoint1a=binRight+cup_to_spatula+.01
        side_waypoint1b=sidepos-horizontal_dim/2-2*horz_offset
        if side_waypoint1a>side_waypoint1b:
            side_waypoint1=side_waypoint1a
            print '[SucSide] side waypoint A'
        else:
            side_waypoint1=side_waypoint1b
            print '[SucSide] side waypoint B'
            
        #side_waypoint2=sidepos+horizontal_dim-side_offset
        side_waypoint2=binLeft-horizontal_dim-horz_offset
        
        if side_waypoint2<side_waypoint1:
            if side_waypoint2<side_waypoint1a:
                print '[SucSide] Not enought gap'
                return (False, False)
            else:
                side_waypoint1=side_waypoint2
        

        
        
    else:
        #this stuff is what happens if the object is to the right
        print '[SucSide] Object is to the right'
        
        #turn the suction cup so that it is sideways right
        scoopOrientation = [0.5,.5,.5,.5]
        side_waypoint1a=binLeft-cup_to_spatula-.01
        side_waypoint1b=sidepos+horizontal_dim/2+2*horz_offset
        if side_waypoint1a<side_waypoint1b:
            side_waypoint1=side_waypoint1a
            print '[SucSide] side waypoint A'
        else:
            side_waypoint1=side_waypoint1b
            print '[SucSide] side waypoint B'
        
        #side_waypoint2=sidepos-horizontal_dim+side_offset
        side_waypoint2=binRight+horizontal_dim+horz_offset
        
        if side_waypoint2>side_waypoint1:
            
            if side_waypoint2>side_waypoint1a:
                print '[SucSide] Not enought gap'
                return (False, False)
            else:
                side_waypoint1=side_waypoint2
        


        
    targetPositionList=[    
    [binMouth[0]-.15, side_waypoint1, target_height+up_down_adjust],
    [objPosition[0], side_waypoint1, target_height+up_down_adjust],
    [objPosition[0], side_waypoint2, target_height+up_down_adjust],
    [objPosition[0], side_waypoint2, target_height]]
    
    
    qf=q0
    
    
    for tp_index in range(0, len(targetPositionList)):
    
        targetPosition = targetPositionList[tp_index]
        frontOfObjectPtOutOfBin = targetPosition
        q_initial = qf
        planner = IK(q0 = q_initial, target_tip_pos = targetPosition, target_tip_ori = scoopOrientation, tip_hand_transform=tip_hand_transform, joint_topic=joint_topic)
        plan = planner.plan()
        s = plan.success()
        if s:
            print '[SucSide] move to COM in y successful'
            print '[SucSide] tcp at:', targetPosition
            plan.visualize(hand_param=hand_gap)
            plans.append(plan)
            #if isExecute:
            #    pauseFunc(withPause)
            #    plan.execute()
        else:
            print '[SucSide] move to COM in y fail'
            return (False, False)
            
        #print plan.q_traj
        qf = plan.q_traj[-1]
        print '[SucSide] qf:', qf
    
    #set robot speed
    setSpeedByName(speedName = 'faster')
    for numOfPlan in range(0, len(plans)):
        if numOfPlan >=len(plans)-2:
            setSpeedByName(speedName = 'fast')
        if isExecute:
            plans[numOfPlan].visualize(hand_param=hand_gap)
            pauseFunc(withPause)
            plans[numOfPlan].execute()
            
    
    
    suction.start()
    
    final_hand_gap=110
    
    gripper.set_force(12)
    gripper.grasp(move_pos=final_hand_gap)
    gripper.close()
    
    hand_gap=final_hand_gap
    print '[SucSide] hand_gap:', hand_gap
    
    continue_suction=suction_items(objId)
    
    if continue_suction:
        print '[SucSide] object is of type that suction side will try to remove from bin'
    else:
        print '[SucSide] object is to big to remove from bin'
        
    ## retreat
    for numOfPlan in range(0, len(plans)-1):
        plans[len(plans)-numOfPlan-1].visualizeBackward(hand_param=hand_gap)
        if isExecute:
            pauseFunc(withPause)
            plans[len(plans)-numOfPlan-1].executeBackward()
            if not continue_suction:
                suction.stop()
    
    rospy.sleep(3)
                
    print '[SucSide] Is suction in contact still? Lets see:'
    print '[SucSide] suction.check(): ', suction.check()
    print '[SucSide] suction.check(): ', suction.check()
    
    if suction.check():
        #set robot speed
        print '[SucSide] got item. continuing. suction'
        setSpeedByName(speedName = 'fast')
        return (True, True)
    else:
        print '[SucSide] did not get item. Stopping suction'
        suction.stop()
        return (True, False)
    def 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)
예제 #4
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)