Commit 24dc458f authored by Matthew Hausknecht's avatar Matthew Hausknecht

Merge pull request #14 from mhauskn/launch_refactor

Launch refactor
parents db95ebef 18a6d4d1
......@@ -4,6 +4,7 @@ __pycache__/
# C extensions
*.so
*.a
# Distribution / packaging
.Python
......@@ -31,6 +32,7 @@ var/
# Installer logs
pip-log.txt
pip-delete-this-directory.txt
install_manifest.txt
# Unit test / coverage reports
htmlcov/
......@@ -64,7 +66,16 @@ bin/agent
bin/sample_coach
bin/sample_player
bin/sample_trainer
bin/rcssserver
bin/soccerwindow2
example/hfo_example_agent
example/high_level_random_agent
example/low_level_random_agent
# Dependency directories
librcsc-prefix/
rcssserver-prefix/
soccerwindow2-prefix/
# Logs
log/
......
......@@ -62,7 +62,7 @@ class Communicator(object):
raise TimeoutError
else:
retryCount -= 1
print 'error receiving message, trying again'
print '[Trainer] waiting for message, retry =', retryCount
time.sleep(0.3)
#raise ValueError('Error while receiving message')
(msg,sep,rest) = msg.partition('\0')
......
......@@ -2,7 +2,6 @@
# encoding: utf-8
import subprocess, os, time, numpy, sys
from signal import SIGKILL
# Global list of all/essential running processes
processes, necProcesses = [], []
......@@ -11,41 +10,27 @@ SERVER_BIN = 'rcssserver'
# Command to run the monitor. Edit as needed.
MONITOR_BIN = 'soccerwindow2'
def getAgentDirCmd(binary_dir, teamname, server_port=6000, coach_port=6002,
logDir='log', record=False):
""" Returns the team name, command, and directory to run a team. """
cmd = 'start.sh -t %s -p %i -P %i --log-dir %s'%(teamname, server_port,
coach_port, logDir)
if record:
cmd += ' --record'
cmd = os.path.join(binary_dir, cmd)
return teamname, cmd
def launch(cmd, necessary=True, supressOutput=True, name='Unknown'):
def launch(cmd, name = 'Unknown', necessary = True, supressOutput = True):
"""Launch a process.
Appends to list of processes and (optionally) necProcesses if
necessary flag is True.
Returns: The launched process.
"""
kwargs = {}
if supressOutput:
kwargs = {'stdout':open('/dev/null','w'),'stderr':open('/dev/null','w')}
p = subprocess.Popen(cmd.split(' '),shell=False,**kwargs)
kwargs = {'stdout': open('/dev/null', 'w'),
'stderr': open('/dev/null', 'w')}
p = subprocess.Popen(cmd.split(' '), shell = False, **kwargs)
processes.append(p)
if necessary:
necProcesses.append([p,name])
return p
def main(args, team1='left', team2='right', rng=numpy.random.RandomState()):
"""Sets up the teams, launches the server and monitor, starts the
trainer.
def main(args, team1='left', team2='right'):
"""Sets up the teams, launches the server and monitor, starts the trainer.
"""
if args.seed:
print '[start.py] Seeding RNG with seed: ', args.seed
rng.seed(args.seed)
if not os.path.exists(args.logDir):
os.makedirs(args.logDir)
num_agents = args.offenseAgents + args.defenseAgents
......@@ -57,21 +42,23 @@ def main(args, team1='left', team2='right', rng=numpy.random.RandomState()):
serverOptions = ' server::port=%i server::coach_port=%i ' \
'server::olcoach_port=%i server::coach=1 ' \
'server::game_logging=%i server::text_logging=%i ' \
'server::hfo_logging=%i server::hfo_log_dir=%s ' \
'server::game_log_dir=%s server::text_log_dir=%s '\
'server::synch_mode=%i ' \
'server::fullstate_l=%i server::fullstate_r=%i' \
'server::synch_mode=%i server::hfo=1 ' \
'server::fullstate_l=%i server::fullstate_r=%i ' \
'server::coach_w_referee=1 server::hfo_max_trial_time=%i ' \
'server::hfo_max_trials=%i server::hfo_max_frames=%i ' \
'server::hfo_offense_on_ball=%i server::random_seed=%i' \
%(server_port, coach_port, olcoach_port,
args.logging, args.logging,
args.logDir, args.logDir,
args.sync,
args.fullstate, args.fullstate)
team1, team1Cmd = getAgentDirCmd(binary_dir, team1, server_port, coach_port,
args.logDir, args.record)
team2, team2Cmd = getAgentDirCmd(binary_dir, team2, server_port, coach_port,
args.logDir, args.record)
args.logging, args.logging, args.logging,
args.logDir, args.logDir, args.logDir,
args.sync, args.fullstate, args.fullstate,
args.maxFramesPerTrial, args.numTrials, args.numFrames,
args.offenseOnBall, args.seed)
# server::record_messages=on -- useful for debug
try:
# Launch the Server
server = launch(serverCommand + serverOptions, name='server')
server = launch(serverCommand + serverOptions, name='server', supressOutput=True)
time.sleep(0.2)
assert server.poll() is None,\
'[start.py] Failed to launch Server with command: \"%s\"' \
......@@ -82,30 +69,25 @@ def main(args, team1='left', team2='right', rng=numpy.random.RandomState()):
launch(monitorCommand + monitorOptions, name='monitor')
# Launch the Trainer
from Trainer import Trainer
trainer = Trainer(args=args, rng=rng, server_port=server_port,
coach_port=coach_port)
trainer = Trainer(args=args, server_port=server_port, coach_port=coach_port)
trainer.initComm()
# Start Team1
launch(team1Cmd,False)
trainer.waitOnTeam(True) # wait to make sure of team order
# Start Team2
launch(team2Cmd,False)
trainer.waitOnTeam(False)
# Make sure all players are connected
trainer.checkIfAllPlayersConnected()
trainer.setTeams()
# Run HFO
# Add Team1
trainer.addTeam(team1)
# Add Team2
trainer.addTeam(team2)
# Run
trainer.run(necProcesses)
except KeyboardInterrupt:
print '[start.py] Exiting for CTRL-C'
finally:
print '[start.py] Cleaning up server and other processes'
for p in processes:
for p in reversed(processes):
try:
p.send_signal(SIGKILL)
p.terminate()
time.sleep(0.1)
p.kill()
except:
pass
time.sleep(0.1)
def parseArgs():
import argparse
......@@ -138,17 +120,33 @@ def parseArgs():
help='Directory to store logs.')
p.add_argument('--record', dest='record', action='store_true',
help='Record logs of states and actions.')
p.add_argument('--agent-on-ball', dest='agent_on_ball', action='store_true',
help='Agent starts with the ball.')
p.add_argument('--offense-on-ball', dest='offenseOnBall', action='store_true',
help='Offense starts with the ball.')
p.add_argument('--fullstate', dest='fullstate', action='store_true',
help='Server provides full-state information to agents.')
p.add_argument('--seed', dest='seed', type=int,
help='Seed the trainer\'s RNG. Default: time.')
p.add_argument('--seed', dest='seed', type=int, default=-1,
help='Seed the server\'s RNG. Default: time.')
args = p.parse_args()
assert args.offenseAgents + args.offenseNPCs in xrange(0, 11), \
'Invalid number of offensive players: (choose from [0,10])'
assert args.defenseAgents + args.defenseNPCs in xrange(0, 12), \
'Invalid number of defensive players: (choose from [0,11])'
if args.offenseAgents not in xrange(0, 11):
p.error('argument --offense-agents: invalid choice: '\
+ str(args.offenseAgents) + ' (choose from [0-10])')
if args.offenseNPCs not in xrange(0, 11):
p.error('argument --offense-npcs: invalid choice: '\
+ str(args.offenseNPCs) + ' (choose from [0-10])')
if args.defenseAgents not in xrange(0, 12):
p.error('argument --defense-agents: invalid choice: '\
+ str(args.defenseAgents) + ' (choose from [0-11])')
if args.defenseNPCs not in xrange(0, 12):
p.error('argument --offense-npcs: invalid choice: '\
+ str(args.defenseNPCs) + ' (choose from [0-11])')
if args.offenseAgents + args.offenseNPCs not in xrange(1, 11):
p.error('Offense players (offense-agents + offense-npcs): '\
'invalid choice: ' + str(args.offenseAgents + args.offenseNPCs) +\
' (choose from [1,10])')
if args.defenseAgents + args.defenseNPCs not in xrange(0, 12):
p.error('Defense players (defense-agents + defense-npcs): '\
'invalid choice: ' + str(args.defenseAgents + args.defenseNPCs) +\
' (choose from [0,11])')
return args
if __name__ == '__main__':
......
#!/usr/bin/env python
# encoding: utf-8
import sys, numpy, time, os, subprocess, re
from signal import SIGINT
import sys, numpy, time, os, subprocess
from Communicator import ClientCommunicator, TimeoutError
class DoneError(Exception):
......@@ -12,52 +11,21 @@ class DoneError(Exception):
def __str__(self):
return 'Done due to %s' % self.msg
class DummyPopen(object):
""" Emulates a Popen object without actually starting a process. """
def __init__(self, pid):
self.pid = pid
def poll(self):
try:
os.kill(self.pid, 0)
return None
except OSError:
return 0
def send_signal(self, sig):
try:
os.kill(self.pid, sig)
except OSError:
pass
class Trainer(object):
""" Trainer is responsible for setting up the players and game.
"""
def __init__(self, args, rng=numpy.random.RandomState(), server_port=6001,
coach_port=6002):
self._rng = rng # The Random Number Generator
def __init__(self, args, server_port=6001, coach_port=6002):
self._serverPort = server_port # The port the server is listening on
self._coachPort = coach_port # The coach port to talk with the server
self._logDir = args.logDir # Directory to store logs
self._record = args.record # Record states + actions
self._numOffense = args.offenseAgents + args.offenseNPCs # Number offensive players
self._numDefense = args.defenseAgents + args.defenseNPCs # Number defensive players
self._maxTrials = args.numTrials # Maximum number of trials to play
self._maxFrames = args.numFrames # Maximum number of frames to play
self._maxFramesPerTrial = args.maxFramesPerTrial
# =============== FIELD DIMENSIONS =============== #
self.NUM_FRAMES_TO_HOLD = 2 # Hold ball this many frames to capture
self.HOLD_FACTOR = 1.5 # Gain to calculate ball control
self.PITCH_WIDTH = 68.0 # Width of the field
self.PITCH_LENGTH = 105.0 # Length of field in long-direction
self.UNTOUCHED_LENGTH = 100 # Trial will end if ball untouched for this long
# allowedBallX, allowedBallY defines the usable area of the playfield
self._allowedBallX = numpy.array([-0.1, 0.5 * self.PITCH_LENGTH])
self._allowedBallY = numpy.array([-0.5 * self.PITCH_WIDTH, 0.5 * self.PITCH_WIDTH])
# =============== COUNTERS =============== #
self._numFrames = 0 # Number of frames seen in HFO trials
self._numGoalFrames = 0 # Number of frames in goal-scoring HFO trials
self._frame = 0 # Current frame id
self._lastTrialStart = -1 # Frame Id in which the last trial started
self._lastFrameBallTouched = -1 # Frame Id in which ball was last touched
# =============== TRIAL RESULTS =============== #
self._numTrials = 0 # Total number of HFO trials
self._numGoals = 0 # Trials in which the offense scored a goal
......@@ -68,31 +36,58 @@ class Trainer(object):
self._numAgents = args.offenseAgents + args.defenseAgents
self._offenseAgents = args.offenseAgents
self._defenseAgents = args.defenseAgents
self._agentReady = set([]) # Unums of ready agents
self._agentTeams = [] # Names of the teams the agents are playing for
self._agentNumInt = [] # List of agents internal team numbers
self._agentNumExt = [] # List of agents external team numbers
self._agentServerPort = args.port # Base Port for agent's server
self._agentOnBall = args.agent_on_ball # If true, agent starts with the ball
# =============== MISC =============== #
self._offenseTeamName = '' # Name of the offensive team
self._defenseTeamName = '' # Name of the defensive team
self._playerPositions = numpy.zeros((11,2,2)) # Positions of the players
self._ballPosition = numpy.zeros(2) # Position of the ball
self._ballHeld = numpy.zeros((11,2)) # Track player holding the ball
self._teams = [] # Team indexes for offensive and defensive teams
self._SP = {} # Sever Parameters. Recieved when connecting to the server.
self._isPlaying = False # Is a game being played?
self._teamHoldingBall = None # Team currently in control of the ball
self._playerHoldingBall = None # Player current in control of ball
self._done = False # Are we finished?
self._agentPopen = [] # Agent's processes
self._npcPopen = [] # NPC's processes
self._connectedPlayers = []
self.initMsgHandlers()
def launch_agent(self, agent_num, play_offense, port):
"""Launch the learning agent using the start_agent.sh script and
return a DummyPopen for the process.
def launch_npc(self, player_num, play_offense, wait_until_join=True):
"""Launches a player using sample_player binary
Returns a Popen process object
"""
print 'Launch npc %s-%d'%(self._offenseTeamName if play_offense
else self._defenseTeamName, player_num)
if play_offense:
team_name = self._offenseTeamName
else:
team_name = self._defenseTeamName
binary_dir = os.path.dirname(os.path.realpath(__file__))
config_dir = os.path.join(binary_dir, '../config/formations-dt')
player_conf = os.path.join(binary_dir, '../config/player.conf')
player_cmd = os.path.join(binary_dir, 'sample_player')
player_cmd += ' -t %s -p %i --config_dir %s ' \
' --log_dir %s --player-config %s' \
%(team_name, self._serverPort, config_dir,
self._logDir, player_conf)
if self._record:
player_cmd += ' --record'
if player_num == 1:
player_cmd += ' -g'
kwargs = {'stdout':open('/dev/null', 'w'),
'stderr':open('/dev/null', 'w')}
p = subprocess.Popen(player_cmd.split(' '), shell = False, **kwargs)
if wait_until_join:
self.waitOnPlayer(player_num, play_offense)
return p
def launch_agent(self, agent_num, agent_ext_num, play_offense, port, wait_until_join=True):
"""Launches a learning agent using the agent binary
Returns a Popen process object
"""
print '[Trainer] Launching Agent', str(agent_num)
print 'Launch agent %s-%d'%(self._offenseTeamName if play_offense
else self._defenseTeamName, agent_num)
if play_offense:
assert self._numOffense > 0
team_name = self._offenseTeamName
......@@ -110,30 +105,26 @@ class Trainer(object):
self._agentNumInt.append(internal_player_num)
numTeammates = self._numDefense - 1
numOpponents = self._numOffense
ext_num = self.convertToExtPlayer(team_name, internal_player_num)
self._agentNumExt.append(ext_num)
binary_dir = os.path.dirname(os.path.realpath(__file__))
agentCmd = 'start_agent.sh -t %s -u %i -p %i -P %i --log-dir %s'\
' --numTeammates %i --numOpponents %i'\
' --playingOffense %i --serverPort %i'\
%(team_name, ext_num, self._serverPort,
self._coachPort, self._logDir, numTeammates,
numOpponents, play_offense, port)
config_dir = os.path.join(binary_dir, '../config/formations-dt')
player_conf = os.path.join(binary_dir, '../config/player.conf')
agent_cmd = os.path.join(binary_dir, 'agent')
agent_cmd += ' -t %s -p %i --numTeammates %i --numOpponents %i' \
' --playingOffense %i --serverPort %i --log_dir %s' \
' --player-config %s --config_dir %s' \
%(team_name, self._serverPort, numTeammates,
numOpponents, play_offense, port, self._logDir,
player_conf, config_dir)
if agent_ext_num == 1:
agent_cmd += ' -g'
if self._record:
agentCmd += ' --record'
agentCmd = os.path.join(binary_dir, agentCmd)
agentCmd = agentCmd.split(' ')
# Ignore stderr because librcsc continually prints to it
kwargs = {'stderr':open('/dev/null','w')}
p = subprocess.Popen(agentCmd, **kwargs)
p.wait()
pid_file = os.path.join(self._logDir, 'start%i'%p.pid)
print '[Trainer] Parsing agent\'s pid from file:', pid_file
assert os.path.isfile(pid_file)
with open(pid_file,'r') as f:
output = f.read()
pid = int(re.findall('PID: (\d+)',output)[0])
return DummyPopen(pid)
agent_cmd += ' --record'
kwargs = {'stdout':open('/dev/null', 'w'),
'stderr':open('/dev/null', 'w')}
p = subprocess.Popen(agent_cmd.split(' '), shell = False, **kwargs)
if wait_until_join:
self.waitOnPlayer(agent_ext_num, play_offense)
return p
def getDefensiveRoster(self, team_name):
"""Returns a list of player numbers on a given team that are thought
......@@ -161,6 +152,10 @@ class Trainer(object):
else:
return [11,7,8,9,10,6,3,2,4,5]
def addTeam(self, team_name):
""" Adds a team to the team list"""
self._teams.append(team_name)
def setTeams(self):
""" Sets the offensive and defensive teams and player rosters. """
self._offenseTeamInd = 0
......@@ -214,26 +209,53 @@ class Trainer(object):
# self.send('(eye on)')
self.send('(ear on)')
def _hearRef(self, body):
""" Handles hear messages from referee. """
assert body[0] == 'referee', 'Expected referee message.'
_,ts,event = body
self._frame = int(ts)
if event == 'GOAL':
self._numGoals += 1
self._numGoalFrames += self._frame - self._lastTrialStart
elif event == 'OUT_OF_BOUNDS':
self._numBallsOOB += 1
elif event == 'CAPTURED_BY_DEFENSE':
self._numBallsCaptured += 1
elif event == 'OUT_OF_TIME':
self._numOutOfTime += 1
elif event == 'HFO_FINISHED':
self._done = True
if event in {'GOAL','OUT_OF_BOUNDS','CAPTURED_BY_DEFENSE','OUT_OF_TIME'}:
self._numTrials += 1
print 'EndOfTrial: %d / %d %d %s'%\
(self._numGoals, self._numTrials, self._frame, event)
self._numFrames += self._frame - self._lastTrialStart
self._lastTrialStart = self._frame
def _hear(self, body):
""" Handle a hear message. """
timestep,playerInfo,msg = body
if len(playerInfo) != 3:
if body[0] == 'referee':
self._hearRef(body)
return
_,team,player = playerInfo
timestep,playerInfo,msg = body
try:
_,team,player = playerInfo[:3]
length = int(msg[0])
except:
return
msg = msg[1:length+1]
if msg == 'START':
if self._isPlaying:
print '[Trainer] Already playing, ignoring message'
print 'Already playing, ignoring message'
else:
self.startGame()
elif msg == 'DONE':
raise DoneError
elif msg == 'ready':
print 'Agent Connected:', team, player
self._agentReady.add((team, player))
else:
print '[Trainer] Unhandled message from agent: %s' % msg
print 'Unhandled message from agent: %s' % msg
def initMsgHandlers(self):
""" Create handlers for different messages. """
......@@ -245,7 +267,7 @@ class Trainer(object):
self.ignoreMsg('ok','move')
self.ignoreMsg('ok','recover')
self.ignoreMsg('ok','say')
self.registerMsgHandler(self._handleSP,'server_param')
self.ignoreMsg('server_param')
self.registerMsgHandler(self._hear,'hear')
def recv(self, retryCount=None):
......@@ -260,16 +282,12 @@ class Trainer(object):
""" Check that the next message is same as expected message. """
msg = self.recv(retryCount)
if msg != expectedMsg:
print >>sys.stderr,'[Trainer] Error with message'
print >>sys.stderr,'Error with message'
print >>sys.stderr,' expected: %s' % expectedMsg
print >>sys.stderr,' received: %s' % msg
# print >>sys.stderr,len(expectedMsg),len(msg)
raise ValueError
def extractPoint(self, msg):
""" Extract a point from the provided message. """
return numpy.array(map(float,msg[:2]))
def convertToExtPlayer(self, team, num):
""" Returns the external player number for a given player. """
assert team == self._offenseTeamName or team == self._defenseTeamName,\
......@@ -280,33 +298,6 @@ class Trainer(object):
else:
return self._defenseOrder[num]
def convertFromExtPlayer(self, team, num):
""" Maps external player number to internal player number. """
if team == self._offenseTeamName:
return self._offenseOrder.index(num)
else:
return self._defenseOrder.index(num)
def seeGlobal(self, body):
"""Send a look message to extract global information on ball and
player positions.
"""
self.send('(look)')
self._frame = int(body[0])
for obj in body[1:]:
objType = obj[0]
objData = obj[1:]
if objType[0] == 'g':
continue
elif objType[0] == 'b':
self._ballPosition = self.extractPoint(objData)
elif objType[0] == 'p':
teamName = objType[1]
team = self.teamToInd(teamName)
playerNum = self.convertFromExtPlayer(teamName,int(objType[2]))
self._playerPositions[playerNum,:,team] = self.extractPoint(objData)
def registerMsgHandler(self,handler,*args,**kwargs):
'''Register a message handler.
......@@ -319,7 +310,7 @@ class Trainer(object):
self._msgHandlers.append([args,handler])
else:
if ('quiet' not in kwargs) or (not kwargs['quiet']):
print '[Trainer] Updating handler for %s' % (' '.join(args))
print 'Updating handler for %s' % (' '.join(args))
self._msgHandlers[i] = [args,handler]
def unregisterMsgHandler(self, *args):
......@@ -341,7 +332,7 @@ class Trainer(object):
""" Handle a message using the registered handlers. """
i,prefixLength,handler = self._findHandlerInd(msg)
if i < 0:
print '[Trainer] Unhandled message:',msg[0:2]
print 'Unhandled message:',msg[0:2]
else:
handler(msg[prefixLength:])
......@@ -349,296 +340,71 @@ class Trainer(object):
""" Ignore a certain type of message. """
self.registerMsgHandler(lambda x: None,*args,**kwargs)
def _handleSP(self, body):
""" Handler for the sever params message. """
for param in body:
try:
val = int(param[1])
except:
try:
val = float(param[1])
except:
val = param[1]
self._SP[param[0]] = val
def listenAndProcess(self):
def listenAndProcess(self, retry_count=None):
""" Gather messages and process them. """
msg = self.recv()
msg = self.recv(retry_count)
assert((msg[0] == '(') and (msg[-1] == ')')),'|%s|' % msg
msg = self.parseMsg(msg)
self.handleMsg(msg)
def _readTeamNames(self,body):
""" Read the names of each of the teams. """
self._teams = []
for _,_,team in body:
self._teams.append(team)
time.sleep(0.1)
self.send('(team_names)')
def disconnectPlayer(self, player, player_num, on_offense):
"""Wait on a launched player to disconnect from the server. """
# print 'Disconnect %s-%d'%(self._offenseTeamName if on_offense
# else self._defenseTeamName, player_num)
team_name = self._offenseTeamName if on_offense else self._defenseTeamName
self.send('(disconnect_player %s %d)'%(team_name, player_num))
player.kill()
def waitOnTeam(self, first):
"""Wait on a given team. First indicates if this is the first team
connected or the second.
def waitOnPlayer(self, player_num, on_offense):
"""Wait on a launched player to connect and be reported by the
server.
"""
self.send('(team_names)')
partial = ['ok','team_names']
self.registerMsgHandler(self._readTeamNames,*partial,quiet=True)
while len(self._teams) < (1 if first else 2):
self.send('(look)')
partial = ['ok','look']
self._numPlayers = 0
def f(body):
del self._connectedPlayers[:]
for i in xrange(4, len(body)):
_,team,num = body[i][0][:3]
if (team, num) not in self._connectedPlayers:
self._connectedPlayers.append((team,num))
self.registerMsgHandler(f,*partial,quiet=True)
team_name = self._offenseTeamName if on_offense else self._defenseTeamName
while (team_name, str(player_num)) not in self._connectedPlayers:
self.listenAndProcess()
#self.unregisterMsgHandler(*partial)
self.send('(look)')
self.ignoreMsg(*partial,quiet=True)
def checkIfAllPlayersConnected(self):
""" Returns true if all players are connected. """
print 'Checking all players are connected'
self.send('(look)')
partial = ['ok','look']
self._numPlayers = 0
def f(x):
self._numPlayers = len(x) - 4 # -4 for time, ball, goal_l, and goal_r
self.send('(look)')
self.registerMsgHandler(f,*partial)
while self._numPlayers != 2 * 11:
self.registerMsgHandler(f,*partial,quiet=True)
while self._numPlayers != self._numOffense + self._numDefense:
self.listenAndProcess()
self.ignoreMsg(*partial,quiet=True)
def startGame(self):
""" Starts a game of HFO. """
self.reset()
self.registerMsgHandler(self.seeGlobal, 'see_global')
self.registerMsgHandler(self.seeGlobal, 'ok', 'look', quiet=True)
#self.registerMsgHandler(self.checkBall,'ok','check_ball')
self.send('(look)')
self._isPlaying = True
def calcBallHolder(self):
'''Calculates the ball holder, returns results in teamInd, playerInd. '''
totalHeld = 0
for team in self._teams:
for i in range(11):
pos = self._playerPositions[i,:,self.teamToInd(team)]
distBound = self._SP['kickable_margin'] + self._SP['player_size'] \
+ self._SP['ball_size']
distBound *= self.HOLD_FACTOR
if numpy.linalg.norm(self._ballPosition - pos) < distBound:
self._ballHeld[i,self.teamToInd(team)] += 1
totalHeld += 1
else:
self._ballHeld[i,self.teamToInd(team)] = 0
# If multiple players are close to the ball, no-one is holding
if totalHeld > 1:
self._ballHeld[:,:] = 0
inds = numpy.transpose((self._ballHeld >= self.NUM_FRAMES_TO_HOLD).nonzero())
assert(len(inds) <= 1)
if len(inds) == 1:
return inds[0,1],inds[0,0]
else:
return None,None
def isGoal(self):
""" Returns true if a goal has been scored. """
return (self._ballPosition[0] > self._allowedBallX[1]) \
and (numpy.abs(self._ballPosition[1]) <= 0.5 * self._SP['goal_width'])
def isOOB(self):
""" Returns true if the ball is out of bounds. """
return self._ballPosition[0] < self._allowedBallX[0] \
or self._ballPosition[0] > self._allowedBallX[1] \
or self._ballPosition[1] < self._allowedBallY[0] \
or self._ballPosition[1] > self._allowedBallY[1]
def isCaptured(self):
""" Returns true if the ball is captured by defense. """
return self._teamHoldingBall not in [None,self._offenseTeamInd]
def isOOT(self):
""" Returns true if the trial has run out of time. """
return self._frame - self._lastFrameBallTouched > self.UNTOUCHED_LENGTH \
or (self._maxFramesPerTrial > 0 and self._frame -
self._lastTrialStart > self._maxFramesPerTrial)
def movePlayer(self, team, internal_num, pos, convertToExt=True):
""" Move a player to a specified position.
Args:
team: the team name of the player
interal_num: the player's internal number
pos: position to move player to
convertToExt: convert interal player num to external
"""
num = self.convertToExtPlayer(team, internal_num) if convertToExt \
else internal_num
self.send('(move (player %s %i) %f %f)' % (team, num, pos[0], pos[1]))
def moveBall(self, pos):
""" Moves the ball to a specified x,y position. """
self.send('(move (ball) %f %f 0.0 0.0 0.0)' % tuple(pos))
def randomPointInBounds(self, xBounds=None, yBounds=None):
"""Returns a random point inside of the box defined by xBounds,
yBounds. Where xBounds=[x_min, x_max] and yBounds=[y_min,
y_max]. Defaults to the xy-bounds of the playable HFO area.
"""
if xBounds is None:
xBounds = self.allowedBallX
if yBounds is None:
yBounds = self.allowedBallY
pos = numpy.zeros(2)
bounds = [xBounds, yBounds]
for i in range(2):
pos[i] = self._rng.rand() * (bounds[i][1] - bounds[i][0]) + bounds[i][0]
return pos
def boundPoint(self, pos):
"""Ensures a point is within the minimum and maximum bounds of the
HFO playing area.
"""
pos[0] = min(max(pos[0], self._allowedBallX[0]), self._allowedBallX[1])
pos[1] = min(max(pos[1], self._allowedBallY[0]), self._allowedBallY[1])
return pos
def reset(self):
""" Resets the HFO domain by moving the ball and players. """
self.resetBallPosition()
self.resetPlayerPositions()
self.send('(recover)')
self.send('(change_mode play_on)')
# self.send('(say RESET)')
def resetBallPosition(self):
"""Reset the position of the ball for a new HFO trial. """
self._ballPosition = self.boundPoint(self.randomPointInBounds(
.2*self._allowedBallX+.05*self.PITCH_LENGTH, .8*self._allowedBallY))
self.moveBall(self._ballPosition)
def getOffensiveResetPosition(self):
""" Returns a random position for an offensive player. """
offsets = [
[-1,-1],
[-1,1],
[1,1],
[1,-1],
[0,2],
[0,-2],
[-2,-2],
[-2,2],
[2,2],
[2,-2],
]
offset = offsets[self._rng.randint(len(offsets))]
offset_from_ball = 0.1 * self.PITCH_LENGTH * self._rng.rand(2) + \
0.1 * self.PITCH_LENGTH * numpy.array(offset)
return self.boundPoint(self._ballPosition + offset_from_ball)
# return self._ballPosition
def getDefensiveResetPosition(self):
""" Returns a random position for a defensive player. """
return self.boundPoint(self.randomPointInBounds(
[0.5 * 0.5 * self.PITCH_LENGTH, 0.75 * 0.5 * self.PITCH_LENGTH],
0.8 * self._allowedBallY))
def resetPlayerPositions(self):
"""Reset the positions of the players. This is called after a trial
ends to setup for the next trial.
"""
# Always Move the offensive goalie to the left goal
self.movePlayer(self._offenseTeamName, 0, [-0.5 * self.PITCH_LENGTH, 0])
# Move the rest of the offense
for i in xrange(1, self._numOffense + 1):
self.movePlayer(self._offenseTeamName, i, self.getOffensiveResetPosition())
# Move the agent to the ball
if self._agentOnBall and self._offenseAgents > 0:
self.movePlayer(self._offenseTeamName, self._agentNumInt[0], self._ballPosition)
# Move the defensive goalie
if self._numDefense > 0:
self.movePlayer(self._defenseTeamName, 0, [0.5 * self.PITCH_LENGTH,0])
# Move the rest of the defense
for i in xrange(1, self._numDefense):
self.movePlayer(self._defenseTeamName, i, self.getDefensiveResetPosition())
def removeNonHFOPlayers(self):
"""Removes players that aren't involved in HFO game.
The players whose numbers are greater than numOffense/numDefense
are sent to left-field.
"""
offensive_agent_numbers = self._agentNumInt[:self._offenseAgents]
defensive_agent_numbers = self._agentNumInt[self._offenseAgents:]
for i in xrange(self._numOffense + 1, 11):
if i not in offensive_agent_numbers:
self.movePlayer(self._offenseTeamName, i, [-0.25 * self.PITCH_LENGTH, 0])
for i in xrange(self._numDefense, 11):
if i not in defensive_agent_numbers:
self.movePlayer(self._defenseTeamName, i, [-0.25 * self.PITCH_LENGTH, 0])
def step(self):
""" Takes a simulated step. """
# self.send('(check_ball)')
self.removeNonHFOPlayers()
self._teamHoldingBall, self._playerHoldingBall = self.calcBallHolder()
if self._teamHoldingBall is not None:
self._lastFrameBallTouched = self._frame
if self.trialOver():
self.updateResults()
self._lastFrameBallTouched = self._frame
self.reset()
def updateResults(self):
""" Updates the various members after a trial has ended. """
if self.isGoal():
self._numGoals += 1
self._numGoalFrames += self._frame - self._lastTrialStart
result = 'Goal'
self.send('(say GOAL)')
elif self.isOOB():
self._numBallsOOB += 1
result = 'Out of Bounds'
self.send('(say OUT_OF_BOUNDS)')
elif self.isCaptured():
self._numBallsCaptured += 1
result = 'Defense Captured'
self.send('(say CAPTURED_BY_DEFENSE)')
elif self.isOOT():
self._numOutOfTime += 1
result = 'Ball untouched for too long'
self.send('(say OUT_OF_TIME)')
else:
print '[Trainer] Error: Unable to detect reason for End of Trial!'
sys.exit(1)
self._numTrials += 1
print '[Trainer] EndOfTrial: %d / %d %d %s'%\
(self._numGoals, self._numTrials, self._frame, result)
self._numFrames += self._frame - self._lastTrialStart
self._lastTrialStart = self._frame
if (self._maxTrials > 0) and (self._numTrials >= self._maxTrials):
raise DoneError
if (self._maxFrames > 0) and (self._numFrames >= self._maxFrames):
raise DoneError
def trialOver(self):
"""Returns true if the trial has ended for one of the following
reasons: Goal scored, out of bounds, captured by defense, or
untouched for too long.
"""
# The trial is still being setup, it cannot be over.
if self._frame - self._lastTrialStart < 5:
return False
return self.isGoal() or self.isOOB() or self.isCaptured() or self.isOOT()
self._isPlaying = True
def printStats(self):
print '[Trainer] TotalFrames = %i, AvgFramesPerTrial = %.1f, AvgFramesPerGoal = %.1f'\
print 'TotalFrames = %i, AvgFramesPerTrial = %.1f, AvgFramesPerGoal = %.1f'\
%(self._numFrames,
self._numFrames / float(self._numTrials) if self._numTrials > 0 else float('nan'),
self._numGoalFrames / float(self._numGoals) if self._numGoals > 0 else float('nan'))
print '[Trainer] Trials : %i' % self._numTrials
print '[Trainer] Goals : %i' % self._numGoals
print '[Trainer] Defense Captured : %i' % self._numBallsCaptured
print '[Trainer] Balls Out of Bounds: %i' % self._numBallsOOB
print '[Trainer] Out of Time : %i' % self._numOutOfTime
print 'Trials : %i' % self._numTrials
print 'Goals : %i' % self._numGoals
print 'Defense Captured : %i' % self._numBallsCaptured
print 'Balls Out of Bounds: %i' % self._numBallsOOB
print 'Out of Time : %i' % self._numOutOfTime
def checkLive(self, necProcesses):
"""Returns true if each of the necessary processes is still alive and
......@@ -647,23 +413,65 @@ class Trainer(object):
"""
for p,name in necProcesses:
if p.poll() is not None:
print '[Trainer] Something necessary closed (%s), exiting' % name
print 'Something necessary closed (%s), exiting' % name
return False
return True
def run(self, necProcesses):
""" Run the trainer """
try:
for agent_num in xrange(self._offenseAgents):
port = self._agentServerPort + agent_num
agent = self.launch_agent(agent_num, play_offense=True, port=port)
self._agentPopen.append(agent)
necProcesses.append([agent, 'offense_agent_' + str(agent_num)])
for agent_num in xrange(self._defenseAgents):
port = self._agentServerPort + agent_num + self._offenseAgents
agent = self.launch_agent(agent_num, play_offense=False, port=port)
self._agentPopen.append(agent)
necProcesses.append([agent, 'defense_agent_' + str(agent_num)])
self.setTeams()
offense_unums = self._offenseOrder[1: self._numOffense + 1]
sorted_offense_agent_unums = sorted(self._offenseOrder[1:self._offenseAgents+1])
defense_unums = self._defenseOrder[: self._numDefense]
sorted_defense_agent_unums = sorted(self._defenseOrder[:self._defenseAgents])
# Launch offense
agent_num = 0
for player_num in xrange(1, 12):
if agent_num < self._offenseAgents and player_num == sorted_offense_agent_unums[agent_num]:
port = self._agentServerPort + agent_num
agent = self.launch_agent(agent_num, sorted_offense_agent_unums[agent_num],
play_offense=True, port=port)
self._agentPopen.append(agent)
necProcesses.append([agent, 'offense_agent_' + str(agent_num)])
agent_num += 1
else:
player = self.launch_npc(player_num, play_offense=True)
if player_num in offense_unums:
self._npcPopen.append(player)
necProcesses.append([player, 'offense_npc_' + str(player_num)])
else:
self.disconnectPlayer(player, player_num, on_offense=True)
# Launch defense
agent_num = 0
for player_num in xrange(1, 12):
if agent_num < self._defenseAgents and player_num == sorted_defense_agent_unums[agent_num]:
port = self._agentServerPort + agent_num + self._offenseAgents
agent = self.launch_agent(agent_num, sorted_defense_agent_unums[agent_num],
play_offense=False, port=port)
self._agentPopen.append(agent)
necProcesses.append([agent, 'defense_agent_' + str(agent_num)])
agent_num += 1
else:
player = self.launch_npc(player_num, play_offense=False)
if player_num in defense_unums:
self._npcPopen.append(player)
necProcesses.append([player, 'defense_npc_' + str(player_num)])
else:
self.disconnectPlayer(player, player_num, on_offense=False)
self.checkIfAllPlayersConnected()
if self._numAgents > 0:
print 'Agents awaiting your connections'
necOff = set([(self._offenseTeamName,str(x)) for x in sorted_offense_agent_unums])
necDef = set([(self._defenseTeamName,str(x)) for x in sorted_defense_agent_unums])
necAgents = necOff.union(necDef)
while self.checkLive(necProcesses) and self._agentReady != necAgents:
self.listenAndProcess(10)
# Broadcast the HFO configuration
offense_nums = ' '.join([str(self.convertToExtPlayer(self._offenseTeamName, i))
for i in xrange(1, self._numOffense + 1)])
......@@ -674,22 +482,33 @@ class Trainer(object):
%(self._offenseTeamName, self._defenseTeamName,
self._numOffense, self._numDefense,
offense_nums, defense_nums))
print 'Starting game'
self.startGame()
while self.checkLive(necProcesses):
while self.checkLive(necProcesses) and not self._done:
prevFrame = self._frame
self.listenAndProcess()
if self._frame != prevFrame:
self.step()
except TimeoutError:
print '[Trainer] Haven\'t heard from the server for too long, Exiting'
print 'Haven\'t heard from the server for too long, Exiting'
except (KeyboardInterrupt, DoneError):
print '[Trainer] Finished'
print 'Finished'
finally:
for p in self._agentPopen:
p.send_signal(SIGINT)
try:
self._comm.sendMsg('(bye)')
except:
pass
for p in self._agentPopen:
try:
p.terminate()
time.sleep(0.1)
p.kill()
except:
pass
for p in self._npcPopen:
try:
p.terminate()
time.sleep(0.1)
p.kill()
except:
pass
self._comm.close()
self.printStats()
......@@ -86,6 +86,7 @@
#include <rcsc/player/say_message_builder.h>
#include <rcsc/player/audio_sensor.h>
#include <rcsc/player/freeform_parser.h>
#include <rcsc/player/free_message.h>
#include <rcsc/common/basic_client.h>
#include <rcsc/common/logger.h>
......@@ -108,6 +109,7 @@
#include <sys/types.h>
#include <sys/socket.h>
#include <netinet/in.h>
#include <poll.h>
using namespace rcsc;
using namespace hfo;
......@@ -119,7 +121,7 @@ Agent::Agent()
M_action_generator(createActionGenerator()),
lastTrainerMessageTime(-1),
server_port(6008),
server_running(false),
client_connected(false),
num_teammates(-1),
num_opponents(-1),
playing_offense(false)
......@@ -230,12 +232,14 @@ bool Agent::initImpl(CmdLineParser & cmd_parser) {
assert(num_teammates >= 0);
assert(num_opponents >= 0);
startServer(server_port);
return true;
}
void Agent::startServer(int server_port) {
std::cout << "[Agent Server] Starting Server on Port " << server_port << std::endl;
struct sockaddr_in serv_addr, cli_addr;
struct sockaddr_in serv_addr;
sockfd = socket(AF_INET, SOCK_STREAM, 0);
if (sockfd < 0) {
perror("[Agent Server] ERROR opening socket");
......@@ -250,16 +254,32 @@ void Agent::startServer(int server_port) {
exit(1);
}
listen(sockfd, 5);
socklen_t clilen = sizeof(cli_addr);
std::cout << "[Agent Server] Waiting for client to connect... " << std::endl;
newsockfd = accept(sockfd, (struct sockaddr *) &cli_addr, &clilen);
if (newsockfd < 0) {
perror("[Agent Server] ERROR on accept");
close(sockfd);
exit(1);
}
void Agent::listenForConnection() {
int rv;
struct pollfd ufd;
ufd.fd = sockfd;
ufd.events = POLLIN;
rv = poll(&ufd, 1, 1000);
if (rv == -1) {
perror("poll"); // error occurred in poll()
} else if (rv == 0) {
std::cout << "[Agent Server] Waiting for client to connect... " << std::endl;
} else {
if (ufd.revents & POLLIN) {
struct sockaddr_in cli_addr;
socklen_t clilen = sizeof(cli_addr);
newsockfd = accept(sockfd, (struct sockaddr *) &cli_addr, &clilen);
if (newsockfd < 0) {
perror("[Agent Server] ERROR on accept");
close(sockfd);
exit(1);
}
std::cout << "[Agent Server] Connected" << std::endl;
clientHandshake();
}
}
std::cout << "[Agent Server] Connected" << std::endl;
server_running = true;
}
void Agent::clientHandshake() {
......@@ -316,6 +336,9 @@ void Agent::clientHandshake() {
exit(1);
}
std::cout << "[Agent Server] Handshake complete" << std::endl;
client_connected = true;
rcsc::FreeMessage<5> *free_msg = new FreeMessage<5>("ready");
addSayMessage(free_msg);
}
FeatureExtractor* Agent::getFeatureExtractor(feature_set_t feature_set_indx,
......@@ -367,9 +390,13 @@ status_t Agent::getGameStatus(const rcsc::AudioSensor& audio_sensor,
virtual method in super class
*/
void Agent::actionImpl() {
if (!server_running) {
startServer(server_port);
clientHandshake();
// For now let's not worry about turning the neck or setting the vision.
this->setViewAction(new View_Tactical());
this->setNeckAction(new Neck_TurnToBallOrScan());
if (!client_connected) {
listenForConnection();
return;
}
// Update and send the game status
......@@ -451,10 +478,6 @@ void Agent::actionImpl() {
close(sockfd);
exit(1);
}
// For now let's not worry about turning the neck or setting the vision.
this->setViewAction(new View_Tactical());
this->setNeckAction(new Neck_TurnToBallOrScan());
}
/*-------------------------------------------------------------------*/
......
......@@ -72,7 +72,7 @@ protected:
// Start the server and listen for a connection.
void startServer(int server_port=6008);
void listenForConnection();
// Transmit information to the client and ensure it can recieve.
void clientHandshake();
......@@ -80,7 +80,7 @@ protected:
FeatureExtractor* feature_extractor;
long lastTrainerMessageTime; // Last time the trainer sent a message
int server_port; // Port to start the server on
bool server_running; // Is the server running?
bool client_connected; // Has the client connected and handshake?
int sockfd, newsockfd; // Server sockets
int num_teammates, num_opponents;
bool playing_offense;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment