$search
00001 #!/usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2008, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of Willow Garage, Inc. nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 00033 # 00034 # Author: Bhaskara Marthi 00035 00036 import roslib 00037 roslib.load_manifest('cart_pushing_executive') 00038 import rospy 00039 import time 00040 import actionlib 00041 import tf 00042 00043 from move_base_msgs.msg import * 00044 from geometry_msgs.msg import * 00045 from roslib.msg import * 00046 00047 goals = [ 00048 [(22.7547492981,17.2507705688,0.0),(0.0,0.0,-0.21978236622,0.975548928296)], 00049 [(28.1076889038,17.9328041077,0.0),(0.0,0.0,0.534407395401,0.84522703207)], 00050 [(26.410533905,23.2363433838,0.0),(0.0,0.0,0.975548880533,0.219782578222)], 00051 [(19.210647583,23.2893428802,0.0),(0.0,0.0,-0.834799107823,0.550554674467)], 00052 [(23.0300712585,17.0846633911,0.0),(0.0,0.0,-0.193364053165,0.981127077877)], 00053 [(27.9582328796,17.5433273315,0.0),(0.0,0.0,0.539956703804,0.841692793136)], 00054 [(34.0350074768,23.7652778625,0.0),(0.0,0.0,-0.195291409231,0.980745260239)], 00055 [(33.3261146545,13.9941511154,0.0),(0.0,0.0,-0.851834538099,0.523810957981)],#inside cafeteria going in 00056 [(30.5941886902,8.5315656662,0.0),(0.0,0.0,-0.841195162852,0.540731632138)],#inside cafeteria coming out 00057 [(30.3537712097,8.00482368469,0.0),(0.0,0.0,0.540731770207,0.8411950741)],#inside cafeteria coming out 00058 [(34.1780052185,23.7703514099,0.0),(0.0,0.0,0.984122604912,0.177489995494)], 00059 [(25.7120513916,23.4842967987,0.0),(0.0,0.0,0.977169336603,0.212461967425)], 00060 [(18.5160522461,22.5130939484,0.0),(0.0,0.0,-0.752447094618,0.658652692852)] 00061 ] 00062 00063 def squared_dist(p1, p2): 00064 dx = p1.point.x - p2[0] 00065 dy = p1.point.y - p2[1] 00066 return dx*dx + dy*dy 00067 00068 def mb_goal(goal): 00069 return MoveBaseGoal(PoseStamped(Header(frame_id = 'map'), 00070 Pose(Point(goal[0][0], goal[0][1], 00071 goal[0][2]), 00072 Quaternion(goal[1][0], goal[1][1], 00073 goal[1][2], goal[1][3])))) 00074 if __name__ == '__main__': 00075 rospy.init_node('willow_tour_node') 00076 client = actionlib.SimpleActionClient('move_base', MoveBaseAction) 00077 rospy.loginfo("Waiting for move_base") 00078 client.wait_for_server() 00079 rospy.loginfo("Sending goals") 00080 tf = tf.TransformListener() 00081 rospy.sleep(2) 00082 00083 p = PointStamped() 00084 p.header.frame_id = 'base_footprint' 00085 p.header.stamp = rospy.Time() 00086 pos = tf.transformPoint('map', p) 00087 00088 best_dist = 1000000 00089 current = 0 00090 for (i, g) in enumerate(goals): 00091 if squared_dist(pos, g[0]) < best_dist: 00092 best_dist = squared_dist(pos, g[0]) 00093 current = i 00094 rospy.loginfo('Closest waypoint is %s: %s', current, goals[current]) 00095 00096 for c in range(5): 00097 while current < len(goals): 00098 mb = mb_goal(goals[current]) 00099 rospy.loginfo("Sending goal %s" % goals[current]) 00100 client.send_goal(mb) 00101 client.wait_for_result() 00102 current +=1 00103 current = 0 00104 00105 rospy.loginfo('Done with tour') 00106 00107 00108