Welcome to RFC Cambridge’s documentation!¶
Welcome to our documentation! Good luck.
Comms Module¶
-
class
comms.comms.Comms(team, is_second_comms=False)¶ Comms class spins a thread to repeated send the commands stored in gamestate to the robots via radio
-
post_run()¶ This function is called exactly once after the last iteratation of self.run() but before the provider is destroyed. Override this to do de-initialization.
-
pre_run()¶ This function is called exactly once whenever a provider is started, and before self.run() is called. Override this function to do initialization that it wouldn’t be possible to to in self.run() (which gets called repeatedly).
-
run()¶ Handle provider specific logic. This function is continuously repeatedly called AT MINIMUM once every second but likely much much more frequently.
It should modify self.gs which will be sent back to the coordinator. Needs to be implemented in child classes.
-
-
comms.robot_commands.TEAM_COMMAND_MESSAGE_LENGTH= 26¶ Contains information about a robot’s command state. Provides functions for deriving lower level commands from high level (i.e. waypoints => (x, y, w)) Also specifies message serialization to interface with firmware.
Gamestate Module¶
-
class
gamestate.gamestate.GameState¶ Game state contains all raw game information in one place. Many threads can edit and use the game state at once, cuz Python GIL Since using python, data types are specified in the comments below. Fundamental physics and game rules functions available from gamestate.
-
get_latest_refbox_message()¶ Returns latest refbox message as an object. See referee.proto for specifications.
-
-
class
gamestate.gamestate_field.Field¶ Part of the Gamestate class we’ve separated out for readability
-
defense_area_corner(team)¶ returns bottom left corner of defense area
-
random_position()¶ return a random position inside the field
-
-
class
gamestate.gamestate_analysis.Analysis¶ Fundamental analysis functions for gamestate that are shared between simulator and strategy - think physics stuff.
-
ball_in_dribbler_single_frame(team, robot_id, ball_pos=None)¶ if ball is in position to be dribbled
-
ball_overlap(pos)¶ overlap of position and ball
-
dribbler_pos(team, robot_id)¶ returns the x, y position in center of robot’s dribbler
-
get_ball_velocity()¶ Here we find ball velocity at most recent timestamp from position data
-
is_ball_in_play()¶ Return whether the ball is in play (i.e. can be played by robots of either team). Approach borrowed from RobocupULaval/StrategyAI/auto_play.py.
-
is_position_open(pos, team, robot_id, buffer_dist=0)¶ return whether robot can be in a location without colliding with another robot
-
is_robot_front_sector(robot_pos, pos)¶ if position is in front face of robot
-
is_shot_coming(team)¶ return where in goal ball is going to if it is going in
-
overlap(pos1, pos2, radius_sum)¶ returns the amount of overlap between circles as (x, y) vector
-
robot_at_position(pos)¶ return robot team and id occupying a current position, if any
-
robot_ball_overlap(robot_pos, ball_pos=None)¶ overlap between robot and ball
-
robot_overlap(pos1, pos2, buffer_dist=0)¶ overlap between two robots
-
Refbox Module¶
-
class
refbox.refbox.RefboxClient(ip='224.5.23.1', port=10003)¶ A client class to get information from the refbox.
-
connect()¶ Connects to the socket but doesn’t start receiving packets yet
- Raises
ValueError – If IP is not string
ValueError – If port is not int type
-
disconnect()¶ Closes the socket
-
receive()¶ Receive a single packet from the refbox
- Returns
The protobuf message from the refbox
- Return type
SSL_Referee
- Raises
socket.timeout exception if no packets are received –
-
-
class
refbox.refbox.RefboxDataProvider(ip='224.5.23.1', port=10003)¶ A wrapper around a RefboxClient to help update a gamestate object Link to SSL Referee User Manual:
-
post_run()¶ Stop updating the gamestate and close the client
-
pre_run()¶ Start updating the gamestate with the latest info.
-
run()¶ A loop to receive the latest packets.
-
Strategy Module¶
-
class
strategy.strategy.Strategy(team, strategy_name)¶ Control loop for playing the game. Calculate desired robot actions, and enters commands into gamestate to be sent by comms
-
full_team_test()¶ Test of a full team setup
-
pre_run()¶ This function is called exactly once whenever a provider is started, and before self.run() is called. Override this function to do initialization that it wouldn’t be possible to to in self.run() (which gets called repeatedly).
-
run()¶ Handle provider specific logic. This function is continuously repeatedly called AT MINIMUM once every second but likely much much more frequently.
It should modify self.gs which will be sent back to the coordinator. Needs to be implemented in child classes.
-
-
class
strategy.analysis.Analysis¶ The high level analysis class
-
RRT_path_find(start_pos, goal_pos, robot_id, lim=1000, allow_illegal=False)¶ generate RRT waypoints
-
attacker_get_open(robot_id: int, pos_rating=None) → Tuple[float, float, float]¶ Sends the attacker to a locally optimal position. Uses pos_rating (rate_attacker_pos by default) to rate positions.
-
best_kick_pos(from_pos: Tuple[float, float], to_pos: Tuple[float, float]) → Tuple[float, float, float]¶ determine the best robot position to kick in desired direction
-
block_goal_center_pos(max_distance_from_goal: float, ball_pos: bool = None, team: bool = None)¶ Return position between the ball and the goal, at a particular distance from the goal
-
find_attacker_pos(robot_id: int) → Tuple[float, float, float]¶ Finds a position for attacker to get open if the ball is outside shooting range. To be deprecated soon; use attacker_get_open(self, robot_id) instead.
-
find_legal_pos(robot_id: int, position=None, perpendicular=False) → Tuple[float, float, float]¶ Returns a nearby legal and open position by searching around the robot. Searches perpendicular to the path to the goal first if perpendicular is set to True. Returns the current position if it is legal.
-
first_path_obstacle(s_pos, g_pos, robot_id, buffer_dist=0, allow_illegal=False)¶ finds first obstacle in a linear robot trajectory
-
get_future_ball_array()¶ Samples incrementally to return array of future predicted ball positions
-
greedy_path_find(start_pos, goal_pos, robot_id, lim=10, allow_illegal: bool = False)¶ Heuristic path finder
-
identify_enemy_threat_level_advanced(defender_id)¶ Seeks to identify enemy threat using distance, openness, and other factors, and returns ids ranked by decreasing level of threat
-
intercept_distances(other_team=False, ids=None)¶ Returns intercept distances for a team as a dictionary
-
intercept_range(robot_id: int) → Tuple[Tuple[float, float], Tuple[float, float]]¶ find the range for which a robot can reach the ball in its trajectory
- @return position1, position2:
returns the positions between which robots can intercept the ball. returns None if interception is not possible
-
is_path_blocked(s_pos, g_pos, robot_id, buffer_dist=0, allow_illegal=False)¶ incrementally check a linear path for obstacles
-
is_straight_path_open(s_pos, g_pos, ignore_ids=[], ignore_opp_ids=[], buffer=None)¶ Checks if a straight path is open, without worrying about whether it is legal for robots. Should be used when finding a path to send the ball.
-
rank_intercept_distances(other_team=False, ids=None)¶ Returns ids and intercept distances as a dictionary sorted in increasing order
-
rate_attacker_pos(pos: Tuple[float, float, float], robot_id: int) → float¶ Function that scores how good a position is for the attacker to get open for a pass. Higher ratings should indicate better positions
-
rate_deep_attacker_pos(pos: Tuple[float, float, float], robot_id: int) → float¶ Function that scores how good a position is for the attacker to get open for a pass while staying deep if necessary. This attacker does not approach the other team’s goal, and it just tries to get into a safe position. Higher ratings should indicate better positions. Written in a separate function to make changing easier.
-
rate_pass_pos(pos: Tuple[float, float, float], robot_id: int) → float¶ Function that scores how good a position is for the attacker to get open for a pass. Higher ratings should indicate better positions.
-
safest_intercept_point(robot_id: int) → Tuple[float, float]¶ determine the point in the ball’s trajectory that the robot can reach soonest relative to the ball (even if it’s too late)
-
-
class
strategy.actions.Actions¶ Definitions + supporting logic for simple robot actions (have a single step/end condition, return True when done)
-
charge_up_to(robot_id, kick_speed: float) → bool¶ Charge kicker up to a power level that attains a specific kick_speed. Definition of kick speed is specified in the robot commands API/lib.
-
full_path_find(robot_id: int, goal_pos: Tuple[float, float, float], allow_illegal: bool = False) → bool¶ Tries to find a legal non-colliding path to goal position. If goal position is not legal or is blocked, goes somewhere nearby.
-
path_find(robot_id: int, goal_pos: Tuple[float, float, float], allow_illegal: bool = False) → bool¶ Makes the robot to start moving to a destination using a greedy approach
-
pivot_with_ball(robot_id, face_pos: Tuple[float, float]) → bool¶ Move robot around ball without losing possession
-
pivot_with_ball_speeds(robot_id, face_pos: Tuple[float, float]) → bool¶ Move robot around ball without losing possession
-
turn_toward(robot_id, face_pos: Tuple[float, float]) → bool¶ Turn robot toward a position without losing possession if it has the ball
-
-
class
strategy.plays.Plays¶ Full team role assignment for specific game cases. Used for very common plays that are called frequently no matter the game strategy.
-
avoid_ball(robot_ids=None, distance=500, speed_limit=1500)¶ Specified (all by default) robots stay at least the specified distance away from the ball.
-
avoid_ball_penalty(robot_ids=None, distance=1000, speed_limit=1500)¶ Specified robots (all by default) stay at least the specified distance behind the ball for a penalty.
-
form_wall(ids, distance_from_ball: float = 500) → None¶ Form a defensive wall. The robots in ids will form a wall between the ball position and the goal at the specified distance, in a direction perpendicular to the line between the ball and the center of goal and centered on that line.
-
kickoff(defending=False)¶ Preparation for kickoff instructions
-
prepare_penalty()¶ Instructions to prepare for when our team takes a penalty
-
timeout() → None¶ Run a timeout play. All robots should stop whatever they’re doing and immediate go out of bounds at coordinates:
TODO: Add coordinates for timeout
-
-
class
strategy.roles.Roles¶ High level strategic roles and analysis
-
attacker_off_ball(robot_id)¶ Commands a given robot id to play as attacker without a ball
-
attacker_off_ball2(robot_id)¶ Commands a given robot id to play as attacker without a ball
-
attacker_on_ball(robot_id)¶ Attacker that has the ball
-
deep_attacker(robot_id)¶ Commands a given robot id to play as attacker without a ball
-
defender2(robot_id)¶ Defender that stays back and blocks enemies that might be a threat
-
goalie(robot_id, is_opposite_goal=False)¶ Commands a given robot id to play as goalie
-
penalty_taker(robot_id)¶ Prepares to take a penalty kick when the penalty command is issued
-
-
strategy.roles.random() → x in the interval [0, 1).¶
-
class
strategy.routines.Routines¶ Definitions + supporting logic for multi-step sequences of actions Use simple state management, return whether finished
-
get_ball(robot_id, charge_during=0)¶ Command robot to go to the ball and start dribbling it
-
prepare_and_kick(robot_id: int, kick_pos: Tuple[float, float, float], min_charge: float = 0) → bool¶ Command robot to get into position, charge to given level, & kick
-
-
class
strategy.utils.Utils¶ Strategy helper functions for geometry + working with commands
-
append_waypoint(robot_id: int, goal_pos: Tuple[float, float], is_urgent=False) → None¶ format + single waypoint into robot commands
-
face_pos(facing_from_pos: Tuple[float, float], facing_towards_pos: Tuple[float, float]) → float¶ Return angle (relative to the x axis) betweeen two positions
-
get_goal_pos(robot_id: int) → Tuple[float, float, float]¶ Return a robot’s final waypoint
-
is_done_moving(robot_id: int) → bool¶ Check if robot has arrived at final waypoint, angle included
-
robot_face_ball(robot_id: int) → float¶ Return angle from robot to ball
-
robot_face_pos(robot_id: int, pos: Tuple[float, float])¶ Return angle from robot to position
-
set_waypoints(robot_id: int, waypoints: List[Tuple[float, float]], is_urgent: bool = False) → None¶ format + insert list of waypoints into robot commands
-
wrap_pi(angle: float) → float¶ convert angle to between -pi and pi
-
Simulator Module¶
-
class
simulator.simulator.Simulator(initial_setup)¶ Simulator class spins to update gamestate instead of vision and comms. Applies rudimentary physics and commands, to allow offline prototyping.
-
pre_run()¶ This function is called exactly once whenever a provider is started, and before self.run() is called. Override this function to do initialization that it wouldn’t be possible to to in self.run() (which gets called repeatedly).
-
put_fake_ball(position, velocity=None)¶ initialize ball position data to reflect desired position + velocity
-
put_fake_robot(team: str, robot_id: int, position: Tuple[float, float, float]) → None¶ initialize a robot with given id + team at (x, y, w) position
-
run()¶ Handle provider specific logic. This function is continuously repeatedly called AT MINIMUM once every second but likely much much more frequently.
It should modify self.gs which will be sent back to the coordinator. Needs to be implemented in child classes.
-
Vision Module¶
A class to provide robot position data from the cameras
-
class
vision.data_providers.SSLVisionDataProvider(HOST='224.5.23.2', PORT=10006)¶ -
post_run()¶ This function is called exactly once after the last iteratation of self.run() but before the provider is destroyed. Override this to do de-initialization.
-
pre_run()¶ Starts listen to SSL-vision and updating gamestate with new data
-
run()¶ Handle provider specific logic. This function is continuously repeatedly called AT MINIMUM once every second but likely much much more frequently.
It should modify self.gs which will be sent back to the coordinator. Needs to be implemented in child classes.
-
Visualization Module¶
-
class
visualization.visualization.Visualizer(log_level='info')¶ Robocup homegrown visualization library that essentially does the same as the modules in OpenAI gym.
-
field_to_screen(pos: Tuple[float, float]) → Tuple[float, float]¶ Takes in either a tuple (x, y, w) or (x, y) and transforms the first two coordinates into the reference frame in our viewer only.
-
post_run()¶ This function is called exactly once after the last iteratation of self.run() but before the provider is destroyed. Override this to do de-initialization.
-
pre_run()¶ This function is called exactly once whenever a provider is started, and before self.run() is called. Override this function to do initialization that it wouldn’t be possible to to in self.run() (which gets called repeatedly).
-
run()¶ Loop that runs the pygame visualization.
-
screen_to_field(pos: Tuple[float, float]) → Tuple[float, float]¶ Takes in either a tuple representing pixel (x, y) in our GUI/visualizer and returns the corresponding (x’, y’) of the location in real life.
-
Coach Module¶
Coach class that takes in the Strategy class and assembles together high level commands. See https://robocup-ssl.github.io/ssl-rules/sslrules.html#_referee_commands