graspit-simulator / graspit

The GraspIt! simulator
http://graspit-simulator.github.io/
Other
180 stars 81 forks source link

GraspIt/moveit_simple_grasps #110

Closed gecastro closed 7 years ago

gecastro commented 7 years ago

I'm looking at using GraspIt with ROS and I was wondering if there is any method to give a pre-computed grasp and refine it in GraspIt.

I'm looking at the option of pipelining moveit_simple_grasps (or simply enter a manual input) to pre-generate solutions and using GraspIt to refine them and compute quality.

Is there any work around this that I could use?

jvarley commented 7 years ago

Depends on how good the precomputed grasp is.
Option 1): Adjust how open/close hand is and distance along approach direction Use graspit_commander optionally use grid sample plugin to get pregrasps: https://github.com/jvarley/grid_sample_client https://github.com/jvarley/grid_sample_plugin

to run this use:

roslaunch grid_sample_plugin grid_sample_plugin.launch 

this will load both the grid_sample and graspit_interface plugins into graspit rather than:

roslaunch graspit_interface graspit_interface.launch

which will only load the graspit_interface plugin.

Then use this python code

def plan_list_grasps(meshfile):
    gc = graspit_commander.GraspitCommander()
    gc.importGraspableBody(meshfile)
    gc.importRobot("BarrettBH8_280")

    pre_grasps = GridSampleClient.getSamples(10).grasps

    completion_results = []
    for i, pre_grasp in enumerate(pre_grasps):
        gc.toggleAllCollisions(False)#turn off collisions
        gc.forceRobotDof([0,0,0,0])#open the hand
        gc.setRobotPose(pre_grasp.pose) # set the hand pose to the backed off pregrasp pose                                                                                                                   
        gc.toggleAllCollisions(True)#turn collisions back on
        gc.findInitialContact()# move the hand along the approach until it hits the object                                                                                                                                                                                                                                                                                                                                        
        gc.autoGrasp() #close the fingers                                                                                                                 
        volume_quality = gc.computeQuality().volume # get the grasp quality
        result = gc.getRobot(0) # get the new grasp pose, and dof values
        grasp = copy.deepcopy(pre_grasp)
        grasp.pose = gc.getRobot(0).robot.pose
        grasp.volume_quality = volume_quality
        completion_results.append((volume_quality, grasp))

    # order grasps best to worst
    completion_results.sort() 
    completion_results.reverse()

    grasps = []
    for quality, grasp in completion_results:
        if quality > 0: #only keep good grasps
            grasps.append((quality,grasp))

   return grasps
jvarley commented 7 years ago

Option 2) Want entirely new grasp seeded with pre grasp. Look at Graspit's online planner. It will start the simulated annealing planner near a prespecified seed location. It is not currently exposed via graspit_commander though. Although it would not be too hard to do. You can play with it inside graspit.

image

Move around the hand in graspit while the planner is running, and the grasps will come from closer to where the hand is currently at. you could use this process, and set the hands starting location to be your pregrasp, and it should come up with refined grasps seeded with your pregrasp.