$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 orrosplanning.srv 00009 import geometry_msgs.msg 00010 import kinematics_msgs.srv 00011 from numpy import * 00012 from arm_navigation_msgs.msg import ArmNavigationErrorCodes 00013 00014 if __name__=='__main__': 00015 rospy.init_node('armik_test') 00016 rospy.wait_for_service('IK') 00017 IKFn = rospy.ServiceProxy('IK',orrosplanning.srv.IK) 00018 req = orrosplanning.srv.IKRequest() 00019 req.pose_stamped.header.frame_id = 'katana_base_link' 00020 req.manip_name = 'arm' 00021 #req.iktype = 'Rotation3D' 00022 #req.iktype = 'Ray4D' 00023 req.iktype = 'TranslationDirection5D' 00024 req.filteroptions = 0 00025 counter = 0 00026 success = 0 00027 while True: 00028 randomquat = random.rand(4) 00029 randomquat /= linalg.norm(randomquat) 00030 req.pose_stamped.pose.orientation = geometry_msgs.msg.Quaternion(*list(randomquat)) 00031 #x = random.rand()*(-0.025-(-0.020))+(-0.020) 00032 #y = random.rand()*(0.025-(0.020))+(0.020) 00033 #z = random.rand()*(0.45-(0.30))+(0.30) 00034 x = random.rand()*(-0.15-(0.15))+(0.15) 00035 y = random.rand()*(0.15-(-0.15))+(-0.15) 00036 z = random.rand()*(0.55-(0.15))+(0.15) 00037 req.pose_stamped.pose.position.x = x 00038 req.pose_stamped.pose.position.y = y 00039 req.pose_stamped.pose.position.z = z 00040 res=IKFn(req) 00041 counter = counter + 1 00042 if res is not None and res.error_code.val == ArmNavigationErrorCodes.SUCCESS: 00043 success = success + 1 00044 print 'found solution for:' 00045 print x 00046 print y 00047 print z 00048 print randomquat 00049 print 'success:' 00050 print success 00051 print 'counter:' 00052 print counter 00053 print res