Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

sSpin.py corrected and it is mergable without previous attacker trash . #16

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
59 changes: 28 additions & 31 deletions PlaySelector.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
import rospy
from krssg_ssl_msgs.msg import BeliefState
from krssg_ssl_msgs.msg import gr_Commands
from krssg_ssl_msgs.msg import Referee
import threading
import time
from std_msgs.msg import Int8
Expand All @@ -18,8 +17,11 @@
from tactics import TDTP,TAttacker
from tactics import TTestIt

from skills import skills_union
from skills import sStop
from skills import skill_node
from skills import sGoToPoint
from utils.role_selector import *

from plays import pStall
from plays import DTP_Play
from plays import pCordinatedPass
Expand All @@ -35,6 +37,7 @@
RDefender_tac = None
cur_goalie = 0

prev_attacker = 3



Expand All @@ -56,20 +59,9 @@ def select_play(state):
# play_Defence = pDefence.pDefence()
# play_Defence.execute()

def referee_callback(msg):
print "Time: {}, Stage: {}, Command: {}".format(msg.packet_timestamp, msg.stage, msg.command)
# global pub, ref_command
# if msg.command == 0:
# ref_command = True
# for i in xrange(6):
# os.environ['bot'+str(i)]=str(start_time)
# skill_node.send_command(pub, isteamyellow, i, 0, 0, 0, 0, False)
# else:
# ref_command = False
# print ("Received referee message",msg.command)
# print ("packet_timestamp ",msg.packet_timestamp)
# global ref_play_id
# ref_play_id = play_id
def ref_callback(play_id):
global ref_play_id
ref_play_id = play_id

def goalKeeper_callback(state):
global pub,goalie_tac,cur_goalie
Expand All @@ -83,11 +75,16 @@ def goalKeeper_callback(state):


def attacker_callback(state):
global pub
attacker_id = 5
global pub,prev_attacker
# print "bef as"
attacker_id = attacker_selector(state)
param = skills_union.SParam()
cur_tactic = TAttacker.TAttacker(attacker_id,state,param)
cur_tactic.execute(state,pub)
if prev_attacker != attacker_id :
sStop.execute(param, state, prev_attacker, pub)
else:
cur_tactic = TAttacker.TAttacker(attacker_id,state,param)
cur_tactic.execute(state,pub)
prev_attacker = attacker_id
print ("attacker : ",attacker_id)

def LDefender_callback(state):
Expand All @@ -112,16 +109,15 @@ def RDefender_callback(state):
RDefender_tac.execute(state,pub)

def planner_callback(state):
global ref_command, pub
if not ref_command:
# print("incoming planner_callback")
bot_id = 0
ballPos = Vector2D(state.ballPos.x, state.ballPos.y)
botpos = Vector2D(state.homePos[bot_id].x,state.homePos[bot_id].y)
# print("dist is ",ballPos.dist(botpos))
new = TestTac.TestTac(bot_id,state)
new.execute(state,pub)
# print(" outgoing planner_callback")
print("incoming planner_callback")
global pub
bot_id = 0
ballPos = Vector2D(state.ballPos.x, state.ballPos.y)
botpos = Vector2D(state.homePos[bot_id].x,state.homePos[bot_id].y)
print("dist is ",ballPos.dist(botpos))
new = TestTac.TestTac(bot_id,state)
new.execute(state,pub)
print(" outgoing planner_callback")

def bs_callback(state):
global cur_play,start_time
Expand Down Expand Up @@ -182,6 +178,7 @@ def main():
# gv.append(GetVelocity(start_time = start_time,kubs_id = i))

pub = rospy.Publisher('/grsim_data', gr_Commands, queue_size=1000)

# rospy.Subscriber("/ref_data", Referee, referee_callback, queue_size=1000)
# rospy.Subscriber('/belief_state', BeliefState, bs_callback, queue_size=1000)
# rospy.Subscriber('/belief_state', BeliefState, goalKeeper_callback, queue_size=1000)
Expand All @@ -190,7 +187,7 @@ def main():
# rospy.Subscriber('/belief_state', BeliefState, LDefender_callback, queue_size=1000)
# rospy.Subscriber('/belief_state', BeliefState, planner_callback, queue_size=1000)
# rospy.Subscriber('/belief_state', BeliefState, RDefender_callback, queue_size=1000)
# rospy.Subscriber('/belief_state', BeliefState, attacker_callback, queue_size=1000)
rospy.Subscriber('/belief_state', BeliefState, attacker_callback, queue_size=1000)
#rospy.Subscriber('/ref_play', Int8, ref_callback, queue_size=1000)
rospy.spin()

Expand Down
4 changes: 2 additions & 2 deletions skills/sSpin.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
import skill_node

def execute(param, state, bot_id):
skill_node.send_command(state.isteamyellow, bot_id, 0, 0, param.SpinP.radPerSec, 0, false)
def execute(param,state,bot_id,pub):
skill_node.send_command(pub , state.isteamyellow , bot_id , 0 , 0 , param.SpinP.radPerSec , 0 , False)
Loading