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

Wall tactic #1661

Merged
merged 28 commits into from
Jun 17, 2021
Merged
Show file tree
Hide file tree
Changes from 17 commits
Commits
Show all changes
28 commits
Select commit Hold shift + click to select a range
5b41bc1
initial commit
kfu02 Jun 3, 2021
9dbac8c
copy move tactic into wall
kfu02 Jun 4, 2021
d43fb25
Merge branch 'ros2' into wall_tactic
kfu02 Jun 7, 2021
0a52a5d
add basic walling infrastructure
kfu02 Jun 7, 2021
98080ca
move skill updates action with tick
kfu02 Jun 8, 2021
99d2df2
move skill updates face point on tick too
kfu02 Jun 8, 2021
db7796c
naive wall tactic implemented
kfu02 Jun 8, 2021
7b9063e
fixed len from def pt, todos added
kfu02 Jun 8, 2021
2e6e543
penalty box added as global obs
kfu02 Jun 11, 2021
eafa1e3
change wall_tactic to move robots on edge of penalty rect
kfu02 Jun 11, 2021
7128681
Merge branch 'ros2' into wall_tactic
kfu02 Jun 11, 2021
2a78343
change to flat wall on line
kfu02 Jun 11, 2021
32259bf
revert to old arc form
kfu02 Jun 11, 2021
1d4a352
clean debug prints, add comments
kfu02 Jun 13, 2021
9ebfa70
reenable face_point
kfu02 Jun 13, 2021
dfa9b14
Revert "penalty box added as global obs" (part of another PR).
kfu02 Jun 14, 2021
2144026
add type hints to returns, fix superfluous class data
kfu02 Jun 14, 2021
54f6039
add missing space
kfu02 Jun 14, 2021
79dcca2
rm unnecessary params
kfu02 Jun 15, 2021
9a6038e
update TODO
kfu02 Jun 15, 2021
6015397
use role req cost fn properly
kfu02 Jun 16, 2021
4bedf5a
deeeeadddd coooddeee
kfu02 Jun 16, 2021
d08ed95
change cost to sec, not m
kfu02 Jun 16, 2021
80de70a
reduce motion planner obs by 10% for our robots radius, introduces cr…
kfu02 Jun 16, 2021
151ceb2
fix invisible robot assignment
kfu02 Jun 16, 2021
0d5c242
Merge branch 'ros2' into wall_tactic
kfu02 Jun 16, 2021
fc051e9
add TODO for invis robot issue
kfu02 Jun 17, 2021
9756688
fix move attribute error (ty Hussain)
kfu02 Jun 17, 2021
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
6 changes: 4 additions & 2 deletions rj_gameplay/rj_gameplay/gameplay_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,8 @@
from stp.global_parameters import GlobalParameterClient
import numpy as np
from rj_gameplay.action.move import Move
from rj_gameplay.play import basic122
from rj_gameplay.play import wall_ball
from rj_gameplay.play import line_up
from typing import List, Optional, Tuple

NUM_ROBOTS = 16
Expand All @@ -24,7 +25,8 @@ def select(self, world_state: rc.WorldState) -> None:

class TestPlaySelector(situation.IPlaySelector):
def select(self, world_state: rc.WorldState) -> Tuple[situation.ISituation, stp.play.IPlay]:
return (None, basic122.Basic122())
return (None, wall_ball.WallBall())
# return (None, line_up.LineUp())

