$search
00001 #!/usr/bin/env python 00002 from __future__ import with_statement # for python 2.5 00003 __author__ = 'Rosen Diankov' 00004 __license__ = 'Apache License, Version 2.0' 00005 00006 import roslib; roslib.load_manifest('orrosplanning') 00007 import rospy, time 00008 import object_manipulation_msgs.srv 00009 import object_manipulation_msgs.msg 00010 import geometry_msgs.msg 00011 import sensor_msgs.msg 00012 from numpy import * 00013 import openravepy 00014 import pickle 00015 if __name__=='__main__': 00016 env=openravepy.Environment() 00017 body=env.ReadKinBodyXMLFile('data/ketchup.kinbody.xml') 00018 env.AddKinBody(body,True) 00019 trimesh=env.Triangulate(body) 00020 env.Remove(body) 00021 env.Destroy() 00022 00023 rospy.init_node('graspplanning_test') 00024 rospy.wait_for_service('GraspPlanning') 00025 GraspPlanningFn = rospy.ServiceProxy('GraspPlanning',object_manipulation_msgs.srv.GraspPlanning) 00026 req = object_manipulation_msgs.srv.GraspPlanningRequest() 00027 req.arm_name = 'arm' 00028 #req.target.type = object_manipulation_msgs.msg.GraspableObject.POINT_CLUSTER 00029 req.target.cluster.header.frame_id = 'Base' 00030 offset = [0.3,-0.05,0.3] 00031 req.target.cluster.points = [geometry_msgs.msg.Point32(p[0]+offset[0],p[1]+offset[1],p[2]+offset[2]) for p in trimesh.vertices] 00032 req.target.cluster.channels.append(sensor_msgs.msg.ChannelFloat32(name='indices',values=trimesh.indices.flatten().tolist())) 00033 req.collision_object_name = '' 00034 req.collision_support_surface_name = '' 00035 res=GraspPlanningFn(req) 00036 pickle.dump(res,open('grasps.pp','w')) 00037 print res