$search
00001 #!/usr/bin/env python 00002 00003 import math 00004 00005 # TODO: are these all required? Shouldn't be for a simple pose... 00006 import naoqi 00007 import motion 00008 from naoqi import ALProxy 00009 00010 00011 import roslib 00012 roslib.load_manifest('nao_driver') 00013 import rospy 00014 00015 00016 # go to crouching position 00017 def scanPose(motionProxy,head_pitch,head_yaw): 00018 numJoints = len(motionProxy.getJointNames('Body')) 00019 print "received " + str(head_pitch) + " " + str(head_yaw) 00020 allAngles = [head_yaw,head_pitch, # head 00021 1.574, 0.212, -0.011, -0.003, 0.003, 0.01, # left arm 00022 -0.423, -0.023, -0.861, 2.223, -1.174, 0.023, # left leg 00023 -0.442, 0.089, -0.823, 2.185, -1.162, -0.066, # right leg 00024 1.574, -0.212, -0.011, -0.005, 0.003, -0.01] # right arm 00025 00026 if (numJoints == 26): 00027 angles = allAngles 00028 elif (numJoints == 22): # no hands (e.g. simulator) 00029 angles = allAngles[0:6] + allAngles[8:24] 00030 else: 00031 rospy.logerr("Unkown number of joints: %d", numJoints) 00032 return 00033 00034 try: 00035 motionProxy.angleInterpolation('Body', angles, 1.5, True); 00036 00037 except RuntimeError,e: 00038 print "An error has been caught" 00039 print e 00040 00041 if __name__ == '__main__': 00042 from optparse import OptionParser 00043 rospy.init_node('headscan') 00044 00045 parser = OptionParser() 00046 parser.add_option("--pip", dest="pip", default="127.0.0.1", 00047 help="IP/hostname of parent broker. Default is 127.0.0.1.", metavar="IP") 00048 parser.add_option("--pport", dest="pport", default=9559, 00049 help="port of parent broker. Default is 9559.", metavar="PORT") 00050 00051 (options, args) = parser.parse_args() 00052 00053 try: 00054 motionProxy = ALProxy("ALMotion",options.pip,int(options.pport)) 00055 ttsProxy = ALProxy("ALTextToSpeech",options.pip,int(options.pport)) 00056 except RuntimeError,e: 00057 print("Error creating Proxy to motion, exiting...") 00058 print e 00059 exit(1) 00060 00061 scan_pose(motionProxy,-26.0*math.pi/180.0,0.0) 00062 print("Scan completed...") 00063 exit(0) 00064