class GameplayNode(Node):
"""
Expand Down
49 changes: 49 additions & 0 deletions rj_gameplay/rj_gameplay/play/wall_ball.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
import stp.play as play
import stp.tactic as tactic

from rj_gameplay.tactic import wall_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
import numpy as np

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)
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 = {}
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)
role_results = play.unflatten_results(flat_results)

# Get list of all skills with assigned roles from tactics
skill_dict = {}
skills = self.wall_tactic.tick(role_results[self.wall_tactic])
skill_dict.update(role_results[self.wall_tactic])

return (skill_dict, skills)

def is_done(self ,world_state):
return self.wall_tactic.is_done(world_state)

6 changes: 4 additions & 2 deletions rj_gameplay/rj_gameplay/skill/move.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,11 +42,13 @@ def __init__(self,
self.root.setup_with_descendants()
self.__name__ = 'move skill'

def tick(self, robot: rc.Robot, world_state): #returns dict of robot and actions
def tick(self, robot: rc.Robot, world_state: rc.WorldState): #returns dict of robot and actions
self.robot = robot
self.move.target_point = self.target_point
# TODO: figure out why AttributeError: 'Move object has no attribute face_point' keeps popping up (move action does have a face_point)
self.move.face_point = self.face_point
actions = self.root.tick_once(self.robot, world_state)
return actions
# TODO: change so this properly returns the actions intent messages

def is_done(self, world_state):
return self.move.is_done(world_state)
194 changes: 194 additions & 0 deletions rj_gameplay/rj_gameplay/tactic/wall_tactic.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,194 @@
"""Tactic to build a wall between mark pt (e.g. ball) and defense pt (e.g. goal)."""

from dataclasses import dataclass
from typing import List, Optional
from typing import Dict, Generic, List, Optional, Tuple, Type, TypeVar

import stp.action as action
import stp.rc as rc
import stp.tactic as tactic
import stp.role as role

import rj_gameplay.eval
import rj_gameplay.skill as skills
from rj_gameplay.skill import move
import stp.skill as skill
import numpy as np
# TODO: replace w/ global param server
from stp.utils.constants import RobotConstants, BallConstants

class wall_cost(role.CostFn):
"""Cost function for role request.
"""
def __call__(
self,
robot: rc.Robot,
prev_result: Optional["RoleResult"],
world_state: rc.WorldState
) -> float:

# TODO: make closest robots form wall, rather than setting on init
# aka actually use this method
kfu02 marked this conversation as resolved.
Show resolved Hide resolved
return 0.0

def find_wall_pts(num_robots: int, ball_pt: np.ndarray, goal_pt: np.ndarray, world_state: rc.WorldState) -> List[np.ndarray]:
"""Calculates num_robots points to form a wall between the ball and goal.
:return list of wall_pts (as numpy arrays)
"""
# TODO: param server this const
WALL_SPACING = BallConstants.RADIUS * 1.9
kfu02 marked this conversation as resolved.
Show resolved Hide resolved

# dist is slightly greater than penalty box bounds
box_w = world_state.field.penalty_long_dist_m
box_h = world_state.field.penalty_short_dist_m
line_w = world_state.field.line_width_m
DIST_FROM_DEF = RobotConstants.RADIUS + line_w + np.hypot(box_w/2, box_h)

# check if vision is up and running
# (if it is these points should not be equal)
if (ball_pt == goal_pt).all():
kfu02 marked this conversation as resolved.
Show resolved Hide resolved
return None

# get direction vec
dir_vec = (ball_pt - goal_pt) / np.linalg.norm(ball_pt - goal_pt)
wall_vec = np.array([dir_vec[1], -dir_vec[0]])

mid_pt = goal_pt + (dir_vec * DIST_FROM_DEF)
wall_pts = [mid_pt]

# set wall points in middle out pattern, given wall dir vector and WALL_SPACING constant
wall_pts = [mid_pt]
for i in range(num_robots-1):
mult = i//2 + 1
delta = (mult * (2 * RobotConstants.RADIUS + WALL_SPACING)) * wall_vec
if i % 2: delta = -delta
wall_pts.append(mid_pt + delta)

return wall_pts

def match_robots_to_wall(num_robots: int, ball_pt: np.ndarray, goal_pt: np.ndarray, world_state: rc.WorldState) -> Dict[int, Tuple[rc.Robot, np.ndarray]]:
"""Matches all wall_points to a robot.
:return dictionary of robot_id to (rc.Robot, pt)
"""
# assignments[robot_id] = (rc.Robot, pt)
assignments = {}

wall_pts = find_wall_pts(num_robots, ball_pt, goal_pt, world_state)
if not wall_pts:
# sometimes tactic is called before ball_pos is seen
return None

# assign every wall pt a robot to move there
for wall_pt in wall_pts:
robot = robot_to_wall_pt(wall_pt, world_state, assignments)
assignments[robot.id] = (robot, wall_pt)

return assignments

def robot_to_wall_pt(wall_pt: np.ndarray, world_state: rc.WorldState, assignments: Dict[int, Tuple[rc.Robot, np.ndarray]])-> rc.Robot:
kfu02 marked this conversation as resolved.
Show resolved Hide resolved
"""Chooses which robot to move to a specific wall pt.
:return closest Robot object by dist
"""
# find closest robot by dist, return it
min_robot = None
min_dist = float('inf')
for robot in world_state.our_robots:
# prevent duplicate assignments
if robot.id in assignments:
continue

robot_pt = robot.pose[0:2]
dist = np.linalg.norm(robot_pt - wall_pt)
if dist < min_dist:
min_dist = dist
min_robot = robot

return min_robot

class WallTactic(tactic.ITactic):

def __init__(self,
num_robots: int,
ball_pt: np.ndarray = None,
goal_pt: np.ndarray = None,
kfu02 marked this conversation as resolved.
Show resolved Hide resolved
):

self.num_robots = num_robots

# create move SkillEntry for every robot
self.move_list = [
tactic.SkillEntry(move.Move())
for _ in range(num_robots)
]

self.wall_pts = None
self.cost = wall_cost()
self.wall_spots = None

def compute_props(self):
pass

def create_request(self, **kwargs) -> role.RoleRequest:
"""Creates a sane default RoleRequest.
:return: A list of size 1 of a sane default RoleRequest.
"""
pass

def get_requests(
self, world_state: rc.WorldState, props
) -> List[tactic.RoleRequests]:
"""
:return: A list of role requests for move skills needed
"""

if world_state and world_state.ball.visible:
# update world_state, ball pos, goal loc
# TODO: resolve scenario when ball_pt/goal_pt don't need to be updated every tick (e.g. manually given)
ball_pt = world_state.ball.pos
goal_pt = world_state.field.our_goal_loc

# get dict of robot to pos in wall
self.wall_spots = match_robots_to_wall(self.num_robots, ball_pt, goal_pt, world_state)
if self.wall_spots is not None:
i = 0
for robot, pt in self.wall_spots.values():
# assign correct robots, target points to each move skill
self.move_list[i].skill.robot = robot
self.move_list[i].skill.target_point = pt
i += 1

# make all robots face ball_pt on move
for move_skill_entry in self.move_list:
move_skill_entry.skill.face_point = ball_pt

# create a RoleRequest for each SkillEntry
role_requests = {
move_skill_entry: [role.RoleRequest(role.Priority.LOW, False, self.cost)]
for move_skill_entry in self.move_list
}

return role_requests

def tick(self, role_results: tactic.RoleResults) -> List[tactic.SkillEntry]:
"""
:return: A list of skills depending on which roles are filled
"""

# create list of skills based on if RoleResult exists for SkillEntry
skills = [
move_skill_entry
for move_skill_entry in self.move_list
if role_results[move_skill_entry][0]
]

return skills

def is_done(self, world_state):
"""
:return boolean indicating if tactic is done
"""
for move_skill in self.move_list:
if not move_skill.skill.is_done(world_state):
return False
return True