$search
00001 #!/usr/bin/env python 00002 00003 import math 00004 import time 00005 import naoqi 00006 import motion 00007 from naoqi import ALProxy 00008 import roslib 00009 roslib.load_manifest('nao_driver') 00010 import rospy 00011 send_robot_state=False 00012 if send_robot_state: 00013 from robot_state.msg import RobotState 00014 from scan_pose import scanPose 00015 from scan_pose_new import scanPoseNew 00016 from camera_walk_pose import cameraWalkPose 00017 00018 def head_scan(motionProxy,headPitchStart=26.0,headPitchEnd=-10.0,angularResolution=0.5,laserScanFreq=10,use_scan_pose=0): 00019 if use_scan_pose: 00020 scanPoseNew(motionProxy,math.pi*headPitchStart/180,0.0) 00021 00022 if send_robot_state: 00023 robotStatePub = rospy.Publisher("robot_state", RobotState) 00024 rospy.sleep(0.25) 00025 robot_state = RobotState() 00026 robot_state.stamp = rospy.Time.now() 00027 robot_state.id = RobotState.SCANNING 00028 robotStatePub.publish(robot_state) 00029 # TODO: check limits of head and compare to headPitchEnd and headPitchStart 00030 headPitchStart = headPitchStart * math.pi/180.0 00031 headPitchEnd = headPitchEnd * math.pi/180.0 00032 degreePerSecond = angularResolution* laserScanFreq 00033 radiansPerSecond = degreePerSecond*math.pi/180.0 00034 #print("Radians per second: " + str(radiansPerSecond)) 00035 #print("Degree per second: " + str(degreePerSecond)) 00036 head_pitch_before_scan = motionProxy.getAngles("HeadPitch",True)[0] 00037 head_pitch_after_scan = head_pitch_before_scan 00038 #print("angles " + str(head_pitch_before_scan) + ", " + str(headPitchStart) + ", " + str(headPitchEnd) + ",and " + str(head_pitch_after_scan)) 00039 00040 motionProxy.stiffnessInterpolation('Body',1.0, 0.5) 00041 t = abs(head_pitch_before_scan - headPitchStart)/radiansPerSecond 00042 t2 = abs(headPitchStart - headPitchEnd)/radiansPerSecond 00043 t3 = abs(headPitchEnd - head_pitch_after_scan)/radiansPerSecond 00044 #print "ang dif is " + str(abs(head_pitch_before_scan - headPitchStart)) 00045 #print "t is " + str(t) 00046 #exit(0) 00047 # set yaw to 0.0 and pitch to headPitchStart 00048 motionProxy.angleInterpolation('Head', [0.0, headPitchStart], t, True) 00049 motionProxy.angleInterpolation('Head', [0.0, headPitchEnd], t2, True) 00050 motionProxy.angleInterpolation('Head', [0.0, head_pitch_after_scan], t3, True) 00051 #ttsProxy.say("Scanning now") 00052 # list of angles and times 00053 #angleList = [headPitchStart, headPitchEnd, head_pitch_after_scan] 00054 #angularDifferences = [head_pitch_before_scan-headPitchStart, 00055 # headPitchEnd-headPitchStart, 00056 # head_pitch_before_scan-headPitchEnd] 00057 #print(angularDifferences) 00058 #timeList = [abs(s)/radiansPerSecond for s in angularDifferences] 00059 # need to accumulate time list (required by angularInterpolation) 00060 #accumulatedTime = 0.0 00061 #for i in range(0,len(timeList)): 00062 # accumulatedTime = accumulatedTime + timeList[i] 00063 #timeList[i] = accumulatedTime 00064 #print(timeList) 00065 #motionProxy.angleInterpolation('HeadPitch', angleList, timeList, True) 00066 #ttsProxy.say("Done") 00067 if use_scan_pose: 00068 cameraWalkPose(motionProxy,math.pi*head_pitch_before_scan/180,0.0) 00069 00070 if send_robot_state: 00071 rospy.sleep(1.0) 00072 robot_state = RobotState() 00073 robot_state.stamp = rospy.Time.now() 00074 robot_state.id = RobotState.SCAN_COMPLETE 00075 robotStatePub.publish(robot_state) 00076 00077 if __name__ == '__main__': 00078 00079 from optparse import OptionParser 00080 rospy.init_node('headscan') 00081 00082 parser = OptionParser() 00083 parser.add_option("--pip", dest="pip", default="127.0.0.1", 00084 help="IP/hostname of parent broker. Default is 127.0.0.1.", metavar="IP") 00085 parser.add_option("--pport", dest="pport", default=9559, 00086 help="port of parent broker. Default is 9559.", metavar="PORT") 00087 00088 parser.add_option("--s", dest="headpitchstart", default=26.0, 00089 help="start head pitch", metavar="START") 00090 parser.add_option("--e", dest="headpitchend", default=-30.0, 00091 help="end head pitch (negative angles are towards sky)", 00092 metavar="END") 00093 parser.add_option("--speed", dest="headpitchspeed", default=10, 00094 help="head pitch speed(degree per second)", metavar="SPEED") 00095 00096 (options, args) = parser.parse_args() 00097 00098 headPitchStart = float(options.headpitchstart ) 00099 headPitchEnd = float(options.headpitchend) 00100 00101 # TODO: useless.. 00102 pitch_speed = float(options.headpitchspeed) 00103 angularResolution = 1 00104 laserScanFreq = pitch_speed 00105 try: 00106 motionProxy = ALProxy("ALMotion",options.pip,int(options.pport)) 00107 ttsProxy = ALProxy("ALTextToSpeech",options.pip,int(options.pport)) 00108 except RuntimeError,e: 00109 print("Error creating Proxy to motion, exiting...") 00110 print e 00111 exit(1) 00112 00113 head_scan(motionProxy,headPitchStart,headPitchEnd,angularResolution,laserScanFreq,1) 00114 print("Scan completed...") 00115 exit(0) 00116 00117