00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015 from __future__ import with_statement
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('orrosplanning')
00020 import rospy
00021
00022 roslib.load_manifest('object_manipulation_msgs')
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.Transform6D)
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
00058 def checkgraspfn(self, contacts,finalconfig,grasp,info):
00059
00060 Tglobalgrasp = self.gmodel.getGlobalGraspTransform(grasp,collisionfree=True)
00061
00062 self.gmodel.setPreshape(grasp)
00063 jointvalues = array(finalconfig[0])
00064 if self.ignoreik:
00065 if self.gmodel.manip.CheckEndEffectorCollision(Tglobalgrasp):
00066 return False
00067
00068 else:
00069 sol = self.gmodel.manip.FindIKSolution(Tglobalgrasp,True)
00070 if sol is None:
00071 return False
00072
00073 jointvalues[self.gmodel.manip.GetArmIndices()] = sol
00074
00075 self.jointvalues.append(jointvalues)
00076 self.grasps.append(grasp)
00077 if len(self.jointvalues) < self.returngrasps:
00078 return True
00079
00080 raise self.GraspingException((self.grasps,self.jointvalues))
00081
00082 def computeGrasp(self,graspparameters):
00083 if len(graspparameters.approachrays) == 0:
00084 approachrays = self.gmodel.computeBoxApproachRays(delta=0.02,normalanglerange=0.5)
00085 else:
00086 approachrays = reshape(graspparameters.approachrays,[len(graspparameters.approachrays)/6,6])
00087
00088 Ttarget = self.gmodel.target.GetTransform()
00089 N = len(approachrays)
00090 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]))]
00091 self.approachgraphs = [env.plot3(points=gapproachrays[:,0:3],pointsize=5,colors=array((1,0,0))),
00092 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)))]
00093
00094 if len(graspparameters.standoffs) == 0:
00095 standoffs = [0]
00096 else:
00097 standoffs = graspparameters.standoffs
00098 if len(graspparameters.rolls) == 0:
00099 rolls = arange(0,2*pi,0.5*pi)
00100 else:
00101 rolls = graspparameters.rolls
00102 if len(graspparameters.preshapes) == 0:
00103
00104 with self.gmodel.target:
00105 self.gmodel.target.Enable(False)
00106 taskmanip = interfaces.TaskManipulation(self.robot)
00107 final,traj = taskmanip.ReleaseFingers(execute=False,outputfinal=True)
00108 preshapes = array([final])
00109 else:
00110 dim = len(self.gmodel.manip.GetGripperIndices())
00111 preshapes = reshape(graspparameters.preshapes,[len(graspparameters.preshapes)/dim,dim])
00112 try:
00113 self.gmodel.disableallbodies=False
00114 self.gmodel.generate(preshapes=preshapes,standoffs=standoffs,rolls=rolls,approachrays=approachrays,checkgraspfn=self.checkgraspfn,graspingnoise=0)
00115 return self.grasps,self.jointvalues
00116 except self.GraspingException, e:
00117 return e.args
00118
00119 if __name__ == "__main__":
00120 parser = OptionParser(description='openrave planning example')
00121 OpenRAVEGlobalArguments.addOptions(parser)
00122 parser.add_option('--scene',action="store",type='string',dest='scene',default='robots/pr2-beta-static.zae',
00123 help='scene to load (default=%default)')
00124 parser.add_option('--collision_map',action="store",type='string',dest='collision_map',default='/collision_map/collision_map',
00125 help='The collision map topic (maping_msgs/CollisionMap), by (default=%default)')
00126 parser.add_option('--ipython', '-i',action="store_true",dest='ipython',default=False,
00127 help='if true will drop into the ipython interpreter rather than spin')
00128 parser.add_option('--mapframe',action="store",type='string',dest='mapframe',default=None,
00129 help='The frame of the map used to position the robot. If --mapframe="" is specified, then nothing will be transformed with tf')
00130 parser.add_option('--returngrasps',action="store",type='int',dest='returngrasps',default=1,
00131 help='return all the grasps')
00132 parser.add_option('--ignoreik',action="store_true",dest='ignoreik',default=False,
00133 help='ignores the ik computations')
00134 (options, args) = parser.parse_args()
00135 env = OpenRAVEGlobalArguments.parseAndCreate(options,defaultviewer=False)
00136 RaveLoadPlugin(os.path.join(roslib.packages.get_pkg_dir('orrosplanning'),'lib','orrosplanning'))
00137 RaveLoadPlugin(os.path.join(roslib.packages.get_pkg_dir('openraveros'),'lib','openraveros'))
00138 namespace = 'openrave'
00139 env.AddModule(RaveCreateModule(env,'rosserver'),namespace)
00140 print 'initializing, please wait for ready signal...'
00141
00142 graspparameters = orrosplanning.srv.SetGraspParametersRequest()
00143 envlock = threading.Lock()
00144 try:
00145 rospy.init_node('graspplanning_openrave',disable_signals=False)
00146 with env:
00147 env.Load(options.scene)
00148 robot = env.GetRobots()[0]
00149
00150
00151
00152
00153
00154
00155
00156
00157
00158 ab=robot.ComputeAABB()
00159 ground=RaveCreateKinBody(env,'')
00160 ground.SetName('map')
00161 ground.InitFromBoxes(array([r_[ab.pos()-array([0,0,ab.extents()[2]+0.002]),2.0,2.0,0.001]]),True)
00162 env.AddKinBody(ground,False)
00163 if options.mapframe is None:
00164 options.mapframe = robot.GetLinks()[0].GetName()
00165 print 'setting map frame to %s'%options.mapframe
00166 if len(options.collision_map) > 0:
00167 collisionmap = RaveCreateSensorSystem(env,'CollisionMap bodyoffset %s topic %s'%(robot.GetName(),options.collision_map))
00168 basemanip = interfaces.BaseManipulation(robot)
00169 grasper = interfaces.Grasper(robot)
00170
00171 listener = tf.TransformListener()
00172 values = robot.GetDOFValues()
00173 def UpdateRobotJoints(msg):
00174 with envlock:
00175 with env:
00176 for name,pos in izip(msg.name,msg.position):
00177 j = robot.GetJoint(name)
00178 if j is not None:
00179 values[j.GetDOFIndex()] = pos
00180 robot.SetDOFValues(values)
00181
00182 def trimeshFromPointCloud(pointcloud):
00183 points = zeros((len(pointcloud.points),3),double)
00184 for i,p in enumerate(pointcloud.points):
00185 points[i,0] = p.x
00186 points[i,1] = p.y
00187 points[i,2] = p.z
00188 cindices = [c.values for c in pointcloud.channels if c.name == 'indices']
00189 if len(cindices) > 0:
00190 vertices = points
00191 indices = reshape(array(cindices[0],int),(len(cindices[0])/3,3))
00192 else:
00193
00194 meanpoint = mean(points,1)
00195 planes,faces,triangles = grasper.ConvexHull(points,returntriangles=True)
00196 usedindices = zeros(len(points),int)
00197 usedindices[triangles.flatten()] = 1
00198 pointindices = flatnonzero(usedindices)
00199 pointindicesinv = zeros(len(usedindices))
00200 pointindicesinv[pointindices] = range(len(pointindices))
00201 vertices = points[pointindices]
00202 indices = reshape(pointindicesinv[triangles.flatten()],triangles.shape)
00203 return TriMesh(vertices=vertices,indices=indices)
00204 def CreateTarget(graspableobject):
00205 target = RaveCreateKinBody(env,'')
00206 Ttarget = eye(4)
00207 if 1:
00208 target.InitFromTrimesh(trimeshFromPointCloud(graspableobject.cluster),True)
00209 if len(options.mapframe) > 0:
00210 (trans,rot) = listener.lookupTransform(options.mapframe, graspableobject.cluster.header.frame_id, rospy.Time(0))
00211 Ttarget = matrixFromQuat([rot[3],rot[0],rot[1],rot[2]])
00212 Ttarget[0:3,3] = trans
00213 else:
00214 Ttarget = eye(4)
00215 else:
00216 raise ValueError('do not support graspable objects of type %s'%str(graspableobject.type))
00217
00218 target.SetName('graspableobject')
00219 env.AddKinBody(target,True)
00220 target.SetTransform(Ttarget)
00221 return target
00222
00223 def GraspPlanning(req):
00224 global graspparameters
00225 with envlock:
00226 with env:
00227
00228 if len(options.mapframe) > 0:
00229 (robot_trans,robot_rot) = listener.lookupTransform(options.mapframe, robot.GetLinks()[0].GetName(), rospy.Time(0))
00230 Trobot = matrixFromQuat([robot_rot[3],robot_rot[0],robot_rot[1],robot_rot[2]])
00231 Trobot[0:3,3] = robot_trans
00232 robot.SetTransform(Trobot)
00233
00234 if len(req.arm_name) > 0:
00235 manip = robot.GetManipulator(req.arm_name)
00236 if manip is None:
00237 rospy.logerr('failed to find manipulator %s'%req.arm_name)
00238 return None
00239 else:
00240 manips = [manip for manip in robot.GetManipulators() if manip.GetIkSolver() is not None and len(manip.GetArmIndices()) >= 6]
00241 if len(manips) == 0:
00242 rospy.logerr('failed to find manipulator end effector %s'%req.hand_frame_id)
00243 return None
00244 manip = manips[0]
00245 robot.SetActiveManipulator(manip)
00246
00247
00248 target = env.GetKinBody(req.collision_object_name)
00249 removetarget=False
00250 if target is None:
00251 target = CreateTarget(req.target)
00252 removetarget = True
00253 try:
00254 res = object_manipulation_msgs.srv.GraspPlanningResponse()
00255
00256 fastgrasping = FastGrasping(robot,target,ignoreik=options.ignoreik,returngrasps=options.returngrasps)
00257 allgrasps,alljointvalues = fastgrasping.computeGrasp(graspparameters)
00258 if allgrasps is not None and len(allgrasps) > 0:
00259 res.error_code.value = object_manipulation_msgs.msg.GraspPlanningErrorCode.SUCCESS
00260 for grasp,jointvalues in izip(allgrasps,alljointvalues):
00261 rosgrasp = object_manipulation_msgs.msg.Grasp()
00262 rosgrasp.pre_grasp_posture.header.stamp = rospy.Time.now()
00263 rosgrasp.pre_grasp_posture.header.frame_id = options.mapframe
00264 rosgrasp.pre_grasp_posture.name = [robot.GetJointFromDOFIndex(index).GetName() for index in fastgrasping.gmodel.manip.GetGripperIndices()]
00265 rosgrasp.pre_grasp_posture.position = fastgrasping.gmodel.getPreshape(grasp)
00266
00267 rosgrasp.grasp_posture.header = rosgrasp.pre_grasp_posture.header
00268 rosgrasp.grasp_posture.name = rosgrasp.pre_grasp_posture.name + [robot.GetJointFromDOFIndex(index).GetName() for index in fastgrasping.gmodel.manip.GetArmIndices()]
00269 rosgrasp.grasp_posture.position = jointvalues[r_[fastgrasping.gmodel.manip.GetGripperIndices(),fastgrasping.gmodel.manip.GetArmIndices()]]
00270 rosgrasp.pre_grasp_posture.name = str(rosgrasp.pre_grasp_posture.name)
00271 rosgrasp.grasp_posture.name = str(rosgrasp.grasp_posture.name)
00272 T = fastgrasping.gmodel.getGlobalGraspTransform(grasp,collisionfree=True)
00273 q = quatFromRotationMatrix(T[0:3,0:3])
00274 rosgrasp.grasp_pose.position = geometry_msgs.msg.Point(T[0,3],T[1,3],T[2,3])
00275 rosgrasp.grasp_pose.orientation = geometry_msgs.msg.Quaternion(q[1],q[2],q[3],q[0])
00276 res.grasps.append(rosgrasp)
00277
00278
00279 else:
00280 res.error_code.value = object_manipulation_msgs.msg.GraspPlanningErrorCode.OTHER_ERROR
00281 rospy.loginfo('removing target %s'%target.GetName())
00282 return res
00283 finally:
00284 with env:
00285 if target is not None:
00286 rospy.loginfo('removing target in finally %s'%target.GetName())
00287 env.Remove(target)
00288
00289 def SetGraspParameters(req):
00290 global graspparameters
00291 graspparameters = req
00292 res = orrosplanning.srv.SetGraspParametersResponse()
00293 return res
00294
00295 sub = rospy.Subscriber("/joint_states", sensor_msgs.msg.JointState, UpdateRobotJoints,queue_size=1)
00296 s = rospy.Service('GraspPlanning', object_manipulation_msgs.srv.GraspPlanning, GraspPlanning)
00297 sparameters = rospy.Service('SetGraspParameters', orrosplanning.srv.SetGraspParameters, SetGraspParameters)
00298 print 'openrave %s service ready'%s.resolved_name
00299
00300
00301 if env.GetViewer() is None:
00302 if options._viewer is None:
00303 env.SetViewer('qtcoin')
00304 elif len(options._viewer) > 0:
00305 env.SetViewer(options._viewer)
00306
00307 if options.ipython:
00308 from IPython.Shell import IPShellEmbed
00309 ipshell = IPShellEmbed(argv='',banner = 'Dropping into IPython',exit_msg = 'Leaving Interpreter, back to program.')
00310 ipshell(local_ns=locals())
00311 else:
00312 rospy.spin()
00313 finally:
00314 RaveDestroy()