-
Notifications
You must be signed in to change notification settings - Fork 187
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
Basic defense play #1671
Basic defense play #1671
Changes from 20 commits
3e81acd
422be41
97844cb
f1f4701
7bd18f5
4d3966d
c988e93
59efb8e
8928a48
65af03f
2cfd6df
60191cf
80fa15f
cc824bc
fa03dec
47e8ab0
d52f283
655e7b8
333aaae
5a7df09
f489e55
f33cdef
9de733f
525ceb5
178b0b5
a44c4c7
9754866
5f27732
c2c1d22
1d40929
2820e76
282f503
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,39 @@ | ||
"""This module contains the interface and action for intercept.""" | ||
|
||
from abc import ABC, abstractmethod | ||
|
||
import stp.role as role | ||
import stp.action as action | ||
import stp.rc as rc | ||
import numpy as np | ||
from rj_msgs.msg import RobotIntent, InterceptMotionCommand, SettleMotionCommand | ||
from rj_geometry_msgs.msg import Point | ||
|
||
class Intercept(action.IAction): | ||
"""Intercept action | ||
""" | ||
|
||
def __init__(self, robot_id: int = None, target_point: np.ndarray = None): | ||
self.robot_id = robot_id | ||
self.target_point = target_point | ||
|
||
|
||
def tick(self, intent: RobotIntent) -> None: | ||
""" | ||
# TODO: use this when intercept is fixed | ||
intercept_command = InterceptMotionCommand() | ||
# TODO: numpy to Point conv | ||
intercept_command.target = Point(x=self.target_point[0], y=self.target_point[1]) | ||
intent.motion_command.intercept_command = [intercept_command] | ||
""" | ||
settle_command = SettleMotionCommand() | ||
intent.motion_command.settle_command = [settle_command] | ||
intent.dribbler_speed = 1.0 | ||
intent.is_active = True | ||
|
||
return intent | ||
|
||
def is_done(self, world_state) -> bool: | ||
if world_state.our_robots[self.robot_id].has_ball_sense: | ||
return True | ||
return False |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,64 @@ | ||
import stp.play as play | ||
import stp.tactic as tactic | ||
|
||
from rj_gameplay.tactic import wall_tactic, nmark_tactic, goalie_tactic | ||
import stp.skill as skill | ||
import stp.role as role | ||
from stp.role.assignment.naive import NaiveRoleAssignment | ||
import stp.rc as rc | ||
from typing import Dict, Generic, Iterator, List, Optional, Tuple, Type, TypeVar | ||
|
||
|
||
class BasicDefense(play.IPlay): | ||
"""For when we don't have the ball and are trying to stop the opponent from scoring. | ||
""" | ||
def __init__(self): | ||
self.tactics = [ | ||
wall_tactic.WallTactic(3), | ||
nmark_tactic.NMarkTactic(2), | ||
goalie_tactic.GoalieTactic() | ||
] | ||
|
||
self.role_assigner = NaiveRoleAssignment() | ||
|
||
def compute_props(self, prev_props): | ||
pass | ||
|
||
def tick( | ||
self, | ||
world_state: rc.WorldState, | ||
prev_results: role.assignment.FlatRoleResults, | ||
props, | ||
) -> Tuple[Dict[Type[tactic.SkillEntry], List[role.RoleRequest]], | ||
List[tactic.SkillEntry]]: | ||
|
||
# Get role requests from all tactics and put them into a dictionary | ||
role_requests: play.RoleRequests = { | ||
tactic: tactic.get_requests(world_state, None) | ||
for tactic in self.tactics | ||
} | ||
|
||
# Flatten requests and use role assigner on them | ||
flat_requests = play.flatten_requests(role_requests) | ||
flat_results = self.role_assigner.assign_roles(flat_requests, | ||
world_state, | ||
prev_results) | ||
role_results = play.unflatten_results(flat_results) | ||
|
||
# Get list of all SkillEntries from all tactics | ||
skills = [] | ||
for tactic in self.tactics: | ||
skills += tactic.tick(role_results[tactic]) | ||
|
||
# Get all role assignments | ||
# SkillEntry to (list of?) RoleResult | ||
skill_dict = {} | ||
for tactic in self.tactics: | ||
skill_dict.update(role_results[tactic]) | ||
|
||
return (skill_dict, skills) | ||
|
||
def is_done(self, world_state): | ||
# returns done when all tactics are done | ||
# TODO: change all is_done() to use all()? | ||
return all([tactic.is_done(world_state) for tactic in self.tactics]) |
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -9,11 +9,11 @@ | |
from typing import Dict, Generic, Iterator, List, Optional, Tuple, Type, TypeVar | ||
import numpy as np | ||
|
||
|
||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. this file is identical to the file merged into ros2 recently by #1661, shows here bc I ran |
||
class WallBall(play.IPlay): | ||
""" | ||
Test play for the wall tactic. Directs robots to form a wall between the ball and goal. | ||
""" | ||
|
||
def __init__(self): | ||
# defaults to walling between ball pos and goal pos | ||
self.wall_tactic = wall_tactic.WallTactic(3) | ||
|
@@ -27,14 +27,18 @@ def tick( | |
world_state: rc.WorldState, | ||
prev_results: role.assignment.FlatRoleResults, | ||
props, | ||
) -> Tuple[Dict[Type[tactic.SkillEntry], List[role.RoleRequest]], List[tactic.SkillEntry]]: | ||
) -> Tuple[Dict[Type[tactic.SkillEntry], List[role.RoleRequest]], | ||
List[tactic.SkillEntry]]: | ||
# Get role requests from all tactics and put them into a dictionary | ||
role_requests: play.RoleRequests = {} | ||
role_requests[self.wall_tactic] = self.wall_tactic.get_requests(world_state, None) | ||
role_requests[self.wall_tactic] = self.wall_tactic.get_requests( | ||
world_state, None) | ||
|
||
# Flatten requests and use role assigner on them | ||
flat_requests = play.flatten_requests(role_requests) | ||
flat_results = self.role_assigner.assign_roles(flat_requests, world_state, prev_results) | ||
flat_results = self.role_assigner.assign_roles(flat_requests, | ||
world_state, | ||
prev_results) | ||
role_results = play.unflatten_results(flat_results) | ||
|
||
# Get list of all skills with assigned roles from tactics | ||
|
@@ -44,6 +48,5 @@ def tick( | |
|
||
return (skill_dict, skills) | ||
|
||
def is_done(self ,world_state): | ||
def is_done(self, world_state): | ||
return self.wall_tactic.is_done(world_state) | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,47 @@ | ||
from abc import ABC, abstractmethod | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. again, intercept isn't used because it's broken, feel free to skip |
||
|
||
import rj_gameplay.eval as eval | ||
import argparse | ||
import py_trees | ||
import sys | ||
import time | ||
|
||
import stp.skill as skill | ||
import stp.role as role | ||
import stp.action as action | ||
from rj_gameplay.action import intercept | ||
from stp.skill.action_behavior import ActionBehavior | ||
import stp.rc as rc | ||
import numpy as np | ||
|
||
class IIntercept(skill.ISkill, ABC): | ||
... | ||
|
||
|
||
""" | ||
A skill version of intercept so that actions don't have to be called in tactics | ||
""" | ||
# TODO: discuss collapsing skills/actions | ||
class Intercept(IIntercept): | ||
|
||
def __init__(self, robot: rc.Robot=None, target_point: np.ndarray=np.array([0.0, 0.0])): | ||
self.robot = robot | ||
self.target_point = target_point | ||
|
||
self.__name__ = 'Intercept Skill' | ||
if self.robot is not None: | ||
self.intercept = intercept.Intercept(self.robot.id, target_point) | ||
else: | ||
self.intercept = intercept.Intercept(None, target_point) | ||
self.intercept_behavior = ActionBehavior('Intercept', self.intercept, self.robot) | ||
self.root = self.intercept_behavior | ||
self.root.setup_with_descendants() | ||
|
||
def tick(self, robot: rc.Robot, world_state: rc.WorldState): | ||
self.robot = robot | ||
self.intercept.robot_id = self.robot.id | ||
self.intercept.target_point = self.target_point | ||
return self.root.tick_once(self.robot, world_state) | ||
|
||
def is_done(self, world_state) -> bool: | ||
return self.intercept.is_done(world_state) |
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -24,7 +24,6 @@ class IMove(skill.ISkill, ABC): | |
A skill version of move so that actions don't have to be called in tactics | ||
""" | ||
class Move(IMove): | ||
|
||
def __init__(self, | ||
robot : rc.Robot = None, | ||
target_point : np.ndarray = np.array([0.0,0.0]), | ||
|
@@ -46,7 +45,8 @@ def __init__(self, | |
self.root.setup_with_descendants() | ||
self.__name__ = 'move skill' | ||
|
||
def tick(self, robot: rc.Robot, world_state: rc.WorldState): #returns dict of robot and actions | ||
def tick(self, robot: rc.Robot, | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. again, |
||
world_state: rc.WorldState): #returns dict of robot and actions | ||
self.robot = robot | ||
self.move.target_point = self.target_point | ||
self.move.face_point = self.face_point | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Broken intercept, not sure if it's motion planning side or here. Feel free to skip for now since it's not used.