1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306
|
import rospy
import actionlib from actionlib_msgs.msg import * from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal from nav_msgs.msg import Path from geometry_msgs.msg import PoseWithCovarianceStamped from tf_conversions import transformations from math import pi from std_msgs.msg import String from geometry_msgs.msg import Twist from ar_track_alvar_msgs.msg import AlvarMarkers from ar_track_alvar_msgs.msg import AlvarMarker
from geometry_msgs.msg import Point import sys reload(sys) sys.setdefaultencoding('utf-8') import os music_path1= "~/abot_ws/'target1.mp3'" music_path2= "~/abot_ws/'target2.mp3'" music_path3= "/home/abot/abot_ws/'target3.mp3'" music_path4 = "/home/abot/abot_ws/'target4.mp3'" music_path5 = "/home/abot/abot_ws/'target5.mp3'" music_path6 = "/home/abot/abot_ws/'target6.mp3'" music_path7 = "/home/abot/abot_ws/'target7.mp3'" music_path8 = "/home/abot/abot_ws/'target8.mp3'" mubiao2 = "/home/abot/abot_ws/'mubiao2.mp3'" mubiao4 = "/home/abot/abot_ws/'mubiao4.mp3'" mubiao6 = "/home/abot/abot_ws/'mubiao6.mp3'" mubiao8 = "/home/abot/abot_ws/'mubiao8.mp3'" mubiao1 = "/home/abot/abot_ws/'mubiao1.mp3'" mubiao3 = "/home/abot/abot_ws/'mubiao3.mp3'" mubiao5 = "/home/abot/abot_ws/'mubiao5.mp3'" mubiao7 = "/home/abot/abot_ws/'mubiao7.mp3'" music_path_start = "/home/abot/abot_ws/'start_dl.mp3'" music_path_end = "/home/abot/abot_ws/'end.mp3'"
id = 0 find_id = 0 flog0=255 flog1=255 flog2=255 flog3=255 flog4=255 flog5=255 flog6=255 flog7=255 count = 0 move_flog = 0
class navigation_demo: def __init__(self): self.set_pose_pub = rospy.Publisher('/initialpose', PoseWithCovarianceStamped, queue_size=1) self.arrive_pub = rospy.Publisher('/voiceWords',String,queue_size=10) self.ar_sub=rospy.Subscriber('/object_position',Point,self.find_cb) self.ar_sub=rospy.Subscriber('/ar_pose_marker',AlvarMarkers,self.ar_cb) self.move_base = actionlib.SimpleActionClient("move_base", MoveBaseAction) self.move_base.wait_for_server(rospy.Duration(60)) self.cmd=rospy.Publisher('/cmd_vel',Twist,queue_size=5)
def move_forward(self): cmd=Twist() cmd.linear.x=0.107 cmd.linear.y=0.11 cmd.angular.z=0.0 self.cmd.publish(cmd)
def ar_cb(self,data): global id for marker in data.markers: id= marker.id print(id) def find_cb(self,data): global find_id point_msg =data if(point_msg.z>=1 and point_msg.z<=8): find_id=1 if(point_msg.z>=9 and point_msg.z<=16): find_id=2 if(point_msg.z>=17 and point_msg.z<=24): find_id=3 if(point_msg.z>=25 and point_msg.z<=32): find_id=4 if(point_msg.z>=33 and point_msg.z<=40): find_id=5 if(point_msg.z>=41 and point_msg.z<=48): find_id=6 if(point_msg.z>=49 and point_msg.z<=56): find_id=7 if(point_msg.z>=57 and point_msg.z<=64): find_id=8 def set_pose(self, p): if self.move_base is None: return False
x, y, th = p
pose = PoseWithCovarianceStamped() pose.header.stamp = rospy.Time.now() pose.header.frame_id = 'map' pose.pose.pose.position.x = x pose.pose.pose.position.y = y q = transformations.quaternion_from_euler(0.0, 0.0, th/180.0*pi) pose.pose.pose.orientation.x = q[0] pose.pose.pose.orientation.y = q[1] pose.pose.pose.orientation.z = q[2] pose.pose.pose.orientation.w = q[3]
self.set_pose_pub.publish(pose) return True
def _done_cb(self, status, result): rospy.loginfo("navigation done! status:%d result:%s"%(status, result)) arrive_str = "arrived to traget point" self.arrive_pub.publish(arrive_str)
def _active_cb(self): rospy.loginfo("[Navi] navigation has be actived")
def _feedback_cb(self, feedback): msg = feedback
def goto(self, p): rospy.loginfo("[Navi] goto %s"%p) goal = MoveBaseGoal()
goal.target_pose.header.frame_id = 'map' goal.target_pose.header.stamp = rospy.Time.now() goal.target_pose.pose.position.x = p[0] goal.target_pose.pose.position.y = p[1] q = transformations.quaternion_from_euler(0.0, 0.0, p[2]/180.0*pi) goal.target_pose.pose.orientation.x = q[0] goal.target_pose.pose.orientation.y = q[1] goal.target_pose.pose.orientation.z = q[2] goal.target_pose.pose.orientation.w = q[3]
self.move_base.send_goal(goal, self._done_cb, self._active_cb, self._feedback_cb) result = self.move_base.wait_for_result(rospy.Duration(60)) if not result: self.move_base.cancel_goal() rospy.loginfo("Timed out achieving goal") else: state = self.move_base.get_state() if state == GoalStatus.SUCCEEDED: rospy.loginfo("reach goal %s succeeded!"%p) return True
def cancel(self): self.move_base.cancel_all_goals() return True if __name__ == "__main__": rospy.init_node('navigation_move',anonymous=True) goalListX = rospy.get_param('~goalListX', '2.0, 2.0') goalListY = rospy.get_param('~goalListY', '2.0, 4.0') goalListYaw = rospy.get_param('~goalListYaw', '0, 90.0')
goals = [[float(x), float(y), float(yaw)] for (x, y, yaw) in zip(goalListX.split(","),goalListY.split(","),goalListYaw.split(","))] print ('Please call DingLiang666 to continue: ') input = raw_input() r = rospy.Rate(1) r.sleep() navi = navigation_demo() if (input == '1'):
print('1') navi.goto(goals[0]) rospy.sleep(5) if (id==1 or find_id==1): os.system('mplayer %s' % music_path1) navi.goto(goals[1]) os.system('mplayer %s' % mubiao1) rospy.sleep(3) elif(id==2 or find_id==2): os.system('mplayer %s' % music_path2) navi.goto(goals[2]) os.system('mplayer %s' % mubiao2) rospy.sleep(3)
print('2') navi.goto(goals[13]) navi.goto(goals[3]) rospy.sleep(5) if (id==3 or find_id==3): os.system('mplayer %s' % music_path3) navi.goto(goals[4]) os.system('mplayer %s' % mubiao3) rospy.sleep(3) elif(id==4 or find_id==4): os.system('mplayer %s' % music_path4) navi.goto(goals[5]) os.system('mplayer %s' % mubiao4) rospy.sleep(3)
print('3') navi.goto(goals[14]) navi.goto(goals[6]) rospy.sleep(5) if (id==5 or find_id==5): os.system('mplayer %s' % music_path5) navi.goto(goals[7]) os.system('mplayer %s' % mubiao5) rospy.sleep(3) elif(id==6 or find_id==6): os.system('mplayer %s' % music_path6) navi.goto(goals[8]) os.system('mplayer %s' % mubiao6) rospy.sleep(3)
print('4') navi.goto(goals[15]) navi.goto(goals[9]) rospy.sleep(5) if (id==7 or find_id==7): os.system('mplayer %s' % music_path7) navi.goto(goals[10]) os.system('mplayer %s' % mubiao7) rospy.sleep(3) elif(id==8 or find_id==8): os.system('mplayer %s' % music_path8) navi.goto(goals[11]) os.system('mplayer %s' % mubiao8) rospy.sleep(3) navi.goto(goals[12]) start_time=rospy.Time.now() while rospy.Time.now()-start_time<rospy.Duration(5): navi.move_forward() os.system('mplayer %s' % music_path_end) while not rospy.is_shutdown(): r.sleep()
|