gripper failures

Issue #180 new
dan created an issue

Since the last update, I am seeing a lot of gripper failures, especially on pulley and gasket parts. Previously, when the gripper was positioned properly on the part, it reliably picked it up. Now it fails about 15% of the time.

Comments (7)

  1. Shane Loretz

    Would you be willing to make a video of it happening, or even better a joint trajectory that reproduces the gripper failure in one of the sample worlds?

  2. Rud Merriam

    I’m seeing an issue that may be related. The AGV had 2 gears and a pulley on it. When it started up all the parts slid on the tray. Since this relates to the ‘stickiness’ of parts it might be related to the gripper problem. I have noticed it seems to take a longer time for the gripper to take hold when enabled.

    I’ll make a video of the sliding parts.

    The underlying question is when does the system do the scoring? Is it after the AGV moves off screen or at the point where the shipment delivery is triggered and before motion commences?

  3. Steven Gray

    I’ve noticed the sliding parts on the tray since the initial release in March. The scoring seems to happen before the AGV starts moving – I haven’t seen any issues with parts being out of place with regards to the product pose score.

  4. Shane Loretz

    @rmerriam Thanks for the video. I’ve also noticed parts slide when the AGV moves too. The shipment is scored before the AGV starts moving, so it doesn’t affect the point total.

  5. Shane Loretz

    I ran some tests using a trial with all 5 parts in bins near arm 2 using two strategies: (edit: using ariac version 3.0.5 from source)

    1. Touch a part for 1 second
    2. Touch a part until the gripper reports it’s attached

    In 10 runs of blindly waiting 1 second I saw successful grasps:

    • disk 4/10
    • piston 6/10
    • gasket 4/10
    • gear 7/10
    • pulley 7/10

    With 10 runs of waiting until the gripper attached:

    • disk 6/10
    • piston 10/10
    • gasket 10*/10
    • gear 10*/10
    • pulley 10/10

    The gasket and gear had one attempt each where they took more than a couple seconds to attach. In the 4 cases that the disk didn’t attach I waited about 10 seconds before nudging the part so the arm would continue. Everything else seemed like it attached in a couple seconds or less, but I didn’t time them.

    Here’s the trial

    # Trial for testing gripper failures
    
    options:
      insert_models_over_bins: false
      spawn_extra_models: true
      gazebo_state_logging: true
    
    time_limit: -1
    random_seed: 1
    
    orders:
      order_0:
        announcement_condition: time
        announcement_condition_value: 0
        shipment_count: 1
        destinations: [agv1]
        products:
          part_0:
            type: gear_part
            pose:
              xyz: [0.1, -0.15, 0]
              rpy: [0, 0, 'pi/2']
    
    models_to_spawn:
      bin2::link:
        models:
          part_to_pick_up_1:
            type: piston_rod_part
            pose:
              xyz: [0.2, 0.2, 0.75]
              rpy: [0, 0, 0]
          part_to_pick_up_2:
            type: gear_part
            pose:
              xyz: [-0.2, -0.2, 0.75]
              rpy: [0, 0, 0]
          part_to_pick_up_3:
            type: disk_part
            pose:
              xyz: [0.2, -0.2, 0.75]
              rpy: [0, 0, 0]
          part_to_pick_up_4:
            type: gasket_part
            pose:
              xyz: [-0.2, 0.2, 0.75]
              rpy: [0, 0, 0]
      bin3::link:
        models:
          part_to_pick_up_5:
            type: pulley_part
            pose:
              xyz: [0.2, 0.2, 0.75]
              rpy: [0, 0, 0]
    

    Here’s the diff to `ariac_example_node.py`

    diff --git a/ariac_example/script/ariac_example_node.py b/ariac_example/script/ariac_example_node.py
    index 18d5210..e8f8d37 100755
    --- a/ariac_example/script/ariac_example_node.py
    +++ b/ariac_example/script/ariac_example_node.py
    @@ -15,6 +15,7 @@
    
     from ariac_example import ariac_example
     import rospy
    +import time
    
    
     def main():
    @@ -34,7 +35,95 @@ def main():
             comp_class.send_arm_to_state([0] * len(comp_class.arm_joint_names), comp_class.arm_2_joint_trajectory_publisher)
             comp_class.arm_2_has_been_zeroed = True
    
    -    rospy.spin()
    +    # Arm poses
    +    away_pos = [0.88, -0.07, -0.75, 2.89, 4.52, -1.58, 0.00]
    +    above_bin_2 = [2.14, -0.07, -0.75, 3.14, 3.27, -1.58, 0.00]
    +    above_disk = [1.86, -0.07, -0.55, 2.88, 3.37, -1.58, 0.00]
    +    touching_disk = [1.86, -0.07, -0.495, 2.88, 3.37, -1.58, 0.00]
    +    above_piston = [1.75, -0.07, -0.50, 3.40, 3.38, -1.58, 0.00]
    +    touching_piston = [1.75, -0.07, -0.44, 3.40, 3.38, -1.58, 0.00]
    +    above_gasket = [2.25, -0.07, -0.55, 3.52, 2.95, -1.58, 0.00]
    +    touching_gasket = [2.25, -0.07, -0.49, 3.52, 2.95, -1.58, 0.00]
    +    above_gear = [2.50, -0.07, -0.30, 2.67, 2.30, -1.58, 0.00]
    +    touching_gear = [2.50, -0.07, -0.30, 2.67, 2.52, -1.58, 0.00]
    +    above_bin_3 = [-1.76, -0.07, -1.01, 2.50, 3.45, -1.58, 0.00]
    +    above_pulley = [1.76, -0.07, -0.63, 2.50, 3.45, -1.58, 0.00]
    +    touching_pulley = [1.76, -0.07, -0.53, 2.50, 3.45, -1.58, 0.00]
    +
    +    def to_arm_order(poses):
    +        rqt_order = [
    +            'elbow_joint',
    +            'linear_arm_actuator_joint',
    +            'shoulder_lift_joint',
    +            'shoulder_pan_joint',
    +            'wrist_1_joint',
    +            'wrist_2_joint',
    +            'wrist_3_joint'
    +        ]
    +        pose_dict = dict(zip(rqt_order, poses))
    +        return [pose_dict[joint] for joint in comp_class.arm_joint_names]
    +
    +    def arm2_go_to(pose):
    +        comp_class.send_arm_to_state(to_arm_order(pose), comp_class.arm_2_joint_trajectory_publisher)
    +        time.sleep(1)
    +
    +    def make_contact():
    +        # Strategy 1, wait a little bit
    +        time.sleep(1)
    +        # Strategy 2, wait until gripper succeeds
    +        # while comp_class.arm_2_current_gripper_state is None or not comp_class.arm_2_current_gripper_state.attached:
    +        #     print "Waiting for gripper"
    +        #     time.sleep(0.5)
    +
    +    # disk
    +    arm2_go_to(above_bin_2)
    +    arm2_go_to(above_disk)
    +    ariac_example.control_gripper(True, 2)
    +    arm2_go_to(touching_disk)
    +    make_contact()
    +    arm2_go_to(above_bin_2)
    +    arm2_go_to(away_pos)
    +    ariac_example.control_gripper(False, 2)
    +
    +    # piston
    +    arm2_go_to(above_bin_2)
    +    arm2_go_to(above_piston)
    +    ariac_example.control_gripper(True, 2)
    +    arm2_go_to(touching_piston)
    +    make_contact()
    +    arm2_go_to(above_bin_2)
    +    arm2_go_to(away_pos)
    +    ariac_example.control_gripper(False, 2)
    +
    +    # gasket
    +    arm2_go_to(above_bin_2)
    +    arm2_go_to(above_gasket)
    +    ariac_example.control_gripper(True, 2)
    +    arm2_go_to(touching_gasket)
    +    make_contact()
    +    arm2_go_to(above_bin_2)
    +    arm2_go_to(away_pos)
    +    ariac_example.control_gripper(False, 2)
    +
    +    # gear
    +    arm2_go_to(above_bin_2)
    +    arm2_go_to(above_gear)
    +    ariac_example.control_gripper(True, 2)
    +    arm2_go_to(touching_gear)
    +    make_contact()
    +    arm2_go_to(above_bin_2)
    +    arm2_go_to(away_pos)
    +    ariac_example.control_gripper(False, 2)
    +
    +    # pulley
    +    arm2_go_to(above_bin_3)
    +    arm2_go_to(above_pulley)
    +    ariac_example.control_gripper(True, 2)
    +    arm2_go_to(touching_pulley)
    +    make_contact()
    +    arm2_go_to(above_bin_3)
    +    arm2_go_to(away_pos)
    +    ariac_example.control_gripper(False, 2)
    
    
     if __name__ == '__main__':
    
  6. Rud Merriam

    I added a ‘jog’ to my code that lifted ad the pushed down the arm after a short period to get the gripper to attach. I would suggest that this needs improvement if the competition is run again. Random timing could affect final scores and ranking. Not that it will matter for my score this year.

  7. Log in to comment