$search
00001 #!/usr/bin/env python 00002 00003 # SVN $HeadURL: http://alufr-ros-pkg.googlecode.com/svn/trunk/humanoid_stacks/nao_robot/nao_driver/scripts/nao_walker.py $ 00004 # SVN $Id: nao_walker.py 2962 2012-07-12 09:41:29Z maierd@informatik.uni-freiburg.de $ 00005 00006 00007 # 00008 # ROS node to control Nao's walking engine (omniwalk and footsteps) 00009 # This code is currently compatible to NaoQI version 1.6 or newer (latest 00010 # tested: 1.10) 00011 # 00012 # Copyright 2009-2011 Armin Hornung & Stefan Osswald, University of Freiburg 00013 # http://www.ros.org/wiki/nao 00014 # 00015 # Redistribution and use in source and binary forms, with or without 00016 # modification, are permitted provided that the following conditions are met: 00017 # 00018 # # Redistributions of source code must retain the above copyright 00019 # notice, this list of conditions and the following disclaimer. 00020 # # Redistributions in binary form must reproduce the above copyright 00021 # notice, this list of conditions and the following disclaimer in the 00022 # documentation and/or other materials provided with the distribution. 00023 # # Neither the name of the University of Freiburg nor the names of its 00024 # contributors may be used to endorse or promote products derived from 00025 # this software without specific prior written permission. 00026 # 00027 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00028 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00029 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00030 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00031 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00032 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00033 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00034 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00035 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00036 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00037 # POSSIBILITY OF SUCH DAMAGE. 00038 # 00039 00040 import roslib 00041 roslib.load_manifest('nao_driver') 00042 import rospy 00043 00044 from nao_driver import * 00045 00046 import math 00047 from math import fabs 00048 00049 from std_msgs.msg import String 00050 from geometry_msgs.msg import Twist 00051 from geometry_msgs.msg import Pose2D 00052 from sensor_msgs.msg import JointState 00053 from std_msgs.msg import Bool 00054 import std_msgs.msg 00055 00056 from std_srvs.srv import Empty, EmptyResponse 00057 from nao_msgs.srv import CmdPoseService, CmdVelService, CmdPoseServiceResponse, CmdVelServiceResponse 00058 from humanoid_nav_msgs.msg import StepTarget 00059 from humanoid_nav_msgs.srv import StepTargetService, StepTargetServiceResponse 00060 00061 import nao_msgs.srv 00062 00063 from start_walk_pose import startWalkPose 00064 00065 class NaoWalker(NaoNode): 00066 def __init__(self): 00067 NaoNode.__init__(self) 00068 00069 # ROS initialization: 00070 rospy.init_node('nao_walker') 00071 00072 self.connectNaoQi() 00073 00074 # head scan is not active 00075 self.scan_active = False 00076 # walking pattern params: 00077 self.stepFrequency = rospy.get_param('~step_frequency', 0.5) 00078 00079 self.useStartWalkPose = rospy.get_param('~use_walk_pose', False) 00080 self.needsStartWalkPose = True 00081 00082 # other params 00083 self.maxHeadSpeed = rospy.get_param('~max_head_speed', 0.2) 00084 # initial stiffness (defaults to 0 so it doesn't strain the robot when no teleoperation is running) 00085 # set to 1.0 if you want to control the robot immediately 00086 initStiffness = rospy.get_param('~init_stiffness', 0.0) 00087 00088 self.for_iros2011 = rospy.get_param('~for_iros2011', False) 00089 rospy.loginfo("for_iros2011 = %d" % self.for_iros2011) 00090 if self.for_iros2011: 00091 self.doubleScan = rospy.get_param('~double_scan', False) 00092 self.doubleScanFrom = rospy.get_param('~double_scan_from', 0.0) 00093 self.doubleScanTo = rospy.get_param('~double_scan_to', -30.0) 00094 self.scanInfoPub = rospy.Publisher("scan_info", Bool, latch=True) 00095 scanInfo = Bool(False) 00096 self.scanInfoPub.publish(scanInfo) 00097 00098 00099 # TODO: parameterize 00100 if initStiffness > 0.0 and initStiffness <= 1.0: 00101 self.motionProxy.stiffnessInterpolation('Body', initStiffness, 0.5) 00102 00103 try: 00104 enableFootContactProtection = rospy.get_param('~enable_foot_contact_protection') 00105 self.motionProxy.setMotionConfig([["ENABLE_FOOT_CONTACT_PROTECTION", enableFootContactProtection]]) 00106 if enableFootContactProtection: 00107 rospy.loginfo("Enabled foot contact protection") 00108 else: 00109 rospy.loginfo("Disabled foot contact protection") 00110 except KeyError: 00111 # do not change foot contact protection 00112 pass 00113 00114 # last: ROS subscriptions (after all vars are initialized) 00115 rospy.Subscriber("cmd_vel", Twist, self.handleCmdVel, queue_size=1) 00116 rospy.Subscriber("cmd_pose", Pose2D, self.handleTargetPose, queue_size=1) 00117 rospy.Subscriber("cmd_step", StepTarget, self.handleStep, queue_size=50) 00118 rospy.Subscriber("speech", String, self.handleSpeech) 00119 rospy.Subscriber("start_scan", std_msgs.msg.Empty, self.handleStartScan, queue_size=1) 00120 00121 # ROS services (blocking functions) 00122 self.cmdPoseSrv = rospy.Service("cmd_pose_srv", CmdPoseService, self.handleTargetPoseService) 00123 self.cmdVelSrv = rospy.Service("cmd_vel_srv", CmdVelService, self.handleCmdVelService) 00124 self.stepToSrv = rospy.Service("cmd_step_srv", StepTargetService, self.handleStepSrv) 00125 self.headScanSrv = rospy.Service("head_scan_srv", Empty, self.handleHeadScanSrv) 00126 self.stopWalkSrv = rospy.Service("stop_walk_srv", Empty, self.handleStopWalkSrv) 00127 self.needsStartWalkPoseSrv = rospy.Service("needs_start_walk_pose_srv", Empty, self.handleNeedsStartWalkPoseSrv) 00128 00129 self.say("Walker online") 00130 00131 rospy.loginfo("nao_walker initialized") 00132 00133 def connectNaoQi(self): 00134 '''(re-) connect to NaoQI''' 00135 rospy.loginfo("Connecting to NaoQi at %s:%d", self.pip, self.pport) 00136 00137 self.motionProxy = self.getProxy("ALMotion") 00138 if self.motionProxy is None: 00139 exit(1) 00140 00141 self.ttsProxy = self.getProxy("ALTextToSpeech", warn=False) 00142 if self.ttsProxy is None: 00143 rospy.logwarn("No Proxy to TTS available, disabling speech output.") 00144 00145 00146 def stopWalk(self): 00147 """ Stops the current walking bahavior and blocks until the clearing is complete. """ 00148 try: 00149 self.motionProxy.setWalkTargetVelocity(0.0, 0.0, 0.0, self.stepFrequency) 00150 self.motionProxy.waitUntilWalkIsFinished() 00151 00152 00153 except RuntimeError,e: 00154 print "An error has been caught" 00155 print e 00156 return False 00157 00158 return True 00159 00160 00161 def handleSpeech(self,data): 00162 self.say(data.data) 00163 00164 def say(self, text): 00165 if (not self.ttsProxy is None): 00166 try: 00167 # self.ttsProxy.say() sometimes causes deadlocks 00168 # see http://users.aldebaran-robotics.com/index.php?option=com_kunena&Itemid=14&func=view&catid=68&id=3857&limit=6&limitstart=6#6251 00169 print("say %s ..." % str(text)) 00170 ttsid = self.ttsProxy.post.say(str(text)) 00171 #self.ttsProxy.wait(ttsid, 0) 00172 print("...done") 00173 except RuntimeError,e: 00174 rospy.logerr("Exception caught:\n%s", e) 00175 00176 def handleCmdVel(self, data): 00177 rospy.logdebug("Walk cmd_vel: %f %f %f, frequency %f", data.linear.x, data.linear.y, data.angular.z, self.stepFrequency) 00178 if data.linear.x != 0 or data.linear.y != 0 or data.angular.z != 0: 00179 self.gotoStartWalkPose() 00180 try: 00181 eps = 1e-3 # maybe 0,0,0 is a special command in motionProxy... 00182 if abs(data.linear.x)<eps and abs(data.linear.y)<eps and abs(data.angular.z)<eps: 00183 self.motionProxy.setWalkTargetVelocity(0,0,0,0.5) 00184 else: 00185 self.motionProxy.setWalkTargetVelocity(data.linear.x, data.linear.y, data.angular.z, self.stepFrequency) 00186 except RuntimeError,e: 00187 # We have to assume there's no NaoQI running anymore => exit! 00188 rospy.logerr("Exception caught in handleCmdVel:\n%s", e) 00189 rospy.signal_shutdown("No NaoQI available anymore") 00190 00191 00192 00193 def handleCmdVelService(self, req): 00194 self.handleCmdVel(req.twist) 00195 return CmdVelServiceResponse() 00196 00197 def handleTargetPose(self, data, post=True): 00198 """handles cmd_pose requests, walks to (x,y,theta) in robot coordinate system""" 00199 if self.scan_active: 00200 return False 00201 00202 rospy.logdebug("Walk target_pose: %f %f %f", data.x, 00203 data.y, data.theta) 00204 00205 self.gotoStartWalkPose() 00206 00207 try: 00208 if post: 00209 self.motionProxy.post.walkTo(data.x, data.y, data.theta ) 00210 else: 00211 self.motionProxy.walkTo(data.x, data.y, data.theta ) 00212 return True 00213 except RuntimeError,e: 00214 rospy.logerr("Exception caught in handleTargetPose:\n%s", e) 00215 return False 00216 00217 00218 def handleStep(self, data): 00219 rospy.logdebug("Step leg: %d; target: %f %f %f", data.leg, data.pose.x, 00220 data.pose.y, data.pose.theta) 00221 try: 00222 if data.leg == StepTarget.right: 00223 leg = "RLeg" 00224 elif data.leg == StepTarget.left: 00225 leg = "LLeg" 00226 else: 00227 rospy.logerr("Received a wrong leg constant: %d, ignoring step command", data.leg) 00228 return 00229 self.motionProxy.stepTo(leg, data.pose.x, data.pose.y, data.pose.theta) 00230 return True 00231 except RuntimeError, e: 00232 rospy.logerr("Exception caught in handleStep:\n%s", e) 00233 return False 00234 00235 def handleStepSrv(self, req): 00236 if self.handleStep(req.step): 00237 return StepTargetServiceResponse() 00238 else: 00239 return None 00240 00241 def handleTargetPoseService(self, req): 00242 """ do NOT use post""" 00243 if self.handleTargetPose(req.pose, False): 00244 return CmdPoseServiceResponse() 00245 else: 00246 return None 00247 00248 def handleHeadScanSrv(self, req): 00249 if self.perform_laser_scan(): 00250 return EmptyResponse() 00251 else: 00252 return None 00253 00254 def handleStartScan(self, msg): 00255 self.perform_laser_scan() 00256 00257 def handleStopWalkSrv(self, req): 00258 if self.stopWalk(): 00259 return EmptyResponse() 00260 else: 00261 return None 00262 00263 def gotoStartWalkPose(self): 00264 if self.useStartWalkPose and self.needsStartWalkPose: 00265 startWalkPose(self.motionProxy) 00266 self.needsStartWalkPose = False 00267 00268 def handleNeedsStartWalkPoseSrv(self, data): 00269 self.needsStartWalkPose = True 00270 return EmptyResponse() 00271 00272 00273 def perform_laser_scan(self): 00274 if self.scan_active: 00275 print "ignoring button press because I'm already scanning" 00276 return False 00277 self.scan_active = True 00278 self.stopWalk() 00279 if self.for_iros2011: 00280 from iros2011_scan import head_scan 00281 head_scan(self.motionProxy,self.ttsProxy, 28.0, -36.0, 1.0, 10.0, True) 00282 if self.doubleScan: 00283 head_scan(self.motionProxy, self.ttsProxy, self.doubleScanFrom, self.doubleScanTo, 1.0, 10.0, False) 00284 self.motionProxy.angleInterpolation('HeadPitch', 0.0, 2.5, True) 00285 else: 00286 # todo: remove sleeps 00287 #from headscan import head_scan 00288 from headscanTop import head_scan 00289 if (not self.ttsProxy is None): 00290 self.say("Starting scan") 00291 else: 00292 rospy.loginfo("Starting scan") 00293 # max angle, min angle (pitch), scan freq, resolution, use squat 00294 rospy.sleep(2) 00295 #head_scan(self.motionProxy,26.0,-5.0,10.0,0.5,True) 00296 head_scan(self.motionProxy,28.0, -35.0, 1.0, 10.0, True) 00297 if (not self.ttsProxy is None): 00298 self.say("Scan complete") 00299 else: 00300 rospy.loginfo("Scan complete") 00301 self.scan_active = False 00302 self.needsStartWalkPose = True 00303 return True 00304 00305 00306 if __name__ == '__main__': 00307 walker = NaoWalker() 00308 rospy.loginfo("nao_walker running...") 00309 rospy.spin() 00310 rospy.loginfo("nao_walker stopping...") 00311 walker.stopWalk() 00312 00313 rospy.loginfo("nao_walker stopped.") 00314 exit(0)