$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 use_robot_state_publisher = False 00012 if use_robot_state_publisher: 00013 from robot_state.msg import RobotState 00014 00015 from scan_pose_bending import scanPoseBending 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=False): 00019 start_time = rospy.Time.now() 00020 if(use_scan_pose): 00021 rospy.loginfo("HeadscanTop IS using scan_pose_new") 00022 else: 00023 rospy.loginfo("HeadscanTop IS NOT using scan_pose_new") 00024 00025 if use_robot_state_publisher: 00026 robotStatePub = rospy.Publisher("robot_state", RobotState) 00027 rospy.sleep(0.5) 00028 robot_state = RobotState() 00029 00030 # TODO: check limits of head and compare to headPitchEnd and headPitchStart 00031 headPitchStart = headPitchStart * math.pi/180.0 00032 headPitchEnd = headPitchEnd * math.pi/180.0 00033 headPitchInflectionPoint = headPitchEnd + (20.0*math.pi/180.0) # go further up than final scan pose 00034 degreePerSecond = angularResolution* laserScanFreq*0.33 00035 radiansPerSecond = degreePerSecond*math.pi/180.0 00036 #print("Radians per second: " + str(radiansPerSecond)) 00037 #print("Degree per second: " + str(degreePerSecond)) 00038 head_pitch_before_scan = motionProxy.getAngles("HeadPitch",True)[0] 00039 head_pitch_camera_learning = 22.0*math.pi/180.0 00040 if use_scan_pose: 00041 scanPoseBending(motionProxy,head_pitch_before_scan,0.0,2) 00042 00043 #motionProxy.stiffnessInterpolation('Body',1.0, 0.5) 00044 # compute some times 00045 t = abs(head_pitch_before_scan - headPitchStart)/radiansPerSecond 00046 t2 = abs(headPitchStart - headPitchEnd)/radiansPerSecond 00047 t3 = abs(headPitchEnd - head_pitch_camera_learning)/radiansPerSecond 00048 # set yaw to 0.0 and pitch to headPitchStart 00049 motionProxy.angleInterpolation('Head', [0.0, headPitchStart], t/4.0, True) 00050 00051 if use_robot_state_publisher: 00052 robot_state.stamp = rospy.Time.now() 00053 robot_state.id = RobotState.SCANNING 00054 robotStatePub.publish(robot_state) 00055 00056 # HACK to make nicer floor scans. TODO: improve me! 00057 angles = list() 00058 times = list() 00059 for i in range(0,9): 00060 angles.append( headPitchStart + (i+1)*(headPitchEnd - headPitchStart)/10.0) 00061 tt = (i+1)*t2/10.0 00062 times.append( tt*tt/t2 ) 00063 00064 rospy.logdebug("using times %s"%(str(times))) 00065 rospy.logdebug("using angles %s"%(str(angles))) 00066 motionProxy.angleInterpolation('HeadPitch', angles, times, True) 00067 #motionProxy.angleInterpolation('Head', [0.0, headPitchEnd], t2, True) 00068 if use_robot_state_publisher: 00069 rospy.sleep(0.5) 00070 robot_state = RobotState() 00071 robot_state.stamp = rospy.Time.now() 00072 robot_state.id = RobotState.SCAN_COMPLETE 00073 rospy.sleep(0.5) 00074 00075 # adopt final pose TODO: this should not necessary be cameraWalkPose 00076 if use_scan_pose: 00077 cameraWalkPose(motionProxy,head_pitch_camera_learning,0.0) 00078 #else: 00079 #t4 = abs(head_pitch_camera_learning - head_pitch_after_scan)/radiansPerSecond 00080 #head_pitch_after_scan = head_pitch_before_scan 00081 #head_pitch_after_scan = 20.0*math.pi/180.0 00082 #motionProxy.angleInterpolation('Head', [0.0, head_pitch_after_scan], t4, True) 00083 if use_robot_state_publisher: 00084 # wait to trigger point cloud assembler and image classifier 00085 rospy.sleep(0.5) 00086 robotStatePub.publish(robot_state) 00087 00088 dur = rospy.Time.now() - start_time 00089 rospy.loginfo("Scan took %f seconds."%(dur.to_sec())) 00090 00091 if __name__ == '__main__': 00092 00093 from optparse import OptionParser 00094 rospy.init_node('headscan') 00095 00096 parser = OptionParser() 00097 parser.add_option("--pip", dest="pip", default="127.0.0.1", 00098 help="IP/hostname of parent broker. Default is 127.0.0.1.", metavar="IP") 00099 parser.add_option("--pport", dest="pport", default=9559, 00100 help="port of parent broker. Default is 9559.", metavar="PORT") 00101 00102 parser.add_option("--s", dest="headpitchstart", default=27.0, 00103 help="start head pitch", metavar="START") 00104 parser.add_option("--e", dest="headpitchend", default=-10.0, 00105 help="end head pitch (negative angles are towards sky)", 00106 metavar="END") 00107 parser.add_option("--speed", dest="headpitchspeed", default=10, 00108 help="head pitch speed(degree per second)", metavar="SPEED") 00109 00110 (options, args) = parser.parse_args() 00111 00112 headPitchStart = float(options.headpitchstart ) 00113 headPitchEnd = float(options.headpitchend) 00114 00115 # TODO: useless.. 00116 pitch_speed = float(options.headpitchspeed) 00117 angularResolution = 1 00118 laserScanFreq = pitch_speed 00119 try: 00120 motionProxy = ALProxy("ALMotion",options.pip,int(options.pport)) 00121 except RuntimeError,e: 00122 print("Error creating Proxy to motion, exiting...") 00123 print e 00124 exit(1) 00125 00126 try: 00127 ttsProxy = ALProxy("ALTextToSpeech",options.pip,int(options.pport)) 00128 except RuntimeError,e: 00129 print("Error creating Proxy to tts ...") 00130 print e 00131 00132 00133 head_scan(motionProxy,headPitchStart,headPitchEnd,angularResolution,laserScanFreq,False) 00134 print("Scan completed...") 00135 exit(0) 00136 00137