Go to the documentation of this file.00001
00002 import roslib; roslib.load_manifest('pacman_controller')
00003 import rospy
00004 import commands
00005 import string
00006 import sys
00007 import math
00008 import actionlib
00009 import random
00010 from collvoid_local_planner.srv import InitGuess
00011 from std_msgs.msg import String
00012 from geometry_msgs.msg import PoseWithCovarianceStamped,PoseStamped
00013 from socket import gethostname
00014 from collvoid_msgs.msg import PoseTwistWithCovariance
00015 from move_base_msgs.msg import *
00016
00017 import tf
00018
00019 from pacman_controller import game_engine as GE
00020
00021
00022 class ControllerPacman():
00023
00024 def __init__(self):
00025 self.initialize()
00026
00027
00028 def initialize(self):
00029 self.move_base_client = actionlib.SimpleActionClient('move_base', MoveBaseAction)
00030 self.move_base_client.wait_for_server()
00031 self.init_guess_srv = rospy.ServiceProxy("init_guess_pub", InitGuess)
00032
00033 self.ghostname = rospy.get_param("~ghostname")
00034 self.home = rospy.get_param("/%s/home"%self.ghostname)
00035
00036
00037 rospy.loginfo("I am: %s home %d",self.ghostname, self.home)
00038 self.gameEngine = GE.GameEngine()
00039 self.state = GE.State.STOPPED
00040 self.dead = False
00041 self.current_wp = None
00042
00043
00044
00045 self.sub_state = rospy.Subscriber("/state", String, self.cb_state)
00046 self.sub_commands_robot = rospy.Subscriber("/commands_robot", String, self.cb_commands_robot)
00047
00048
00049
00050 def update(self):
00051 if self.state == GE.State.SETUP:
00052 return
00053 new_wp = None
00054 if (self.state == GE.State.STOPPED or self.state == GE.State.PAUSED):
00055 self.move_base_client.cancel_all_goals()
00056 self.current_wp = None
00057 return
00058 if (self.state in [GE.State.INIT, GE.State.GAME_OVER, GE.State.WON] or self.dead):
00059 new_wp = self.return_home();
00060 if not new_wp == None and not (new_wp == self.current_wp):
00061 self.current_wp = new_wp
00062 self.move_base_client.cancel_all_goals()
00063 self.send_goal(self.current_wp)
00064
00065 def send_goal(self,wp):
00066 goal = MoveBaseGoal()
00067 goal.target_pose.pose.position.x = self.gameEngine.points[wp]["x"]
00068 goal.target_pose.pose.position.y = self.gameEngine.points[wp]["y"]
00069
00070 goal.target_pose.pose.orientation.x = 0
00071 goal.target_pose.pose.orientation.y = 0
00072 goal.target_pose.pose.orientation.z = 0
00073 goal.target_pose.pose.orientation.w = 1.0
00074
00075
00076 goal.target_pose.header.frame_id = "/map"
00077
00078 self.move_base_client.send_goal(goal)
00079 return
00080
00081 def cb_state(self,msg):
00082 if self.state == GE.State.INIT and int(msg.data) == GE.State.RUNNING:
00083 self.current_wp = None
00084 self.move_base_client.cancel_all_goals()
00085 if self.state in [GE.State.RUNNING, GE.State.FLEEING] and int(msg.data) in [GE.State.STOPPED, GE.State.PAUSED, GE.State.WON, GE.State.GAME_OVER]:
00086 self.move_base_client.cancel_all_goals()
00087 self.current_wp = None
00088 if not self.state == GE.State.SETUP and int(msg.data) == GE.State.SETUP:
00089 self.move_base_client.cancel_all_goals()
00090
00091
00092 self.state = int(msg.data)
00093
00094
00095 def return_home(self):
00096 if GE.dist(self.gameEngine.points[self.home], self.gameEngine.pacman) < self.gameEngine.pacman['radius'] + GE.THRESHOLD:
00097 self.dead = False
00098 my_position = self.gameEngine.pacman
00099 my_wp = self.gameEngine.findClosestMapPoint(my_position)
00100
00101 path = self.gameEngine.find_shortest_path(my_wp,self.gameEngine.points[self.home])
00102 index = 1
00103 while index < len(path)-1 and GE.dist(path[index], self.gameEngine.pacman) < self.gameEngine.pacman['radius'] + 1.5 * GE.THRESHOLD :
00104 index += 1;
00105
00106 return path[index]['id']
00107
00108 def cb_commands_robot(self,msg):
00109 if (msg.data == "init Guess"):
00110 self.init_guess_srv(0.1)
00111
00112 if __name__ == '__main__':
00113
00114
00115
00116
00117
00118 rospy.init_node('controller_pacman')
00119 controller_pacman = ControllerPacman()
00120 while not rospy.is_shutdown():
00121 controller_pacman.update()
00122 rospy.sleep(0.1)
00123
00124