$search
00001 #!/usr/bin/env python 00002 # -*- coding: utf-8 -*- 00003 # Copyright (c) 2010 Rosen Diankov (rosen.diankov@gmail.com) 00004 # 00005 # Licensed under the Apache License, Version 2.0 (the "License"); 00006 # you may not use this file except in compliance with the License. 00007 # You may obtain a copy of the License at 00008 # http://www.apache.org/licenses/LICENSE-2.0 00009 # 00010 # Unless required by applicable law or agreed to in writing, software 00011 # distributed under the License is distributed on an "AS IS" BASIS, 00012 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 00013 # See the License for the specific language governing permissions and 00014 # limitations under the License. 00015 from __future__ import with_statement # for python 2.5 00016 __author__ = 'Rosen Diankov' 00017 __copyright__ = 'Copyright (C) 2010 Rosen Diankov (rosen.diankov@gmail.com)' 00018 __license__ = 'Apache License, Version 2.0' 00019 import roslib; roslib.load_manifest('katana_openrave_grasp_planner') 00020 import rospy 00021 00022 roslib.load_manifest('object_manipulation_msgs') # copied from orrosplanning; TODO: remove? 00023 from optparse import OptionParser 00024 from openravepy import * 00025 from openravepy.misc import OpenRAVEGlobalArguments 00026 from numpy import * 00027 import numpy,time,threading 00028 from itertools import izip 00029 import tf 00030 import os 00031 00032 import sensor_msgs.msg 00033 import trajectory_msgs.msg 00034 import geometry_msgs.msg 00035 import object_manipulation_msgs.srv 00036 import object_manipulation_msgs.msg 00037 import orrosplanning.srv 00038 00039 class FastGrasping: 00040 """Computes a valid grasp for a given object as fast as possible without relying on a pre-computed grasp set 00041 """ 00042 class GraspingException(Exception): 00043 def __init__(self,args): 00044 self.args=args 00045 00046 def __init__(self,robot,target,ignoreik=False,returngrasps=1): 00047 self.ignoreik=ignoreik 00048 self.returngrasps = returngrasps 00049 self.robot = robot 00050 self.ikmodel = databases.inversekinematics.InverseKinematicsModel(robot=robot,iktype=IkParameterization.Type.TranslationDirection5D) 00051 if not self.ikmodel.load(): 00052 self.ikmodel.autogenerate() 00053 self.gmodel = databases.grasping.GraspingModel(robot,target) 00054 self.gmodel.init(friction=0.4,avoidlinks=[]) 00055 self.jointvalues = [] 00056 self.grasps = [] 00057 self.manipulatordirections = array([[0.0,0.0,1.0]]) # ik manipulator direction is [1,0,0], which seems to work not that well for aquiring grasps 00058 self.count_ik_sols = 0; 00059 00060 def checkgraspfn(self, contacts,finalconfig,grasp,info): 00061 print 'call checkgraspfn...' 00062 #print grasp 00063 #print info 00064 # check if grasp can be reached by robot 00065 Tglobalgrasp = self.gmodel.getGlobalGraspTransform(grasp,collisionfree=True) 00066 # have to set the preshape since the current robot is at the final grasp! 00067 self.gmodel.setPreshape(grasp) 00068 jointvalues = array(finalconfig[0]) 00069 print 'preshape values:' 00070 print jointvalues 00071 00072 if self.ignoreik: 00073 if self.gmodel.manip.CheckEndEffectorCollision(Tglobalgrasp): 00074 print 'end-effector collision' 00075 return False 00076 00077 else: 00078 if self.gmodel.manip.GetIkSolver().Supports(IkParameterization.Type.Transform6D): 00079 print 'hehe lets do 6D ik' 00080 sol = self.gmodel.manip.FindIKSolution(Tglobalgrasp,True) 00081 elif self.gmodel.manip.GetIkSolver().Supports(IkParameterization.Type.TranslationDirection5D): 00082 #print 'grasp position:' 00083 #print Tglobalgrasp[0:3,3] 00084 print 'grasp orientation matrix' 00085 print Tglobalgrasp[0:3,0:3] 00086 print 'manipulator direction:' 00087 print self.gmodel.manip.GetDirection() 00088 print 'grasp direction:' 00089 print dot(Tglobalgrasp[0:3,0:3],[0,0,1]) 00090 ikparam = IkParameterization(Ray(Tglobalgrasp[0:3,3],dot(Tglobalgrasp[0:3,0:3],self.gmodel.manip.GetDirection())),IkParameterization.Type.TranslationDirection5D) 00091 sol = self.gmodel.manip.FindIKSolution(ikparam,True) 00092 00093 if sol is None: 00094 print 'no ik solution found, abort checkgraspfn...' 00095 return False 00096 00097 jointvalues[self.gmodel.manip.GetArmIndices()] = sol 00098 00099 print 'hooray, found IK solution,append:' 00100 print sol 00101 print 'grasp position:' 00102 print Tglobalgrasp[0:3,3] 00103 print 'grasp orientation matrix' 00104 print Tglobalgrasp[0:3,0:3] 00105 print 'manipulator direction:' 00106 print self.gmodel.manip.GetDirection() 00107 print 'grasp direction:' 00108 print dot(Tglobalgrasp[0:3,0:3],self.gmodel.manip.GetDirection()) 00109 self.count_ik_sols = self.count_ik_sols + 1 00110 print self.count_ik_sols 00111 00112 self.jointvalues.append(jointvalues) 00113 self.grasps.append(grasp) 00114 if len(self.jointvalues) < self.returngrasps: 00115 return True 00116 00117 raise self.GraspingException((self.grasps,self.jointvalues)) 00118 00119 def computeGrasp(self,graspparameters): 00120 if len(graspparameters.approachrays) == 0: 00121 approachrays = self.gmodel.computeBoxApproachRays(delta=0.001,normalanglerange=0) # rays to approach object (was 0.02/0.5 by default) 00122 else: 00123 approachrays = reshape(graspparameters.approachrays,[len(graspparameters.approachrays)/6,6]) 00124 00125 Ttarget = self.gmodel.target.GetTransform() 00126 N = len(approachrays) 00127 gapproachrays = c_[dot(approachrays[:,0:3],transpose(Ttarget[0:3,0:3]))+tile(Ttarget[0:3,3],(N,1)),dot(approachrays[:,3:6],transpose(Ttarget[0:3,0:3]))] 00128 self.approachgraphs = [env.plot3(points=gapproachrays[:,0:3],pointsize=5,colors=array((1,0,0))), 00129 env.drawlinelist(points=reshape(c_[gapproachrays[:,0:3],gapproachrays[:,0:3]+0.005*gapproachrays[:,3:6]],(2*N,3)),linewidth=4,colors=array((1,0,0,1)))] 00130 00131 if len(graspparameters.standoffs) == 0: 00132 standoffs = [0.01] 00133 else: 00134 standoffs = graspparameters.standoffs 00135 if len(graspparameters.rolls) == 0: 00136 rolls = [0.0] # was before: arange(0,2*pi,0.5*pi) 00137 print rolls 00138 else: 00139 rolls = graspparameters.rolls 00140 if len(graspparameters.preshapes) == 0: 00141 # initial preshape for robot is the released fingers 00142 with self.gmodel.target: 00143 self.gmodel.target.Enable(False) 00144 taskmanip = interfaces.TaskManipulation(self.robot) 00145 final,traj = taskmanip.ReleaseFingers(execute=False,outputfinal=True) 00146 preshapes = array([final]) 00147 else: 00148 dim = len(self.gmodel.manip.GetGripperIndices()) 00149 preshapes = reshape(graspparameters.preshapes,[len(graspparameters.preshapes)/dim,dim]) 00150 try: 00151 self.gmodel.disableallbodies=False 00152 00153 ## with pre-set manip dir and checkgraspfn 00154 self.gmodel.generate(preshapes=preshapes,standoffs=standoffs,rolls=rolls,approachrays=approachrays,manipulatordirections=self.manipulatordirections, checkgraspfn=self.checkgraspfn,graspingnoise=0) 00155 ## with pre-set manip dir and no checkgraspfn 00156 # self.gmodel.generate(preshapes=preshapes,standoffs=standoffs,rolls=rolls,approachrays=approachrays,manipulatordirections=self.manipulatordirections,graspingnoise=0) 00157 ## with auto-set manip dir and no checkgraspfn 00158 # self.gmodel.generate (preshapes=preshapes,standoffs=standoffs,rolls=rolls,approachrays=approachrays,graspingnoise=0) 00159 ## with auto-set manip dir and checkgraspfn 00160 # self.gmodel.generate (preshapes=preshapes,standoffs=standoffs,rolls=rolls,approachrays=approachrays, checkgraspfn=self.checkgraspfn, graspingnoise=0) 00161 return self.grasps,self.jointvalues 00162 except self.GraspingException, e: 00163 return e.args 00164 00165 if __name__ == "__main__": 00166 parser = OptionParser(description='openrave planning example') 00167 OpenRAVEGlobalArguments.addOptions(parser) 00168 parser.add_option('--scene',action="store",type='string',dest='scene',default='robots/pr2-beta-static.zae', 00169 help='scene to load (default=%default)') 00170 parser.add_option('--collision_map',action="store",type='string',dest='collision_map',default='/collision_map/collision_map', 00171 help='The collision map topic (maping_msgs/CollisionMap), by (default=%default)') 00172 parser.add_option('--ipython', '-i',action="store_true",dest='ipython',default=False, 00173 help='if true will drop into the ipython interpreter rather than spin') 00174 parser.add_option('--mapframe',action="store",type='string',dest='mapframe',default=None, 00175 help='The frame of the map used to position the robot. If --mapframe="" is specified, then nothing will be transformed with tf') 00176 parser.add_option('--returngrasps',action="store",type='int',dest='returngrasps',default=1, 00177 help='return all the grasps') 00178 parser.add_option('--ignoreik',action="store_true",dest='ignoreik',default=False, 00179 help='ignores the ik computations') 00180 (options, args) = parser.parse_args() 00181 env = OpenRAVEGlobalArguments.parseAndCreate(options,defaultviewer=False) 00182 RaveLoadPlugin(os.path.join(roslib.packages.get_pkg_dir('orrosplanning'),'lib','orrosplanning')) 00183 RaveLoadPlugin(os.path.join(roslib.packages.get_pkg_dir('openraveros'),'lib','openraveros')) 00184 namespace = 'openrave' 00185 env.AddModule(RaveCreateModule(env,'rosserver'),namespace) 00186 print 'initializing, please wait for ready signal...' 00187 00188 graspparameters = orrosplanning.srv.SetGraspParametersRequest() 00189 envlock = threading.Lock() 00190 try: 00191 rospy.init_node('graspplanning_openrave',disable_signals=False) 00192 with env: 00193 env.Load(options.scene) 00194 robot = env.GetRobots()[0] 00195 00196 # set robot weights/resolutions (without this planning will be slow) 00197 # lmodel = databases.linkstatistics.LinkStatisticsModel(robot) 00198 # if not lmodel.load(): 00199 # lmodel.autogenerate() 00200 # lmodel.setRobotWeights() 00201 # lmodel.setRobotResolutions() 00202 00203 # create ground right under the robot 00204 ab=robot.ComputeAABB() 00205 ground=RaveCreateKinBody(env,'') 00206 ground.SetName('map') 00207 ground.InitFromBoxes(array([r_[ab.pos()-array([0,0,ab.extents()[2]+0.002]),2.0,2.0,0.001]]),True) 00208 #env.AddKinBody(ground,False) # removed ground to avoid ik collisions, unsure if this is really necessary 00209 if options.mapframe is None: 00210 options.mapframe = robot.GetLinks()[0].GetName() 00211 print 'setting map frame to %s'%options.mapframe 00212 if len(options.collision_map) > 0: 00213 collisionmap = RaveCreateSensorSystem(env,'CollisionMap bodyoffset %s topic %s'%(robot.GetName(),options.collision_map)) 00214 basemanip = interfaces.BaseManipulation(robot) 00215 grasper = interfaces.Grasper(robot) 00216 00217 listener = tf.TransformListener() 00218 values = robot.GetDOFValues() 00219 def UpdateRobotJoints(msg): 00220 with envlock: 00221 with env: 00222 for name,pos in izip(msg.name,msg.position): 00223 j = robot.GetJoint(name) 00224 if j is not None: 00225 values[j.GetDOFIndex()] = pos 00226 robot.SetDOFValues(values) 00227 00228 def trimeshFromPointCloud(pointcloud): 00229 points = zeros((len(pointcloud.points),3),double) 00230 for i,p in enumerate(pointcloud.points): 00231 points[i,0] = p.x 00232 points[i,1] = p.y 00233 points[i,2] = p.z 00234 cindices = [c.values for c in pointcloud.channels if c.name == 'indices'] 00235 if len(cindices) > 0: 00236 vertices = points 00237 indices = reshape(array(cindices[0],int),(len(cindices[0])/3,3)) 00238 else: 00239 # compute the convex hull triangle mesh 00240 meanpoint = mean(points,1) 00241 planes,faces,triangles = grasper.ConvexHull(points,returntriangles=True) 00242 usedindices = zeros(len(points),int) 00243 usedindices[triangles.flatten()] = 1 00244 pointindices = flatnonzero(usedindices) 00245 pointindicesinv = zeros(len(usedindices)) 00246 pointindicesinv[pointindices] = range(len(pointindices)) 00247 vertices = points[pointindices] 00248 indices = reshape(pointindicesinv[triangles.flatten()],triangles.shape) 00249 return TriMesh(vertices=vertices,indices=indices) 00250 def CreateTarget(graspableobject): 00251 target = RaveCreateKinBody(env,'') 00252 Ttarget = eye(4) 00253 if 1:#graspableobject.type == object_manipulation_msgs.msg.GraspableObject.POINT_CLUSTER: 00254 target.InitFromTrimesh(trimeshFromPointCloud(graspableobject.cluster),True) 00255 if len(options.mapframe) > 0: 00256 print 'set mapframe %s'%options.mapframe 00257 (trans,rot) = listener.lookupTransform(options.mapframe, graspableobject.cluster.header.frame_id, rospy.Time(0)) 00258 Ttarget = matrixFromQuat([rot[3],rot[0],rot[1],rot[2]]) 00259 Ttarget[0:3,3] = trans 00260 else: 00261 print 'didnt set any mapframe' 00262 Ttarget = eye(4) 00263 else: 00264 raise ValueError('do not support graspable objects of type %s'%str(graspableobject.type)) 00265 00266 target.SetName('graspableobject') 00267 env.AddKinBody(target,True) 00268 target.SetTransform(Ttarget) 00269 return target 00270 00271 def GraspPlanning(req): 00272 global graspparameters 00273 with envlock: 00274 with env: 00275 # update the robot 00276 if len(options.mapframe) > 0: 00277 print 'set mapframe %s'%options.mapframe 00278 (robot_trans,robot_rot) = listener.lookupTransform(options.mapframe, robot.GetLinks()[0].GetName(), rospy.Time(0)) 00279 Trobot = matrixFromQuat([robot_rot[3],robot_rot[0],robot_rot[1],robot_rot[2]]) 00280 Trobot[0:3,3] = robot_trans 00281 robot.SetTransform(Trobot) 00282 # set the manipulator 00283 if len(req.arm_name) > 0: 00284 manip = robot.GetManipulator(req.arm_name) 00285 rospy.loginfo('computing for manipulator %s'%req.arm_name) 00286 if manip is None: 00287 rospy.logerr('failed to find manipulator %s'%req.arm_name) 00288 return None 00289 else: 00290 print 'no manip set, trying to find one' 00291 manips = [manip for manip in robot.GetManipulators() if manip.GetIkSolver() is not None and len(manip.GetArmIndices()) >= 6] 00292 if len(manips) == 0: 00293 rospy.logerr('failed to find manipulator end effector %s'%req.hand_frame_id) 00294 return None 00295 manip = manips[0] 00296 robot.SetActiveManipulator(manip) 00297 00298 # create the target 00299 target = env.GetKinBody(req.collision_object_name) 00300 removetarget=False 00301 if target is None: 00302 target = CreateTarget(req.target) 00303 removetarget = True 00304 try: 00305 res = object_manipulation_msgs.srv.GraspPlanningResponse() 00306 # start planning 00307 fastgrasping = FastGrasping(robot,target,ignoreik=options.ignoreik,returngrasps=options.returngrasps) 00308 allgrasps,alljointvalues = fastgrasping.computeGrasp(graspparameters) 00309 if allgrasps is not None and len(allgrasps) > 0: 00310 res.error_code.value = object_manipulation_msgs.msg.GraspPlanningErrorCode.SUCCESS 00311 for grasp,jointvalues in izip(allgrasps,alljointvalues): 00312 rosgrasp = object_manipulation_msgs.msg.Grasp() 00313 rosgrasp.pre_grasp_posture.header.stamp = rospy.Time.now() 00314 rosgrasp.pre_grasp_posture.header.frame_id = options.mapframe 00315 rosgrasp.pre_grasp_posture.name = [robot.GetJointFromDOFIndex(index).GetName() for index in fastgrasping.gmodel.manip.GetGripperIndices()] 00316 print 'rosgrasp.pre_grasp_posture.name:%s'%rosgrasp.pre_grasp_posture.name 00317 rosgrasp.pre_grasp_posture.position = fastgrasping.gmodel.getPreshape(grasp) 00318 print 'rosgrasp.pre_grasp_posture.position:%s'%rosgrasp.pre_grasp_posture.position 00319 # also include the arm positions 00320 rosgrasp.grasp_posture.header = rosgrasp.pre_grasp_posture.header 00321 rosgrasp.grasp_posture.name = rosgrasp.pre_grasp_posture.name + [robot.GetJointFromDOFIndex(index).GetName() for index in fastgrasping.gmodel.manip.GetArmIndices()] 00322 print 'rosgrasp.grasp_posture.name:%s'%rosgrasp.grasp_posture.name 00323 rosgrasp.grasp_posture.position = jointvalues[r_[fastgrasping.gmodel.manip.GetGripperIndices(),fastgrasping.gmodel.manip.GetArmIndices()]] 00324 print 'rosgrasp.grasp_posture.position:%s'%rosgrasp.grasp_posture.position 00325 rosgrasp.pre_grasp_posture.name = str(rosgrasp.pre_grasp_posture.name) 00326 rosgrasp.grasp_posture.name = str(rosgrasp.grasp_posture.name) 00327 T = fastgrasping.gmodel.getGlobalGraspTransform(grasp,collisionfree=True) 00328 q = quatFromRotationMatrix(T[0:3,0:3]) 00329 rosgrasp.grasp_pose.position = geometry_msgs.msg.Point(T[0,3],T[1,3],T[2,3]) 00330 rosgrasp.grasp_pose.orientation = geometry_msgs.msg.Quaternion(q[1],q[2],q[3],q[0]) 00331 print 'grasp position:' 00332 print rosgrasp.grasp_pose.position.x 00333 print rosgrasp.grasp_pose.position.y 00334 print rosgrasp.grasp_pose.position.z 00335 print 'grasp orientation:' 00336 print rosgrasp.grasp_pose.orientation.x 00337 print rosgrasp.grasp_pose.orientation.y 00338 print rosgrasp.grasp_pose.orientation.z 00339 print rosgrasp.grasp_pose.orientation.w 00340 res.grasps.append(rosgrasp) 00341 #indices = [robot.GetJoint(name).GetDOFIndex() for name in rosgrasp.grasp_posture.name] 00342 #robot.SetDOFValues(rosgrasp.grasp_posture.position,indices) 00343 else: 00344 res.error_code.value = object_manipulation_msgs.msg.GraspPlanningErrorCode.OTHER_ERROR 00345 rospy.loginfo('removing target %s'%target.GetName()) 00346 return res 00347 finally: 00348 with env: 00349 if target is not None: 00350 rospy.loginfo('removing target in finally %s'%target.GetName()) 00351 env.Remove(target) 00352 00353 def SetGraspParameters(req): 00354 global graspparameters 00355 graspparameters = req 00356 res = orrosplanning.srv.SetGraspParametersResponse() 00357 return res 00358 00359 sub = rospy.Subscriber("/joint_states", sensor_msgs.msg.JointState, UpdateRobotJoints,queue_size=1) 00360 s = rospy.Service('GraspPlanning', object_manipulation_msgs.srv.GraspPlanning, GraspPlanning) 00361 sparameters = rospy.Service('SetGraspParameters', orrosplanning.srv.SetGraspParameters, SetGraspParameters) 00362 print 'openrave %s service ready'%s.resolved_name 00363 00364 # have to do this manually because running linkstatistics when viewer is enabled segfaults things 00365 if env.GetViewer() is None: 00366 if options._viewer is None: 00367 env.SetViewer('qtcoin') 00368 elif len(options._viewer) > 0: 00369 env.SetViewer(options._viewer) 00370 00371 if options.ipython: 00372 from IPython.Shell import IPShellEmbed 00373 ipshell = IPShellEmbed(argv='',banner = 'Dropping into IPython',exit_msg = 'Leaving Interpreter, back to program.') 00374 ipshell(local_ns=locals()) 00375 else: 00376 rospy.spin() 00377 finally: 00378 RaveDestroy()