From 9720dc1197e005246fd5b4ba6e02906e1409f4fe Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 26 Nov 2025 15:50:27 +0000 Subject: [PATCH 001/121] feat: referee support in rsim --- utama_core/entities/game/game_frame.py | 2 + .../src/ssl/envs/standard_ssl.py | 26 +- .../src/ssl/referee_state_machine.py | 289 ++++++++++++++++++ utama_core/run/refiners/referee.py | 29 +- utama_core/run/strategy_runner.py | 34 ++- 5 files changed, 365 insertions(+), 15 deletions(-) create mode 100644 utama_core/rsoccer_simulator/src/ssl/referee_state_machine.py diff --git a/utama_core/entities/game/game_frame.py b/utama_core/entities/game/game_frame.py index 9f815e11..8c06ae37 100644 --- a/utama_core/entities/game/game_frame.py +++ b/utama_core/entities/game/game_frame.py @@ -3,6 +3,7 @@ from dataclasses import dataclass from typing import Dict, Optional +from utama_core.entities.data.referee import RefereeData from utama_core.entities.game.ball import Ball from utama_core.entities.game.field import Field from utama_core.entities.game.robot import Robot @@ -18,6 +19,7 @@ class GameFrame: friendly_robots: Dict[int, Robot] enemy_robots: Dict[int, Robot] ball: Optional[Ball] + referee: Optional[RefereeData] = None def is_ball_in_goal(self, right_goal: bool) -> bool: ball_pos = self.ball.p diff --git a/utama_core/rsoccer_simulator/src/ssl/envs/standard_ssl.py b/utama_core/rsoccer_simulator/src/ssl/envs/standard_ssl.py index b482091c..643f0ce6 100644 --- a/utama_core/rsoccer_simulator/src/ssl/envs/standard_ssl.py +++ b/utama_core/rsoccer_simulator/src/ssl/envs/standard_ssl.py @@ -10,6 +10,7 @@ from utama_core.config.settings import TIMESTEP from utama_core.entities.data.command import RobotResponse from utama_core.entities.data.raw_vision import RawBallData, RawRobotData, RawVisionData +from utama_core.entities.data.referee import RefereeData from utama_core.global_utils.math_utils import deg_to_rad, rad_to_deg from utama_core.rsoccer_simulator.src.Entities import Ball, Frame, Robot from utama_core.rsoccer_simulator.src.ssl.ssl_gym_base import SSLBaseEnv @@ -101,7 +102,16 @@ def __init__( self.blue_formation = LEFT_START_ONE if not blue_starting_formation else blue_starting_formation self.yellow_formation = RIGHT_START_ONE if not yellow_starting_formation else yellow_starting_formation - logger.info(f"{n_robots_blue}v{n_robots_yellow} SSL Environment Initialized") + # Initialize embedded referee state machine + from utama_core.rsoccer_simulator.src.ssl.referee_state_machine import ( + RefereeStateMachine, + ) + + self.referee_state_machine = RefereeStateMachine( + n_robots_blue=n_robots_blue, n_robots_yellow=n_robots_yellow, field=self.field + ) + + logger.info(f"{n_robots_blue}v{n_robots_yellow} SSL Environment Initialized with embedded referee") def reset(self, *, seed=None, options=None): self.reward_shaping_total = None @@ -110,17 +120,22 @@ def reset(self, *, seed=None, options=None): def step(self, action): observation, reward, terminated, truncated, _ = super().step(action) + # Update referee state + current_time = self.time_step * self.steps + self.referee_state_machine.update(self.frame, current_time) + return observation, reward, terminated, truncated, self.reward_shaping_total def _frame_to_observations( self, - ) -> Tuple[RawVisionData, RobotResponse, RobotResponse]: + ) -> Tuple[RawVisionData, RobotResponse, RobotResponse, RefereeData]: """Return observation data that aligns with grSim. - Returns (vision_observation, yellow_robot_feedback, blue_robot_feedback) + Returns (vision_observation, yellow_robot_feedback, blue_robot_feedback, referee_data) vision_observation: closely aligned to SSLVision that returns a FramData object yellow_robots_info: feedback from individual yellow robots that returns a List[RobotInfo] blue_robots_info: feedback from individual blue robots that returns a List[RobotInfo] + referee_data: current referee state from embedded referee state machine """ # Ball observation shared by all robots ball_obs = RawBallData(self.frame.ball.x, -self.frame.ball.y, self.frame.ball.z, 1.0) @@ -146,11 +161,16 @@ def _frame_to_observations( # note that ball_obs stored in list to standardise with SSLVision # As there is sometimes multiple possible positions for the ball + # Get referee data + current_time = self.time_step * self.steps + referee_data = self.referee_state_machine.get_referee_data(current_time) + # Camera id as 0, only one camera for RSim return ( RawVisionData(self.time_step * self.steps, yellow_obs, blue_obs, [ball_obs], 0), yellow_robots_info, blue_robots_info, + referee_data, ) def _get_robot_observation(self, robot): diff --git a/utama_core/rsoccer_simulator/src/ssl/referee_state_machine.py b/utama_core/rsoccer_simulator/src/ssl/referee_state_machine.py new file mode 100644 index 00000000..caa8ec2a --- /dev/null +++ b/utama_core/rsoccer_simulator/src/ssl/referee_state_machine.py @@ -0,0 +1,289 @@ +"""Embedded referee state machine for RSim environment. + +This module implements a referee system for the RSim SSL environment that +generates RefereeData synchronously with simulation steps, maintaining +interface compatibility with network-based referee systems. +""" + +import logging +from typing import Optional + +import numpy as np + +from utama_core.entities.data.referee import RefereeData +from utama_core.entities.game.team_info import TeamInfo +from utama_core.entities.referee.referee_command import RefereeCommand +from utama_core.entities.referee.stage import Stage +from utama_core.rsoccer_simulator.src.Entities import Frame + +logger = logging.getLogger(__name__) + + +class RefereeStateMachine: + """Manages referee state and generates RefereeData for RSim. + + This class detects game events from simulation state, tracks scores and + timers, and generates valid RefereeData objects compatible with the + network-based referee system used in GRSIM/REAL modes. + + Attributes: + stage: Current game stage (NORMAL_FIRST_HALF, etc.) + command: Current referee command (HALT, STOP, NORMAL_START, etc.) + command_counter: Increments each time command changes + command_timestamp: Timestamp when current command was issued + stage_start_time: When current stage started + stage_duration: Duration of current stage in seconds + yellow_team: Team info for yellow team (score, cards, etc.) + blue_team: Team info for blue team + """ + + def __init__( + self, + n_robots_blue: int, + n_robots_yellow: int, + field, + initial_stage: Stage = Stage.NORMAL_FIRST_HALF_PRE, + initial_command: RefereeCommand = RefereeCommand.HALT, + ): + """Initialize referee state machine. + + Args: + n_robots_blue: Number of blue robots + n_robots_yellow: Number of yellow robots + field: Field object with dimensions + initial_stage: Starting game stage + initial_command: Starting referee command + """ + self.n_robots_blue = n_robots_blue + self.n_robots_yellow = n_robots_yellow + self.field = field + + # Field dimensions (meters) + self.field_half_length = field.length / 2 + self.field_half_width = field.width / 2 + + # State tracking + self.stage = initial_stage + self.command = initial_command + self.command_counter = 0 + self.command_timestamp = 0.0 + + # Timers + self.stage_start_time = 0.0 + self.stage_duration = 300.0 # 5 minutes per half + self.action_timeout = None + + # Team info + self.yellow_team = TeamInfo( + name="Yellow", + score=0, + red_cards=0, + yellow_card_times=[], + yellow_cards=0, + timeouts=4, + timeout_time=300, + goalkeeper=0, + foul_counter=0, + ball_placement_failures=0, + can_place_ball=True, + max_allowed_bots=n_robots_yellow, + bot_substitution_intent=False, + bot_substitution_allowed=True, + bot_substitutions_left=5, + ) + + self.blue_team = TeamInfo( + name="Blue", + score=0, + red_cards=0, + yellow_card_times=[], + yellow_cards=0, + timeouts=4, + timeout_time=300, + goalkeeper=0, + foul_counter=0, + ball_placement_failures=0, + can_place_ball=True, + max_allowed_bots=n_robots_blue, + bot_substitution_intent=False, + bot_substitution_allowed=True, + bot_substitutions_left=5, + ) + + # Game state + self.ball_last_touched_by = None + self.ball_placement_target = None + self.next_command = None + self.goal_scored_by = None + + # Event detection state + self.last_ball_position = None + self.last_goal_time = 0.0 + self.goal_cooldown = 0.5 # seconds before detecting another goal + + logger.info( + "RefereeStateMachine initialized: stage=%s, command=%s", + self.stage.name, + self.command.name, + ) + + def update(self, frame: Frame, current_time: float) -> None: + """Update referee state based on simulation frame. + + This should be called every simulation step. + + Args: + frame: Current simulation frame with ball and robot positions + current_time: Current simulation time in seconds + """ + # Detect and process game events + self._detect_and_process_events(frame, current_time) + + # Update timers + self._update_timers(current_time) + + def _detect_and_process_events(self, frame: Frame, current_time: float) -> None: + """Detect game events and update state accordingly. + + Args: + frame: Current simulation frame + current_time: Current simulation time + """ + # Goal detection (with cooldown to prevent multiple detections) + if current_time - self.last_goal_time > self.goal_cooldown: + if self._is_goal(frame): + self._process_goal(current_time) + + def _is_goal(self, frame: Frame) -> bool: + """Detect if ball is in goal. + + Args: + frame: Current simulation frame + + Returns: + True if goal scored, False otherwise + """ + ball = frame.ball + # goal_depth = 0.2 # meters behind goal line + goal_width = self.field.goal_width / 2 # half width + + # Left goal (yellow defends) - negative x + if ball.x < -self.field_half_length and abs(ball.y) < goal_width: + self.goal_scored_by = "blue" + logger.info("Goal scored by blue team!") + return True + + # Right goal (blue defends) - positive x + if ball.x > self.field_half_length and abs(ball.y) < goal_width: + self.goal_scored_by = "yellow" + logger.info("Goal scored by yellow team!") + return True + + return False + + def _process_goal(self, current_time: float) -> None: + """Process a goal event. + + Updates score, sets STOP command, and prepares kickoff for opposite team. + + Args: + current_time: Time when goal was scored + """ + if self.goal_scored_by == "yellow": + self.yellow_team = self.yellow_team._replace(score=self.yellow_team.score + 1) + self.next_command = RefereeCommand.PREPARE_KICKOFF_BLUE + logger.info("Yellow scored! Score: Yellow %d - Blue %d", self.yellow_team.score, self.blue_team.score) + elif self.goal_scored_by == "blue": + self.blue_team = self.blue_team._replace(score=self.blue_team.score + 1) + self.next_command = RefereeCommand.PREPARE_KICKOFF_YELLOW + logger.info("Blue scored! Score: Yellow %d - Blue %d", self.yellow_team.score, self.blue_team.score) + + # Set STOP command after goal + self.command = RefereeCommand.STOP + self.command_counter += 1 + self.command_timestamp = current_time + self.last_goal_time = current_time + + logger.info( + "Referee command: STOP (after goal), next: %s", self.next_command.name if self.next_command else "None" + ) + + def _update_timers(self, current_time: float) -> None: + """Update stage and action timers. + + Args: + current_time: Current simulation time + """ + # Stage timer automatically counts down based on elapsed time + # No action needed here, calculated in _generate_referee_data() + pass + + def _generate_referee_data(self, current_time: float) -> RefereeData: + """Generate RefereeData from current state. + + Args: + current_time: Current simulation time + + Returns: + RefereeData object with current referee state + """ + stage_time_left = max(0, self.stage_duration - (current_time - self.stage_start_time)) + + return RefereeData( + source_identifier="rsim-embedded", + time_sent=current_time, + time_received=current_time, + referee_command=self.command, + referee_command_timestamp=self.command_timestamp, + stage=self.stage, + stage_time_left=stage_time_left, + blue_team=self.blue_team, + yellow_team=self.yellow_team, + designated_position=self.ball_placement_target, + blue_team_on_positive_half=None, + next_command=self.next_command, + current_action_time_remaining=self.action_timeout, + ) + + def get_referee_data(self, current_time: float) -> RefereeData: + """Get current referee data without updating state. + + Args: + current_time: Current simulation time + + Returns: + RefereeData object with current referee state + """ + return self._generate_referee_data(current_time) + + def set_command(self, command: RefereeCommand, timestamp: float = None) -> None: + """Manually set referee command (for testing/scenarios). + + Args: + command: Referee command to set + timestamp: Optional timestamp, uses current command timestamp if None + """ + self.command = command + self.command_counter += 1 + if timestamp is not None: + self.command_timestamp = timestamp + logger.info("Referee command manually set to: %s", command.name) + + def advance_stage(self, new_stage: Stage, timestamp: float) -> None: + """Manually advance to a new stage. + + Args: + new_stage: Stage to advance to + timestamp: Timestamp when stage change occurs + """ + logger.info("Stage advancing from %s to %s", self.stage.name, new_stage.name) + self.stage = new_stage + self.stage_start_time = timestamp + + # Set appropriate duration for new stage + if new_stage in [Stage.NORMAL_FIRST_HALF, Stage.NORMAL_SECOND_HALF]: + self.stage_duration = 300.0 # 5 minutes + elif new_stage in [Stage.EXTRA_FIRST_HALF, Stage.EXTRA_SECOND_HALF]: + self.stage_duration = 150.0 # 2.5 minutes + else: + self.stage_duration = 0.0 diff --git a/utama_core/run/refiners/referee.py b/utama_core/run/refiners/referee.py index 92d5760b..c2e1d9c3 100644 --- a/utama_core/run/refiners/referee.py +++ b/utama_core/run/refiners/referee.py @@ -1,3 +1,4 @@ +import dataclasses from typing import Optional from utama_core.entities.data.referee import RefereeData @@ -8,11 +9,33 @@ class RefereeRefiner(BaseRefiner): - def refine(self, game, data): - return game - + def __init__(self): self._referee_records = [] + def refine(self, game, data: Optional[RefereeData]): + """Process referee data and update game state. + + Args: + game: Current game object + data: Referee data to process (None if no referee) + + Returns: + Updated game object with referee data in frame + """ + if data is None: + return game + + # Add to history + self.add_new_referee_data(data) + + # Update game frame with referee data + new_frame = dataclasses.replace(game.current_frame, referee=data) + + # Update game with new frame + updated_game = game.update_frame(new_frame) + + return updated_game + def add_new_referee_data(self, referee_data: RefereeData) -> None: if not self._referee_records: self._referee_records.append(referee_data) diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index fef8cbe4..fe9f3ec5 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -32,7 +32,12 @@ from utama_core.rsoccer_simulator.src.ssl.envs import SSLStandardEnv from utama_core.run import GameGater from utama_core.run.receivers import VisionReceiver -from utama_core.run.refiners import PositionRefiner, RobotInfoRefiner, VelocityRefiner +from utama_core.run.refiners import ( + PositionRefiner, + RefereeRefiner, + RobotInfoRefiner, + VelocityRefiner, +) from utama_core.strategy.common.abstract_strategy import AbstractStrategy from utama_core.team_controller.src.controllers import ( AbstractSimController, @@ -117,7 +122,7 @@ def __init__( self.position_refiner = PositionRefiner(self.field_bounds) self.velocity_refiner = VelocityRefiner() self.robot_info_refiner = RobotInfoRefiner() - # self.referee_refiner = RefereeRefiner() + self.referee_refiner = RefereeRefiner() ( self.my_game_history, self.my_current_game_frame, @@ -538,20 +543,29 @@ def _run_step(self): """ frame_start = time.perf_counter() if self.mode == Mode.RSIM: - vision_frames = [self.rsim_env._frame_to_observations()[0]] + obs = self.rsim_env._frame_to_observations() + if len(obs) == 4: + # New format with referee + vision_frames = [obs[0]] + referee_data = obs[3] + else: + # Old format without referee (backwards compat) + vision_frames = [obs[0]] + referee_data = None + print(referee_data) else: vision_frames = [buffer.popleft() if buffer else None for buffer in self.vision_buffers] - # referee_frame = ref_buffer.popleft() + referee_data = self.ref_buffer.popleft() if self.ref_buffer else None # alternate between opp and friendly playing if self.toggle_opp_first: if self.opp_strategy: - self._step_game(vision_frames, True) - self._step_game(vision_frames, False) + self._step_game(vision_frames, referee_data, True) + self._step_game(vision_frames, referee_data, False) else: - self._step_game(vision_frames, False) + self._step_game(vision_frames, referee_data, False) if self.opp_strategy: - self._step_game(vision_frames, True) + self._step_game(vision_frames, referee_data, True) self.toggle_opp_first = not self.toggle_opp_first # --- rate limiting --- @@ -581,12 +595,14 @@ def _run_step(self): def _step_game( self, vision_frames: List[RawVisionData], + referee_data, running_opp: bool, ): """Step the game for the robot controller and strategy. Args: vision_frames (List[RawVisionData]): The vision frames. + referee_data: The referee data from RSim or network receiver. running_opp (bool): Whether to run the opponent strategy. """ # Select which side to step @@ -608,7 +624,7 @@ def _step_game( new_game_frame = self.position_refiner.refine(current_game_frame, vision_frames) new_game_frame = self.velocity_refiner.refine(game_history, new_game_frame) # , robot_frame.imu_data) new_game_frame = self.robot_info_refiner.refine(new_game_frame, responses) - # new_game_frame = self.referee_refiner.refine(new_game_frame, responses) + new_game_frame = self.referee_refiner.refine(new_game_frame, referee_data) # Store updated game frame if running_opp: From 4cff9351869adcb6b91d9f4fbbdf06e108da61d8 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 26 Nov 2025 16:02:57 +0000 Subject: [PATCH 002/121] hotfix: self.name bug --- utama_core/entities/referee/stage.py | 4 ---- 1 file changed, 4 deletions(-) diff --git a/utama_core/entities/referee/stage.py b/utama_core/entities/referee/stage.py index 5e92f726..b0693ed2 100644 --- a/utama_core/entities/referee/stage.py +++ b/utama_core/entities/referee/stage.py @@ -26,10 +26,6 @@ def from_id(stage_id: int): except ValueError: raise ValueError(f"Invalid stage ID: {stage_id}") - @property - def name(self): - return self.name - @property def stage_id(self): return self.value From 3f6b0d9a0811d76b32eeb6f9f0a31b9a1d007f64 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 18 Feb 2026 15:32:50 +0000 Subject: [PATCH 003/121] feat: receive complete referee data and use it in strategy runner --- main.py | 2 +- utama_core/entities/data/referee.py | 16 +++++- .../entities/game/current_game_frame.py | 1 + utama_core/entities/game/game.py | 4 ++ utama_core/run/receivers/referee_receiver.py | 3 ++ utama_core/run/refiners/referee.py | 19 +++---- utama_core/run/strategy_runner.py | 52 +++++++++++++------ 7 files changed, 66 insertions(+), 31 deletions(-) diff --git a/main.py b/main.py index 814b3ffe..b9471336 100644 --- a/main.py +++ b/main.py @@ -20,7 +20,7 @@ def main(): strategy=TwoRobotPlacementStrategy(first_robot_id=0, second_robot_id=1, field_bounds=custom_bounds), my_team_is_yellow=True, my_team_is_right=True, - mode="grsim", + mode="rsim", exp_friendly=2, exp_enemy=0, replay_writer_config=ReplayWriterConfig(replay_name="test_replay", overwrite_existing=True), diff --git a/utama_core/entities/data/referee.py b/utama_core/entities/data/referee.py index ba4c331a..9960b834 100644 --- a/utama_core/entities/data/referee.py +++ b/utama_core/entities/data/referee.py @@ -1,4 +1,4 @@ -from typing import NamedTuple, Optional, Tuple +from typing import List, NamedTuple, Optional, Tuple from utama_core.entities.game.team_info import TeamInfo from utama_core.entities.referee.referee_command import RefereeCommand @@ -36,9 +36,23 @@ class RefereeData(NamedTuple): # * ball placement current_action_time_remaining: Optional[int] = None + # All game events detected since the last RUNNING state (e.g. foul type, ball-out side). + # Stored as raw protobuf GameEvent objects. Cleared when the game resumes. + # Useful for logging and future decision-making; not required for basic compliance. + game_events: List = [] + + # Meta information about the match type: + # 0 = UNKNOWN_MATCH, 1 = GROUP_PHASE, 2 = ELIMINATION_PHASE, 3 = FRIENDLY + match_type: int = 0 + + # Human-readable message from the referee UI (e.g. reason for a stoppage). + status_message: Optional[str] = None + def __eq__(self, other): if not isinstance(other, RefereeData): return NotImplemented + # game_events, match_type, and status_message are intentionally excluded + # from equality so they do not trigger spurious re-records in RefereeRefiner. return ( self.stage == other.stage and self.referee_command == other.referee_command diff --git a/utama_core/entities/game/current_game_frame.py b/utama_core/entities/game/current_game_frame.py index 4ae31849..33b851e6 100644 --- a/utama_core/entities/game/current_game_frame.py +++ b/utama_core/entities/game/current_game_frame.py @@ -18,6 +18,7 @@ def __init__(self, game: GameFrame): object.__setattr__(self, "friendly_robots", game.friendly_robots) object.__setattr__(self, "enemy_robots", game.enemy_robots) object.__setattr__(self, "ball", game.ball) + object.__setattr__(self, "referee", game.referee) object.__setattr__(self, "robot_with_ball", self._set_robot_with_ball(game)) object.__setattr__(self, "proximity_lookup", self._init_proximity_lookup(game)) diff --git a/utama_core/entities/game/game.py b/utama_core/entities/game/game.py index 3bb25e18..44d7054d 100644 --- a/utama_core/entities/game/game.py +++ b/utama_core/entities/game/game.py @@ -53,3 +53,7 @@ def robot_with_ball(self): @property def proximity_lookup(self): return self.current.proximity_lookup + + @property + def referee(self): + return self.current.referee diff --git a/utama_core/run/receivers/referee_receiver.py b/utama_core/run/receivers/referee_receiver.py index 50a54a21..f16280f7 100644 --- a/utama_core/run/receivers/referee_receiver.py +++ b/utama_core/run/receivers/referee_receiver.py @@ -179,6 +179,9 @@ def _update_data(self, referee_packet: Referee) -> None: if referee_packet.HasField("current_action_time_remaining") else None ), + game_events=list(referee_packet.game_events), + match_type=referee_packet.match_type, + status_message=referee_packet.status_message if referee_packet.status_message else None, ) # add to referee buffer diff --git a/utama_core/run/refiners/referee.py b/utama_core/run/refiners/referee.py index c2e1d9c3..6171834c 100644 --- a/utama_core/run/refiners/referee.py +++ b/utama_core/run/refiners/referee.py @@ -12,29 +12,24 @@ class RefereeRefiner(BaseRefiner): def __init__(self): self._referee_records = [] - def refine(self, game, data: Optional[RefereeData]): - """Process referee data and update game state. + def refine(self, game_frame, data: Optional[RefereeData]): + """Process referee data and update the game frame. Args: - game: Current game object + game_frame: Current GameFrame object data: Referee data to process (None if no referee) Returns: - Updated game object with referee data in frame + Updated GameFrame with referee data attached, or the original frame if data is None """ if data is None: - return game + return game_frame # Add to history self.add_new_referee_data(data) - # Update game frame with referee data - new_frame = dataclasses.replace(game.current_frame, referee=data) - - # Update game with new frame - updated_game = game.update_frame(new_frame) - - return updated_game + # Return a new GameFrame with referee data injected + return dataclasses.replace(game_frame, referee=data) def add_new_referee_data(self, referee_data: RefereeData) -> None: if not self._referee_records: diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index a338e8fa..c29a78c6 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -33,7 +33,7 @@ from utama_core.rsoccer_simulator.src.ssl.envs import SSLStandardEnv from utama_core.rsoccer_simulator.src.Utils.gaussian_noise import RsimGaussianNoise from utama_core.run import GameGater -from utama_core.run.receivers import VisionReceiver +from utama_core.run.receivers import RefereeMessageReceiver, VisionReceiver from utama_core.run.refiners import ( PositionRefiner, RefereeRefiner, @@ -208,25 +208,23 @@ def data_update_listener(self, receiver: VisionReceiver): # Start receiving game data; this will run in a separate thread. receiver.pull_game_data() - def start_threads(self, vision_receiver: VisionReceiver): # , referee_receiver): - """Start background threads for receiving vision (and referee) data. + def start_threads(self, vision_receiver: VisionReceiver, referee_receiver: RefereeMessageReceiver): + """Start background threads for receiving vision and referee data. Starts daemon threads so they do not prevent process exit. Args: vision_receiver: VisionReceiver to run in a background thread. + referee_receiver: RefereeMessageReceiver to run in a background thread. """ - # Start the data receiving in separate threads vision_thread = threading.Thread(target=vision_receiver.pull_game_data) - # referee_thread = threading.Thread(target=referee_receiver.pull_referee_data) + referee_thread = threading.Thread(target=referee_receiver.pull_referee_data) - # Allows the thread to close when the main program exits vision_thread.daemon = True - # referee_thread.daemon = True + referee_thread.daemon = True - # Start both thread vision_thread.start() - # referee_thread.start() + referee_thread.start() def _load_sim( self, rsim_noise: RsimGaussianNoise, rsim_vanishing: float @@ -306,10 +304,10 @@ def _setup_vision_and_referee(self) -> Tuple[deque, deque]: """ vision_buffers = [deque(maxlen=1) for _ in range(MAX_CAMERAS)] ref_buffer = deque(maxlen=1) - # referee_receiver = RefereeMessageReceiver(ref_buffer, debug=False) vision_receiver = VisionReceiver(vision_buffers) if self.mode != Mode.RSIM: - self.start_threads(vision_receiver) # , referee_receiver) + referee_receiver = RefereeMessageReceiver(ref_buffer) + self.start_threads(vision_receiver, referee_receiver) return vision_buffers, ref_buffer @@ -630,14 +628,13 @@ def _run_step(self): if self.mode == Mode.RSIM: obs = self.rsim_env._frame_to_observations() if len(obs) == 4: - # New format with referee + # New format with referee embedded in observations vision_frames = [obs[0]] referee_data = obs[3] else: - # Old format without referee (backwards compat) + # Standard format — check ref_buffer for externally injected referee data vision_frames = [obs[0]] - referee_data = None - print(referee_data) + referee_data = self.ref_buffer.popleft() if self.ref_buffer else None else: vision_frames = [buffer.popleft() if buffer else None for buffer in self.vision_buffers] referee_data = self.ref_buffer.popleft() if self.ref_buffer else None @@ -670,8 +667,29 @@ def _run_step(self): if self.elapsed_time >= FPS_PRINT_INTERVAL: fps = self.num_frames_elapsed / self.elapsed_time - # Update the live FPS area (one line, no box) - self._fps_live.update(Text(f"FPS: {fps:.2f}")) + ref = self.referee_refiner + stage_secs = ref.stage_time_left + stage_min = int(stage_secs // 60) + stage_sec = int(stage_secs % 60) + + display = Text() + display.append(f"FPS: {fps:.1f}", style="bold cyan") + display.append(" | ") + display.append(ref.last_command.name, style="bold yellow") + display.append(" | ") + display.append(ref.stage.name.replace("_", " ").title()) + display.append(" | Blue ") + display.append(str(ref.blue_team.score), style="bold blue") + display.append(" - ") + display.append(str(ref.yellow_team.score), style="bold yellow") + display.append(" Yellow") + display.append(f" | {stage_min}:{stage_sec:02d} left") + + last_ref = self.referee_refiner._referee_records[-1] if self.referee_refiner._referee_records else None + if last_ref and last_ref.status_message: + display.append(f" | {last_ref.status_message}", style="dim") + + self._fps_live.update(display) self._fps_live.refresh() self.elapsed_time = 0.0 From 27850b1821c69b62e9e265523867ef9bfa5e1d3f Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 18 Feb 2026 15:34:42 +0000 Subject: [PATCH 004/121] feat: referee command nodes and test --- .../strategy/common/abstract_strategy.py | 15 +- utama_core/strategy/referee/__init__.py | 2 + utama_core/strategy/referee/actions.py | 375 ++++++++++++ utama_core/strategy/referee/conditions.py | 31 + utama_core/strategy/referee/tree.py | 270 +++++++++ utama_core/tests/referee/__init__.py | 0 utama_core/tests/referee/referee_sim.py | 163 +++++ utama_core/tests/referee/test_referee_unit.py | 556 ++++++++++++++++++ .../tests/referee/wandering_strategy.py | 119 ++++ 9 files changed, 1530 insertions(+), 1 deletion(-) create mode 100644 utama_core/strategy/referee/__init__.py create mode 100644 utama_core/strategy/referee/actions.py create mode 100644 utama_core/strategy/referee/conditions.py create mode 100644 utama_core/strategy/referee/tree.py create mode 100644 utama_core/tests/referee/__init__.py create mode 100644 utama_core/tests/referee/referee_sim.py create mode 100644 utama_core/tests/referee/test_referee_unit.py create mode 100644 utama_core/tests/referee/wandering_strategy.py diff --git a/utama_core/strategy/common/abstract_strategy.py b/utama_core/strategy/common/abstract_strategy.py index 9a289b7d..f107291f 100644 --- a/utama_core/strategy/common/abstract_strategy.py +++ b/utama_core/strategy/common/abstract_strategy.py @@ -61,7 +61,20 @@ class AbstractStrategy(ABC): """ def __init__(self): - self.behaviour_tree = py_trees.trees.BehaviourTree(self.create_behaviour_tree()) + # Lazy import to break the circular dependency: + # abstract_strategy → referee.tree → referee.conditions → abstract_behaviour + # → strategy.common.__init__ → abstract_strategy + from utama_core.strategy.referee.tree import build_referee_override_tree + + strategy_subtree = self.create_behaviour_tree() + + # Wrap the user's strategy tree with the referee override layer (Option B). + # The root Selector checks referee commands first; if none match (e.g. NORMAL_START + # or FORCE_START), it falls through to the strategy subtree. + root = py_trees.composites.Selector(name="Root", memory=False) + root.add_children([build_referee_override_tree(), strategy_subtree]) + + self.behaviour_tree = py_trees.trees.BehaviourTree(root) ### These attributes are set by the StrategyRunner before the strategy is run. ### self.robot_controller: AbstractRobotController = None diff --git a/utama_core/strategy/referee/__init__.py b/utama_core/strategy/referee/__init__.py new file mode 100644 index 00000000..54ab846e --- /dev/null +++ b/utama_core/strategy/referee/__init__.py @@ -0,0 +1,2 @@ +from utama_core.strategy.referee.conditions import CheckRefereeCommand +from utama_core.strategy.referee.tree import build_referee_override_tree diff --git a/utama_core/strategy/referee/actions.py b/utama_core/strategy/referee/actions.py new file mode 100644 index 00000000..a2d5f049 --- /dev/null +++ b/utama_core/strategy/referee/actions.py @@ -0,0 +1,375 @@ +"""Hardcoded action nodes for each referee game state. + +Each node: + - Reads game state from blackboard.game + - Writes robot commands to blackboard.cmd_map for every friendly robot + - Returns RUNNING (the parent Selector holds here until the command changes) + +All positions are in the ssl-vision coordinate system (metres). +Team side is resolved at tick-time via game.my_team_is_yellow and +game.my_team_is_right so no construction-time team colour is needed. +""" + +import math + +import py_trees + +from utama_core.entities.data.vector import Vector2D +from utama_core.entities.referee.referee_command import RefereeCommand +from utama_core.skills.src.utils.move_utils import empty_command, move +from utama_core.strategy.common.abstract_behaviour import AbstractBehaviour + +# SSL Div B field constants (metres) +_PENALTY_MARK_DIST = 6.0 # distance from goal centre to penalty mark +_HALF_FIELD_X = 4.5 # half field length +_CENTRE_CIRCLE_R = 0.5 # centre circle radius +_BALL_KEEP_DIST = 0.55 # ≥0.5 m required; 5 cm buffer +_PENALTY_BEHIND_OFFSET = 0.4 # robots must be ≥0.4 m behind penalty mark +_OPP_DEF_AREA_KEEP_DIST = 0.25 # ≥0.2 m from opponent defence area; 5 cm buffer + + +def _all_stop(blackboard) -> py_trees.common.Status: + """Send empty_command to every friendly robot and return RUNNING.""" + for robot_id in blackboard.game.friendly_robots: + blackboard.cmd_map[robot_id] = empty_command(False) + return py_trees.common.Status.RUNNING + + +# --------------------------------------------------------------------------- +# HALT — zero velocity, highest priority +# --------------------------------------------------------------------------- + + +class HaltStep(AbstractBehaviour): + """Sends zero-velocity commands to all friendly robots. + + Required: robots must stop immediately on HALT (2-second grace period allowed). + """ + + def update(self) -> py_trees.common.Status: + return _all_stop(self.blackboard) + + +# --------------------------------------------------------------------------- +# STOP — stop in place (≤1.5 m/s; ≥0.5 m from ball) +# Stopping cold satisfies both constraints. +# --------------------------------------------------------------------------- + + +class StopStep(AbstractBehaviour): + """Sends zero-velocity commands to all friendly robots. + + Complies with STOP: robots are stationary, so speed = 0 m/s ≤ 1.5 m/s + and they do not approach the ball. + """ + + def update(self) -> py_trees.common.Status: + return _all_stop(self.blackboard) + + +# --------------------------------------------------------------------------- +# BALL PLACEMENT — ours +# --------------------------------------------------------------------------- + + +class BallPlacementOursStep(AbstractBehaviour): + """Moves the closest friendly robot to the designated_position to place the ball. + + All other robots stop in place. If can_place_ball is False, all robots stop. + + The placing robot drives toward designated_position using the move() skill. + Ball capture and release are handled by the dribbler (future: dribble_subtree). + """ + + def update(self) -> py_trees.common.Status: + game = self.blackboard.game + ref = game.referee + motion_controller = self.blackboard.motion_controller + + # Determine which team is ours + our_team = ref.yellow_team if game.my_team_is_yellow else ref.blue_team + if not getattr(our_team, "can_place_ball", True): + return _all_stop(self.blackboard) + + target = ref.designated_position + if target is None: + return _all_stop(self.blackboard) + + target_pos = Vector2D(target[0], target[1]) + ball = game.ball + + # Pick the placer: robot closest to the ball + placer_id = min( + game.friendly_robots, + key=lambda rid: game.friendly_robots[rid].p.distance_to(ball.p) if ball else float("inf"), + ) + + for robot_id in game.friendly_robots: + if robot_id == placer_id: + # Face the target while approaching + robot = game.friendly_robots[robot_id] + oren = robot.p.angle_to(target_pos) + self.blackboard.cmd_map[robot_id] = move( + game, motion_controller, robot_id, target_pos, oren, dribbling=True + ) + else: + self.blackboard.cmd_map[robot_id] = empty_command(False) + + return py_trees.common.Status.RUNNING + + +# --------------------------------------------------------------------------- +# BALL PLACEMENT — theirs +# --------------------------------------------------------------------------- + + +class BallPlacementTheirsStep(AbstractBehaviour): + """Stops all friendly robots during the opponent's ball placement. + + Robots stopped in place are guaranteed not to approach the ball or interfere + with the placement. Active clearance (move ≥0.5 m from ball) is a future + enhancement. + """ + + def update(self) -> py_trees.common.Status: + return _all_stop(self.blackboard) + + +# --------------------------------------------------------------------------- +# PREPARE_KICKOFF — ours +# --------------------------------------------------------------------------- + +# Kickoff formation positions (own half, outside centre circle). +# Relative x is negative = own half when we are on the right; sign is flipped below. +_KICKOFF_SUPPORT_POSITIONS_RIGHT = [ + Vector2D(-0.8, 0.5), + Vector2D(-0.8, -0.5), + Vector2D(-1.5, 0.8), + Vector2D(-1.5, -0.8), + Vector2D(-2.5, 0.0), +] +_KICKOFF_SUPPORT_POSITIONS_LEFT = [Vector2D(-p.x, p.y) for p in _KICKOFF_SUPPORT_POSITIONS_RIGHT] + + +class PrepareKickoffOursStep(AbstractBehaviour): + """Positions robots for our kickoff. + + Robot with the lowest ID approaches the ball at (0, 0). + All other robots move to own-half support positions outside the centre circle. + """ + + def update(self) -> py_trees.common.Status: + game = self.blackboard.game + motion_controller = self.blackboard.motion_controller + + robot_ids = sorted(game.friendly_robots.keys()) + kicker_id = robot_ids[0] + + # Support positions depend on which side we defend + support_positions = ( + _KICKOFF_SUPPORT_POSITIONS_RIGHT if game.my_team_is_right else _KICKOFF_SUPPORT_POSITIONS_LEFT + ) + + support_idx = 0 + for robot_id in robot_ids: + if robot_id == kicker_id: + # Approach the ball at centre, face the opponent goal + target = Vector2D(0.0, 0.0) + goal_x = _HALF_FIELD_X if not game.my_team_is_right else -_HALF_FIELD_X + oren = math.atan2(0.0 - target.y, goal_x - target.x) + self.blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, target, oren) + else: + pos = support_positions[support_idx % len(support_positions)] + support_idx += 1 + self.blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, pos, 0.0) + + return py_trees.common.Status.RUNNING + + +# --------------------------------------------------------------------------- +# PREPARE_KICKOFF — theirs +# --------------------------------------------------------------------------- + +_KICKOFF_DEFENCE_POSITIONS_RIGHT = [ + Vector2D(-0.8, 0.4), + Vector2D(-0.8, -0.4), + Vector2D(-1.5, 0.6), + Vector2D(-1.5, -0.6), + Vector2D(-2.5, 0.0), + Vector2D(-1.5, 0.0), +] +_KICKOFF_DEFENCE_POSITIONS_LEFT = [Vector2D(-p.x, p.y) for p in _KICKOFF_DEFENCE_POSITIONS_RIGHT] + + +class PrepareKickoffTheirsStep(AbstractBehaviour): + """Moves all our robots to own half, outside the centre circle, for the opponent kickoff.""" + + def update(self) -> py_trees.common.Status: + game = self.blackboard.game + motion_controller = self.blackboard.motion_controller + + positions = _KICKOFF_DEFENCE_POSITIONS_RIGHT if game.my_team_is_right else _KICKOFF_DEFENCE_POSITIONS_LEFT + + for idx, robot_id in enumerate(sorted(game.friendly_robots.keys())): + pos = positions[idx % len(positions)] + self.blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, pos, 0.0) + + return py_trees.common.Status.RUNNING + + +# --------------------------------------------------------------------------- +# PREPARE_PENALTY — ours +# --------------------------------------------------------------------------- + + +class PreparePenaltyOursStep(AbstractBehaviour): + """Positions robots for our penalty kick. + + Kicker (lowest non-keeper ID): moves to our penalty mark, faces goal. + All others: stop on a line 0.4 m behind the penalty mark (on own side). + + Penalty mark is at (opp_goal_x ∓ 6.0, 0), sign depends on which side we attack. + """ + + def update(self) -> py_trees.common.Status: + game = self.blackboard.game + ref = game.referee + motion_controller = self.blackboard.motion_controller + + # Our goalkeeper ID from the referee packet + our_team_info = ref.yellow_team if game.my_team_is_yellow else ref.blue_team + keeper_id = our_team_info.goalkeeper + + # Opponent goal is on the right if we are on the right, else on the left + opp_goal_x = _HALF_FIELD_X if not game.my_team_is_right else -_HALF_FIELD_X + sign = 1 if not game.my_team_is_right else -1 + penalty_mark = Vector2D(opp_goal_x - sign * _PENALTY_MARK_DIST, 0.0) + behind_line_x = penalty_mark.x - sign * _PENALTY_BEHIND_OFFSET + + goal_oren = math.atan2(0.0, opp_goal_x - penalty_mark.x) + + robot_ids = sorted(game.friendly_robots.keys()) + non_keeper_ids = [rid for rid in robot_ids if rid != keeper_id] + kicker_id = non_keeper_ids[0] if non_keeper_ids else robot_ids[0] + + behind_idx = 0 + behind_y_step = 0.35 + for robot_id in robot_ids: + if robot_id == kicker_id: + self.blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, penalty_mark, goal_oren) + else: + # Place behind the line, spread in y + offset = (behind_idx - (len(robot_ids) - 1) / 2.0) * behind_y_step + pos = Vector2D(behind_line_x, offset) + self.blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, pos, 0.0) + behind_idx += 1 + + return py_trees.common.Status.RUNNING + + +# --------------------------------------------------------------------------- +# PREPARE_PENALTY — theirs +# --------------------------------------------------------------------------- + + +class PreparePenaltyTheirsStep(AbstractBehaviour): + """Positions our robots for the opponent's penalty kick. + + Goalkeeper: moves to our goal line centre. + All others: move to a line 0.4 m behind the penalty mark on our half. + """ + + def update(self) -> py_trees.common.Status: + game = self.blackboard.game + ref = game.referee + motion_controller = self.blackboard.motion_controller + + our_team_info = ref.yellow_team if game.my_team_is_yellow else ref.blue_team + keeper_id = our_team_info.goalkeeper + + # Our goal is on the right if my_team_is_right, else on the left + our_goal_x = _HALF_FIELD_X if game.my_team_is_right else -_HALF_FIELD_X + sign = 1 if game.my_team_is_right else -1 + + # Opponent's penalty mark is in their half attacking our goal + opp_penalty_mark_x = our_goal_x - sign * _PENALTY_MARK_DIST + behind_line_x = opp_penalty_mark_x + sign * _PENALTY_BEHIND_OFFSET + + robot_ids = sorted(game.friendly_robots.keys()) + behind_idx = 0 + behind_y_step = 0.35 + + for robot_id in robot_ids: + if robot_id == keeper_id: + # Keeper on own goal line, facing the incoming ball + keeper_pos = Vector2D(our_goal_x, 0.0) + self.blackboard.cmd_map[robot_id] = move( + game, motion_controller, robot_id, keeper_pos, math.pi if game.my_team_is_right else 0.0 + ) + else: + offset = (behind_idx - (len(robot_ids) - 1) / 2.0) * behind_y_step + pos = Vector2D(behind_line_x, offset) + self.blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, pos, 0.0) + behind_idx += 1 + + return py_trees.common.Status.RUNNING + + +# --------------------------------------------------------------------------- +# DIRECT_FREE — ours +# --------------------------------------------------------------------------- + + +class DirectFreeOursStep(AbstractBehaviour): + """Positions our robots for our direct free kick. + + The robot closest to the ball becomes the kicker and drives toward the ball. + All other robots stop in place (they may be repositioned by the strategy tree + after NORMAL_START transitions the override layer to pass-through). + """ + + def update(self) -> py_trees.common.Status: + game = self.blackboard.game + motion_controller = self.blackboard.motion_controller + ball = game.ball + + kicker_id = min( + game.friendly_robots, + key=lambda rid: game.friendly_robots[rid].p.distance_to(ball.p) if ball else float("inf"), + ) + + for robot_id in game.friendly_robots: + if robot_id == kicker_id and ball: + robot = game.friendly_robots[robot_id] + oren = robot.p.angle_to(ball.p) + self.blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, ball.p, oren) + else: + self.blackboard.cmd_map[robot_id] = empty_command(False) + + return py_trees.common.Status.RUNNING + + +# --------------------------------------------------------------------------- +# DIRECT_FREE — theirs +# --------------------------------------------------------------------------- + + +class DirectFreeTheirsStep(AbstractBehaviour): + """Stops all our robots during the opponent's direct free kick. + + All robots must remain ≥ 0.5 m from the ball. Stopping in place satisfies this + assuming robots are not already within 0.5 m (future: add active clearance). + """ + + def update(self) -> py_trees.common.Status: + return _all_stop(self.blackboard) + + +# --------------------------------------------------------------------------- +# Helper: resolve bilateral commands +# --------------------------------------------------------------------------- + + +def is_our_command(command: RefereeCommand, our_command: RefereeCommand, their_command: RefereeCommand) -> bool: + """Not used directly — bilateral resolution is done in tree.py via command sets.""" + return command == our_command diff --git a/utama_core/strategy/referee/conditions.py b/utama_core/strategy/referee/conditions.py new file mode 100644 index 00000000..a0c100d1 --- /dev/null +++ b/utama_core/strategy/referee/conditions.py @@ -0,0 +1,31 @@ +from typing import Tuple + +import py_trees + +from utama_core.entities.referee.referee_command import RefereeCommand +from utama_core.strategy.common.abstract_behaviour import AbstractBehaviour + + +class CheckRefereeCommand(AbstractBehaviour): + """Returns SUCCESS if the current referee command matches any of the given expected commands. + + Returns FAILURE if there is no referee data, or if the command does not match. + Used as the first child of each referee subtree's Sequence so the Sequence fails fast + and the parent Selector moves on to the next subtree. + + Args: + expected_commands: One or more RefereeCommand values to match against. + """ + + def __init__(self, *expected_commands: RefereeCommand): + name = "CheckCmd?" + "|".join(c.name for c in expected_commands) + super().__init__(name=name) + self.expected_commands: Tuple[RefereeCommand, ...] = expected_commands + + def update(self) -> py_trees.common.Status: + ref = self.blackboard.game.referee + if ref is None: + return py_trees.common.Status.FAILURE + if ref.referee_command in self.expected_commands: + return py_trees.common.Status.SUCCESS + return py_trees.common.Status.FAILURE diff --git a/utama_core/strategy/referee/tree.py b/utama_core/strategy/referee/tree.py new file mode 100644 index 00000000..01413d68 --- /dev/null +++ b/utama_core/strategy/referee/tree.py @@ -0,0 +1,270 @@ +"""Factory for the RefereeOverride subtree. + +The RefereeOverride Selector sits as the first (highest-priority) child of the root +Selector in AbstractStrategy. Each child is a Sequence: + + Sequence + ├── CheckRefereeCommand(expected_command, ...) ← FAILURE if no match → Selector continues + └── ← RUNNING while command is active + +When no override matches (e.g. NORMAL_START, FORCE_START), the Selector falls through +to the user's strategy subtree. + +Bilateral commands (KICKOFF / PENALTY / FREE_KICK / BALL_PLACEMENT) are split into +"ours" and "theirs" at tick-time: each action node reads my_team_is_yellow from the +game frame, so no construction-time team colour is needed. +""" + +import py_trees + +from utama_core.entities.referee.referee_command import RefereeCommand +from utama_core.strategy.referee.actions import ( + BallPlacementOursStep, + BallPlacementTheirsStep, + DirectFreeOursStep, + DirectFreeTheirsStep, + HaltStep, + PrepareKickoffOursStep, + PrepareKickoffTheirsStep, + PreparePenaltyOursStep, + PreparePenaltyTheirsStep, + StopStep, +) +from utama_core.strategy.referee.conditions import CheckRefereeCommand + + +def _make_subtree(name: str, condition: CheckRefereeCommand, action: py_trees.behaviour.Behaviour): + """Create a Sequence([condition, action]) subtree for one referee command group.""" + seq = py_trees.composites.Sequence(name=name, memory=False) + seq.add_children([condition, action]) + return seq + + +def build_referee_override_tree() -> py_trees.composites.Selector: + """Build and return the RefereeOverride Selector. + + The returned Selector should be added as the *first* child of the root Selector + in AbstractStrategy so that referee compliance always takes priority over strategy. + + Ours-vs-theirs resolution for bilateral commands: + Each pair of action nodes (e.g. BallPlacementOursStep / BallPlacementTheirsStep) + reads my_team_is_yellow from the game frame at tick-time to determine which role + to play. The CheckRefereeCommand condition simply checks which specific command + (YELLOW or BLUE variant) is active; the action node then maps that to our/their role. + + Priority order (top = highest): + 1. HALT — immediate stop, no exceptions + 2. STOP — slowed stop, keep distance from ball + 3. TIMEOUT — idle (same as STOP) + 4. BALL_PLACEMENT — ours or theirs + 5. PREPARE_KICKOFF + 6. PREPARE_PENALTY + 7. DIRECT_FREE + """ + override = py_trees.composites.Selector(name="RefereeOverride", memory=False) + + # 1. HALT + override.add_child( + _make_subtree( + "Halt", + CheckRefereeCommand(RefereeCommand.HALT), + HaltStep(name="HaltStep"), + ) + ) + + # 2. STOP + override.add_child( + _make_subtree( + "Stop", + CheckRefereeCommand(RefereeCommand.STOP), + StopStep(name="StopStep"), + ) + ) + + # 3. TIMEOUT (yellow or blue — same behaviour: idle) + override.add_child( + _make_subtree( + "Timeout", + CheckRefereeCommand(RefereeCommand.TIMEOUT_YELLOW, RefereeCommand.TIMEOUT_BLUE), + StopStep(name="TimeoutStop"), + ) + ) + + # 4a. BALL_PLACEMENT — yellow team places ball + override.add_child( + _make_subtree( + "BallPlacementYellow", + CheckRefereeCommand(RefereeCommand.BALL_PLACEMENT_YELLOW), + _BallPlacementDispatch(is_yellow_command=True, name="BallPlacementYellowStep"), + ) + ) + + # 4b. BALL_PLACEMENT — blue team places ball + override.add_child( + _make_subtree( + "BallPlacementBlue", + CheckRefereeCommand(RefereeCommand.BALL_PLACEMENT_BLUE), + _BallPlacementDispatch(is_yellow_command=False, name="BallPlacementBlueStep"), + ) + ) + + # 5a. PREPARE_KICKOFF — yellow team kicks off + override.add_child( + _make_subtree( + "KickoffYellow", + CheckRefereeCommand(RefereeCommand.PREPARE_KICKOFF_YELLOW), + _KickoffDispatch(is_yellow_command=True, name="KickoffYellowStep"), + ) + ) + + # 5b. PREPARE_KICKOFF — blue team kicks off + override.add_child( + _make_subtree( + "KickoffBlue", + CheckRefereeCommand(RefereeCommand.PREPARE_KICKOFF_BLUE), + _KickoffDispatch(is_yellow_command=False, name="KickoffBlueStep"), + ) + ) + + # 6a. PREPARE_PENALTY — yellow team takes penalty + override.add_child( + _make_subtree( + "PenaltyYellow", + CheckRefereeCommand(RefereeCommand.PREPARE_PENALTY_YELLOW), + _PenaltyDispatch(is_yellow_command=True, name="PenaltyYellowStep"), + ) + ) + + # 6b. PREPARE_PENALTY — blue team takes penalty + override.add_child( + _make_subtree( + "PenaltyBlue", + CheckRefereeCommand(RefereeCommand.PREPARE_PENALTY_BLUE), + _PenaltyDispatch(is_yellow_command=False, name="PenaltyBlueStep"), + ) + ) + + # 7a. DIRECT_FREE — yellow team's free kick + override.add_child( + _make_subtree( + "DirectFreeYellow", + CheckRefereeCommand(RefereeCommand.DIRECT_FREE_YELLOW), + _DirectFreeDispatch(is_yellow_command=True, name="DirectFreeYellowStep"), + ) + ) + + # 7b. DIRECT_FREE — blue team's free kick + override.add_child( + _make_subtree( + "DirectFreeBlue", + CheckRefereeCommand(RefereeCommand.DIRECT_FREE_BLUE), + _DirectFreeDispatch(is_yellow_command=False, name="DirectFreeBlueStep"), + ) + ) + + return override + + +# --------------------------------------------------------------------------- +# Dispatcher nodes +# +# Each dispatcher reads my_team_is_yellow from the game frame at tick-time +# and delegates to the correct Ours/Theirs action node. +# +# Using separate Ours/Theirs classes directly (rather than conditionals in +# a single node) keeps each action node's logic clean and single-purpose. +# The dispatcher is a thin routing layer that composes them. +# --------------------------------------------------------------------------- + +from utama_core.strategy.common.abstract_behaviour import ( # noqa: E402 + AbstractBehaviour, +) + + +class _BallPlacementDispatch(AbstractBehaviour): + """Routes to BallPlacementOursStep or BallPlacementTheirsStep at tick-time.""" + + def __init__(self, is_yellow_command: bool, name: str): + super().__init__(name=name) + self._is_yellow_command = is_yellow_command + self._ours = BallPlacementOursStep(name="BallPlacementOurs") + self._theirs = BallPlacementTheirsStep(name="BallPlacementTheirs") + + def setup_(self): + # Propagate setup to the inner nodes so their blackboards are initialised + self._ours.setup(is_opp_strat=False) + self._theirs.setup(is_opp_strat=False) + + def update(self) -> py_trees.common.Status: + if self._is_yellow_command == self.blackboard.game.my_team_is_yellow: + self._ours.blackboard = self.blackboard + return self._ours.update() + else: + self._theirs.blackboard = self.blackboard + return self._theirs.update() + + +class _KickoffDispatch(AbstractBehaviour): + """Routes to PrepareKickoffOursStep or PrepareKickoffTheirsStep at tick-time.""" + + def __init__(self, is_yellow_command: bool, name: str): + super().__init__(name=name) + self._is_yellow_command = is_yellow_command + self._ours = PrepareKickoffOursStep(name="KickoffOurs") + self._theirs = PrepareKickoffTheirsStep(name="KickoffTheirs") + + def setup_(self): + self._ours.setup(is_opp_strat=False) + self._theirs.setup(is_opp_strat=False) + + def update(self) -> py_trees.common.Status: + if self._is_yellow_command == self.blackboard.game.my_team_is_yellow: + self._ours.blackboard = self.blackboard + return self._ours.update() + else: + self._theirs.blackboard = self.blackboard + return self._theirs.update() + + +class _PenaltyDispatch(AbstractBehaviour): + """Routes to PreparePenaltyOursStep or PreparePenaltyTheirsStep at tick-time.""" + + def __init__(self, is_yellow_command: bool, name: str): + super().__init__(name=name) + self._is_yellow_command = is_yellow_command + self._ours = PreparePenaltyOursStep(name="PenaltyOurs") + self._theirs = PreparePenaltyTheirsStep(name="PenaltyTheirs") + + def setup_(self): + self._ours.setup(is_opp_strat=False) + self._theirs.setup(is_opp_strat=False) + + def update(self) -> py_trees.common.Status: + if self._is_yellow_command == self.blackboard.game.my_team_is_yellow: + self._ours.blackboard = self.blackboard + return self._ours.update() + else: + self._theirs.blackboard = self.blackboard + return self._theirs.update() + + +class _DirectFreeDispatch(AbstractBehaviour): + """Routes to DirectFreeOursStep or DirectFreeTheirsStep at tick-time.""" + + def __init__(self, is_yellow_command: bool, name: str): + super().__init__(name=name) + self._is_yellow_command = is_yellow_command + self._ours = DirectFreeOursStep(name="DirectFreeOurs") + self._theirs = DirectFreeTheirsStep(name="DirectFreeTheirs") + + def setup_(self): + self._ours.setup(is_opp_strat=False) + self._theirs.setup(is_opp_strat=False) + + def update(self) -> py_trees.common.Status: + if self._is_yellow_command == self.blackboard.game.my_team_is_yellow: + self._ours.blackboard = self.blackboard + return self._ours.update() + else: + self._theirs.blackboard = self.blackboard + return self._theirs.update() diff --git a/utama_core/tests/referee/__init__.py b/utama_core/tests/referee/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/utama_core/tests/referee/referee_sim.py b/utama_core/tests/referee/referee_sim.py new file mode 100644 index 00000000..8f2ea5c3 --- /dev/null +++ b/utama_core/tests/referee/referee_sim.py @@ -0,0 +1,163 @@ +"""Visual RSim simulation for verifying referee command behaviour. + +Run with: + pixi run python utama_core/tests/referee/referee_sim.py + +What it does: + - Starts a 3v3 RSim with StartupStrategy as the base strategy. + - The RefereeOverride tree (built automatically by AbstractStrategy) intercepts + referee commands and overrides robot behaviour accordingly. + - A scripted referee cycles through all referee commands every few seconds so + you can watch how robots respond visually in the RSim window. + +Command cycle (each held for SECS_PER_COMMAND seconds): + 1. HALT → all robots stop immediately + 2. STOP → all robots stop in place + 3. TIMEOUT_YELLOW → all robots idle + 4. PREPARE_KICKOFF_YELLOW → robot 0 approaches centre, others fan out to own half + 5. PREPARE_KICKOFF_BLUE → all robots move to own-half defence positions + 6. PREPARE_PENALTY_YELLOW → kicker at penalty mark, others line up behind + 7. PREPARE_PENALTY_BLUE → goalkeeper on goal line, others line up behind mark + 8. DIRECT_FREE_YELLOW → closest robot approaches ball + 9. DIRECT_FREE_BLUE → all robots stop + 10. BALL_PLACEMENT_YELLOW → closest robot drives to designated position + 11. NORMAL_START → pass-through: StartupStrategy runs freely +""" + +import time + +from utama_core.entities.data.referee import RefereeData +from utama_core.entities.game.team_info import TeamInfo +from utama_core.entities.referee.referee_command import RefereeCommand +from utama_core.entities.referee.stage import Stage +from utama_core.run import StrategyRunner +from utama_core.tests.referee.wandering_strategy import WanderingStrategy + +# --------------------------------------------------------------------------- +# Configuration +# --------------------------------------------------------------------------- + +SECS_PER_COMMAND = 5.0 # seconds to hold each referee command before advancing +MY_TEAM_IS_YELLOW = True +MY_TEAM_IS_RIGHT = True +N_ROBOTS = 3 # robots per side + +# Ball placement designated position (used for BALL_PLACEMENT_* commands) +DESIGNATED_POSITION = (1.0, 0.5) + +# Goalkeeper robot ID used in PREPARE_PENALTY scenarios +GOALKEEPER_ID = 0 + +_COMMAND_SEQUENCE = [ + (RefereeCommand.NORMAL_START, "NORMAL_START — normal play (strategy free)"), + (RefereeCommand.HALT, "HALT — all robots stop immediately"), + (RefereeCommand.STOP, "STOP — all robots idle, keep ball distance"), + (RefereeCommand.TIMEOUT_YELLOW, "TIMEOUT_YELLOW — team idle"), + (RefereeCommand.PREPARE_KICKOFF_YELLOW, "PREPARE_KICKOFF_YELLOW — we kick off"), + (RefereeCommand.PREPARE_KICKOFF_BLUE, "PREPARE_KICKOFF_BLUE — opponent kicks off"), + (RefereeCommand.PREPARE_PENALTY_YELLOW, "PREPARE_PENALTY_YELLOW — our penalty"), + (RefereeCommand.PREPARE_PENALTY_BLUE, "PREPARE_PENALTY_BLUE — opponent penalty"), + (RefereeCommand.DIRECT_FREE_YELLOW, "DIRECT_FREE_YELLOW — our direct free kick"), + (RefereeCommand.DIRECT_FREE_BLUE, "DIRECT_FREE_BLUE — opponent direct free kick"), + (RefereeCommand.BALL_PLACEMENT_YELLOW, "BALL_PLACEMENT_YELLOW — we place the ball"), +] + + +# --------------------------------------------------------------------------- +# Scripted referee state machine +# --------------------------------------------------------------------------- + + +class _ScriptedReferee: + """Cycles through _COMMAND_SEQUENCE, advancing every SECS_PER_COMMAND seconds.""" + + def __init__(self): + self._index = 0 + self._start = time.time() + print("\n=== Referee Visualisation Simulation ===") + print(f"Each command lasts {SECS_PER_COMMAND}s. Press Ctrl+C to stop.\n") + self._print_current() + + def _print_current(self): + cmd, desc = _COMMAND_SEQUENCE[self._index] + print(f" [{self._index + 1}/{len(_COMMAND_SEQUENCE)}] {desc}") + + def current_data(self) -> RefereeData: + now = time.time() + if now - self._start >= SECS_PER_COMMAND: + self._index = (self._index + 1) % len(_COMMAND_SEQUENCE) + self._start = now + self._print_current() + + cmd, _ = _COMMAND_SEQUENCE[self._index] + + is_placement = cmd in ( + RefereeCommand.BALL_PLACEMENT_YELLOW, + RefereeCommand.BALL_PLACEMENT_BLUE, + ) + + yellow_gk = GOALKEEPER_ID if MY_TEAM_IS_YELLOW else GOALKEEPER_ID + blue_gk = GOALKEEPER_ID if not MY_TEAM_IS_YELLOW else GOALKEEPER_ID + + return RefereeData( + source_identifier="scripted", + time_sent=now, + time_received=now, + referee_command=cmd, + referee_command_timestamp=now, + stage=Stage.NORMAL_FIRST_HALF, + stage_time_left=300.0, + blue_team=_team_info(goalkeeper=blue_gk), + yellow_team=_team_info(goalkeeper=yellow_gk), + designated_position=DESIGNATED_POSITION if is_placement else None, + blue_team_on_positive_half=False, + ) + + +def _team_info(goalkeeper: int = 0) -> TeamInfo: + return TeamInfo( + name="Demo", + score=0, + red_cards=0, + yellow_card_times=[], + yellow_cards=0, + timeouts=2, + timeout_time=300_000_000, + goalkeeper=goalkeeper, + ) + + +# --------------------------------------------------------------------------- +# Entry point +# --------------------------------------------------------------------------- + + +def main(): + scripted_referee = _ScriptedReferee() + + runner = StrategyRunner( + strategy=WanderingStrategy(), + my_team_is_yellow=MY_TEAM_IS_YELLOW, + my_team_is_right=MY_TEAM_IS_RIGHT, + mode="rsim", + exp_friendly=N_ROBOTS, + exp_enemy=N_ROBOTS, + print_real_fps=True, + ) + + # Patch _run_step to push scripted RefereeData into ref_buffer before each + # step. StrategyRunner._run_step now reads ref_buffer in RSim mode when + # _frame_to_observations returns the standard 3-tuple. + original_run_step = runner._run_step + + def _patched_run_step(): + runner.ref_buffer.append(scripted_referee.current_data()) + original_run_step() + + runner._run_step = _patched_run_step + + runner.run() + + +if __name__ == "__main__": + main() diff --git a/utama_core/tests/referee/test_referee_unit.py b/utama_core/tests/referee/test_referee_unit.py new file mode 100644 index 00000000..8d6768e3 --- /dev/null +++ b/utama_core/tests/referee/test_referee_unit.py @@ -0,0 +1,556 @@ +"""Unit tests for the referee integration layer. + +Tests cover: + - RefereeData new fields (game_events, match_type, status_message) and custom __eq__ + - RefereeRefiner.refine injects data into GameFrame; deduplication logic + - Game.referee property proxies correctly from CurrentGameFrame + - CheckRefereeCommand condition node (SUCCESS / FAILURE / None-referee guard) + - Dispatcher routing (ours vs. theirs) for bilateral commands + - build_referee_override_tree structure and priority +""" + +from types import SimpleNamespace + +import py_trees +import pytest + +from utama_core.entities.data.referee import RefereeData +from utama_core.entities.data.vector import Vector2D, Vector3D +from utama_core.entities.game.ball import Ball +from utama_core.entities.game.field import Field +from utama_core.entities.game.game import Game +from utama_core.entities.game.game_frame import GameFrame +from utama_core.entities.game.game_history import GameHistory +from utama_core.entities.game.robot import Robot +from utama_core.entities.game.team_info import TeamInfo +from utama_core.entities.referee.referee_command import RefereeCommand +from utama_core.entities.referee.stage import Stage +from utama_core.run.refiners.referee import RefereeRefiner +from utama_core.strategy.referee.conditions import CheckRefereeCommand +from utama_core.strategy.referee.tree import build_referee_override_tree + +# --------------------------------------------------------------------------- +# Helpers +# --------------------------------------------------------------------------- + + +def _team_info(goalkeeper: int = 0) -> TeamInfo: + return TeamInfo( + name="TestTeam", + score=0, + red_cards=0, + yellow_card_times=[], + yellow_cards=0, + timeouts=0, + timeout_time=0, + goalkeeper=goalkeeper, + ) + + +def _make_referee_data( + command: RefereeCommand = RefereeCommand.HALT, + stage: Stage = Stage.NORMAL_FIRST_HALF, + game_events=None, + match_type: int = 0, + status_message=None, +) -> RefereeData: + return RefereeData( + source_identifier="test", + time_sent=1.0, + time_received=1.0, + referee_command=command, + referee_command_timestamp=1.0, + stage=stage, + stage_time_left=300.0, + blue_team=_team_info(goalkeeper=1), + yellow_team=_team_info(goalkeeper=2), + game_events=game_events if game_events is not None else [], + match_type=match_type, + status_message=status_message, + ) + + +def _robot(robot_id: int, x: float = 0.0, y: float = 0.0) -> Robot: + zv = Vector2D(0, 0) + return Robot(id=robot_id, is_friendly=True, has_ball=False, p=Vector2D(x, y), v=zv, a=zv, orientation=0.0) + + +def _ball(x: float = 0.0, y: float = 0.0) -> Ball: + zv = Vector3D(0, 0, 0) + return Ball(p=Vector3D(x, y, 0), v=zv, a=zv) + + +def _make_game_frame( + friendly_robots=None, + referee=None, + my_team_is_yellow: bool = True, + my_team_is_right: bool = True, +) -> GameFrame: + if friendly_robots is None: + friendly_robots = {0: _robot(0)} + return GameFrame( + ts=0.0, + my_team_is_yellow=my_team_is_yellow, + my_team_is_right=my_team_is_right, + friendly_robots=friendly_robots, + enemy_robots={}, + ball=_ball(), + referee=referee, + ) + + +def _make_game( + friendly_robots=None, + referee=None, + my_team_is_yellow: bool = True, + my_team_is_right: bool = True, +) -> Game: + frame = _make_game_frame(friendly_robots, referee, my_team_is_yellow, my_team_is_right) + history = GameHistory() + return Game(past=history, current=frame, field=Field.FULL_FIELD_BOUNDS) + + +def _make_blackboard(game: Game, cmd_map=None): + """Construct a minimal SimpleNamespace blackboard as used by AbstractBehaviour.""" + bb = SimpleNamespace() + bb.game = game + bb.cmd_map = cmd_map if cmd_map is not None else {} + bb.motion_controller = None + return bb + + +# --------------------------------------------------------------------------- +# RefereeData — new fields and __eq__ +# --------------------------------------------------------------------------- + + +class TestRefereeDataNewFields: + def test_default_game_events_is_empty_list(self): + data = _make_referee_data() + assert data.game_events == [] + + def test_default_match_type_is_zero(self): + data = _make_referee_data() + assert data.match_type == 0 + + def test_default_status_message_is_none(self): + data = _make_referee_data() + assert data.status_message is None + + def test_custom_game_events_stored(self): + events = [object(), object()] + data = _make_referee_data(game_events=events) + assert data.game_events is events + + def test_custom_match_type_stored(self): + data = _make_referee_data(match_type=2) + assert data.match_type == 2 + + def test_custom_status_message_stored(self): + data = _make_referee_data(status_message="Foul by blue") + assert data.status_message == "Foul by blue" + + def test_eq_ignores_game_events(self): + """Two records with different game_events but identical core fields must compare equal.""" + a = _make_referee_data(game_events=[]) + b = _make_referee_data(game_events=["something"]) + assert a == b + + def test_eq_ignores_match_type(self): + a = _make_referee_data(match_type=0) + b = _make_referee_data(match_type=3) + assert a == b + + def test_eq_ignores_status_message(self): + a = _make_referee_data(status_message=None) + b = _make_referee_data(status_message="Ball out of bounds") + assert a == b + + def test_eq_sensitive_to_referee_command(self): + a = _make_referee_data(command=RefereeCommand.HALT) + b = _make_referee_data(command=RefereeCommand.STOP) + assert a != b + + def test_eq_sensitive_to_stage(self): + a = _make_referee_data(stage=Stage.NORMAL_FIRST_HALF) + b = _make_referee_data(stage=Stage.NORMAL_SECOND_HALF) + assert a != b + + +# --------------------------------------------------------------------------- +# RefereeRefiner +# --------------------------------------------------------------------------- + + +class TestRefereeRefiner: + def setup_method(self): + self.refiner = RefereeRefiner() + + def test_refine_none_data_returns_original_frame(self): + frame = _make_game_frame() + result = self.refiner.refine(frame, None) + assert result is frame + + def test_refine_injects_referee_into_frame(self): + frame = _make_game_frame(referee=None) + data = _make_referee_data(command=RefereeCommand.STOP) + result = self.refiner.refine(frame, data) + assert result.referee is data + + def test_refine_preserves_other_frame_fields(self): + robots = {0: _robot(0, 1.0, 2.0)} + frame = _make_game_frame(friendly_robots=robots, my_team_is_yellow=False) + data = _make_referee_data() + result = self.refiner.refine(frame, data) + assert result.my_team_is_yellow is False + assert result.friendly_robots == robots + + def test_first_data_is_always_recorded(self): + data = _make_referee_data() + frame = _make_game_frame() + self.refiner.refine(frame, data) + assert len(self.refiner._referee_records) == 1 + + def test_duplicate_data_not_re_recorded(self): + """Records with same core fields (equal by __eq__) are not duplicated.""" + data1 = _make_referee_data() + data2 = _make_referee_data(status_message="different but equal core") + frame = _make_game_frame() + self.refiner.refine(frame, data1) + self.refiner.refine(frame, data2) + assert len(self.refiner._referee_records) == 1 + + def test_changed_command_is_recorded(self): + frame = _make_game_frame() + data1 = _make_referee_data(command=RefereeCommand.HALT) + data2 = _make_referee_data(command=RefereeCommand.STOP) + self.refiner.refine(frame, data1) + self.refiner.refine(frame, data2) + assert len(self.refiner._referee_records) == 2 + + def test_last_command_property(self): + frame = _make_game_frame() + self.refiner.refine(frame, _make_referee_data(command=RefereeCommand.BALL_PLACEMENT_BLUE)) + assert self.refiner.last_command == RefereeCommand.BALL_PLACEMENT_BLUE + + def test_last_command_defaults_to_halt_when_empty(self): + assert self.refiner.last_command == RefereeCommand.HALT + + def test_source_identifier_none_when_empty(self): + assert self.refiner.source_identifier() is None + + def test_source_identifier_after_record(self): + frame = _make_game_frame() + self.refiner.refine(frame, _make_referee_data()) + assert self.refiner.source_identifier() == "test" + + +# --------------------------------------------------------------------------- +# Game.referee property +# --------------------------------------------------------------------------- + + +class TestGameRefereeProperty: + def test_referee_none_when_no_data(self): + game = _make_game(referee=None) + assert game.referee is None + + def test_referee_returns_injected_data(self): + data = _make_referee_data(command=RefereeCommand.STOP) + game = _make_game(referee=data) + assert game.referee is data + + def test_referee_command_accessible(self): + data = _make_referee_data(command=RefereeCommand.PREPARE_KICKOFF_YELLOW) + game = _make_game(referee=data) + assert game.referee.referee_command == RefereeCommand.PREPARE_KICKOFF_YELLOW + + def test_add_game_frame_updates_referee(self): + """After add_game_frame, game.referee reflects the new frame.""" + game = _make_game(referee=None) + assert game.referee is None + + new_data = _make_referee_data(command=RefereeCommand.HALT) + new_frame = _make_game_frame(referee=new_data) + game.add_game_frame(new_frame) + assert game.referee is new_data + + +# --------------------------------------------------------------------------- +# CheckRefereeCommand condition node +# --------------------------------------------------------------------------- + + +def _setup_check_node(*commands: RefereeCommand, game: Game) -> CheckRefereeCommand: + """Build and set up a CheckRefereeCommand node with the given expected commands.""" + # Reset py_trees blackboard between tests + py_trees.blackboard.Blackboard.enable_activity_stream() + node = CheckRefereeCommand(*commands) + node.blackboard = _make_blackboard(game) + return node + + +class TestCheckRefereeCommand: + def test_returns_failure_when_referee_is_none(self): + game = _make_game(referee=None) + node = CheckRefereeCommand(RefereeCommand.HALT) + node.blackboard = _make_blackboard(game) + assert node.update() == py_trees.common.Status.FAILURE + + def test_returns_success_on_matching_single_command(self): + data = _make_referee_data(command=RefereeCommand.HALT) + game = _make_game(referee=data) + node = CheckRefereeCommand(RefereeCommand.HALT) + node.blackboard = _make_blackboard(game) + assert node.update() == py_trees.common.Status.SUCCESS + + def test_returns_failure_on_non_matching_command(self): + data = _make_referee_data(command=RefereeCommand.STOP) + game = _make_game(referee=data) + node = CheckRefereeCommand(RefereeCommand.HALT) + node.blackboard = _make_blackboard(game) + assert node.update() == py_trees.common.Status.FAILURE + + def test_returns_success_on_any_matching_multi_command(self): + for cmd in (RefereeCommand.TIMEOUT_YELLOW, RefereeCommand.TIMEOUT_BLUE): + data = _make_referee_data(command=cmd) + game = _make_game(referee=data) + node = CheckRefereeCommand(RefereeCommand.TIMEOUT_YELLOW, RefereeCommand.TIMEOUT_BLUE) + node.blackboard = _make_blackboard(game) + assert node.update() == py_trees.common.Status.SUCCESS + + def test_returns_failure_when_command_not_in_multi_list(self): + data = _make_referee_data(command=RefereeCommand.HALT) + game = _make_game(referee=data) + node = CheckRefereeCommand(RefereeCommand.TIMEOUT_YELLOW, RefereeCommand.TIMEOUT_BLUE) + node.blackboard = _make_blackboard(game) + assert node.update() == py_trees.common.Status.FAILURE + + def test_node_name_contains_command_names(self): + node = CheckRefereeCommand(RefereeCommand.HALT, RefereeCommand.STOP) + assert "HALT" in node.name + assert "STOP" in node.name + + +# --------------------------------------------------------------------------- +# HaltStep and StopStep — basic output verification +# --------------------------------------------------------------------------- + + +def _make_cmd_map(game: Game) -> dict: + return {rid: None for rid in game.friendly_robots} + + +class TestHaltAndStopStep: + def _run_step(self, step_class, game: Game) -> tuple: + from types import SimpleNamespace + + cmd_map = _make_cmd_map(game) + bb = _make_blackboard(game, cmd_map) + node = step_class(name="TestStep") + node.blackboard = bb + status = node.update() + return status, cmd_map + + def test_halt_returns_running(self): + from utama_core.strategy.referee.actions import HaltStep + + game = _make_game(referee=_make_referee_data(command=RefereeCommand.HALT)) + status, _ = self._run_step(HaltStep, game) + assert status == py_trees.common.Status.RUNNING + + def test_halt_writes_to_all_robots(self): + from utama_core.strategy.referee.actions import HaltStep + + robots = {0: _robot(0), 1: _robot(1)} + game = _make_game(friendly_robots=robots, referee=_make_referee_data()) + status, cmd_map = self._run_step(HaltStep, game) + assert set(cmd_map.keys()) == {0, 1} + for rid in robots: + assert cmd_map[rid] is not None + + def test_stop_returns_running(self): + from utama_core.strategy.referee.actions import StopStep + + game = _make_game(referee=_make_referee_data(command=RefereeCommand.STOP)) + status, _ = self._run_step(StopStep, game) + assert status == py_trees.common.Status.RUNNING + + def test_stop_writes_to_all_robots(self): + from utama_core.strategy.referee.actions import StopStep + + robots = {0: _robot(0), 1: _robot(1), 2: _robot(2)} + game = _make_game(friendly_robots=robots, referee=_make_referee_data()) + status, cmd_map = self._run_step(StopStep, game) + assert set(cmd_map.keys()) == {0, 1, 2} + + +# --------------------------------------------------------------------------- +# build_referee_override_tree — structure checks +# --------------------------------------------------------------------------- + + +class TestRefereeOverrideTreeStructure: + def setup_method(self): + self.tree = build_referee_override_tree() + + def test_root_is_selector(self): + assert isinstance(self.tree, py_trees.composites.Selector) + + def test_root_name(self): + assert self.tree.name == "RefereeOverride" + + def test_has_eleven_children(self): + # HALT, STOP, TIMEOUT, BALL_PLACEMENT×2, KICKOFF×2, PENALTY×2, DIRECT_FREE×2 + assert len(self.tree.children) == 11 + + def test_each_child_is_sequence(self): + for child in self.tree.children: + assert isinstance(child, py_trees.composites.Sequence) + + def test_each_sequence_has_two_children(self): + for child in self.tree.children: + assert len(child.children) == 2 + + def test_each_sequence_first_child_is_check_command(self): + for child in self.tree.children: + assert isinstance(child.children[0], CheckRefereeCommand) + + def test_halt_is_first(self): + first_seq = self.tree.children[0] + condition = first_seq.children[0] + assert RefereeCommand.HALT in condition.expected_commands + + def test_stop_is_second(self): + second_seq = self.tree.children[1] + condition = second_seq.children[0] + assert RefereeCommand.STOP in condition.expected_commands + + def test_timeout_handles_both_colours(self): + timeout_seq = self.tree.children[2] + condition = timeout_seq.children[0] + assert RefereeCommand.TIMEOUT_YELLOW in condition.expected_commands + assert RefereeCommand.TIMEOUT_BLUE in condition.expected_commands + + def test_all_bilateral_commands_covered(self): + """Every bilateral referee command must appear in at least one condition node.""" + covered = set() + for child in self.tree.children: + condition = child.children[0] + covered.update(condition.expected_commands) + + bilateral = { + RefereeCommand.BALL_PLACEMENT_YELLOW, + RefereeCommand.BALL_PLACEMENT_BLUE, + RefereeCommand.PREPARE_KICKOFF_YELLOW, + RefereeCommand.PREPARE_KICKOFF_BLUE, + RefereeCommand.PREPARE_PENALTY_YELLOW, + RefereeCommand.PREPARE_PENALTY_BLUE, + RefereeCommand.DIRECT_FREE_YELLOW, + RefereeCommand.DIRECT_FREE_BLUE, + } + assert bilateral.issubset(covered) + + +# --------------------------------------------------------------------------- +# Dispatcher ours-vs-theirs routing (no actual motion controller required) +# --------------------------------------------------------------------------- + + +def _make_dispatch_blackboard(game: Game) -> SimpleNamespace: + bb = _make_blackboard(game) + return bb + + +class TestDispatcherRouting: + """Verify that dispatcher nodes call the correct Ours/Theirs child based on team colour.""" + + def _tick_dispatcher(self, dispatcher, game: Game) -> py_trees.common.Status: + cmd_map = {rid: None for rid in game.friendly_robots} + bb = _make_blackboard(game, cmd_map) + dispatcher.blackboard = bb + # Propagate blackboard to inner ours/theirs nodes + dispatcher._ours.blackboard = bb + dispatcher._theirs.blackboard = bb + return dispatcher.update() + + def test_ball_placement_yellow_calls_ours_when_yellow(self): + from utama_core.strategy.referee.actions import ( + BallPlacementOursStep, + BallPlacementTheirsStep, + ) + from utama_core.strategy.referee.tree import _BallPlacementDispatch + + data = _make_referee_data(command=RefereeCommand.BALL_PLACEMENT_YELLOW) + # my_team_is_yellow=True, is_yellow_command=True → ours + game = _make_game(referee=data, my_team_is_yellow=True) + dispatcher = _BallPlacementDispatch(is_yellow_command=True, name="test") + + called = [] + # original_ours = dispatcher._ours.update + # original_theirs = dispatcher._theirs.update + dispatcher._ours.update = lambda: called.append("ours") or py_trees.common.Status.RUNNING + dispatcher._theirs.update = lambda: called.append("theirs") or py_trees.common.Status.RUNNING + + self._tick_dispatcher(dispatcher, game) + assert called == ["ours"] + + def test_ball_placement_yellow_calls_theirs_when_blue(self): + from utama_core.strategy.referee.tree import _BallPlacementDispatch + + data = _make_referee_data(command=RefereeCommand.BALL_PLACEMENT_YELLOW) + # my_team_is_yellow=False, is_yellow_command=True → theirs + game = _make_game(referee=data, my_team_is_yellow=False) + dispatcher = _BallPlacementDispatch(is_yellow_command=True, name="test") + + called = [] + dispatcher._ours.update = lambda: called.append("ours") or py_trees.common.Status.RUNNING + dispatcher._theirs.update = lambda: called.append("theirs") or py_trees.common.Status.RUNNING + + self._tick_dispatcher(dispatcher, game) + assert called == ["theirs"] + + def test_kickoff_blue_calls_ours_when_blue(self): + from utama_core.strategy.referee.tree import _KickoffDispatch + + data = _make_referee_data(command=RefereeCommand.PREPARE_KICKOFF_BLUE) + # my_team_is_yellow=False, is_yellow_command=False → ours + game = _make_game(referee=data, my_team_is_yellow=False) + dispatcher = _KickoffDispatch(is_yellow_command=False, name="test") + + called = [] + dispatcher._ours.update = lambda: called.append("ours") or py_trees.common.Status.RUNNING + dispatcher._theirs.update = lambda: called.append("theirs") or py_trees.common.Status.RUNNING + + self._tick_dispatcher(dispatcher, game) + assert called == ["ours"] + + def test_penalty_yellow_calls_theirs_when_blue(self): + from utama_core.strategy.referee.tree import _PenaltyDispatch + + data = _make_referee_data(command=RefereeCommand.PREPARE_PENALTY_YELLOW) + # my_team_is_yellow=False, is_yellow_command=True → theirs + game = _make_game(referee=data, my_team_is_yellow=False) + dispatcher = _PenaltyDispatch(is_yellow_command=True, name="test") + + called = [] + dispatcher._ours.update = lambda: called.append("ours") or py_trees.common.Status.RUNNING + dispatcher._theirs.update = lambda: called.append("theirs") or py_trees.common.Status.RUNNING + + self._tick_dispatcher(dispatcher, game) + assert called == ["theirs"] + + def test_direct_free_blue_calls_ours_when_blue(self): + from utama_core.strategy.referee.tree import _DirectFreeDispatch + + data = _make_referee_data(command=RefereeCommand.DIRECT_FREE_BLUE) + # my_team_is_yellow=False, is_yellow_command=False → ours + game = _make_game(referee=data, my_team_is_yellow=False) + dispatcher = _DirectFreeDispatch(is_yellow_command=False, name="test") + + called = [] + dispatcher._ours.update = lambda: called.append("ours") or py_trees.common.Status.RUNNING + dispatcher._theirs.update = lambda: called.append("theirs") or py_trees.common.Status.RUNNING + + self._tick_dispatcher(dispatcher, game) + assert called == ["ours"] diff --git a/utama_core/tests/referee/wandering_strategy.py b/utama_core/tests/referee/wandering_strategy.py new file mode 100644 index 00000000..3680aa39 --- /dev/null +++ b/utama_core/tests/referee/wandering_strategy.py @@ -0,0 +1,119 @@ +"""WanderingStrategy — base strategy for referee visualisation. + +Each robot cycles through its own list of waypoints on the field indefinitely. +When a referee command fires, the RefereeOverride tree (built into AbstractStrategy) +intercepts before this strategy runs, so you can clearly see robots interrupted +and repositioned by the referee. +""" + +import math + +import py_trees + +from utama_core.entities.data.vector import Vector2D +from utama_core.skills.src.utils.move_utils import move +from utama_core.strategy.common import AbstractBehaviour, AbstractStrategy + +# One waypoint list per robot (by index into sorted robot IDs). +# Robots on the right half defend the right goal, so positions are spread +# across both halves to make motion easy to see. +_WAYPOINT_SETS = [ + # Robot 0 — large figure-8 across the field + [ + Vector2D(-3.0, 1.5), + Vector2D(0.0, 0.0), + Vector2D(3.0, -1.5), + Vector2D(0.0, 0.0), + ], + # Robot 1 — diagonal patrol + [ + Vector2D(-2.0, -2.0), + Vector2D(2.0, 2.0), + ], + # Robot 2 — wide horizontal sweep + [ + Vector2D(-3.5, 0.5), + Vector2D(3.5, 0.5), + Vector2D(3.5, -0.5), + Vector2D(-3.5, -0.5), + ], + # Robot 3 — small loop near centre + [ + Vector2D(1.0, 1.0), + Vector2D(-1.0, 1.0), + Vector2D(-1.0, -1.0), + Vector2D(1.0, -1.0), + ], + # Robot 4 — left-half patrol + [ + Vector2D(-3.0, 0.0), + Vector2D(-1.0, 2.0), + Vector2D(-1.0, -2.0), + ], + # Robot 5 — right-half patrol + [ + Vector2D(3.0, 0.0), + Vector2D(1.0, 2.0), + Vector2D(1.0, -2.0), + ], +] + +_ARRIVAL_THRESHOLD = 0.15 # metres — how close counts as "reached" + + +class WanderingStep(AbstractBehaviour): + """Moves each robot through its waypoint list, advancing when it arrives.""" + + def initialise(self): + # Track waypoint index per robot ID + self._wp_index: dict[int, int] = {} + + def update(self) -> py_trees.common.Status: + game = self.blackboard.game + motion_controller = self.blackboard.motion_controller + + robot_ids = sorted(game.friendly_robots.keys()) + + for slot, robot_id in enumerate(robot_ids): + waypoints = _WAYPOINT_SETS[slot % len(_WAYPOINT_SETS)] + + if robot_id not in self._wp_index: + self._wp_index[robot_id] = 0 + + wp_idx = self._wp_index[robot_id] + target = waypoints[wp_idx] + + robot = game.friendly_robots[robot_id] + dist = robot.p.distance_to(target) + + if dist < _ARRIVAL_THRESHOLD: + # Advance to next waypoint + self._wp_index[robot_id] = (wp_idx + 1) % len(waypoints) + target = waypoints[self._wp_index[robot_id]] + + oren = robot.p.angle_to(target) + self.blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, target, oren) + + return py_trees.common.Status.RUNNING + + +class WanderingStrategy(AbstractStrategy): + """Strategy where every robot continuously patrols a set of waypoints. + + Intended for use with the referee visualisation simulation so that referee + commands visibly interrupt robot motion. + """ + + def assert_exp_robots(self, n_runtime_friendly: int, n_runtime_enemy: int) -> bool: + return True + + def assert_exp_goals(self, includes_my_goal_line: bool, includes_opp_goal_line: bool) -> bool: + return True + + def get_min_bounding_zone(self): + return None + + def create_behaviour_tree(self) -> py_trees.behaviour.Behaviour: + root = py_trees.composites.Sequence(name="WanderingRoot", memory=False) + root.add_child(WanderingStep()) + return root From ec2558b4b0e69b0a12badc7cb598cddcdcc076f8 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Fri, 13 Mar 2026 09:57:54 +0000 Subject: [PATCH 005/121] fix: make RefereeData.__eq__ actually override tuple equality; fix test bugs MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Convert RefereeData from NamedTuple to @dataclass(eq=False) so the custom __eq__ is respected (NamedTuple.__eq__ cannot be overridden — tuple equality always wins) - Use TYPE_CHECKING guard for TeamInfo import to avoid circular import (game/__init__ → Game → GameFrame → RefereeData → TeamInfo → game/__init__) - __eq__ compares TeamInfo by .score and .goalkeeper (the mutable game-state fields) since TeamInfo has no structural __eq__ of its own - Add __hash__ consistent with the subset of fields used in __eq__ - RefereeRefiner.add_new_referee_data: replace tuple slicing [1:] with == (now correctly uses the custom __eq__) - test_referee_unit.py: fix GameHistory() → GameHistory(10) (max_history is a required positional argument) Co-Authored-By: Claude Sonnet 4.6 --- utama_core/entities/data/referee.py | 40 ++++++++++++++----- utama_core/run/refiners/referee.py | 4 +- utama_core/tests/referee/test_referee_unit.py | 2 +- 3 files changed, 33 insertions(+), 13 deletions(-) diff --git a/utama_core/entities/data/referee.py b/utama_core/entities/data/referee.py index 9960b834..b97b6c2a 100644 --- a/utama_core/entities/data/referee.py +++ b/utama_core/entities/data/referee.py @@ -1,12 +1,18 @@ -from typing import List, NamedTuple, Optional, Tuple +from __future__ import annotations + +from dataclasses import dataclass, field +from typing import TYPE_CHECKING, List, Optional, Tuple -from utama_core.entities.game.team_info import TeamInfo from utama_core.entities.referee.referee_command import RefereeCommand from utama_core.entities.referee.stage import Stage +if TYPE_CHECKING: + from utama_core.entities.game.team_info import TeamInfo + -class RefereeData(NamedTuple): - """Namedtuple for referee data.""" +@dataclass(eq=False) +class RefereeData: + """Dataclass for referee data.""" source_identifier: Optional[str] time_sent: float @@ -39,7 +45,7 @@ class RefereeData(NamedTuple): # All game events detected since the last RUNNING state (e.g. foul type, ball-out side). # Stored as raw protobuf GameEvent objects. Cleared when the game resumes. # Useful for logging and future decision-making; not required for basic compliance. - game_events: List = [] + game_events: List = field(default_factory=list) # Meta information about the match type: # 0 = UNKNOWN_MATCH, 1 = GROUP_PHASE, 2 = ELIMINATION_PHASE, 3 = FRIENDLY @@ -51,16 +57,32 @@ class RefereeData(NamedTuple): def __eq__(self, other): if not isinstance(other, RefereeData): return NotImplemented - # game_events, match_type, and status_message are intentionally excluded - # from equality so they do not trigger spurious re-records in RefereeRefiner. + # game_events, match_type, status_message, source_identifier, and + # timestamps are intentionally excluded from equality so they do not + # trigger spurious re-records in RefereeRefiner. + # TeamInfo has no __eq__ so compare the mutable game-state fields only. return ( self.stage == other.stage and self.referee_command == other.referee_command and self.referee_command_timestamp == other.referee_command_timestamp - and self.yellow_team == other.yellow_team - and self.blue_team == other.blue_team + and self.yellow_team.score == other.yellow_team.score + and self.yellow_team.goalkeeper == other.yellow_team.goalkeeper + and self.blue_team.score == other.blue_team.score + and self.blue_team.goalkeeper == other.blue_team.goalkeeper and self.designated_position == other.designated_position and self.blue_team_on_positive_half == other.blue_team_on_positive_half and self.next_command == other.next_command and self.current_action_time_remaining == other.current_action_time_remaining ) + + def __hash__(self): + return hash( + ( + self.stage, + self.referee_command, + self.referee_command_timestamp, + self.designated_position, + self.blue_team_on_positive_half, + self.next_command, + ) + ) diff --git a/utama_core/run/refiners/referee.py b/utama_core/run/refiners/referee.py index 6171834c..797a43d7 100644 --- a/utama_core/run/refiners/referee.py +++ b/utama_core/run/refiners/referee.py @@ -32,9 +32,7 @@ def refine(self, game_frame, data: Optional[RefereeData]): return dataclasses.replace(game_frame, referee=data) def add_new_referee_data(self, referee_data: RefereeData) -> None: - if not self._referee_records: - self._referee_records.append(referee_data) - elif referee_data[1:] != self._referee_records[-1][1:]: + if not self._referee_records or referee_data != self._referee_records[-1]: self._referee_records.append(referee_data) def source_identifier(self) -> Optional[str]: diff --git a/utama_core/tests/referee/test_referee_unit.py b/utama_core/tests/referee/test_referee_unit.py index 8d6768e3..01dd138f 100644 --- a/utama_core/tests/referee/test_referee_unit.py +++ b/utama_core/tests/referee/test_referee_unit.py @@ -106,7 +106,7 @@ def _make_game( my_team_is_right: bool = True, ) -> Game: frame = _make_game_frame(friendly_robots, referee, my_team_is_yellow, my_team_is_right) - history = GameHistory() + history = GameHistory(10) return Game(past=history, current=frame, field=Field.FULL_FIELD_BOUNDS) From 769a8a66cd59e2bac9b1651341ff9deb22f1a28e Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Tue, 31 Mar 2026 21:54:56 +0100 Subject: [PATCH 006/121] Add custom referee integration and profile rename --- demo_custom_referee.py | 694 +++++++++++ demo_referee_gui_rsim.py | 76 ++ docs/custom_referee.md | 407 +++++++ docs/custom_referee_design_decisions.md | 104 ++ docs/custom_referee_gui.md | 379 ++++++ docs/referee_integration.md | 501 ++++++++ main.py | 2 +- start_test_env.sh | 18 +- utama_core/custom_referee/__init__.py | 4 + utama_core/custom_referee/custom_referee.py | 163 +++ utama_core/custom_referee/geometry.py | 71 ++ utama_core/custom_referee/gui.py | 1018 +++++++++++++++++ .../custom_referee/profiles/__init__.py | 3 + utama_core/custom_referee/profiles/human.yaml | 36 + .../custom_referee/profiles/profile_loader.py | 223 ++++ .../custom_referee/profiles/simulation.yaml | 35 + utama_core/custom_referee/rules/__init__.py | 14 + utama_core/custom_referee/rules/base_rule.py | 43 + .../custom_referee/rules/defense_area_rule.py | 72 ++ utama_core/custom_referee/rules/goal_rule.py | 96 ++ .../custom_referee/rules/keep_out_rule.py | 124 ++ .../rules/out_of_bounds_rule.py | 137 +++ utama_core/custom_referee/state_machine.py | 521 +++++++++ utama_core/run/strategy_runner.py | 96 +- utama_core/strategy/referee/actions.py | 28 +- utama_core/tests/custom_referee/__init__.py | 0 .../custom_referee/test_custom_referee.py | 444 +++++++ .../tests/referee/demo_referee_gui_rsim.py | 74 ++ utama_core/tests/referee/referee_sim.py | 2 +- utama_core/tests/referee/test_referee_unit.py | 101 +- .../strategy_runner/test_runner_misconfig.py | 38 + 31 files changed, 5492 insertions(+), 32 deletions(-) create mode 100644 demo_custom_referee.py create mode 100644 demo_referee_gui_rsim.py create mode 100644 docs/custom_referee.md create mode 100644 docs/custom_referee_design_decisions.md create mode 100644 docs/custom_referee_gui.md create mode 100644 docs/referee_integration.md create mode 100644 utama_core/custom_referee/__init__.py create mode 100644 utama_core/custom_referee/custom_referee.py create mode 100644 utama_core/custom_referee/geometry.py create mode 100644 utama_core/custom_referee/gui.py create mode 100644 utama_core/custom_referee/profiles/__init__.py create mode 100644 utama_core/custom_referee/profiles/human.yaml create mode 100644 utama_core/custom_referee/profiles/profile_loader.py create mode 100644 utama_core/custom_referee/profiles/simulation.yaml create mode 100644 utama_core/custom_referee/rules/__init__.py create mode 100644 utama_core/custom_referee/rules/base_rule.py create mode 100644 utama_core/custom_referee/rules/defense_area_rule.py create mode 100644 utama_core/custom_referee/rules/goal_rule.py create mode 100644 utama_core/custom_referee/rules/keep_out_rule.py create mode 100644 utama_core/custom_referee/rules/out_of_bounds_rule.py create mode 100644 utama_core/custom_referee/state_machine.py create mode 100644 utama_core/tests/custom_referee/__init__.py create mode 100644 utama_core/tests/custom_referee/test_custom_referee.py create mode 100644 utama_core/tests/referee/demo_referee_gui_rsim.py diff --git a/demo_custom_referee.py b/demo_custom_referee.py new file mode 100644 index 00000000..a1b5322d --- /dev/null +++ b/demo_custom_referee.py @@ -0,0 +1,694 @@ +"""demo_custom_referee.py — visual demonstration of the CustomReferee system. + +Runs entirely in-process (no network, no RSim binary needed). A scripted +scenario exercises every referee rule in sequence while the pygame window shows: + - The field with robots and ball + - Purple polygons: defense area boundaries + - Red circle: keep-out zone (during stoppages) + - Green crosshair: designated_position (ball reset target, e.g. centre after goal) + - HUD bar: current command (colour-coded), score, next command, designated pos, scene label + +Each scene in SCENES declares: + - What command to force at scene start (simulates operator "play" button) + - How the ball moves (keyframes interpolated over the scene duration) + - How robots move (per-robot keyframes) + - Whether to simulate the ball teleport on STOP (ball_teleports_on_stop=True) + +Controls: + ESC / close window — quit + SPACE — pause / unpause + R — restart from scene 0 + → / ← — skip forward / back one scene +""" + +from __future__ import annotations + +import dataclasses +import math +import sys +import time +from dataclasses import dataclass, field +from typing import Optional + +import pygame + +from utama_core.custom_referee import CustomReferee, RefereeGeometry +from utama_core.entities.data.vector import Vector2D, Vector3D +from utama_core.entities.game.ball import Ball +from utama_core.entities.game.game_frame import GameFrame +from utama_core.entities.game.robot import Robot +from utama_core.entities.referee.referee_command import RefereeCommand +from utama_core.rsoccer_simulator.src.Render import COLORS, SSLRenderField +from utama_core.rsoccer_simulator.src.Render.ball import RenderBall +from utama_core.rsoccer_simulator.src.Render.overlay import ( + OverlayObject, + OverlayType, + RenderOverlay, +) +from utama_core.rsoccer_simulator.src.Render.robot import RenderSSLRobot + +# --------------------------------------------------------------------------- +# Scene definition +# --------------------------------------------------------------------------- + + +@dataclass +class Vec2KF: + """A (t, x, y) keyframe for linear interpolation.""" + + t: float + x: float + y: float + + +def _interp(kfs: list[Vec2KF], t: float) -> tuple[float, float]: + """Linearly interpolate a list of Vec2KF keyframes at time t.""" + if not kfs: + return 0.0, 0.0 + if t <= kfs[0].t: + return kfs[0].x, kfs[0].y + if t >= kfs[-1].t: + return kfs[-1].x, kfs[-1].y + for i in range(len(kfs) - 1): + k0, k1 = kfs[i], kfs[i + 1] + if k0.t <= t <= k1.t: + a = (t - k0.t) / (k1.t - k0.t) + return k0.x + a * (k1.x - k0.x), k0.y + a * (k1.y - k0.y) + return kfs[-1].x, kfs[-1].y + + +@dataclass +class Scene: + """One demo scene: sets up initial command, describes motion, and labels it.""" + + title: str # shown large in HUD + subtitle: str # shown small in HUD + duration: float # seconds + # Command forced at t=0 of this scene (simulates operator input) + force_command: Optional[RefereeCommand] = None + # Ball keyframes relative to scene start + ball_kfs: list[Vec2KF] = field(default_factory=list) + # Per-robot overrides: dict robot_index → list[Vec2KF] + # Robot layout indices: 0,1,2 = yellow; 3,4,5 = blue + robot_kfs: dict[int, list[Vec2KF]] = field(default_factory=dict) + # If True, once the referee issues STOP the ball position is overridden to + # designated_position for the rest of the scene (mirrors StrategyRunner teleport). + ball_teleports_on_stop: bool = False + + +# Base robot positions (field coords, metres) +# Index: 0=(Y0), 1=(Y1), 2=(Y2), 3=(B0), 4=(B1), 5=(B2) +_Y0 = Vec2KF(0, 1.5, 0.0) +_Y1 = Vec2KF(0, 3.0, 1.2) +_Y2 = Vec2KF(0, 3.0, -1.2) +_B0 = Vec2KF(0, -1.5, 0.0) +_B1 = Vec2KF(0, -3.0, 1.2) +_B2 = Vec2KF(0, -3.0, -1.2) + +BASE_ROBOTS = [_Y0, _Y1, _Y2, _B0, _B1, _B2] # one keyframe each (static default) + + +SCENES: list[Scene] = [ + # ------------------------------------------------------------------ + # 0. NORMAL START — play in progress, nothing happening + # ------------------------------------------------------------------ + Scene( + title="NORMAL START", + subtitle="Active play — no violations", + duration=3.0, + force_command=RefereeCommand.NORMAL_START, + ball_kfs=[ + Vec2KF(0.0, 0.0, 0.0), + Vec2KF(3.0, 2.0, 1.0), + ], + ), + # ------------------------------------------------------------------ + # 1. GOAL — yellow robot dribbles ball into the LEFT goal (blue's goal). + # yellow_is_right=True so the left goal is blue's → Yellow scores. + # Ball teleports to (0,0) the moment STOP fires (simulates StrategyRunner). + # ------------------------------------------------------------------ + Scene( + title="GOAL RULE", + subtitle="Yellow attacks left goal (Blue's) → Yellow scores, STOP + ball teleport to centre", + duration=5.0, + force_command=RefereeCommand.NORMAL_START, + ball_kfs=[ + Vec2KF(0.0, 0.0, 0.3), + Vec2KF(2.5, -5.5, 0.0), # crosses left goal line — triggers GoalRule + Vec2KF(5.0, -5.5, 0.0), + ], + robot_kfs={ + # Yellow robot 1 starts centre-left and charges toward the left goal. + # Stops just outside the defense area (x=-3.2) to avoid entering it. + 1: [Vec2KF(0.0, -0.5, 0.3), Vec2KF(2.0, -3.2, 0.2), Vec2KF(5.0, -3.2, 0.2)], + }, + ball_teleports_on_stop=True, + ), + # ------------------------------------------------------------------ + # 2. STOP phase after goal — ball already at centre (0,0) + # ------------------------------------------------------------------ + Scene( + title="STOP (after goal)", + subtitle="Ball at centre (designated_position) — keep-out circle active", + duration=4.0, + # No force_command here — the state machine already issued STOP from scene 1. + ball_kfs=[Vec2KF(0.0, 0.0, 0.0), Vec2KF(4.0, 0.0, 0.0)], + robot_kfs={ + # Yellow robot 0 respects the circle + 0: [Vec2KF(0.0, 1.5, 0.0), Vec2KF(4.0, 1.5, 0.0)], + # Blue robot 0 also stays back + 3: [Vec2KF(0.0, -1.5, 0.0), Vec2KF(4.0, -1.5, 0.0)], + }, + ), + # ------------------------------------------------------------------ + # 3. OUT OF BOUNDS — ball kicked off sideline + # ------------------------------------------------------------------ + Scene( + title="OUT OF BOUNDS RULE", + subtitle="Ball crosses top sideline → STOP + DIRECT_FREE issued", + duration=5.0, + force_command=RefereeCommand.NORMAL_START, + ball_kfs=[ + Vec2KF(0.0, 0.5, 1.0), + Vec2KF(2.5, 1.5, 3.8), # crosses top boundary (half_width=3.0) + Vec2KF(5.0, 1.5, 3.8), + ], + robot_kfs={ + # Yellow robot 0 kicked it + 0: [Vec2KF(0.0, 0.5, 1.0), Vec2KF(2.0, 1.0, 2.5), Vec2KF(5.0, 1.0, 2.5)], + }, + ), + # ------------------------------------------------------------------ + # 4. DEFENSE AREA — blue attacker walks into yellow's right defense area + # ------------------------------------------------------------------ + Scene( + title="DEFENSE AREA RULE", + subtitle="Enemy attacker enters right defense area → STOP + DIRECT_FREE", + duration=5.0, + force_command=RefereeCommand.NORMAL_START, + ball_kfs=[ + Vec2KF(0.0, 2.0, 0.0), + Vec2KF(5.0, 3.5, 0.0), + ], + robot_kfs={ + # Blue robot 0 drives from midfield into the right defense area + # Right defense area: x >= 4.5 - 2*0.5 = 3.5, |y| <= 1.0 + 3: [Vec2KF(0.0, 0.5, 0.0), Vec2KF(2.5, 3.8, 0.3), Vec2KF(5.0, 3.8, 0.3)], + # Blue robot 1 stays put + 4: [Vec2KF(0.0, -3.0, 1.2), Vec2KF(5.0, -3.0, 1.2)], + }, + ), + # ------------------------------------------------------------------ + # 5. KEEP-OUT — blue robot creeps inside the 0.5 m circle during STOP + # ------------------------------------------------------------------ + Scene( + title="KEEP-OUT RULE", + subtitle="Robot stays < 0.5 m from ball for 30 frames → DIRECT_FREE issued", + duration=6.0, + force_command=RefereeCommand.STOP, + ball_kfs=[Vec2KF(0.0, 0.0, 0.0), Vec2KF(6.0, 0.0, 0.0)], + robot_kfs={ + # Blue robot 0 slowly creeps inside the keep-out circle + 3: [Vec2KF(0.0, -2.0, 0.0), Vec2KF(1.5, -0.3, 0.0), Vec2KF(6.0, -0.3, 0.0)], + }, + ), +] + +TOTAL_SCENES = len(SCENES) + + +# --------------------------------------------------------------------------- +# Robot position at time t within a scene +# --------------------------------------------------------------------------- + + +def _robot_pos(scene: Scene, robot_idx: int, t: float) -> tuple[float, float]: + """Return (x, y) for robot_idx at scene-relative time t.""" + if robot_idx in scene.robot_kfs: + return _interp(scene.robot_kfs[robot_idx], t) + # Fall back to base position (static). + base = BASE_ROBOTS[robot_idx] + return base.x, base.y + + +def _make_frame(scene: Scene, t: float, current_time: float) -> GameFrame: + bx, by = _interp(scene.ball_kfs, t) if scene.ball_kfs else (0.0, 0.0) + ball = Ball(p=Vector3D(bx, by, 0.0), v=Vector3D(0, 0, 0), a=Vector3D(0, 0, 0)) + + friendly: dict[int, Robot] = {} + enemy: dict[int, Robot] = {} + + for idx in range(3): # yellow robots — attack left, so face −x (π radians) + x, y = _robot_pos(scene, idx, t) + friendly[idx] = Robot( + id=idx, + is_friendly=True, + has_ball=False, + p=Vector2D(x, y), + v=Vector2D(0, 0), + a=Vector2D(0, 0), + orientation=math.pi, + ) + + for idx in range(3): # blue robots — attack right, so face +x (0 radians) + x, y = _robot_pos(scene, idx + 3, t) + enemy[idx] = Robot( + id=idx, + is_friendly=False, + has_ball=False, + p=Vector2D(x, y), + v=Vector2D(0, 0), + a=Vector2D(0, 0), + orientation=0.0, + ) + + return GameFrame( + ts=current_time, + my_team_is_yellow=True, + my_team_is_right=True, # yellow defends right goal, blue defends left + friendly_robots=friendly, + enemy_robots=enemy, + ball=ball, + referee=None, + ) + + +# --------------------------------------------------------------------------- +# Overlay helpers +# --------------------------------------------------------------------------- + + +def _field_to_screen(x: float, y: float, fr: SSLRenderField) -> tuple[int, int]: + return ( + int(x * fr.scale + fr.center_x), + int(-y * fr.scale + fr.center_y), + ) + + +_STOPPAGE_CMDS = { + RefereeCommand.STOP, + RefereeCommand.DIRECT_FREE_YELLOW, + RefereeCommand.DIRECT_FREE_BLUE, + RefereeCommand.PREPARE_KICKOFF_YELLOW, + RefereeCommand.PREPARE_KICKOFF_BLUE, +} + + +def _draw_designated_position( + surface: pygame.Surface, + dx: float, + dy: float, + fr: SSLRenderField, +) -> None: + """Draw a green crosshair + diamond at the designated ball position.""" + cx, cy = _field_to_screen(dx, dy, fr) + color = (0, 220, 80) + + arm = int(18 * fr.scale / 100) # crosshair arm length scaled with field + arm = max(arm, 10) + thick = 2 + + # Crosshair + pygame.draw.line(surface, color, (cx - arm, cy), (cx + arm, cy), thick) + pygame.draw.line(surface, color, (cx, cy - arm), (cx, cy + arm), thick) + + # Diamond outline + d = int(arm * 0.7) + pts = [(cx, cy - d), (cx + d, cy), (cx, cy + d), (cx - d, cy)] + pygame.draw.polygon(surface, color, pts, thick) + + +def _build_overlays( + geo: RefereeGeometry, + command: RefereeCommand, + bx: float, + by: float, + fr: SSLRenderField, +) -> list[OverlayObject]: + ovs: list[OverlayObject] = [] + + # Defense area outlines (purple, always visible) + rdx = geo.half_length - 2 * geo.half_defense_length # 3.5 + ldx = -geo.half_length + 2 * geo.half_defense_length # -3.5 + + for pts in [ + # Right defense area (yellow's goal) + [ + (rdx, geo.half_defense_width), + (geo.half_length, geo.half_defense_width), + (geo.half_length, -geo.half_defense_width), + (rdx, -geo.half_defense_width), + ], + # Left defense area (blue's goal) + [ + (-geo.half_length, geo.half_defense_width), + (ldx, geo.half_defense_width), + (ldx, -geo.half_defense_width), + (-geo.half_length, -geo.half_defense_width), + ], + ]: + ovs.append( + OverlayObject( + type=OverlayType.POLYGON, + color="PURPLE", + points=[_field_to_screen(px, py, fr) for px, py in pts], + width=2, + ) + ) + + # Keep-out circle (red ring, during stoppages) + if command in _STOPPAGE_CMDS: + cx, cy = _field_to_screen(bx, by, fr) + r_px = int(geo.center_circle_radius * fr.scale) + n = 48 + circle_pts = [ + (int(cx + r_px * math.cos(2 * math.pi * i / n)), int(cy + r_px * math.sin(2 * math.pi * i / n))) + for i in range(n) + ] + ovs.append( + OverlayObject( + type=OverlayType.POLYGON, + color="RED", + points=circle_pts, + width=2, + ) + ) + + return ovs + + +# --------------------------------------------------------------------------- +# HUD +# --------------------------------------------------------------------------- + +_CMD_COLORS: dict[RefereeCommand, tuple] = { + RefereeCommand.HALT: (200, 50, 50), + RefereeCommand.STOP: (230, 130, 0), + RefereeCommand.NORMAL_START: (60, 210, 60), + RefereeCommand.FORCE_START: (60, 210, 60), + RefereeCommand.DIRECT_FREE_YELLOW: (240, 210, 50), + RefereeCommand.DIRECT_FREE_BLUE: (80, 150, 255), + RefereeCommand.PREPARE_KICKOFF_YELLOW: (240, 210, 50), + RefereeCommand.PREPARE_KICKOFF_BLUE: (80, 150, 255), +} + + +def _draw_hud( + surface: pygame.Surface, + fonts: dict, + ref_data, + scene_idx: int, + scene_title: str, + scene_subtitle: str, + paused: bool, + scene_t: float, + scene_dur: float, +) -> None: + W = surface.get_width() + panel_h = 120 + panel = pygame.Surface((W, panel_h), pygame.SRCALPHA) + panel.fill((0, 0, 0, 170)) + surface.blit(panel, (0, 0)) + + cmd = ref_data.referee_command + cmd_color = _CMD_COLORS.get(cmd, (200, 200, 200)) + next_cmd = ref_data.next_command + + # Scene counter (top right) + sc_surf = fonts["tiny"].render( + f"Scene {scene_idx + 1}/{TOTAL_SCENES} [{scene_t:.1f}/{scene_dur:.0f}s]", + True, + (150, 150, 150), + ) + surface.blit(sc_surf, (W - sc_surf.get_width() - 10, 6)) + + # Command (large, colour-coded) + cmd_surf = fonts["large"].render(cmd.name.replace("_", " "), True, cmd_color) + surface.blit(cmd_surf, (10, 6)) + + # Score + score_str = f"Yellow {ref_data.yellow_team.score} – {ref_data.blue_team.score} Blue" + score_surf = fonts["medium"].render(score_str, True, (230, 230, 230)) + surface.blit(score_surf, (10, 40)) + + # next command + designated position (right column) + right_x = W // 2 + if next_cmd: + nc_surf = fonts["small"].render(f"next → {next_cmd.name.replace('_', ' ')}", True, (180, 180, 180)) + surface.blit(nc_surf, (right_x, 40)) + desg = ref_data.designated_position + if desg is not None and cmd == RefereeCommand.STOP: + dp_surf = fonts["small"].render(f"designated → ({desg[0]:.2f}, {desg[1]:.2f}) m", True, (0, 220, 80)) + surface.blit(dp_surf, (right_x, 58)) + + # Scene title / subtitle + title_surf = fonts["small"].render(f"▶ {scene_title}", True, (200, 255, 200)) + surface.blit(title_surf, (10, 68)) + + sub_surf = fonts["tiny"].render(scene_subtitle, True, (170, 200, 170)) + surface.blit(sub_surf, (10, 90)) + + # Pause indicator + if paused: + p_surf = fonts["small"].render("PAUSED — SPACE to resume", True, (255, 200, 80)) + surface.blit(p_surf, (W // 2, 90)) + + # Progress bar + bar_y = panel_h - 4 + bar_w = int(W * min(scene_t / max(scene_dur, 0.001), 1.0)) + pygame.draw.rect(surface, (80, 80, 80), (0, bar_y, W, 4)) + pygame.draw.rect(surface, cmd_color, (0, bar_y, bar_w, 4)) + + +# --------------------------------------------------------------------------- +# Drawing helpers +# --------------------------------------------------------------------------- + + +def _draw_robots( + surface: pygame.Surface, + frame: GameFrame, + fr: SSLRenderField, +) -> None: + for robot in frame.friendly_robots.values(): + sx, sy = _field_to_screen(robot.p.x, robot.p.y, fr) + direction_deg = math.degrees(robot.orientation) + RenderSSLRobot(sx, sy, direction_deg, fr.scale, robot.id, COLORS["YELLOW"]).draw(surface) + for robot in frame.enemy_robots.values(): + sx, sy = _field_to_screen(robot.p.x, robot.p.y, fr) + direction_deg = math.degrees(robot.orientation) + RenderSSLRobot(sx, sy, direction_deg, fr.scale, robot.id, COLORS["BLUE"]).draw(surface) + + +def _draw_ball( + surface: pygame.Surface, + bx: float, + by: float, + fr: SSLRenderField, +) -> None: + sx, sy = _field_to_screen(bx, by, fr) + RenderBall(sx, sy, fr.scale).draw(surface) + + +def _draw_frame( + screen: pygame.Surface, + fr_renderer: SSLRenderField, + fonts: dict, + geo: RefereeGeometry, + frame: GameFrame, + ref_data, + scene_idx: int, + scene: Scene, + scene_t: float, + paused: bool, +) -> None: + bx, by = frame.ball.p.x, frame.ball.p.y + fr_renderer.draw(screen) + + ovs = _build_overlays(geo, ref_data.referee_command, bx, by, fr_renderer) + if ovs: + RenderOverlay(ovs, fr_renderer.scale).draw(screen) + + _draw_robots(screen, frame, fr_renderer) + _draw_ball(screen, bx, by, fr_renderer) + + # Designated position marker (green crosshair) — only during STOP, + # where it signals where the ball should be placed before play resumes. + if ref_data.designated_position is not None and ref_data.referee_command == RefereeCommand.STOP: + dx, dy = ref_data.designated_position + _draw_designated_position(screen, dx, dy, fr_renderer) + + _draw_hud( + screen, + fonts, + ref_data, + scene_idx, + scene.title, + scene.subtitle, + paused, + scene_t, + scene.duration, + ) + + pygame.display.flip() + + +# --------------------------------------------------------------------------- +# Main loop +# --------------------------------------------------------------------------- + + +def _make_referee() -> CustomReferee: + referee = CustomReferee.from_profile_name("simulation", n_robots_yellow=3, n_robots_blue=3) + referee.set_command(RefereeCommand.HALT, timestamp=0.0) + return referee + + +def main() -> None: + pygame.init() + fr_renderer = SSLRenderField() + W, H = fr_renderer.window_size + screen = pygame.display.set_mode((W, H)) + pygame.display.set_caption("Custom Referee — Visual Demo | SPACE pause R restart ←→ scenes") + clock = pygame.time.Clock() + + fonts = { + "large": pygame.font.SysFont("monospace", 22, bold=True), + "medium": pygame.font.SysFont("monospace", 18, bold=True), + "small": pygame.font.SysFont("monospace", 15), + "tiny": pygame.font.SysFont("monospace", 12), + } + + geo = RefereeGeometry.from_standard_div_b() + referee = _make_referee() + + scene_idx = 0 + scene_start_wall = time.perf_counter() + scene_forced = False # whether we've already applied force_command this scene + paused = False + pause_wall = 0.0 + pause_acc = 0.0 # accumulated pause time in current scene + prev_command = RefereeCommand.HALT # for teleport edge detection + teleport_pos: Optional[tuple[float, float]] = None # active teleport override + + # Hold latest data for redraw during pause + last_frame = _make_frame(SCENES[0], 0.0, 0.0) + last_ref = referee.step(last_frame, current_time=0.0) + + def reset_scene(idx: int, wall_now: float) -> None: + nonlocal scene_idx, scene_start_wall, scene_forced, pause_acc, prev_command, teleport_pos + scene_idx = idx + scene_start_wall = wall_now + scene_forced = False + pause_acc = 0.0 + prev_command = RefereeCommand.HALT + teleport_pos = None + + running = True + while running: + wall_now = time.perf_counter() + + # ---- Events -------------------------------------------------------- + for event in pygame.event.get(): + if event.type == pygame.QUIT: + running = False + elif event.type == pygame.KEYDOWN: + if event.key == pygame.K_ESCAPE: + running = False + + elif event.key == pygame.K_SPACE: + if paused: + pause_acc += wall_now - pause_wall + paused = False + else: + pause_wall = wall_now + paused = True + + elif event.key == pygame.K_r: + referee = _make_referee() + reset_scene(0, wall_now) + paused = False + pause_acc = 0.0 + + elif event.key == pygame.K_RIGHT: + nxt = (scene_idx + 1) % TOTAL_SCENES + reset_scene(nxt, wall_now) + + elif event.key == pygame.K_LEFT: + prv = (scene_idx - 1) % TOTAL_SCENES + reset_scene(prv, wall_now) + + # ---- Scene time ---------------------------------------------------- + if paused: + _draw_frame( + screen, + fr_renderer, + fonts, + geo, + last_frame, + last_ref, + scene_idx, + SCENES[scene_idx], + # show time as it was when paused + (pause_wall - scene_start_wall) - pause_acc, + paused=True, + ) + clock.tick(30) + continue + + scene = SCENES[scene_idx] + scene_t = (wall_now - scene_start_wall) - pause_acc + + # Force command at scene start (once per scene) + if not scene_forced and scene.force_command is not None: + referee.set_command(scene.force_command, timestamp=scene_t) + scene_forced = True + + # Clamp to scene duration + scene_t_clamped = min(scene_t, scene.duration) + current_time = wall_now # absolute time for referee cooldowns + + frame = _make_frame(scene, scene_t_clamped, current_time) + ref_data = referee.step(frame, current_time=current_time) + + # Simulate StrategyRunner ball teleport: on STOP transition edge with + # a designated_position, snap the ball there for the rest of the scene. + if ( + scene.ball_teleports_on_stop + and ref_data.referee_command == RefereeCommand.STOP + and ref_data.designated_position is not None + and prev_command != RefereeCommand.STOP + ): + teleport_pos = ref_data.designated_position + + # If a teleport is active, rebuild the frame with the ball at that position. + if teleport_pos is not None and scene.ball_teleports_on_stop: + tx, ty = teleport_pos + teleported_ball = frame.ball.__class__( + p=frame.ball.p.__class__(tx, ty, 0.0), + v=frame.ball.v, + a=frame.ball.a, + ) + frame = dataclasses.replace(frame, ball=teleported_ball) + + prev_command = ref_data.referee_command + last_frame = frame + last_ref = ref_data + + _draw_frame(screen, fr_renderer, fonts, geo, frame, ref_data, scene_idx, scene, scene_t_clamped, paused=False) + + # ---- Auto-advance to next scene ------------------------------------ + if scene_t > scene.duration + 0.8: # 0.8 s pause between scenes + next_idx = scene_idx + 1 + if next_idx < TOTAL_SCENES: + reset_scene(next_idx, wall_now) + # else: stay on last scene + + clock.tick(60) + + pygame.quit() + sys.exit(0) + + +if __name__ == "__main__": + main() diff --git a/demo_referee_gui_rsim.py b/demo_referee_gui_rsim.py new file mode 100644 index 00000000..b3c6b04b --- /dev/null +++ b/demo_referee_gui_rsim.py @@ -0,0 +1,76 @@ +"""demo_referee_gui_rsim.py — CustomReferee + web GUI + StrategyRunner (RSim). + +Run: + pixi run python utama_core/tests/referee/demo_referee_gui_rsim.py + # RSim window opens; open http://localhost:8080 in a browser + +What it does: + - Creates a CustomReferee (human profile) with enable_gui=True so the + browser panel starts automatically. + - Passes the referee to StrategyRunner via custom_referee=. StrategyRunner + calls referee.step() on every tick and handles ball teleports on STOP + automatically — no patching required. + - WanderingStrategy is used as the base strategy so robots visibly move and + you can watch the RefereeOverride tree interrupt them when you issue + commands from the GUI (Halt, Kickoff Yellow, etc.). + +Operator workflow: + 1. Open http://localhost:8080 in a browser. + 2. Robots start moving under WanderingStrategy. + 3. Click any command button (Halt, Stop, Kickoff Yellow…) — robots reposition. + 4. Click Normal Start to resume free play. + 5. With the human profile, the referee stays in STOP after a goal until the operator advances play. +""" + +from utama_core.custom_referee import CustomReferee +from utama_core.custom_referee.profiles.profile_loader import load_profile +from utama_core.run import StrategyRunner +from utama_core.tests.referee.wandering_strategy import WanderingStrategy + +# --------------------------------------------------------------------------- +# Configuration +# --------------------------------------------------------------------------- + +PROFILE = "human" # "human" or "simulation" +GUI_PORT = 8080 +N_ROBOTS = 3 # robots per side +MY_TEAM_IS_YELLOW = True +MY_TEAM_IS_RIGHT = True + +# --------------------------------------------------------------------------- +# Entry point +# --------------------------------------------------------------------------- + + +def main() -> None: + profile = load_profile(PROFILE) + + # enable_gui=True starts the HTTP server in a background daemon thread. + # referee.step() is called by StrategyRunner on every tick; the GUI + # receives state automatically after each call. + referee = CustomReferee( + profile, + n_robots_yellow=N_ROBOTS, + n_robots_blue=N_ROBOTS, + enable_gui=True, + gui_port=GUI_PORT, + ) + + runner = StrategyRunner( + strategy=WanderingStrategy(), + my_team_is_yellow=MY_TEAM_IS_YELLOW, + my_team_is_right=MY_TEAM_IS_RIGHT, + mode="rsim", + control_scheme="dwa", + exp_friendly=N_ROBOTS, + exp_enemy=N_ROBOTS, + custom_referee=referee, # StrategyRunner drives referee.step() each tick + show_live_status=True, + opp_strategy=WanderingStrategy(), + ) + + runner.run() + + +if __name__ == "__main__": + main() diff --git a/docs/custom_referee.md b/docs/custom_referee.md new file mode 100644 index 00000000..e71b6c09 --- /dev/null +++ b/docs/custom_referee.md @@ -0,0 +1,407 @@ +# Custom Referee + +The `CustomReferee` is an in-process, mode-agnostic referee that operates on `GameFrame` objects and produces `RefereeData` — the same type consumed by the behaviour tree's `CheckRefereeCommand` nodes. It requires no network connection, no AutoReferee process, and no simulator-specific code. It works identically across RSim, grSim, and Real modes. + +--- + +## Why a Custom Referee? + +The official [TIGERs AutoReferee](https://github.com/TIGERs-Mannheim/AutoReferee) is a Java process that broadcasts UDP multicast packets. It works well in Real and grSim modes but is not usable in RSim (no AutoReferee process is running) and is impractical for RL training (asynchronous, real-time only, can't step faster than 60 Hz). + +The `CustomReferee` addresses three specific use cases: + +**1. RSim / RL training** +RSim runs as fast as the CPU allows. The custom referee steps synchronously in the same Python process, so there is no network latency or synchronisation overhead. You can train at 10 000× real-time. + +**2. Custom field geometry** +The official AutoReferee has hardcoded thresholds (defence area size, keep-out radius) that break on small physical test fields. `RefereeGeometry` is a frozen dataclass you configure per-deployment — shrink the defence area, tighten or loosen the keep-out radius, disable rules entirely. + +**3. Exhibition and human game modes** +Strict SSL rules (double-touch, ball speed, keep-out distance) ruin human-vs-robot exhibition matches because humans constantly trigger fouls. Profile-based configuration lets you switch rule sets without touching code. + +--- + +## Architecture + +``` +CustomReferee +├── RefereeGeometry # frozen field dimensions (configurable) +├── list[BaseRule] # ordered rule checkers (first match wins) +│ ├── GoalRule +│ ├── OutOfBoundsRule +│ ├── DefenseAreaRule +│ └── KeepOutRule +└── GameStateMachine # mutable command / score / stage state +``` + +### Data flow per tick + +``` +GameFrame (ball + robots + ts) + │ + ▼ +CustomReferee.step(game_frame, current_time) + │ + ├─► for each BaseRule (in priority order): + │ rule.check(game_frame, geometry, current_command) + │ → Optional[RuleViolation] first match wins + │ + ▼ +GameStateMachine.step(current_time, violation) + │ + ├─► if violation and not in cooldown (0.3 s): + │ goal → increment score, set STOP, set next_command, + │ set designated_position = (0.0, 0.0) + │ foul → set suggested_command, set next_command, set designated_position + │ + ▼ +RefereeData (source_identifier="custom_referee") +``` + +The one-frame lag (the `GameFrame` used is from the previous step) is acceptable and matches how the existing RSim `RefereeStateMachine` works. + +--- + +## State Machine + +The `GameStateMachine` owns all mutable state: command, score, stage, and next command. It does **not** auto-advance from `STOP` to `NORMAL_START` — that transition is always explicit (operator input or a fixed-delay script). This keeps control predictable. + +```mermaid +stateDiagram-v2 + direction LR + + [*] --> HALT : initialise + + HALT --> STOP + HALT --> NORMAL_START + + STOP --> NORMAL_START\n[operator / script] + STOP --> PREPARE_KICKOFF_YELLOW + STOP --> PREPARE_KICKOFF_BLUE + STOP --> DIRECT_FREE_YELLOW + STOP --> DIRECT_FREE_BLUE + + NORMAL_START --> STOP : GoalRule fires\n[score++, next_cmd set] + NORMAL_START --> STOP : OutOfBoundsRule fires\n[designated_position set] + NORMAL_START --> STOP : DefenseAreaRule fires + FORCE_START --> STOP : GoalRule fires + FORCE_START --> STOP : OutOfBoundsRule fires + FORCE_START --> STOP : DefenseAreaRule fires + + STOP --> STOP : KeepOutRule fires\n[next_cmd = DIRECT_FREE_*] + + PREPARE_KICKOFF_YELLOW --> NORMAL_START + PREPARE_KICKOFF_BLUE --> NORMAL_START + DIRECT_FREE_YELLOW --> NORMAL_START + DIRECT_FREE_BLUE --> NORMAL_START + + NORMAL_START --> FORCE_START + FORCE_START --> NORMAL_START +``` + +> **Key design principle:** `CustomReferee` only ever *moves into* `STOP` automatically. All transitions *out of* `STOP` require an explicit `set_command()` call. This matches how a human operator interacts with a real game controller. +> More thoughts on this, in RL loop / automated testing, we do want the referee system to resume the game after our system is ready, e.g. putting ball at designated location and ready to start. + +### Transition cooldown + +A 0.3 s cooldown (`_TRANSITION_COOLDOWN`) prevents the same violation from being applied multiple times in quick succession (e.g., the ball briefly in the goal for several frames). + +--- + +## Rule Checkers + +Each rule is a `BaseRule` subclass. Rules are evaluated in priority order; the **first match wins** and subsequent rules are skipped for that tick. + +### Priority order + +| Priority | Rule | Active during | +|----------|------|---------------| +| 1 | `GoalRule` | `NORMAL_START`, `FORCE_START` | +| 2 | `OutOfBoundsRule` | `NORMAL_START`, `FORCE_START` | +| 3 | `DefenseAreaRule` | `NORMAL_START`, `FORCE_START` | +| 4 | `KeepOutRule` | `STOP`, `DIRECT_FREE_*`, `PREPARE_KICKOFF_*`, `PREPARE_PENALTY_*` | + +### GoalRule + +Detects when the ball crosses the goal line within the goal posts. Uses `game_frame.my_team_is_right` and `game_frame.my_team_is_yellow` to determine which team scored — not a hardcoded assignment. + +``` +yellow_is_right = (my_team_is_right == my_team_is_yellow) + +ball in right goal: + yellow_is_right=True → blue scored → PREPARE_KICKOFF_YELLOW + yellow_is_right=False → yellow scored → PREPARE_KICKOFF_BLUE + +ball in left goal: + yellow_is_right=True → yellow scored → PREPARE_KICKOFF_BLUE + yellow_is_right=False → blue scored → PREPARE_KICKOFF_YELLOW +``` + +A configurable `cooldown_seconds` (default 1.0 s) prevents duplicate detections while the ball sits past the goal line for multiple frames. + +### OutOfBoundsRule + +Fires when `abs(ball.p.x) > half_length` (not in a goal) or `abs(ball.p.y) > half_width`. Tracks last-touch by: +1. Checking `robot.has_ball` (reliable IR sensor on friendly robots). +2. Falling back to the closest robot within 0.15 m. + +The non-touching team receives the `DIRECT_FREE_*`. The `designated_position` is placed 0.1 m infield from the nearest boundary point. + +### DefenseAreaRule + +Only active during `NORMAL_START` and `FORCE_START`. Checks two conditions: + +- **Too many defenders:** more than `max_defenders` (default 1) friendly robots inside their own defence area → opponent gets `DIRECT_FREE_*`. +- **Attacker infringement:** any enemy robot inside the friendly team's defence area → friendly team gets `DIRECT_FREE_*`. + +Uses `game_frame.my_team_is_right` to resolve which geometry helper (`is_in_left/right_defense_area`) corresponds to "my" goal. + +### KeepOutRule + +Only active during stoppages (`STOP`, `DIRECT_FREE_*`, `PREPARE_KICKOFF_*`, `PREPARE_PENALTY_*`). Checks that non-kicking-team robots stay outside a configurable `radius_meters` (default 0.5 m) from the ball. + +Uses a persistence counter: a violation is only issued after `violation_persistence_frames` (default 30, ≈ 0.5 s at 60 Hz) **consecutive** frames of encroachment. This avoids false positives from robots passing through the zone. + +--- + +## Geometry + +`RefereeGeometry` is a frozen dataclass that decouples the referee from `Field`. It never modifies `Field` constants. + +```python +@dataclass(frozen=True) +class RefereeGeometry: + half_length: float # metres from centre to goal line + half_width: float # metres from centre to sideline + half_goal_width: float # half the goal opening width + half_defense_length: float # depth of defence area + half_defense_width: float # half-width of defence area + center_circle_radius: float # keep-out radius for kickoffs +``` + +Two convenience constructors: + +- `RefereeGeometry.from_standard_div_b()` — mirrors `Field` constants exactly (9 m × 6 m field). +- `RefereeGeometry.from_field_bounds(field_bounds)` — derives `half_length`/`half_width` from a `FieldBounds`; uses `Field` constants for goal and defence dimensions. + +--- + +## Profiles + +Three built-in YAML profiles select the active rule set. Load by name or file path: + +```python +referee = CustomReferee.from_profile_name("simulation") +referee = CustomReferee.from_profile_name("/path/to/my_profile.yaml") +``` + +| Setting | `simulation` | `exhibition` | `human` | +|---|---|---|---| +| Goal detection | ✅ 1.0 s cooldown | ✅ 1.0 s cooldown | ✅ 1.0 s cooldown | +| Out of bounds | ✅ | ✅ | ❌ | +| Defence area | ✅ max 1 defender | ✅ max 1 defender | ❌ | +| Keep-out radius | ✅ 0.5 m | ✅ 0.2 m | ❌ | +| Force start after goal | ❌ | ❌ | ❌ | +| Half duration | 300 s | 300 s | 300 s | + +**`simulation`** — Full SSL-compatible rule set with auto-advance enabled for most restarts. Use for simulator testing, AI-vs-AI development, and RL training. + +**`human`** — Goal detection only, with operator-controlled stage transitions. Use for human-involved scenarios such as real-world testing and physical field sessions where a referee operator should control restarts explicitly. + +### YAML schema + +```yaml +profile_name: "simulation" +geometry: + half_length: 4.5 + half_width: 3.0 + half_goal_width: 0.5 + half_defense_length: 0.5 + half_defense_width: 1.0 + center_circle_radius: 0.5 +rules: + goal_detection: + enabled: true + cooldown_seconds: 1.0 + out_of_bounds: + enabled: true + free_kick_assigner: "last_touch" + defense_area: + enabled: true + max_defenders: 1 + attacker_infringement: true + keep_out: + enabled: true + radius_meters: 0.5 + violation_persistence_frames: 30 +game: + half_duration_seconds: 300.0 + kickoff_team: "yellow" + force_start_after_goal: false +``` + +--- + +## Integration with StrategyRunner + +`StrategyRunner` accepts an optional `custom_referee` parameter. When set: + +1. `RefereeMessageReceiver` is **not** started (no UDP multicast thread). +2. Each tick, `CustomReferee.step()` is called with `self.my_current_game_frame` and the result is pushed into `ref_buffer` before `_step_game()` reads it. +3. On the **transition edge** into `STOP` (i.e. the first frame the command becomes `STOP`), if `RefereeData.designated_position` is not `None` and a `sim_controller` is present, the ball is teleported to `designated_position` in the simulator. After a goal this is always `(0.0, 0.0)` — the centre spot. + +```python +from utama_core.custom_referee import CustomReferee +from utama_core.entities.referee.referee_command import RefereeCommand + +referee = CustomReferee.from_profile_name("simulation", n_robots_yellow=3, n_robots_blue=3) +referee.set_command(RefereeCommand.NORMAL_START, timestamp=0.0) + +runner = StrategyRunner( + strategy=MyStrategy(), + my_team_is_yellow=True, + my_team_is_right=False, + mode="rsim", + exp_friendly=3, + exp_enemy=3, + custom_referee=referee, +) +runner.run() +``` + +The same `CustomReferee` instance works unchanged when `mode="grsim"` or `mode="real"` — the referee has no code paths that depend on mode. In `mode="real"` the ball teleport is silently skipped (`sim_controller` is `None`). + +### Ball teleport after goal (RSim / grSim) + +When a goal is scored the state machine sets `designated_position = (0.0, 0.0)` and issues `STOP`. On the very next `_run_step()` call `StrategyRunner` detects the `NORMAL_START → STOP` edge and calls `sim_controller.teleport_ball(0.0, 0.0)`. This resets the ball to the kick-off spot without any manual operator intervention. + +The edge-detection guard (`_prev_custom_ref_command != STOP`) ensures the teleport fires exactly once — not every frame while the game remains in `STOP`. + +### Manual command injection (RL / test scripts) + +```python +referee.set_command(RefereeCommand.NORMAL_START, timestamp=time.time()) +``` + +This is the standard way to resume play after a stoppage in scripted environments. + +--- + +## Downstream pipeline (unchanged) + +`CustomReferee` slots into the existing pipeline without any changes below `StrategyRunner`: + +``` +CustomReferee.step(game_frame, t) + → RefereeData (source_identifier="custom_referee") + → ref_buffer + → StrategyRunner._run_step reads ref_buffer + → RefereeRefiner.refine(game_frame, referee_data) + → game_frame.referee = RefereeData + → game.referee (via Game.referee property) + → CheckRefereeCommand reads game.referee.referee_command + → Behaviour tree reacts +``` + +--- + +## File structure + +``` +utama_core/custom_referee/ +├── __init__.py # exports CustomReferee, RefereeGeometry +├── custom_referee.py # CustomReferee — rule loop + orchestration +├── geometry.py # RefereeGeometry frozen dataclass +├── state_machine.py # GameStateMachine — score, command, stage +├── rules/ +│ ├── __init__.py +│ ├── base_rule.py # BaseRule ABC, RuleViolation dataclass +│ ├── goal_rule.py # GoalRule +│ ├── out_of_bounds_rule.py # OutOfBoundsRule +│ ├── defense_area_rule.py # DefenseAreaRule +│ └── keep_out_rule.py # KeepOutRule +└── profiles/ + ├── __init__.py + ├── profile_loader.py # load_profile(name|path) → RefereeProfile + ├── simulation.yaml + ├── exhibition.yaml + └── human.yaml + +utama_core/tests/custom_referee/ +├── __init__.py +└── test_custom_referee.py # 34 unit tests + +demo_custom_referee.py # pygame visualisation (run with pixi run python demo_custom_referee.py) +demo_referee_gui_rsim.py # browser GUI + StrategyRunner + RSim (replaces deprecated demo_referee_gui.py) +``` + +--- + +## Running tests + +```bash +pixi run pytest utama_core/tests/custom_referee/ -v +``` + +## Running the visual demo + +```bash +pixi run python demo_custom_referee.py +``` + +The demo runs 6 scripted scenes in sequence, each exercising one rule. Controls: `SPACE` pause, `R` restart, `←` / `→` skip scenes. + +## Running the custom referee GUI with RSim + +`demo_referee_gui_rsim.py` combines `CustomReferee`, a browser-based GUI, and `StrategyRunner` in RSim mode. It replaces the deprecated `demo_referee_gui.py` and `referee_gui.py`. + +```bash +pixi run python demo_referee_gui_rsim.py +# RSim window opens; open http://localhost:8080 in a browser +``` + +### What it does + +- Creates a `CustomReferee` with `enable_gui=True`, which starts an HTTP server on a background daemon thread. +- Passes the referee to `StrategyRunner` via `custom_referee=`. `StrategyRunner` calls `referee.step()` on every tick and handles ball teleports on `STOP` automatically. +- Uses `WanderingStrategy` so robots visibly move; the `RefereeOverride` behaviour tree interrupts them when you issue commands from the GUI. + +### Operator workflow + +1. Open `http://localhost:8080` in a browser. +2. Robots start moving under `WanderingStrategy`. +3. Click any command button (Halt, Stop, Kickoff Yellow…) — robots reposition. +4. Click **Normal Start** to resume free play. +5. With the `human` profile, a goal triggers `STOP` and waits for operator input. + +### Configuration (top of file) + +| Variable | Default | Description | +|---|---|---| +| `PROFILE` | `"human"` | Profile name (`"human"` or `"simulation"`) | +| `GUI_PORT` | `8080` | Browser GUI port | +| `N_ROBOTS` | `3` | Robots per side | +| `MY_TEAM_IS_YELLOW` | `True` | Team colour | +| `MY_TEAM_IS_RIGHT` | `True` | Team side | + +### Enabling the GUI in your own code + +Pass `enable_gui=True` (and optionally `gui_port`) to `CustomReferee`: + +```python +referee = CustomReferee( + profile, + n_robots_yellow=3, + n_robots_blue=3, + enable_gui=True, + gui_port=8080, +) +``` + +Or via the convenience constructor: + +```python +referee = CustomReferee.from_profile_name("simulation", enable_gui=True, gui_port=8080) +``` + +The GUI server imports `referee_gui` lazily, so there is no HTTP/GUI dependency overhead when `enable_gui=False` (the default). diff --git a/docs/custom_referee_design_decisions.md b/docs/custom_referee_design_decisions.md new file mode 100644 index 00000000..47f12652 --- /dev/null +++ b/docs/custom_referee_design_decisions.md @@ -0,0 +1,104 @@ +# Custom Referee — Open Design Decisions + +These are deferred design decisions identified during the code audit against the SSL rulebook. +Each item describes the current behaviour, the relevant rule, and the options to choose from. + +Items marked **✅ Resolved** have been implemented and are kept here for reference. + +--- + +## 1. ✅ Human profile keeps operator-controlled STOP after goals — resolved + +**Resolution (2026-03-31):** The built-in `human` profile now disables all auto-advance +transitions. After a goal or foul, the referee remains in the current stoppage until the +operator explicitly advances the game stage. The `simulation` profile remains the +auto-progressing built-in profile for simulator, testing, and RL workflows. + +--- + +## 2. ✅ `PrepareKickoffTheirsStep` doesn't enforce own-half requirement — resolved + +**Resolution (2026-03-13):** Implemented Option B. After radial clearance, each robot's x +coordinate is clamped to our own half (`max(0, x)` when right, `min(0, x)` when left). + +--- + +## 3. `OutOfBoundsRule` unknown last-touch defaults to yellow + +**File:** `utama_core/custom_referee/rules/out_of_bounds_rule.py` + +**Current behaviour:** +When the ball goes out and no robot was detected touching it (`_last_touch_was_friendly = None`), +the rule awards `DIRECT_FREE_YELLOW`. + +**Relevant rule (SSL):** The last-touching team loses possession (other team gets free kick). +If truly unknown, the standard is a coin flip or alternating possession — not a fixed team. + +**Options:** +- **A (current, keep):** Default to yellow. Simple, predictable, slightly unfair. +- **B (alternate):** Track which team was awarded the last unknown-touch free kick and + alternate. Fairer over many occurrences. +- **C (favor defending team):** Award to the team in whose half the ball went out. Rough + approximation of "attacker kicked it out". + +**Recommendation:** Option A is fine for a simplified system. Option C is easy to implement +and slightly more realistic if desired. + +--- + +## 4. `KeepOutRule` violation count carries over between command changes + +**File:** `utama_core/custom_referee/rules/keep_out_rule.py` + +**Current behaviour:** +`_violation_count` accumulates across command changes (e.g., transitions from +`DIRECT_FREE_YELLOW` to `PREPARE_KICKOFF_BLUE`). If a robot was encroaching for 20 frames +under one command and the command changes, it only needs 10 more frames under the new command +to trigger a violation. + +**Risk level:** Low — the transition cooldown (`_TRANSITION_COOLDOWN = 0.3 s`) means the +command change and any new violation are unlikely to overlap. Also, robot positions are +usually compliant after a command transition. + +**Options:** +- **A (current, keep):** Accept the minor inconsistency. The persistence threshold (30 frames) + is large enough to make false positives very unlikely. +- **B (reset on command change):** Track the previous command and reset `_violation_count` + whenever `current_command` changes. Clean, low cost. + +**Recommendation:** Option B is a one-liner fix with no downside. + +--- + +## 5. ✅ `BallPlacementTheirsStep` has no active clearance — resolved + +**Resolution (2026-03-13):** Implemented Option B. Robots within `_BALL_KEEP_DIST` (0.55 m) +of the ball are now pushed radially outward, matching the pattern used in `DirectFreeTheirsStep`. +Option C (line-segment clearance) remains deferred. + +--- + +## 6. `GoalRule` only fires during NORMAL_START and FORCE_START + +**File:** `utama_core/custom_referee/rules/goal_rule.py` + +**Current behaviour:** +Goal detection is disabled during all stoppages (STOP, PREPARE_KICKOFF, etc.). + +**Edge case:** If the ball rolls into a goal during a stoppage (e.g., a robot accidentally +nudges it during STOP clearance), no goal is detected. + +**Relevant rule:** In SSL, the game is stopped during stoppages so the ball isn't "in play" +and a goal during a stoppage doesn't count. This is correct behaviour. + +**Status:** No change needed. Documented here for clarity. + +--- + +## 7. ✅ Penalty kick rules are incomplete — partially resolved + +**Resolution (2026-03-13):** Implemented Option B. Non-kicker robots (both teams) are now +placed at `y = ±3.0 m` (touch-line boundary) rather than spread across the field. +The x-coordinate (`behind_line_x`) is unchanged — robots remain behind the penalty mark. +Full off-field placement (Option C) is deferred until the simulator supports it. +Penalty kicks remain disabled in all built-in profiles. diff --git a/docs/custom_referee_gui.md b/docs/custom_referee_gui.md new file mode 100644 index 00000000..b3b28534 --- /dev/null +++ b/docs/custom_referee_gui.md @@ -0,0 +1,379 @@ +# Custom Referee Web GUI + +`demo_referee_gui_rsim.py` (project root) is a standalone browser-based operator panel for the +`CustomReferee`. It lets you issue referee commands, watch live scores and robot positions, +and inspect the active profile — all from a browser tab. It requires no npm, no build step, +and no dependencies beyond the project's existing Python environment. + +--- + +## Quick start + +```bash +pixi run python demo_referee_gui_rsim.py +``` + +Then open **http://localhost:8080** in any browser. + +The referee starts in **HALT**. A typical pre-match sequence is: + +``` +Halt → Stop → Kickoff Yellow → Normal Start +``` + +--- + + +## UI areas + +The page has five areas. + +### 1. Scoreboard + +Live yellow / blue scores, updated in real time. + +### 2. Status block + +Four read-only fields that reflect the current referee state: + +| Field | What it shows | +|---|---| +| **Command** | Current referee command, colour-coded: red = HALT, orange = STOP, green = NORMAL/FORCE START, yellow/blue = team-specific commands | +| **Next** | `next_command` — the command that will follow the current stoppage, if known | +| **Stage** | Game stage (e.g. `NORMAL FIRST HALF`) and time remaining (mm:ss) | +| **Designated** | Ball placement target in metres — hidden when `designated_position` is null | + +### 3. Command buttons + +Clicking a button immediately issues that command to the `CustomReferee`. + +The **Advanced** toggle reveals penalty and ball-placement buttons that are rarely needed +manually (they are usually auto-detected). Hover over any button to see a tooltip describing +when to use it. + +| Row | Buttons | +|---|---| +| Flow control | Halt · Stop · Normal Start · Force Start | +| Kickoffs | Kickoff Yellow · Kickoff Blue | +| Free kicks | Free Kick Yellow · Free Kick Blue | +| Penalties *(adv)* | Penalty Yellow · Penalty Blue | +| Ball placement *(adv)* | Ball Placement Yellow · Ball Placement Blue | + +#### Button reference + +| Button | Command issued | When to press | What robots do | +|---|---|---|---| +| **Halt** | `HALT` | Emergency stop; any unsafe situation | Immediately zero velocity — no movement | +| **Stop** | `STOP` | Pause between incidents; pre-match | Slow to ≤1.5 m/s, stay ≥0.5 m from ball | +| **Normal Start** | `NORMAL_START` | After kickoff / free kick robots are in position | Game live — strategy tree takes over | +| **Force Start** | `FORCE_START` | Double-touch infringement; stalled play | Game live — ball at current position, no placement | +| **Kickoff Yellow** | `PREPARE_KICKOFF_YELLOW` | Half-start or after Blue scores | Yellow kicker approaches centre; others to own half | +| **Kickoff Blue** | `PREPARE_KICKOFF_BLUE` | After Yellow scores | Blue kicker approaches centre; others to own half | +| **Free Kick Yellow** | `DIRECT_FREE_YELLOW` | Foul by Blue | Yellow kicker near ball; Blue ≥0.5 m away | +| **Free Kick Blue** | `DIRECT_FREE_BLUE` | Foul by Yellow | Blue kicker near ball; Yellow ≥0.5 m away | +| **Penalty Yellow** *(adv)* | `PREPARE_PENALTY_YELLOW` | Usually auto-detected; manual override only | Yellow kicker at penalty mark; others behind line | +| **Penalty Blue** *(adv)* | `PREPARE_PENALTY_BLUE` | Usually auto-detected; manual override only | Blue kicker at penalty mark; others behind line | +| **Ball Placement Yellow** *(adv)* | `BALL_PLACEMENT_YELLOW` | Manual placement command | Yellow robot moves ball to `designated_position` | +| **Ball Placement Blue** *(adv)* | `BALL_PLACEMENT_BLUE` | Manual placement command | Blue robot moves ball to `designated_position` | + +#### Auto-detected vs manual + +| Command category | Detection | Notes | +|---|---|---| +| Goal → kickoff | Auto (`GoalRule`) | Operator sets kickoff team before half starts | +| Out-of-bounds → free kick | Auto (`OutOfBoundsRule`) | `free_kick_assigner` in profile controls which team | +| Defense area → penalty | Auto (`DefenseAreaRule`, if enabled) | Penalty buttons are in **Advanced** row; hidden by default | +| Ball placement | Auto (`OutOfBoundsRule`, if enabled) | Manual override via Advanced row if auto fails | + +#### Typical sequences + +Standard half start: +``` +Halt → Stop → Kickoff Yellow → Normal Start +``` + +After goal (human profile — auto-restart): +``` +(Goal auto-detected) → Stop → (auto Force Start after stop_duration_seconds) +``` + +Manual free kick: +``` +Halt → Stop → Free Kick Yellow → Normal Start +``` + +### 4. Field canvas + +A top-down view of the field, updated at ~30 Hz via SSE. + +| Element | Colour | Notes | +|---|---|---| +| Field background | Green | Scales automatically to profile geometry | +| Lines / circles | White | Boundary, centre line, centre circle, defence areas | +| Left goal | Yellow (translucent) | Yellow team's goal (negative x side) | +| Right goal | Blue (translucent) | Blue team's goal (positive x side) | +| Friendly robots | Yellow filled circle | ID label above; orientation line shows heading | +| Enemy robots | Blue filled circle | ID label above; orientation line shows heading | +| Ball | Orange filled circle | Minimum 4 px radius | +| Designated × | White cross | Ball placement target; hidden when `designated_position` is null | + +### 5. Profile config panel + +A read-only display of the active profile loaded at startup, confirming what geometry and +rules are in effect. + +| Section | Fields shown | +|---|---| +| Field geometry | half length, half width, half goal width, defense length/width (half), centre circle radius — all in metres | +| Game settings | half duration (minutes), kickoff team, force-start-after-goal flag, stop duration (seconds), auto-advance flags | +| Goal detection | enabled (ON/OFF), cooldown seconds | +| Out of bounds | enabled (ON/OFF), free-kick assigner method | +| Defense area | enabled (ON/OFF), max defenders, attacker infringement flag | +| Keep-out zone | enabled (ON/OFF), radius (metres), violation persistence (frames) | + +Boolean fields are shown as green **ON** / red **OFF** pills. The panel title and browser tab +title both show the profile name. + +A small green dot at the bottom of the page indicates the SSE connection is live. If it turns +grey, the browser will reconnect automatically. + +### Event log + +The **Event Log** panel shows the 20 most recent events, newest first. + +| Entry type | Colour | Trigger | +|---|---|---| +| Command change | Green | `d.command` differs from the previous message | +| Score change | Yellow | `d.yellow_score` or `d.blue_score` differs | +| Status message | Grey (muted) | `d.status_message` is non-empty and differs from previous value | + +--- + +## Profiles + +Built-in profiles live in `utama_core/custom_referee/profiles/`: + +| Profile | Rules active | Auto-advances | +|---|---|---| +| `human` | Goal detection only | All off — operator advances commands manually | +| `simulation` | All four rules (goal, out-of-bounds, defense area, keep-out) | Mostly on — simulator workflow auto-progresses when criteria are met | + +Use `human` for physical environments where a referee operator must control transitions for +safety and testing. Use `simulation` for simulator, strategy testing, and RL workflows. + +--- + +## Changing field dimensions + +All six `geometry` fields are in **metres** and are fully dynamic — every rule reads geometry +on each tick, so changing a value in the profile instantly changes rule behaviour. The field +canvas auto-scales to match. + +| Field | Controls | Rules affected | +|---|---|---| +| `half_length` | Distance from centre to goal line | GoalRule, OutOfBoundsRule, DefenseAreaRule | +| `half_width` | Distance from centre to touch line | OutOfBoundsRule | +| `half_goal_width` | Half-width of each goal mouth | GoalRule | +| `half_defense_length` | Depth of defence area | DefenseAreaRule | +| `half_defense_width` | Half-width of defence area | DefenseAreaRule | +| `center_circle_radius` | Centre circle drawn on canvas; reserved for future keep-out rule | — | + +--- + +## Configuring rules + +Every tuneable parameter and its effect: + +| Key | Type | Effect | +|---|---|---| +| `goal_detection.enabled` | bool | Enables/disables goal scoring | +| `goal_detection.cooldown_seconds` | float | Prevents double-counting within this window | +| `out_of_bounds.enabled` | bool | Enables free-kick on ball exit | +| `out_of_bounds.free_kick_assigner` | `"last_touch"` | Team awarded the free kick | +| `defense_area.enabled` | bool | Enables defender/attacker penalty | +| `defense_area.max_defenders` | int | Max robots allowed inside own defence area | +| `defense_area.attacker_infringement` | bool | Also penalise attackers who enter opponent area | +| `keep_out.enabled` | bool | Enables exclusion zone around ball during stoppages | +| `keep_out.radius_meters` | float | Exclusion radius in metres | +| `keep_out.violation_persistence_frames` | int | Frames robot must stay clear before violation clears | +| `game.half_duration_seconds` | float | Length of each half | +| `game.kickoff_team` | `"yellow"` or `"blue"` | Which team kicks off at the start | +| `game.force_start_after_goal` | bool | Legacy human fast-path; superseded by `auto_advance` flags | +| `game.stop_duration_seconds` | float | STOP hold time before auto FORCE START (legacy human path) | +| `game.auto_advance.stop_to_prepare_kickoff` | bool | Auto STOP → PREPARE_KICKOFF when all robots clear | +| `game.auto_advance.prepare_kickoff_to_normal` | bool | Auto PREPARE_KICKOFF → NORMAL_START when kicker in position (2 s delay) | +| `game.auto_advance.direct_free_to_normal` | bool | Auto DIRECT_FREE → NORMAL_START when kicker ready (2 s delay) | +| `game.auto_advance.ball_placement_to_next` | bool | Auto BALL_PLACEMENT → next command when ball at target (2 s delay) | +| `game.auto_advance.normal_start_to_force` | bool | Auto NORMAL_START → FORCE_START after kickoff timeout if ball hasn't moved | + +--- + +## Auto-advance configuration + +The state machine can automatically advance through referee states when certain conditions are +met. Each transition is independently configurable via the `auto_advance` block in the profile. + +### The five auto-advances + +| # | Transition | Trigger | Delay | +|---|---|---|---| +| 1 | `STOP` → `PREPARE_KICKOFF_*` | All robots ≥ 0.5 m from ball | None | +| 2 | `PREPARE_KICKOFF_*` → `NORMAL_START` | Timer elapsed + kicker inside centre circle | **2 s** | +| 3 | `DIRECT_FREE_*` → `NORMAL_START` | Kicker ≤ 0.3 m from ball + defenders ≥ 0.5 m away | **2 s** | +| 4 | `BALL_PLACEMENT_*` → next command | Ball ≤ 0.15 m from placement target | **2 s** | +| 5 | `NORMAL_START` → `FORCE_START` | Kickoff timeout elapsed + ball hasn't moved | None (uses `kickoff_timeout_seconds`) | + +Advances 2, 3, and 4 require the readiness condition to be **sustained for 2 seconds** before +firing. If the condition drops out during that window (e.g. kicker steps back), the countdown +resets. This gives robots time to settle before play begins. + +### Choosing settings by environment + +**Simulation (default):** All advances on. The state machine drives itself — no operator needed. + +```yaml +game: + auto_advance: + stop_to_prepare_kickoff: true + prepare_kickoff_to_normal: true + direct_free_to_normal: true + ball_placement_to_next: true + normal_start_to_force: true +``` + +**Physical environment (safety):** All advances off. A human operator must explicitly issue +every command. Robots will not start moving until the operator presses a button — ensuring +nobody is on the field when play begins. + +```yaml +game: + auto_advance: + stop_to_prepare_kickoff: false + prepare_kickoff_to_normal: false + direct_free_to_normal: false + ball_placement_to_next: false + normal_start_to_force: false +``` + +--- + +## Creating a custom profile + +1. Copy an existing profile as a starting point: + ```bash + cp utama_core/custom_referee/profiles/human.yaml my_field.yaml + ``` + +2. Edit `my_field.yaml` to match your field and rule requirements. + +3. Run the GUI with your profile: + ```bash + pixi run python demo_referee_gui_rsim.py --profile my_field.yaml + ``` + +### Annotated YAML template + +```yaml +profile_name: "my_profile" + +geometry: + half_length: 4.5 # metres from centre to goal line (full length = 9.0 m) + half_width: 3.0 # metres from centre to touch line (full width = 6.0 m) + half_goal_width: 0.5 # metres from centre of goal mouth to post + half_defense_length: 0.5 # depth of defence area from goal line + half_defense_width: 1.0 # half-width of defence area + center_circle_radius: 0.5 # used for canvas only (future: keep-out at kickoff) + +rules: + goal_detection: + enabled: true + cooldown_seconds: 1.0 # ignore further goals for this many seconds after one is scored + + out_of_bounds: + enabled: true + free_kick_assigner: "last_touch" # only option currently + + defense_area: + enabled: true + max_defenders: 1 # robots allowed inside own defence area + attacker_infringement: true # penalise attackers entering opponent defence area + + keep_out: + enabled: true + radius_meters: 0.5 # exclusion radius around ball during stoppages + violation_persistence_frames: 30 # consecutive frames of encroachment before penalty + +game: + half_duration_seconds: 300.0 + kickoff_team: "yellow" + force_start_after_goal: false + stop_duration_seconds: 3.0 + auto_advance: + stop_to_prepare_kickoff: true # set false for physical/operator-driven environments + prepare_kickoff_to_normal: true + direct_free_to_normal: true + ball_placement_to_next: true + normal_start_to_force: true +``` + +### Worked example: small practice field (4 m × 2.67 m) + +```yaml +profile_name: "practice_room" + +geometry: + half_length: 2.0 + half_width: 1.335 + half_goal_width: 0.35 + half_defense_length: 0.4 + half_defense_width: 0.7 + center_circle_radius: 0.35 + +rules: + goal_detection: + enabled: true + cooldown_seconds: 1.0 + out_of_bounds: + enabled: true + free_kick_assigner: "last_touch" + defense_area: + enabled: false + max_defenders: 1 + attacker_infringement: false + keep_out: + enabled: false + radius_meters: 0.3 + violation_persistence_frames: 30 + +game: + half_duration_seconds: 120.0 + kickoff_team: "yellow" + force_start_after_goal: true + stop_duration_seconds: 2.0 + auto_advance: + stop_to_prepare_kickoff: true + prepare_kickoff_to_normal: true + direct_free_to_normal: true + ball_placement_to_next: true + normal_start_to_force: true +``` + +The canvas will render a noticeably smaller field, and the profile panel will confirm the +updated geometry values. + +--- + +## Running with a live game loop + +`demo_referee_gui_rsim.py` on its own runs in standalone mode — the canvas shows a static empty field. +To see live robots: + +```bash +pixi run python utama_core/tests/referee/demo_referee_gui_rsim.py +# RSim window opens; open http://localhost:8080 in a browser +``` + +This script starts a `CustomReferee` (default: `simulation` profile) with `enable_gui=True`, +connects it to RSim, and drives `referee.step()` on every tick. Edit the `PROFILE`, +`N_ROBOTS`, `MY_TEAM_IS_YELLOW`, and `MY_TEAM_IS_RIGHT` constants at the top of the file to +configure it. diff --git a/docs/referee_integration.md b/docs/referee_integration.md new file mode 100644 index 00000000..d4a3d49e --- /dev/null +++ b/docs/referee_integration.md @@ -0,0 +1,501 @@ +# Referee Integration Design + +This document captures the design decisions for integrating the SSL Game Controller referee +into Utama's behaviour tree architecture. + +--- + +## 1. Referee Data + +### Fields in `RefereeData` + +| Field | Type | Purpose | +|---|---|---| +| `referee_command` | `RefereeCommand` | Primary driver of the hardcoded tree | +| `stage` | `Stage` | Game phase (first half, penalty shootout, etc.) | +| `stage_time_left` | `float` | Seconds remaining in current stage | +| `blue_team` / `yellow_team` | `TeamInfo` | Scores, cards, goalkeeper ID, foul counts | +| `designated_position` | `Optional[Tuple[float, float]]` | Ball placement target (x, y) in metres | +| `blue_team_on_positive_half` | `Optional[bool]` | Which side blue team defends | +| `next_command` | `Optional[RefereeCommand]` | Command after current stoppage — use to pre-position | +| `current_action_time_remaining` | `Optional[int]` | Microseconds remaining for ball placement / free kick | +| `source_identifier` | `Optional[str]` | Which autoreferee sent this packet | + +### Fields recently added + +| Field | Protobuf source | Why useful | +|---|---|---| +| `game_events` | `repeated GameEvent game_events = 16` | Why the command was issued (foul type, ball-out side, etc.); useful for logging and future decision-making | +| `match_type` | `optional MatchType match_type = 19` | FRIENDLY / GROUP_PHASE / ELIMINATION_PHASE; may affect strategy aggression | +| `status_message` | `optional string status_message = 20` | Human-readable reason shown by referee UI; shown in live FPS display | + +`game_events`, `match_type`, and `status_message` are intentionally **excluded from `__eq__`** +so they do not trigger spurious re-records in `RefereeRefiner`. + +`game_event_proposals` (field 17) are multi-referee vote accumulations and are not needed. + +--- + +## 2. Game States and Required Robot Behaviour + +Rules sourced from the [SSL Rulebook](https://robocup-ssl.github.io/ssl-rules/sslrules.html). + +| Command | Our robots must... | Key constraint | +|---|---|---| +| **HALT** | Immediately zero velocity. No movement. | 2-second grace period to brake. Highest priority. | +| **STOP** | Slow to ≤ 1.5 m/s, stay ≥ 0.5 m from ball. No ball contact. | Also ≥ 0.2 m from opponent defence area. | +| **TIMEOUT_YELLOW / BLUE** | Idle; effectively STOP behaviour. | Not our timeout: nothing forced, but safe to stop. | +| **PREPARE_KICKOFF (ours)** | All except kicker go to own half, outside centre circle. Kicker approaches ball at centre. Do not touch ball yet. | Centre circle radius = 0.5 m. | +| **PREPARE_KICKOFF (theirs)** | All robots to own half, outside centre circle. | Same zone constraint. | +| **NORMAL_START** (after kickoff / free kick) | Game live — pass to strategy tree. | Ball is now in play. | +| **FORCE_START** | Game live — pass to strategy tree. | Ball at current position; no placement needed. | +| **PREPARE_PENALTY (ours)** | Kicker: approach penalty mark, do not touch. Our other robots: ≥ 0.4 m behind penalty mark line. | Penalty mark: 6 m from goal centre (Div B). | +| **PREPARE_PENALTY (theirs)** | Our goalkeeper: touch own goal line. All other our robots: ≥ 0.4 m behind the penalty mark (on our side). | Goalkeeper ID from `referee.{our_team}.goalkeeper`. | +| **DIRECT_FREE (ours)** | One robot (kicker) approaches ball. Others position freely. After NORMAL_START the kicker may shoot directly. | Ball must move ≥ 0.05 m to be in play. | +| **DIRECT_FREE (theirs)** | All our robots ≥ 0.5 m from ball. Full speed allowed (unlike STOP). | Same distance as STOP but no speed cap. | +| **BALL_PLACEMENT (ours)** | One robot moves the ball to `designated_position`. Other robots clear ≥ 0.5 m from ball. | If `can_place_ball` is False we cannot place — skip to STOP-like behaviour. | +| **BALL_PLACEMENT (theirs)** | All our robots stay ≥ 0.5 m from ball and from the `designated_position`. | Do not interfere with their placement robot. | + +### "Ours vs. theirs" resolution + +Each bilateral command (KICKOFF / PENALTY / DIRECT_FREE / BALL_PLACEMENT) comes in YELLOW and BLUE +variants. Resolved at **tick-time** inside each dispatcher node: + +```python +# In _BallPlacementDispatch.update(): +if self._is_yellow_command == self.blackboard.game.my_team_is_yellow: + return self._ours.update() +else: + return self._theirs.update() +``` + +This avoids any construction-time dependency on team colour. + +### Using `next_command` for pre-positioning + +During STOP, `next_command` reveals what restart is coming before it happens. +Example: if `next_command == DIRECT_FREE_BLUE` and we are blue, robots can already drift +toward their free-kick positions during the STOP phase, gaining a timing advantage. +This is an optimisation and does not affect compliance. + +--- + +## 3. Architecture — Option B: Referee Priority Child (implemented) + +The referee override layer sits as the first (highest-priority) child of a root `Selector` +inside every `AbstractStrategy`. This makes it: + +- Visible in tree renders (DOT/PNG/SVG via `render()`). +- Automatically applied to every strategy — no per-strategy changes needed. +- Decoupled from `StrategyRunner` — all logic lives in the tree. + +### Tree structure + +``` +Root [Selector, memory=False] +├── RefereeOverride [Selector, memory=False] ← injected automatically by AbstractStrategy +│ ├── Halt [Sequence] +│ │ ├── CheckRefereeCommand(HALT) +│ │ └── HaltStep +│ ├── Stop [Sequence] +│ │ ├── CheckRefereeCommand(STOP) +│ │ └── StopStep +│ ├── Timeout [Sequence] +│ │ ├── CheckRefereeCommand(TIMEOUT_YELLOW | TIMEOUT_BLUE) +│ │ └── StopStep +│ ├── BallPlacementYellow [Sequence] +│ │ ├── CheckRefereeCommand(BALL_PLACEMENT_YELLOW) +│ │ └── _BallPlacementDispatch(is_yellow_command=True) +│ ├── BallPlacementBlue [Sequence] +│ │ ├── CheckRefereeCommand(BALL_PLACEMENT_BLUE) +│ │ └── _BallPlacementDispatch(is_yellow_command=False) +│ ├── KickoffYellow [Sequence] +│ ├── KickoffBlue [Sequence] +│ ├── PenaltyYellow [Sequence] +│ ├── PenaltyBlue [Sequence] +│ ├── DirectFreeYellow [Sequence] +│ └── DirectFreeBlue [Sequence] +│ [Each Sequence returns FAILURE if its condition doesn't match → Selector continues] +└── CoachRoot ← returned by create_behaviour_tree() — unchanged +``` + +**Priority order**: HALT first (highest). NORMAL_START and FORCE_START have no override node — +the Selector falls through to the strategy tree ("game is live"). + +### Change to `AbstractStrategy` + +`__init__` wraps the user's tree. Uses a lazy import to break the circular dependency: + +```python +def __init__(self): + # Lazy import to break circular dependency: + # abstract_strategy → referee.tree → referee.conditions → abstract_behaviour + # → strategy.common.__init__ → abstract_strategy + from utama_core.strategy.referee.tree import build_referee_override_tree + + strategy_subtree = self.create_behaviour_tree() + root = py_trees.composites.Selector(name="Root", memory=False) + root.add_children([build_referee_override_tree(), strategy_subtree]) + self.behaviour_tree = py_trees.trees.BehaviourTree(root) +``` + +--- + +## 4. Folder Structure + +``` +utama_core/strategy/referee/ +├── __init__.py # exports CheckRefereeCommand, build_referee_override_tree +├── conditions.py # CheckRefereeCommand — returns SUCCESS if command matches, else FAILURE +├── actions.py # HaltStep, StopStep, BallPlacement{Ours,Theirs}Step, +│ # PrepareKickoff{Ours,Theirs}Step, PreparePenalty{Ours,Theirs}Step, +│ # DirectFree{Ours,Theirs}Step +└── tree.py # build_referee_override_tree() + _*Dispatch routing nodes + +utama_core/tests/referee/ +├── __init__.py +├── referee_sim.py # Visual RSim simulation cycling through all 11 commands +└── wandering_strategy.py # Base strategy for simulation — robots patrol waypoints +``` + +--- + +## 5. Bugs Fixed During Integration + +### Bug 1 — `RefereeRefiner.refine` called wrong methods on `GameFrame` + +`refine(game, data)` was calling `game.current_frame` and `game.update_frame()` on a +`GameFrame` object (not a `Game`). This was a pre-existing bug that never triggered because +`RefereeMessageReceiver` was commented out. + +**Fix**: Rewrote to use `dataclasses.replace(game_frame, referee=data)` directly. + +### Bug 2 — `CurrentGameFrame` did not copy `referee` field + +`CurrentGameFrame.__init__` was missing: +```python +object.__setattr__(self, "referee", game.referee) +``` + +This caused `AttributeError: 'CurrentGameFrame' object has no attribute 'referee'`. + +### Bug 3 — Dispatcher nodes used `game.current_frame` instead of `game.my_team_is_yellow` + +All four dispatcher nodes (`_BallPlacementDispatch`, `_KickoffDispatch`, `_PenaltyDispatch`, +`_DirectFreeDispatch`) used `self.blackboard.game.current_frame.my_team_is_yellow` — but +`Game` has no `current_frame` attribute (it has `current`). Fixed to use +`self.blackboard.game.my_team_is_yellow` directly via the `Game.my_team_is_yellow` property. + +--- + +## 6. Data Flow + +### Real mode (AutoReferee → WSL → robot) + +``` +AutoReferee (224.5.23.1:10003) + → RefereeMessageReceiver (UDP multicast thread) + → ref_buffer (deque maxlen=1) + → strategy_runner._run_step reads ref_buffer + → RefereeRefiner.refine(game_frame, referee_data) + → game_frame.referee = RefereeData + → game.referee (via Game.referee property) + → CheckRefereeCommand reads game.referee.referee_command +``` + +Requires WSL `networkingMode=mirrored` in `.wslconfig` for multicast UDP to reach WSL. + +### RSim mode (simulation) + +``` +ref_buffer.append(RefereeData) ← pushed externally (e.g. referee_sim.py) + → strategy_runner._run_step reads ref_buffer (when _frame_to_observations returns 3-tuple) + → same pipeline as above +``` + +### RSim / grSim with CustomReferee (ball teleport) + +When `custom_referee` is set and a simulator is active, `StrategyRunner` additionally +teleports the ball on the STOP transition edge if `designated_position` is set: + +``` +CustomReferee.step(game_frame, t) + → RefereeData.designated_position = (0.0, 0.0) (after a goal) + → _prev_custom_ref_command != STOP, new command == STOP + → sim_controller.teleport_ball(0.0, 0.0) (RSim or grSim only) + → _prev_custom_ref_command = STOP +``` + +This fires **once** on the transition edge and is silently skipped in Real mode. + +--- + +## 7. Visualisation Simulation + +Two scripts in `utama_core/tests/referee/` provide visual ways to verify referee behaviour in RSim. + +### Automated command cycling (`referee_sim.py`) + +```bash +pixi run python -m utama_core.tests.referee.referee_sim +``` + +- Uses `WanderingStrategy` as the base (robots continuously patrol waypoints) +- Cycles through all 11 referee commands every 5 seconds +- The `RefereeOverride` tree intercepts each command and you can watch robots reposition +- Command sequence starts with `NORMAL_START` so robots are visibly moving before the first override + +To change timing, edit `SECS_PER_COMMAND` in `referee_sim.py`. + +### Interactive GUI demo (`demo_referee_gui_rsim.py`) + +```bash +pixi run python utama_core/tests/referee/demo_referee_gui_rsim.py +# RSim window opens; open http://localhost:8080 in a browser +``` + +- Starts a `CustomReferee` (default: `simulation` profile) with `enable_gui=True` +- `StrategyRunner` drives `referee.step()` on every tick — GUI receives live robot/ball positions +- Uses `WanderingStrategy` so robots visibly move and you can watch the `RefereeOverride` tree interrupt them +- Operator issues commands from the browser; the canvas shows robots repositioning in real time +- Edit `PROFILE`, `N_ROBOTS`, `MY_TEAM_IS_YELLOW`, `MY_TEAM_IS_RIGHT` constants at the top of the file to configure + +--- + +## 8. Custom Referee Web GUI (`referee_gui.py`) + +`referee_gui.py` (project root) is a standalone browser-based operator panel for the +`CustomReferee`. It requires no npm, no build step, and no dependencies beyond the project's +existing Python environment. + +### Starting the server + +```bash +pixi run python referee_gui.py +``` + +Then open **http://localhost:8080** in any browser. + +#### CLI options + +| Flag | Default | Description | +|---|---|---| +| `--profile` | `human` | Referee profile: `human`, `simulation`, or path to a YAML file | +| `--port` | `8080` | HTTP port to listen on | +| `--yellow-robots` | `3` | Number of yellow robots passed to `CustomReferee` | +| `--blue-robots` | `3` | Number of blue robots passed to `CustomReferee` | + +Example with a non-default profile and port: + +```bash +pixi run python referee_gui.py --profile simulation --port 9090 --yellow-robots 6 --blue-robots 6 +``` + +### Using the GUI + +The page is divided into four areas: + +**Scoreboard** — live yellow / blue scores updated in real time. + +**Status block** — four read-only fields: + +| Field | What it shows | +|---|---| +| Command | Current referee command, colour-coded (red = HALT, orange = STOP, green = NORMAL / FORCE START, yellow/blue = team-specific commands) | +| Next | `next_command` — the command that will follow the current stoppage, if known | +| Stage | Current game stage (e.g. `NORMAL FIRST HALF`) and time remaining (mm:ss) | +| Designated | `designated_position` in metres — the ball placement target after a stoppage | + +**Command buttons** — clicking a button immediately calls `CustomReferee.set_command()` on the server: + +| Row | Buttons | +|---|---| +| Flow control | Halt · Stop · Normal Start · Force Start | +| Kickoffs | Kickoff Yellow · Kickoff Blue | +| Free kicks | Free Kick Yellow · Free Kick Blue | +| Penalties | Penalty Yellow · Penalty Blue | +| Ball placement | Ball Placement Yellow · Ball Placement Blue | + +**Profile config panel** — read-only display of the active profile loaded at startup, split into six sections: + +| Section | Fields shown | +|---|---| +| Field geometry | half length, half width, half goal width, defense length/width (half), centre circle radius — all in metres | +| Game settings | half duration (minutes), kickoff team, force-start-after-goal flag, stop duration (seconds) | +| Goal detection | enabled (ON/OFF), cooldown seconds | +| Out of bounds | enabled (ON/OFF), free-kick assigner method | +| Defense area | enabled (ON/OFF), max defenders, attacker infringement flag | +| Keep-out zone | enabled (ON/OFF), radius (metres), violation persistence (frames) | + +Boolean fields are shown as green **ON** / red **OFF** pills. The panel title and browser tab title both show the profile name. + +A small green dot at the bottom of the page indicates the SSE connection is live. If it turns grey the browser will reconnect automatically. + +### Profiles + +Built-in profiles live in `utama_core/custom_referee/profiles/`: + +| Profile | Rules active | Auto-restart after goal | +|---|---|---| +| `human` | Goal detection only | No — operator controls the next stage | +| `simulation` | All four rules (goal, out-of-bounds, defense area, keep-out) | Yes — progresses automatically when restart criteria are met | + +To customise, copy a YAML file, edit the values, and pass the path: + +```bash +pixi run python referee_gui.py --profile /path/to/my_profile.yaml +``` + +The YAML structure mirrors the dataclasses in `profile_loader.py`: + +```yaml +profile_name: "my_profile" +geometry: + half_length: 4.5 # metres from centre to goal line + half_width: 3.0 # metres from centre to touch line + half_goal_width: 0.5 # metres from centre of goal to post + half_defense_length: 0.5 # depth of defense area from goal line + half_defense_width: 1.0 # half-width of defense area + center_circle_radius: 0.5 +rules: + goal_detection: + enabled: true + cooldown_seconds: 1.0 # ignore further goals for this many seconds after one is scored + out_of_bounds: + enabled: true + free_kick_assigner: "last_touch" # only option currently + defense_area: + enabled: true + max_defenders: 1 # robots allowed inside own defense area + attacker_infringement: true # penalise attackers entering opponent defense area + keep_out: + enabled: true + radius_meters: 0.5 # exclusion radius around ball during stoppages + violation_persistence_frames: 30 # frames a robot must stay clear before violation clears +game: + half_duration_seconds: 300.0 + kickoff_team: "yellow" + force_start_after_goal: false # true = auto FORCE START; false = wait for operator + stop_duration_seconds: 3.0 # STOP hold time before auto FORCE START (if enabled) +``` + +### Architecture + +``` +referee_gui.py +│ +├── _tick_loop (daemon thread, ~30 Hz) +│ └── CustomReferee.step() → stores latest RefereeData, broadcasts to SSE clients +│ +├── GET / → serves inline HTML + CSS + JS (no external resources) +├── GET /config → returns profile config as JSON (fetched once on page load) +├── GET /events → SSE stream; browser EventSource reconnects automatically +└── POST /command → JSON body {"command": "HALT"}, calls set_command(), returns 204 +``` + +The server uses only `http.server.BaseHTTPRequestHandler` (stdlib). The browser page has no +framework dependency — state updates arrive via `EventSource`, config is fetched once with +`fetch('/config')`, and buttons call `fetch('/command')`. + +### Typical operator workflow + +1. Start the GUI with the desired profile. +2. The referee starts in **HALT**. Click **Stop** to begin a pre-match pause. +3. Click **Kickoff Yellow** (or Blue) to issue `PREPARE_KICKOFF_*`. +4. Click **Normal Start** to begin play — the stage timer starts counting down. +5. Use **Halt** / **Stop** between incidents; issue free kicks or penalties as needed. +6. The stage advances automatically (e.g. `NORMAL_FIRST_HALF` → `NORMAL_HALF_TIME`) according to the profile's `half_duration_seconds`. + +### Button reference + +| Button | Command issued | When to press | What robots do | +|---|---|---|---| +| **Halt** | `HALT` | Emergency stop; any unsafe situation | Immediately zero velocity — no movement | +| **Stop** | `STOP` | Pause between incidents; pre-match | Slow to ≤1.5 m/s, stay ≥0.5 m from ball | +| **Normal Start** | `NORMAL_START` | After kickoff / free kick robots are in position | Game live — strategy tree takes over | +| **Force Start** | `FORCE_START` | Double-touch infringement; stalled play | Game live — ball at current position, no placement | +| **Kickoff Yellow** | `PREPARE_KICKOFF_YELLOW` | Half-start or after Blue scores | Yellow kicker approaches centre; others to own half | +| **Kickoff Blue** | `PREPARE_KICKOFF_BLUE` | After Yellow scores | Blue kicker approaches centre; others to own half | +| **Free Kick Yellow** | `DIRECT_FREE_YELLOW` | Foul by Blue | Yellow kicker near ball; Blue ≥0.5 m away | +| **Free Kick Blue** | `DIRECT_FREE_BLUE` | Foul by Yellow | Blue kicker near ball; Yellow ≥0.5 m away | +| **Penalty Yellow** *(adv)* | `PREPARE_PENALTY_YELLOW` | Usually auto-detected; manual override only | Yellow kicker at penalty mark; others behind line | +| **Penalty Blue** *(adv)* | `PREPARE_PENALTY_BLUE` | Usually auto-detected; manual override only | Blue kicker at penalty mark; others behind line | +| **Ball Placement Yellow** *(adv)* | `BALL_PLACEMENT_YELLOW` | Manual placement command | Yellow robot moves ball to `designated_position` | +| **Ball Placement Blue** *(adv)* | `BALL_PLACEMENT_BLUE` | Manual placement command | Blue robot moves ball to `designated_position` | + +#### Auto-detected vs manual + +| Command category | Detection | Notes | +|---|---|---| +| Goal → kickoff | Auto (GoalRule) | Operator sets kickoff team before half starts | +| Out-of-bounds → free kick | Auto (OutOfBoundsRule) | `free_kick_assigner` in profile controls which team | +| Defense area → penalty | Auto (DefenseAreaRule, if enabled) | Penalty buttons are in **Advanced** row; hidden by default | +| Ball placement | Auto (OutOfBoundsRule, if enabled) | Manual override via Advanced row if auto fails | + +#### Typical sequences + +Standard half start: +``` +Halt → Stop → Kickoff Yellow → Normal Start +``` + +After goal (human profile — auto-restart): +``` +(Goal auto-detected) → Stop → (auto Force Start after stop_duration_seconds) +``` + +Manual free kick: +``` +Halt → Stop → Free Kick Yellow → Normal Start +``` + +### Live field visualisation + +The **Field** panel shows a top-down canvas updated in real time at ~30 Hz via SSE. + +| Element | Colour | Notes | +|---|---|---| +| Field background | Green | Scaled to profile geometry | +| Lines / circles | White | Boundary, centre line, centre circle, defence areas | +| Left goal | Yellow (translucent) | Yellow team's goal (negative x side) | +| Right goal | Blue (translucent) | Blue team's goal (positive x side) | +| Friendly robots | Yellow filled circle | ID label above; orientation line shows heading | +| Enemy robots | Blue filled circle | ID label above; orientation line shows heading | +| Ball | Orange filled circle | Minimum 4 px radius | +| Designated × | White cross | Ball placement target; hidden when `designated_position` is null | + +> **Standalone mode**: the canvas shows an empty green field with the ball at (0, 0) because +> `_make_static_frame()` creates a frame with no robots. Robots appear when driven by +> `demo_referee_gui_rsim.py` or another live game loop. + +### Event log + +The **Event Log** panel shows the 20 most recent events, newest first. + +| Entry type | Colour | Trigger | +|---|---|---| +| Command change | Green | `d.command` differs from previous message | +| Score change | Yellow | `d.yellow_score` or `d.blue_score` differs from previous message | +| Status message | Grey (muted) | `d.status_message` is non-empty and differs from previous value | + +--- + +## 9. Open Questions / Future Work + +- **Active distance-keeping during STOP/free kicks**: Currently we stop in place. + A better implementation moves robots away from the ball if they are within 0.5 m. + +- **Ball placement precision**: `BallPlacementOursStep` uses `move()` which will stop the ball + near (not exactly at) `designated_position`. The tolerance is ±0.15 m per the rules. + Future work: dribble to position then release. + +- **Kicker selection**: Currently lowest robot ID. Should prefer the robot closest to ball. + +- **Using `next_command` for pre-positioning**: A future optimisation reads `next_command` + during STOP and begins drifting to the correct position before the command changes. + +- **`can_place_ball` fallback**: If `TeamInfo.can_place_ball` is False (too many placement + failures), `BallPlacementOursStep` must fall back to STOP behaviour. + +- **Active ball-distance enforcement during DIRECT_FREE (theirs)**: Currently stops in place. + Should actively move away if within 0.5 m of ball. diff --git a/main.py b/main.py index bfb4c138..55bd9bf4 100644 --- a/main.py +++ b/main.py @@ -25,7 +25,7 @@ def main(): exp_friendly=2, exp_enemy=0, replay_writer_config=ReplayWriterConfig(replay_name="test_replay", overwrite_existing=True), - print_real_fps=True, + show_live_status=True, profiler_name=None, ) runner.my.strategy.render() diff --git a/start_test_env.sh b/start_test_env.sh index b97e6f67..475434f0 100755 --- a/start_test_env.sh +++ b/start_test_env.sh @@ -44,17 +44,17 @@ if [ $? -ne 0 ]; then fi # Change to the ssl-game-controller directory and run the game controller, suppressing output -# echo "Starting game controller..." -# cd ssl-game-controller/ -# ./ssl-game-controller > /dev/null 2>&1 & -# GAME_CONTROLLER_PID=$! -# cd .. +echo "Starting game controller..." +cd ssl-game-controller/ +./ssl-game-controller > /dev/null 2>&1 & +GAME_CONTROLLER_PID=$! +cd .. # Check if the game controller started successfully -# if [ $? -ne 0 ]; then -# echo "Failed to start game controller. Exiting." -# cleanup -# fi +if [ $? -ne 0 ]; then + echo "Failed to start game controller. Exiting." + cleanup +fi # Change to the AutoReferee directory and run the run.sh script, suppressing output echo "Starting AutoReferee..." diff --git a/utama_core/custom_referee/__init__.py b/utama_core/custom_referee/__init__.py new file mode 100644 index 00000000..6b08039e --- /dev/null +++ b/utama_core/custom_referee/__init__.py @@ -0,0 +1,4 @@ +from utama_core.custom_referee.custom_referee import CustomReferee +from utama_core.custom_referee.geometry import RefereeGeometry + +__all__ = ["CustomReferee", "RefereeGeometry"] diff --git a/utama_core/custom_referee/custom_referee.py b/utama_core/custom_referee/custom_referee.py new file mode 100644 index 00000000..8675b30a --- /dev/null +++ b/utama_core/custom_referee/custom_referee.py @@ -0,0 +1,163 @@ +"""CustomReferee: orchestrates rule checking and state management.""" + +from __future__ import annotations + +from typing import List, Optional + +from utama_core.custom_referee.geometry import RefereeGeometry +from utama_core.custom_referee.profiles.profile_loader import ( + RefereeProfile, + load_profile, +) +from utama_core.custom_referee.rules.base_rule import BaseRule, RuleViolation +from utama_core.custom_referee.rules.defense_area_rule import DefenseAreaRule +from utama_core.custom_referee.rules.goal_rule import GoalRule +from utama_core.custom_referee.rules.keep_out_rule import KeepOutRule +from utama_core.custom_referee.rules.out_of_bounds_rule import OutOfBoundsRule +from utama_core.custom_referee.state_machine import GameStateMachine +from utama_core.entities.data.referee import RefereeData +from utama_core.entities.game.game_frame import GameFrame +from utama_core.entities.referee.referee_command import RefereeCommand + + +def _build_active_rules(rules_cfg) -> List[BaseRule]: + """Construct the ordered list of active rules from a RulesConfig.""" + active: List[BaseRule] = [] + + # Priority order: GoalRule → OutOfBoundsRule → DefenseAreaRule → KeepOutRule + if rules_cfg.goal_detection.enabled: + active.append(GoalRule(cooldown_seconds=rules_cfg.goal_detection.cooldown_seconds)) + + if rules_cfg.out_of_bounds.enabled: + active.append(OutOfBoundsRule()) + + if rules_cfg.defense_area.enabled: + active.append( + DefenseAreaRule( + max_defenders=rules_cfg.defense_area.max_defenders, + attacker_infringement=rules_cfg.defense_area.attacker_infringement, + ) + ) + + if rules_cfg.keep_out.enabled: + active.append( + KeepOutRule( + radius_meters=rules_cfg.keep_out.radius_meters, + violation_persistence_frames=rules_cfg.keep_out.violation_persistence_frames, + ) + ) + + return active + + +class CustomReferee: + """Stateful referee that operates on ``GameFrame`` objects. + + Works uniformly across Real, grSim, and RSim modes because it does not + depend on any network receiver or simulator-specific data. + + Usage:: + + referee = CustomReferee.from_profile_name("simulation") + ref_data = referee.step(game_frame, time.time()) + + To also open the browser GUI (http://localhost:8080) when the referee + is created, pass ``enable_gui=True``:: + + referee = CustomReferee(profile, enable_gui=True, gui_port=8080) + """ + + def __init__( + self, + profile: RefereeProfile, + n_robots_yellow: int = 3, + n_robots_blue: int = 3, + enable_gui: bool = False, + gui_port: int = 8080, + ) -> None: + self._geometry: RefereeGeometry = profile.geometry + self._rules: List[BaseRule] = _build_active_rules(profile.rules) + self._state = GameStateMachine( + half_duration_seconds=profile.game.half_duration_seconds, + kickoff_team=profile.game.kickoff_team, + n_robots_yellow=n_robots_yellow, + n_robots_blue=n_robots_blue, + force_start_after_goal=profile.game.force_start_after_goal, + stop_duration_seconds=profile.game.stop_duration_seconds, + prepare_duration_seconds=profile.game.prepare_duration_seconds, + kickoff_timeout_seconds=profile.game.kickoff_timeout_seconds, + geometry=profile.geometry, + auto_advance=profile.game.auto_advance, + ) + self._gui_server = None + if enable_gui: + # Lazy import to keep this module free of HTTP/GUI dependencies + # when the GUI is not needed. + from utama_core.custom_referee.gui import ( + _build_config_json, + _RefereeGUIServer, + attach_gui, + ) + + self._gui_server = _RefereeGUIServer(self, profile, gui_port, run_tick_loop=False) + self._gui_server.start() + print(f"Referee GUI → http://localhost:{gui_port}") + print(f"Profile: {profile.profile_name}") + + @classmethod + def from_profile_name( + cls, + name: str, + n_robots_yellow: int = 3, + n_robots_blue: int = 3, + enable_gui: bool = False, + gui_port: int = 8080, + ) -> "CustomReferee": + """Convenience constructor: load profile by built-in name or file path.""" + profile = load_profile(name) + return cls( + profile, + n_robots_yellow=n_robots_yellow, + n_robots_blue=n_robots_blue, + enable_gui=enable_gui, + gui_port=gui_port, + ) + + # ------------------------------------------------------------------ + # Main loop interface + # ------------------------------------------------------------------ + + def step(self, game_frame: GameFrame, current_time: float) -> RefereeData: + """Evaluate all rules and advance the state machine by one tick. + + First matching rule (in priority order) wins; subsequent rules are + not evaluated. + """ + violation: Optional[RuleViolation] = None + for rule in self._rules: + result = rule.check(game_frame, self._geometry, self._state.command) + if result is not None: + violation = result + break + + # Notify rules of any command transition so they can reset internal state. + if violation is not None: + for rule in self._rules: + rule.reset() + + result = self._state.step(current_time, violation, game_frame) + if self._gui_server is not None: + self._gui_server.notify(result, game_frame) + return result + + def set_command(self, command: RefereeCommand, timestamp: float) -> None: + """Manual override — for operator use or test scripting.""" + self._state.set_command(command, timestamp) + + # ------------------------------------------------------------------ + # Properties (read-only access for callers that need to inspect state) + # ------------------------------------------------------------------ + + @property + def geometry(self) -> RefereeGeometry: + return self._geometry diff --git a/utama_core/custom_referee/geometry.py b/utama_core/custom_referee/geometry.py new file mode 100644 index 00000000..5d714200 --- /dev/null +++ b/utama_core/custom_referee/geometry.py @@ -0,0 +1,71 @@ +"""RefereeGeometry: configurable field dimensions for the CustomReferee.""" + +from dataclasses import dataclass + +from utama_core.entities.game.field import Field, FieldBounds + + +@dataclass(frozen=True) +class RefereeGeometry: + """Immutable field geometry used by referee rule checkers. + + All measurements are in metres, using the standard SSL coordinate system + (origin at centre, +x toward right goal, +y toward top of field). + """ + + half_length: float + half_width: float + half_goal_width: float + half_defense_length: float + half_defense_width: float + center_circle_radius: float + + @classmethod + def from_standard_div_b(cls) -> "RefereeGeometry": + """Return geometry matching the standard SSL Division B field.""" + return cls( + half_length=Field._FULL_FIELD_HALF_LENGTH, # 4.5 + half_width=Field._FULL_FIELD_HALF_WIDTH, # 3.0 + half_goal_width=Field._HALF_GOAL_WIDTH, # 0.5 + half_defense_length=Field._HALF_DEFENSE_AREA_LENGTH, # 0.5 + half_defense_width=Field._HALF_DEFENSE_AREA_WIDTH, # 1.0 + center_circle_radius=0.5, + ) + + @classmethod + def from_field_bounds(cls, field_bounds: FieldBounds) -> "RefereeGeometry": + """Derive half_length/width from a FieldBounds; use Field constants for the rest.""" + half_length = (field_bounds.bottom_right[0] - field_bounds.top_left[0]) / 2.0 + half_width = (field_bounds.top_left[1] - field_bounds.bottom_right[1]) / 2.0 + return cls( + half_length=half_length, + half_width=half_width, + half_goal_width=Field._HALF_GOAL_WIDTH, + half_defense_length=Field._HALF_DEFENSE_AREA_LENGTH, + half_defense_width=Field._HALF_DEFENSE_AREA_WIDTH, + center_circle_radius=0.5, + ) + + # ------------------------------------------------------------------ + # Spatial query helpers + # ------------------------------------------------------------------ + + def is_in_field(self, x: float, y: float) -> bool: + """True if (x, y) is within the playing field (including boundary).""" + return abs(x) <= self.half_length and abs(y) <= self.half_width + + def is_in_left_goal(self, x: float, y: float) -> bool: + """True if the ball has crossed the left goal line inside the goal.""" + return x < -self.half_length and abs(y) < self.half_goal_width + + def is_in_right_goal(self, x: float, y: float) -> bool: + """True if the ball has crossed the right goal line inside the goal.""" + return x > self.half_length and abs(y) < self.half_goal_width + + def is_in_left_defense_area(self, x: float, y: float) -> bool: + """True if (x, y) is inside the left defense area.""" + return x <= -self.half_length + 2 * self.half_defense_length and abs(y) <= self.half_defense_width + + def is_in_right_defense_area(self, x: float, y: float) -> bool: + """True if (x, y) is inside the right defense area.""" + return x >= self.half_length - 2 * self.half_defense_length and abs(y) <= self.half_defense_width diff --git a/utama_core/custom_referee/gui.py b/utama_core/custom_referee/gui.py new file mode 100644 index 00000000..16571750 --- /dev/null +++ b/utama_core/custom_referee/gui.py @@ -0,0 +1,1018 @@ +"""Browser-based operator panel for the CustomReferee. + +Library mode (attach to a referee already driven by your own loop): + from utama_core.custom_referee.gui import attach_gui + referee = CustomReferee.from_profile_name("simulation") + attach_gui(referee, profile, port=8080) # starts server in background + # your loop: referee.step(frame, time.time()) as normal + +Or use the convenience flag on CustomReferee: + referee = CustomReferee(profile, enable_gui=True, gui_port=8080) + +Serves a single-page HTML GUI over a stdlib HTTP server. +State is pushed via SSE (~30 Hz); commands come back via POST /command. +The active profile's configuration (geometry + rules + game settings) is +available at GET /config and displayed in a read-only panel on the page. + +No external dependencies beyond what the project already installs. +""" + +from __future__ import annotations + +import json +import threading +import time +from http.server import BaseHTTPRequestHandler, ThreadingHTTPServer +from typing import TYPE_CHECKING, List, Optional + +if TYPE_CHECKING: + from utama_core.custom_referee import CustomReferee + from utama_core.custom_referee.profiles.profile_loader import RefereeProfile + +from utama_core.entities.data.vector import Vector3D +from utama_core.entities.game.ball import Ball +from utama_core.entities.game.game_frame import GameFrame +from utama_core.entities.referee.referee_command import RefereeCommand + +# --------------------------------------------------------------------------- +# Public API +# --------------------------------------------------------------------------- + + +def attach_gui( + referee: "CustomReferee", + profile: "RefereeProfile", + port: int = 8080, + *, + run_tick_loop: bool = False, +) -> None: + """Attach the web GUI to an existing CustomReferee instance. + + Starts the HTTP server in a background daemon thread. The GUI will show + live state as long as the caller keeps calling ``referee.step()`` from its + own loop. + + Args: + referee: The CustomReferee instance to observe / control. + profile: The RefereeProfile used to create the referee (used to + populate the /config endpoint and the config panel). + port: HTTP port to listen on (default 8080). + run_tick_loop: If True, also start an internal tick loop that calls + ``referee.step()`` with a static frame at ~30 Hz. Use + this when you have *no* external game loop (standalone + operator-panel mode). Leave False when your own loop + drives ``referee.step()``. + """ + server = _RefereeGUIServer(referee, profile, port, run_tick_loop=run_tick_loop) + server.start() + print(f"Referee GUI → http://localhost:{port}") + print(f"Profile: {profile.profile_name}") + + +# --------------------------------------------------------------------------- +# Internal server (one instance per attach_gui call) +# --------------------------------------------------------------------------- + + +class _RefereeGUIServer(threading.Thread): + """HTTP server + optional tick loop, all in daemon threads.""" + + def __init__( + self, + referee: "CustomReferee", + profile: "RefereeProfile", + port: int, + *, + run_tick_loop: bool, + ) -> None: + super().__init__(daemon=True, name="RefereeGUIServer") + self._referee = referee + self._port = port + self._run_tick_loop = run_tick_loop + self._config_json = _build_config_json(profile) + + self._lock = threading.Lock() + self._ref_data = None + self._game_frame = None # Optional[GameFrame] + self._sse_clients: List = [] + self._sse_lock = threading.Lock() + + # ---- threading.Thread entry point ---- + + def run(self) -> None: + if self._run_tick_loop: + threading.Thread(target=self._tick_loop, daemon=True, name="RefereeGUITick").start() + + handler_factory = self._make_handler_class() + server = ThreadingHTTPServer(("", self._port), handler_factory) + server.serve_forever() + + def start(self) -> None: + super().start() + + # ---- tick loop (standalone mode only) ---- + + def _tick_loop(self) -> None: + frame = _make_static_frame() + while True: + result = self._referee.step(frame, time.time()) + with self._lock: + self._ref_data = result + self._game_frame = frame + self._broadcast() + time.sleep(1 / 30) + + # ---- called by external loops to push a new state snapshot ---- + + def notify(self, ref_data, game_frame=None) -> None: + """Push a RefereeData snapshot from an external game loop.""" + with self._lock: + self._ref_data = ref_data + self._game_frame = game_frame + self._broadcast() + + # ---- SSE broadcast ---- + + def _broadcast(self) -> None: + with self._lock: + data = self._ref_data + frame = self._game_frame + if data is None: + return + + payload = ("data: " + _serialise_state(data, frame) + "\n\n").encode() + dead: List = [] + + with self._sse_lock: + clients = list(self._sse_clients) + + for wfile in clients: + try: + wfile.write(payload) + wfile.flush() + except (BrokenPipeError, ConnectionResetError, OSError): + dead.append(wfile) + + if dead: + with self._sse_lock: + for w in dead: + if w in self._sse_clients: + self._sse_clients.remove(w) + + # ---- handler class factory (captures self) ---- + + def _make_handler_class(self): + server_instance = self + + class _Handler(BaseHTTPRequestHandler): + + def log_message(self, fmt, *args): + pass # suppress default access log + + def _serve_index(self): + body = _HTML.encode() + self.send_response(200) + self.send_header("Content-Type", "text/html; charset=utf-8") + self.send_header("Content-Length", str(len(body))) + self.end_headers() + self.wfile.write(body) + + def _serve_config(self): + body = server_instance._config_json.encode() + self.send_response(200) + self.send_header("Content-Type", "application/json") + self.send_header("Content-Length", str(len(body))) + self.end_headers() + self.wfile.write(body) + + def _serve_sse(self): + self.send_response(200) + self.send_header("Content-Type", "text/event-stream") + self.send_header("Cache-Control", "no-cache") + self.send_header("Connection", "keep-alive") + self.send_header("X-Accel-Buffering", "no") + self.end_headers() + self.wfile.flush() + + with server_instance._sse_lock: + server_instance._sse_clients.append(self.wfile) + + try: + while True: + time.sleep(0.5) + self.wfile.write(b": keep-alive\n\n") + self.wfile.flush() + except (BrokenPipeError, ConnectionResetError, OSError): + pass + finally: + with server_instance._sse_lock: + if self.wfile in server_instance._sse_clients: + server_instance._sse_clients.remove(self.wfile) + + def _handle_command(self): + length = int(self.headers.get("Content-Length", 0)) + body = self.rfile.read(length) + try: + payload = json.loads(body) + cmd = RefereeCommand[payload["command"]] + with server_instance._lock: + server_instance._referee.set_command(cmd, time.time()) + self.send_response(204) + self.end_headers() + except (KeyError, ValueError, json.JSONDecodeError) as exc: + msg = f"Bad request: {exc}".encode() + self.send_response(400) + self.send_header("Content-Type", "text/plain") + self.send_header("Content-Length", str(len(msg))) + self.end_headers() + self.wfile.write(msg) + + def do_GET(self): + if self.path == "/": + self._serve_index() + elif self.path == "/config": + self._serve_config() + elif self.path == "/events": + self._serve_sse() + else: + self.send_response(404) + self.end_headers() + + def do_POST(self): + if self.path == "/command": + self._handle_command() + else: + self.send_response(404) + self.end_headers() + + return _Handler + + +# --------------------------------------------------------------------------- +# Helpers +# --------------------------------------------------------------------------- + + +def _make_static_frame() -> GameFrame: + """Minimal GameFrame with no robots and ball at centre.""" + ball = Ball( + p=Vector3D(0.0, 0.0, 0.0), + v=Vector3D(0.0, 0.0, 0.0), + a=Vector3D(0.0, 0.0, 0.0), + ) + return GameFrame( + ts=time.time(), + my_team_is_yellow=True, + my_team_is_right=False, + friendly_robots={}, + enemy_robots={}, + ball=ball, + referee=None, + ) + + +def _serialise_robots(game_frame) -> dict: + if game_frame is None: + return {"friendly": [], "enemy": []} + + def _robot_list(robots_dict): + return [{"id": r.id, "x": r.p.x, "y": r.p.y, "orientation": r.orientation} for r in robots_dict.values()] + + return {"friendly": _robot_list(game_frame.friendly_robots), "enemy": _robot_list(game_frame.enemy_robots)} + + +def _serialise_ball(game_frame): + if game_frame is None or game_frame.ball is None: + return None + return {"x": game_frame.ball.p.x, "y": game_frame.ball.p.y} + + +def _serialise_state(ref_data, game_frame=None) -> str: + designated = None + if ref_data.designated_position is not None: + try: + designated = list(ref_data.designated_position) + except TypeError: + designated = [ref_data.designated_position.x, ref_data.designated_position.y] + + return json.dumps( + { + "command": ref_data.referee_command.name, + "next_command": ref_data.next_command.name if ref_data.next_command else None, + "stage": ref_data.stage.name, + "stage_time_left": ref_data.stage_time_left or 0.0, + "yellow_score": ref_data.yellow_team.score, + "blue_score": ref_data.blue_team.score, + "designated": designated, + "status_message": ref_data.status_message, + "robots": _serialise_robots(game_frame), + "ball": _serialise_ball(game_frame), + } + ) + + +def _build_config_json(profile: "RefereeProfile") -> str: + g = profile.geometry + r = profile.rules + gm = profile.game + return json.dumps( + { + "profile_name": profile.profile_name, + "geometry": { + "half_length": g.half_length, + "half_width": g.half_width, + "half_goal_width": g.half_goal_width, + "half_defense_length": g.half_defense_length, + "half_defense_width": g.half_defense_width, + "center_circle_radius": g.center_circle_radius, + }, + "rules": { + "goal_detection": { + "enabled": r.goal_detection.enabled, + "cooldown_seconds": r.goal_detection.cooldown_seconds, + }, + "out_of_bounds": { + "enabled": r.out_of_bounds.enabled, + "free_kick_assigner": r.out_of_bounds.free_kick_assigner, + }, + "defense_area": { + "enabled": r.defense_area.enabled, + "max_defenders": r.defense_area.max_defenders, + "attacker_infringement": r.defense_area.attacker_infringement, + }, + "keep_out": { + "enabled": r.keep_out.enabled, + "radius_meters": r.keep_out.radius_meters, + "violation_persistence_frames": r.keep_out.violation_persistence_frames, + }, + }, + "game": { + "half_duration_seconds": gm.half_duration_seconds, + "kickoff_team": gm.kickoff_team, + "force_start_after_goal": gm.force_start_after_goal, + "stop_duration_seconds": gm.stop_duration_seconds, + "auto_advance": { + "stop_to_prepare_kickoff": gm.auto_advance.stop_to_prepare_kickoff, + "prepare_kickoff_to_normal": gm.auto_advance.prepare_kickoff_to_normal, + "direct_free_to_normal": gm.auto_advance.direct_free_to_normal, + "ball_placement_to_next": gm.auto_advance.ball_placement_to_next, + "normal_start_to_force": gm.auto_advance.normal_start_to_force, + }, + }, + } + ) + + +# --------------------------------------------------------------------------- +# Inline HTML page +# --------------------------------------------------------------------------- + +_HTML = r""" + + + + +Custom Referee + + + + +

Custom Referee

+ +
+
+
+
Yellow
+
+
+
+
Blue
+
+
+
+ +
+
+ Command + +
+
+ Next + +
+
+ Stage +   + +
+
+ Designated + +
+ +
+
+ +
+
+ + + + +
+
+ + +
+
+ + +
+ +
+ + +
+
+ + +
+
+ +
+
+
Field
+ +
+
+
Event Log
+
+
+
+ +
+
Profile — loading…
+
+
+ +
+
+ connecting… +
+ + + + +""" diff --git a/utama_core/custom_referee/profiles/__init__.py b/utama_core/custom_referee/profiles/__init__.py new file mode 100644 index 00000000..5b9edc28 --- /dev/null +++ b/utama_core/custom_referee/profiles/__init__.py @@ -0,0 +1,3 @@ +from utama_core.custom_referee.profiles.profile_loader import load_profile + +__all__ = ["load_profile"] diff --git a/utama_core/custom_referee/profiles/human.yaml b/utama_core/custom_referee/profiles/human.yaml new file mode 100644 index 00000000..24ed3c4d --- /dev/null +++ b/utama_core/custom_referee/profiles/human.yaml @@ -0,0 +1,36 @@ +profile_name: "human" +geometry: + half_length: 4.5 + half_width: 3.0 + half_goal_width: 0.5 + half_defense_length: 0.5 + half_defense_width: 1.0 + center_circle_radius: 0.5 +rules: + goal_detection: + enabled: true + cooldown_seconds: 1.0 + out_of_bounds: + enabled: false + free_kick_assigner: "last_touch" + defense_area: + enabled: false + max_defenders: 1 + attacker_infringement: true + keep_out: + enabled: false + radius_meters: 0.5 + violation_persistence_frames: 30 +game: + half_duration_seconds: 300.0 + kickoff_team: "yellow" + force_start_after_goal: false + stop_duration_seconds: 2.0 + prepare_duration_seconds: 2.0 + kickoff_timeout_seconds: 10.0 + auto_advance: + stop_to_prepare_kickoff: false # Operator advances restarts manually + prepare_kickoff_to_normal: false + direct_free_to_normal: false + ball_placement_to_next: false + normal_start_to_force: false diff --git a/utama_core/custom_referee/profiles/profile_loader.py b/utama_core/custom_referee/profiles/profile_loader.py new file mode 100644 index 00000000..97ff9888 --- /dev/null +++ b/utama_core/custom_referee/profiles/profile_loader.py @@ -0,0 +1,223 @@ +"""Profile loader: parses YAML referee profiles into typed dataclasses.""" + +from __future__ import annotations + +import os +import warnings +from dataclasses import dataclass, field +from pathlib import Path +from typing import Optional + +import yaml + +from utama_core.custom_referee.geometry import RefereeGeometry + +_PROFILES_DIR = Path(__file__).parent + + +# --------------------------------------------------------------------------- +# Rule config dataclasses +# --------------------------------------------------------------------------- + + +@dataclass +class GoalDetectionConfig: + enabled: bool = True + cooldown_seconds: float = 1.0 + + +@dataclass +class OutOfBoundsConfig: + enabled: bool = True + free_kick_assigner: str = "last_touch" + + +@dataclass +class DefenseAreaConfig: + enabled: bool = True + max_defenders: int = 1 + attacker_infringement: bool = True + + +@dataclass +class KeepOutConfig: + enabled: bool = True + radius_meters: float = 0.5 + violation_persistence_frames: int = 30 + + +@dataclass +class RulesConfig: + goal_detection: GoalDetectionConfig = field(default_factory=GoalDetectionConfig) + out_of_bounds: OutOfBoundsConfig = field(default_factory=OutOfBoundsConfig) + defense_area: DefenseAreaConfig = field(default_factory=DefenseAreaConfig) + keep_out: KeepOutConfig = field(default_factory=KeepOutConfig) + + +# --------------------------------------------------------------------------- +# Game config +# --------------------------------------------------------------------------- + + +@dataclass +class AutoAdvanceConfig: + """Controls which state-machine transitions fire automatically. + + Set all to False for physical environments where a human operator must + explicitly advance the state to prevent robots from moving unexpectedly. + """ + + # STOP → PREPARE_KICKOFF_* when all robots have cleared the ball. + stop_to_prepare_kickoff: bool = True + # PREPARE_KICKOFF_* → NORMAL_START after prepare_duration_seconds when + # the kicker is inside the centre circle. + prepare_kickoff_to_normal: bool = True + # DIRECT_FREE_* → NORMAL_START when kicker is in position and defenders + # have cleared. + direct_free_to_normal: bool = True + # BALL_PLACEMENT_* → next_command when ball reaches placement target. + ball_placement_to_next: bool = True + # NORMAL_START → FORCE_START after kickoff_timeout_seconds if ball hasn't + # moved (catches a stuck kickoff). + normal_start_to_force: bool = True + + +@dataclass +class GameConfig: + half_duration_seconds: float = 300.0 + kickoff_team: str = "yellow" + # If True, skip PREPARE_KICKOFF and issue FORCE_START automatically after + # stop_duration_seconds. Optional fast-path for continuous-play scenarios. + force_start_after_goal: bool = False + # How long to stay in STOP before auto-advancing (only when + # force_start_after_goal=True). Set to 0.0 to advance immediately. + stop_duration_seconds: float = 3.0 + # How long to stay in PREPARE_KICKOFF_* before auto-issuing NORMAL_START. + # Gives robots time to reach their kickoff formation. SSL Div B allows + # 10 s to execute the kick after NORMAL_START, so this just covers the + # formation phase. + prepare_duration_seconds: float = 3.0 + # How long after NORMAL_START (kickoff/free-kick) before FORCE_START is + # issued automatically if the ball has not moved. SSL rule: 10 s. + kickoff_timeout_seconds: float = 10.0 + auto_advance: AutoAdvanceConfig = field(default_factory=AutoAdvanceConfig) + + +# --------------------------------------------------------------------------- +# Top-level profile +# --------------------------------------------------------------------------- + + +@dataclass +class RefereeProfile: + profile_name: str + geometry: RefereeGeometry + rules: RulesConfig + game: GameConfig + + +# --------------------------------------------------------------------------- +# Loader +# --------------------------------------------------------------------------- + + +def load_profile(name_or_path: str) -> RefereeProfile: + """Load a RefereeProfile from a built-in name or an absolute/relative path. + + Built-in names: "simulation", "human". + """ + aliases = {"strict_ai": "simulation", "arcade": "human"} + if name_or_path in aliases: + warnings.warn( + f"Profile '{name_or_path}' is deprecated; use '{aliases[name_or_path]}' instead.", + DeprecationWarning, + stacklevel=2, + ) + name_or_path = aliases[name_or_path] + + p = Path(name_or_path) + if not p.is_absolute(): + # Try built-in profiles directory + candidate = _PROFILES_DIR / f"{name_or_path}.yaml" + if candidate.exists(): + p = candidate + elif not p.exists(): + raise FileNotFoundError(f"Profile '{name_or_path}' not found as a built-in name or file path.") + + with open(p, "r") as fh: + data = yaml.safe_load(fh) + + return _parse_profile(data) + + +def _parse_profile(data: dict) -> RefereeProfile: + geo_d = data.get("geometry", {}) + geometry = RefereeGeometry( + half_length=geo_d.get("half_length", 4.5), + half_width=geo_d.get("half_width", 3.0), + half_goal_width=geo_d.get("half_goal_width", 0.5), + half_defense_length=geo_d.get("half_defense_length", 0.5), + half_defense_width=geo_d.get("half_defense_width", 1.0), + center_circle_radius=geo_d.get("center_circle_radius", 0.5), + ) + + rules_d = data.get("rules", {}) + + gd = rules_d.get("goal_detection", {}) + goal_cfg = GoalDetectionConfig( + enabled=gd.get("enabled", True), + cooldown_seconds=gd.get("cooldown_seconds", 1.0), + ) + + ob = rules_d.get("out_of_bounds", {}) + oob_cfg = OutOfBoundsConfig( + enabled=ob.get("enabled", True), + free_kick_assigner=ob.get("free_kick_assigner", "last_touch"), + ) + + da = rules_d.get("defense_area", {}) + da_cfg = DefenseAreaConfig( + enabled=da.get("enabled", True), + max_defenders=da.get("max_defenders", 1), + attacker_infringement=da.get("attacker_infringement", True), + ) + + ko = rules_d.get("keep_out", {}) + ko_cfg = KeepOutConfig( + enabled=ko.get("enabled", True), + radius_meters=ko.get("radius_meters", 0.5), + violation_persistence_frames=ko.get("violation_persistence_frames", 30), + ) + + rules = RulesConfig( + goal_detection=goal_cfg, + out_of_bounds=oob_cfg, + defense_area=da_cfg, + keep_out=ko_cfg, + ) + + game_d = data.get("game", {}) + aa = game_d.get("auto_advance", {}) + auto_advance = AutoAdvanceConfig( + stop_to_prepare_kickoff=aa.get("stop_to_prepare_kickoff", True), + prepare_kickoff_to_normal=aa.get("prepare_kickoff_to_normal", True), + direct_free_to_normal=aa.get("direct_free_to_normal", True), + ball_placement_to_next=aa.get("ball_placement_to_next", True), + normal_start_to_force=aa.get("normal_start_to_force", True), + ) + game = GameConfig( + half_duration_seconds=game_d.get("half_duration_seconds", 300.0), + kickoff_team=game_d.get("kickoff_team", "yellow"), + force_start_after_goal=game_d.get("force_start_after_goal", False), + stop_duration_seconds=game_d.get("stop_duration_seconds", 3.0), + prepare_duration_seconds=game_d.get("prepare_duration_seconds", 3.0), + kickoff_timeout_seconds=game_d.get("kickoff_timeout_seconds", 10.0), + auto_advance=auto_advance, + ) + + return RefereeProfile( + profile_name=data.get("profile_name", "unknown"), + geometry=geometry, + rules=rules, + game=game, + ) diff --git a/utama_core/custom_referee/profiles/simulation.yaml b/utama_core/custom_referee/profiles/simulation.yaml new file mode 100644 index 00000000..c1c4b119 --- /dev/null +++ b/utama_core/custom_referee/profiles/simulation.yaml @@ -0,0 +1,35 @@ +profile_name: "simulation" +geometry: + half_length: 4.5 + half_width: 3.0 + half_goal_width: 0.5 + half_defense_length: 0.5 + half_defense_width: 1.0 + center_circle_radius: 0.5 +rules: + goal_detection: + enabled: true + cooldown_seconds: 1.0 + out_of_bounds: + enabled: true + free_kick_assigner: "last_touch" + defense_area: + enabled: true + max_defenders: 1 + attacker_infringement: true + keep_out: + enabled: true + radius_meters: 0.5 + violation_persistence_frames: 30 +game: + half_duration_seconds: 300.0 + kickoff_team: "yellow" + force_start_after_goal: false + prepare_duration_seconds: 3.0 # seconds in PREPARE_KICKOFF before NORMAL_START is auto-issued + kickoff_timeout_seconds: 10.0 # seconds after NORMAL_START before FORCE_START if ball hasn't moved + auto_advance: + stop_to_prepare_kickoff: true # STOP → PREPARE_KICKOFF_* when all robots clear + prepare_kickoff_to_normal: true # PREPARE_KICKOFF_* → NORMAL_START when kicker in circle + direct_free_to_normal: true # DIRECT_FREE_* → NORMAL_START when kicker ready + ball_placement_to_next: true # BALL_PLACEMENT_* → next_command when ball at target + normal_start_to_force: true # NORMAL_START → FORCE_START on kickoff timeout diff --git a/utama_core/custom_referee/rules/__init__.py b/utama_core/custom_referee/rules/__init__.py new file mode 100644 index 00000000..7a6548f0 --- /dev/null +++ b/utama_core/custom_referee/rules/__init__.py @@ -0,0 +1,14 @@ +from utama_core.custom_referee.rules.base_rule import BaseRule, RuleViolation +from utama_core.custom_referee.rules.defense_area_rule import DefenseAreaRule +from utama_core.custom_referee.rules.goal_rule import GoalRule +from utama_core.custom_referee.rules.keep_out_rule import KeepOutRule +from utama_core.custom_referee.rules.out_of_bounds_rule import OutOfBoundsRule + +__all__ = [ + "BaseRule", + "RuleViolation", + "GoalRule", + "OutOfBoundsRule", + "DefenseAreaRule", + "KeepOutRule", +] diff --git a/utama_core/custom_referee/rules/base_rule.py b/utama_core/custom_referee/rules/base_rule.py new file mode 100644 index 00000000..f341e7ba --- /dev/null +++ b/utama_core/custom_referee/rules/base_rule.py @@ -0,0 +1,43 @@ +"""Base class and violation dataclass for all referee rules.""" + +from __future__ import annotations + +from abc import ABC, abstractmethod +from dataclasses import dataclass +from typing import Optional + +from utama_core.custom_referee.geometry import RefereeGeometry +from utama_core.entities.game.game_frame import GameFrame +from utama_core.entities.referee.referee_command import RefereeCommand + + +@dataclass(frozen=True) +class RuleViolation: + """Describes a detected rule infringement and the appropriate response.""" + + rule_name: str + suggested_command: RefereeCommand + next_command: Optional[RefereeCommand] + status_message: str + designated_position: Optional[tuple[float, float]] = None + + +class BaseRule(ABC): + """Abstract base class for all modular referee rules.""" + + @abstractmethod + def check( + self, + game_frame: GameFrame, + geometry: RefereeGeometry, + current_command: RefereeCommand, + ) -> Optional[RuleViolation]: + """Check for a rule violation in the current game frame. + + Returns a RuleViolation if one is detected, otherwise None. + """ + ... + + def reset(self) -> None: + """Called when a command transition occurs; reset internal state.""" + pass diff --git a/utama_core/custom_referee/rules/defense_area_rule.py b/utama_core/custom_referee/rules/defense_area_rule.py new file mode 100644 index 00000000..a5820772 --- /dev/null +++ b/utama_core/custom_referee/rules/defense_area_rule.py @@ -0,0 +1,72 @@ +"""DefenseAreaRule: detects illegal entry into defense areas.""" + +from __future__ import annotations + +from typing import Optional + +from utama_core.custom_referee.geometry import RefereeGeometry +from utama_core.custom_referee.rules.base_rule import BaseRule, RuleViolation +from utama_core.entities.game.game_frame import GameFrame +from utama_core.entities.referee.referee_command import RefereeCommand + +_ACTIVE_PLAY_COMMANDS = { + RefereeCommand.NORMAL_START, + RefereeCommand.FORCE_START, +} + + +class DefenseAreaRule(BaseRule): + """Detects attacker encroachment or too many defenders in the defense area.""" + + def __init__(self, max_defenders: int = 1, attacker_infringement: bool = True) -> None: + self._max_defenders = max_defenders + self._attacker_infringement = attacker_infringement + + def check( + self, + game_frame: GameFrame, + geometry: RefereeGeometry, + current_command: RefereeCommand, + ) -> Optional[RuleViolation]: + if current_command not in _ACTIVE_PLAY_COMMANDS: + return None + + my_team_is_right = game_frame.my_team_is_right + my_team_is_yellow = game_frame.my_team_is_yellow + + # Determine which geometry helper corresponds to "my" defense area. + if my_team_is_right: + in_my_defense = geometry.is_in_right_defense_area + # in_opp_defense = geometry.is_in_left_defense_area + else: + in_my_defense = geometry.is_in_left_defense_area + # in_opp_defense = geometry.is_in_right_defense_area + + # Check: too many friendly defenders in own area. + n_friendly_in_own = sum(1 for r in game_frame.friendly_robots.values() if in_my_defense(r.p.x, r.p.y)) + if n_friendly_in_own > self._max_defenders: + # Opponent gets a free kick. + free_kick_cmd = RefereeCommand.DIRECT_FREE_BLUE if my_team_is_yellow else RefereeCommand.DIRECT_FREE_YELLOW + return RuleViolation( + rule_name="defense_area", + suggested_command=RefereeCommand.STOP, + next_command=free_kick_cmd, + status_message="Too many defenders in own area", + ) + + # Check: enemy attacker inside our defense area. + if self._attacker_infringement: + for robot in game_frame.enemy_robots.values(): + if in_my_defense(robot.p.x, robot.p.y): + # Defending team (friendly) gets the free kick. + free_kick_cmd = ( + RefereeCommand.DIRECT_FREE_YELLOW if my_team_is_yellow else RefereeCommand.DIRECT_FREE_BLUE + ) + return RuleViolation( + rule_name="defense_area", + suggested_command=RefereeCommand.STOP, + next_command=free_kick_cmd, + status_message="Attacker in defense area", + ) + + return None diff --git a/utama_core/custom_referee/rules/goal_rule.py b/utama_core/custom_referee/rules/goal_rule.py new file mode 100644 index 00000000..5601302c --- /dev/null +++ b/utama_core/custom_referee/rules/goal_rule.py @@ -0,0 +1,96 @@ +"""GoalRule: detects when the ball crosses a goal line.""" + +from __future__ import annotations + +import math +from typing import Optional + +from utama_core.custom_referee.geometry import RefereeGeometry +from utama_core.custom_referee.rules.base_rule import BaseRule, RuleViolation +from utama_core.entities.game.game_frame import GameFrame +from utama_core.entities.referee.referee_command import RefereeCommand + +# Commands that represent active play — goal detection is only relevant here. +_ACTIVE_PLAY_COMMANDS = { + RefereeCommand.NORMAL_START, + RefereeCommand.FORCE_START, +} + + +class GoalRule(BaseRule): + """Detects goals with a cooldown to suppress duplicate detections.""" + + def __init__(self, cooldown_seconds: float = 1.0) -> None: + self._cooldown = cooldown_seconds + self._last_goal_time: float = -math.inf + + def check( + self, + game_frame: GameFrame, + geometry: RefereeGeometry, + current_command: RefereeCommand, + ) -> Optional[RuleViolation]: + if current_command not in _ACTIVE_PLAY_COMMANDS: + return None + + ball = game_frame.ball + if ball is None: + return None + + current_time = game_frame.ts + + # Respect cooldown — prevents the same goal being reported for multiple frames. + if current_time - self._last_goal_time < self._cooldown: + return None + + bx, by = ball.p.x, ball.p.y + # Determine which colour team defends each goal from the frame's perspective. + # my_team_is_right=True → yellow defends right goal, blue defends left goal. + # my_team_is_right=False → blue defends right goal, yellow defends left goal. + yellow_is_right = game_frame.my_team_is_right == game_frame.my_team_is_yellow + + # Right goal: the team defending the right side conceded. + if geometry.is_in_right_goal(bx, by): + self._last_goal_time = current_time + if yellow_is_right: + # Yellow conceded → Blue scored → Yellow kicks off + return RuleViolation( + rule_name="goal", + suggested_command=RefereeCommand.STOP, + next_command=RefereeCommand.PREPARE_KICKOFF_YELLOW, + status_message="Goal by Blue", + ) + else: + # Blue conceded → Yellow scored → Blue kicks off + return RuleViolation( + rule_name="goal", + suggested_command=RefereeCommand.STOP, + next_command=RefereeCommand.PREPARE_KICKOFF_BLUE, + status_message="Goal by Yellow", + ) + + # Left goal: the team defending the left side conceded. + if geometry.is_in_left_goal(bx, by): + self._last_goal_time = current_time + if yellow_is_right: + # Blue conceded → Yellow scored → Blue kicks off + return RuleViolation( + rule_name="goal", + suggested_command=RefereeCommand.STOP, + next_command=RefereeCommand.PREPARE_KICKOFF_BLUE, + status_message="Goal by Yellow", + ) + else: + # Yellow conceded → Blue scored → Yellow kicks off + return RuleViolation( + rule_name="goal", + suggested_command=RefereeCommand.STOP, + next_command=RefereeCommand.PREPARE_KICKOFF_YELLOW, + status_message="Goal by Blue", + ) + + return None + + def reset(self) -> None: + # Keep last_goal_time across resets so cooldown still applies. + pass diff --git a/utama_core/custom_referee/rules/keep_out_rule.py b/utama_core/custom_referee/rules/keep_out_rule.py new file mode 100644 index 00000000..549a9e51 --- /dev/null +++ b/utama_core/custom_referee/rules/keep_out_rule.py @@ -0,0 +1,124 @@ +"""KeepOutRule: enforces minimum distance to the ball during stoppages.""" + +from __future__ import annotations + +import math +from typing import Optional + +from utama_core.custom_referee.geometry import RefereeGeometry +from utama_core.custom_referee.rules.base_rule import BaseRule, RuleViolation +from utama_core.entities.game.game_frame import GameFrame +from utama_core.entities.referee.referee_command import RefereeCommand + +# Commands during which the keep-out circle must be respected. +# STOP is intentionally excluded: during STOP robots are actively clearing the +# ball and the state machine already handles this via StopStep. Firing a +# keep-out violation during STOP would overwrite next_command (e.g. replacing +# PREPARE_KICKOFF_BLUE with DIRECT_FREE_YELLOW), which is wrong. +_STOPPAGE_COMMANDS = { + RefereeCommand.DIRECT_FREE_YELLOW, + RefereeCommand.DIRECT_FREE_BLUE, + RefereeCommand.PREPARE_KICKOFF_YELLOW, + RefereeCommand.PREPARE_KICKOFF_BLUE, + RefereeCommand.PREPARE_PENALTY_YELLOW, + RefereeCommand.PREPARE_PENALTY_BLUE, +} + + +class KeepOutRule(BaseRule): + """Penalises robots that remain inside the keep-out radius around the ball. + + A violation is only issued after ``violation_persistence_frames`` consecutive + frames of encroachment, preventing false positives from transient positions. + """ + + def __init__( + self, + radius_meters: float = 0.5, + violation_persistence_frames: int = 30, + ) -> None: + self._radius = radius_meters + self._persistence = violation_persistence_frames + self._violation_count: int = 0 + + def check( + self, + game_frame: GameFrame, + geometry: RefereeGeometry, + current_command: RefereeCommand, + ) -> Optional[RuleViolation]: + if current_command not in _STOPPAGE_COMMANDS: + self._violation_count = 0 + return None + + ball = game_frame.ball + if ball is None: + self._violation_count = 0 + return None + + bx, by = ball.p.x, ball.p.y + my_team_is_yellow = game_frame.my_team_is_yellow + + # Determine which team is the *kicking* team (they are exempt). + # During DIRECT_FREE_*, the kicking team is indicated by the command. + kicking_team_is_yellow = _kicking_team_is_yellow(current_command, my_team_is_yellow) + + # Check non-kicking team robots for encroachment. + encroaching = False + if kicking_team_is_yellow is None: + # STOP: both teams must stay back. + encroaching = self._any_robot_encroaching( + game_frame.friendly_robots.values(), bx, by + ) or self._any_robot_encroaching(game_frame.enemy_robots.values(), bx, by) + elif kicking_team_is_yellow == my_team_is_yellow: + # Friendly is kicking — check enemy only. + encroaching = self._any_robot_encroaching(game_frame.enemy_robots.values(), bx, by) + else: + # Enemy is kicking — check friendly only. + encroaching = self._any_robot_encroaching(game_frame.friendly_robots.values(), bx, by) + + if encroaching: + self._violation_count += 1 + else: + self._violation_count = 0 + + if self._violation_count >= self._persistence: + self._violation_count = 0 # Reset after issuing. + # Award free kick to the kicking team (they get to retry). + # kicking_team_is_yellow is always True or False here because STOP + # is excluded from _STOPPAGE_COMMANDS above. + if kicking_team_is_yellow: + next_cmd = RefereeCommand.DIRECT_FREE_YELLOW + else: + next_cmd = RefereeCommand.DIRECT_FREE_BLUE + return RuleViolation( + rule_name="keep_out", + suggested_command=RefereeCommand.STOP, + next_command=next_cmd, + status_message="Keep-out circle violation", + ) + + return None + + def reset(self) -> None: + self._violation_count = 0 + + def _any_robot_encroaching(self, robots, bx: float, by: float) -> bool: + return any(math.hypot(r.p.x - bx, r.p.y - by) < self._radius for r in robots) + + +def _kicking_team_is_yellow(command: RefereeCommand, my_team_is_yellow: bool) -> Optional[bool]: + """Return True if the kicking team is yellow, False if blue, None if STOP (both stop).""" + if command in ( + RefereeCommand.DIRECT_FREE_YELLOW, + RefereeCommand.PREPARE_KICKOFF_YELLOW, + RefereeCommand.PREPARE_PENALTY_YELLOW, + ): + return True + if command in ( + RefereeCommand.DIRECT_FREE_BLUE, + RefereeCommand.PREPARE_KICKOFF_BLUE, + RefereeCommand.PREPARE_PENALTY_BLUE, + ): + return False + return None # STOP — no kicking team diff --git a/utama_core/custom_referee/rules/out_of_bounds_rule.py b/utama_core/custom_referee/rules/out_of_bounds_rule.py new file mode 100644 index 00000000..3f40adf2 --- /dev/null +++ b/utama_core/custom_referee/rules/out_of_bounds_rule.py @@ -0,0 +1,137 @@ +"""OutOfBoundsRule: detects when the ball leaves the field.""" + +from __future__ import annotations + +import math +from typing import Optional + +from utama_core.custom_referee.geometry import RefereeGeometry +from utama_core.custom_referee.rules.base_rule import BaseRule, RuleViolation +from utama_core.entities.game.game_frame import GameFrame +from utama_core.entities.referee.referee_command import RefereeCommand + +_ACTIVE_PLAY_COMMANDS = { + RefereeCommand.NORMAL_START, + RefereeCommand.FORCE_START, +} + +_INFIELD_OFFSET = 0.1 # metres inside the boundary for free-kick placement + + +class OutOfBoundsRule(BaseRule): + """Fires a free kick for the non-touching team when the ball leaves the field.""" + + def __init__(self) -> None: + # Track last robot to have the ball (friendly vs enemy) across frames. + # True = friendly last touched, False = enemy last touched, None = unknown. + self._last_touch_was_friendly: Optional[bool] = None + + def check( + self, + game_frame: GameFrame, + geometry: RefereeGeometry, + current_command: RefereeCommand, + ) -> Optional[RuleViolation]: + if current_command not in _ACTIVE_PLAY_COMMANDS: + return None + + ball = game_frame.ball + if ball is None: + return None + + bx, by = ball.p.x, ball.p.y + + # Update last-touch tracking regardless of out-of-bounds state. + self._update_last_touch(game_frame, bx, by) + + # Only fire when ball is outside field AND not in a goal. + if geometry.is_in_field(bx, by) or geometry.is_in_left_goal(bx, by) or geometry.is_in_right_goal(bx, by): + return None + + # Determine which team gets the free kick (non-touching team). + free_kick_cmd = self._assign_free_kick(game_frame) + placement = self._nearest_infield_point(bx, by, geometry) + + return RuleViolation( + rule_name="out_of_bounds", + suggested_command=RefereeCommand.STOP, + next_command=free_kick_cmd, + status_message="Ball out of bounds", + designated_position=placement, + ) + + def reset(self) -> None: + self._last_touch_was_friendly = None + + # ------------------------------------------------------------------ + # Helpers + # ------------------------------------------------------------------ + + def _update_last_touch(self, game_frame: GameFrame, bx: float, by: float) -> None: + """Update last-touch tracking based on robot proximity / has_ball flag.""" + # Check friendly robots first (has_ball from IR sensor is reliable). + for robot in game_frame.friendly_robots.values(): + if robot.has_ball: + self._last_touch_was_friendly = True + return + + # Fall back to closest robot proximity. + min_dist = math.inf + closest_is_friendly: Optional[bool] = None + + for robot in game_frame.friendly_robots.values(): + d = math.hypot(robot.p.x - bx, robot.p.y - by) + if d < min_dist: + min_dist = d + closest_is_friendly = True + + for robot in game_frame.enemy_robots.values(): + d = math.hypot(robot.p.x - bx, robot.p.y - by) + if d < min_dist: + min_dist = d + closest_is_friendly = False + + # Only update if a robot was actually close enough to plausibly touch (≤ 0.15 m). + if closest_is_friendly is not None and min_dist <= 0.15: + self._last_touch_was_friendly = closest_is_friendly + + def _assign_free_kick(self, game_frame: GameFrame) -> RefereeCommand: + """Return the free-kick command for the non-touching team.""" + my_team_is_yellow = game_frame.my_team_is_yellow + + # Non-touching team gets the free kick. + if self._last_touch_was_friendly is None: + # Unknown last touch: give to yellow by default. + return RefereeCommand.DIRECT_FREE_YELLOW + + if self._last_touch_was_friendly: + # Friendly last touched → enemy gets free kick. + if my_team_is_yellow: + return RefereeCommand.DIRECT_FREE_BLUE + else: + return RefereeCommand.DIRECT_FREE_YELLOW + else: + # Enemy last touched → friendly gets free kick. + if my_team_is_yellow: + return RefereeCommand.DIRECT_FREE_YELLOW + else: + return RefereeCommand.DIRECT_FREE_BLUE + + @staticmethod + def _nearest_infield_point(bx: float, by: float, geometry: RefereeGeometry) -> tuple[float, float]: + """Return the nearest point on the field boundary, offset inward.""" + # Clamp to field bounds and shift inward. + px = max(-geometry.half_length, min(geometry.half_length, bx)) + py = max(-geometry.half_width, min(geometry.half_width, by)) + + # If clamped on x boundary, offset inward along x. + if abs(bx) > geometry.half_length: + sign = 1.0 if bx > 0 else -1.0 + px = sign * (geometry.half_length - _INFIELD_OFFSET) + + # If clamped on y boundary, offset inward along y. + if abs(by) > geometry.half_width: + sign = 1.0 if by > 0 else -1.0 + py = sign * (geometry.half_width - _INFIELD_OFFSET) + + return (px, py) diff --git a/utama_core/custom_referee/state_machine.py b/utama_core/custom_referee/state_machine.py new file mode 100644 index 00000000..13140e02 --- /dev/null +++ b/utama_core/custom_referee/state_machine.py @@ -0,0 +1,521 @@ +"""GameStateMachine: owns all mutable game state for the CustomReferee.""" + +from __future__ import annotations + +import logging +import math +import time +from typing import Optional + +from utama_core.custom_referee.geometry import RefereeGeometry +from utama_core.custom_referee.profiles.profile_loader import AutoAdvanceConfig +from utama_core.custom_referee.rules.base_rule import RuleViolation +from utama_core.entities.data.referee import RefereeData +from utama_core.entities.game.game_frame import GameFrame +from utama_core.entities.game.team_info import TeamInfo +from utama_core.entities.referee.referee_command import RefereeCommand +from utama_core.entities.referee.stage import Stage + +logger = logging.getLogger(__name__) + +_TRANSITION_COOLDOWN = 0.3 # seconds — prevents command oscillation +_BALL_CLEAR_DIST = 0.5 # metres — all robots must be this far from ball before PREPARE_KICKOFF +_KICKER_READY_DIST = 0.3 # metres — kicker must be within this distance to trigger free kick start +_PLACEMENT_DONE_DIST = 0.15 # metres — ball within this dist of target → placement complete +_AUTO_ADVANCE_DELAY = 2.0 # seconds — readiness must be sustained this long before play starts + + +class GameStateMachine: + """Owns score, command, and stage. Produces ``RefereeData`` each tick.""" + + def __init__( + self, + half_duration_seconds: float, + kickoff_team: str, + n_robots_yellow: int, + n_robots_blue: int, + initial_stage: Stage = Stage.NORMAL_FIRST_HALF_PRE, + initial_command: RefereeCommand = RefereeCommand.HALT, + force_start_after_goal: bool = False, + stop_duration_seconds: float = 3.0, + prepare_duration_seconds: float = 3.0, + kickoff_timeout_seconds: float = 10.0, + geometry: Optional[RefereeGeometry] = None, + auto_advance: Optional[AutoAdvanceConfig] = None, + ) -> None: + self.command = initial_command + self.command_counter = 0 + self.command_timestamp = 0.0 + + self.stage = initial_stage + self.stage_start_time = time.time() # initialise to now so timer is correct immediately + self.stage_duration = half_duration_seconds + + self.yellow_team = TeamInfo( + name="Yellow", + score=0, + red_cards=0, + yellow_card_times=[], + yellow_cards=0, + timeouts=4, + timeout_time=300, + goalkeeper=0, + foul_counter=0, + ball_placement_failures=0, + can_place_ball=True, + max_allowed_bots=n_robots_yellow, + bot_substitution_intent=False, + bot_substitution_allowed=True, + bot_substitutions_left=5, + ) + self.blue_team = TeamInfo( + name="Blue", + score=0, + red_cards=0, + yellow_card_times=[], + yellow_cards=0, + timeouts=4, + timeout_time=300, + goalkeeper=0, + foul_counter=0, + ball_placement_failures=0, + can_place_ball=True, + max_allowed_bots=n_robots_blue, + bot_substitution_intent=False, + bot_substitution_allowed=True, + bot_substitutions_left=5, + ) + + self.next_command: Optional[RefereeCommand] = None + self.ball_placement_target: Optional[tuple[float, float]] = None + + # Kickoff team initialised from profile. + self._kickoff_team_is_yellow = kickoff_team.lower() == "yellow" + + # Arcade auto-advance: after stop_duration_seconds in STOP following a + # goal, automatically issue FORCE_START instead of waiting for operator. + self._force_start_after_goal = force_start_after_goal + self._stop_duration_seconds = stop_duration_seconds + self._stop_entered_time: float = -math.inf # wall time when STOP was last entered + + # Auto-advance timings. + self._prepare_duration_seconds = prepare_duration_seconds + self._kickoff_timeout_seconds = kickoff_timeout_seconds + self._prepare_entered_time: float = -math.inf # wall time when PREPARE_KICKOFF was entered + self._normal_start_time: float = -math.inf # wall time when NORMAL_START was entered + + # Ball position snapshot at NORMAL_START — used to detect if the ball has moved. + self._ball_pos_at_normal_start: Optional[tuple[float, float]] = None + + # Timestamps for sustained-readiness countdown before play-starting advances. + # Set to math.inf when condition is not yet met; fire when elapsed >= _AUTO_ADVANCE_DELAY. + self._advance2_ready_since: float = math.inf # PREPARE_KICKOFF_* → NORMAL_START + self._advance3_ready_since: float = math.inf # DIRECT_FREE_* → NORMAL_START + self._advance4_ready_since: float = math.inf # BALL_PLACEMENT_* → next_command + + # Field geometry (used for readiness checks). + self._geometry: Optional[RefereeGeometry] = geometry + + # Cooldown: don't process a new violation within this window. + self._last_transition_time: float = -math.inf + + # Per-transition enable flags (default: all on). + self._auto_advance = auto_advance if auto_advance is not None else AutoAdvanceConfig() + + # ------------------------------------------------------------------ + # Public API + # ------------------------------------------------------------------ + + _PREPARE_KICKOFF_COMMANDS = frozenset( + { + RefereeCommand.PREPARE_KICKOFF_YELLOW, + RefereeCommand.PREPARE_KICKOFF_BLUE, + } + ) + _DIRECT_FREE_COMMANDS = frozenset( + { + RefereeCommand.DIRECT_FREE_YELLOW, + RefereeCommand.DIRECT_FREE_BLUE, + } + ) + _BALL_PLACEMENT_COMMANDS = frozenset( + { + RefereeCommand.BALL_PLACEMENT_YELLOW, + RefereeCommand.BALL_PLACEMENT_BLUE, + } + ) + + def step( + self, + current_time: float, + violation: Optional[RuleViolation], + game_frame: Optional["GameFrame"] = None, + ) -> RefereeData: + """Process one tick. Apply violation if not in cooldown. Return RefereeData.""" + if violation is not None and self._can_transition(current_time): + self._apply_violation(violation, current_time) + + # ---------------------------------------------------------------- + # Auto-advance 1: STOP → PREPARE_KICKOFF_* + # Fires when all robots are ≥ _BALL_CLEAR_DIST from the ball. + # ---------------------------------------------------------------- + if ( + self._auto_advance.stop_to_prepare_kickoff + and self.command == RefereeCommand.STOP + and self.next_command in self._PREPARE_KICKOFF_COMMANDS + and game_frame is not None + and self._all_robots_clear(game_frame) + ): + logger.info("All robots clear — auto-advancing STOP → %s", self.next_command.name) + self.command = self.next_command + self.command_counter += 1 + self.command_timestamp = current_time + self.next_command = RefereeCommand.NORMAL_START + self._prepare_entered_time = current_time + self._last_transition_time = current_time + + # ---------------------------------------------------------------- + # Auto-advance 2: PREPARE_KICKOFF_* → NORMAL_START + # Fires after prepare_duration_seconds AND one attacker is inside + # the centre circle (i.e. kicker is in position), sustained for + # _AUTO_ADVANCE_DELAY seconds. + # ---------------------------------------------------------------- + elif self._auto_advance.prepare_kickoff_to_normal and self.command in self._PREPARE_KICKOFF_COMMANDS: + ready = ( + (current_time - self._prepare_entered_time) >= self._prepare_duration_seconds + and game_frame is not None + and self._kicker_in_centre_circle(self.command, game_frame) + ) + if ready: + if self._advance2_ready_since == math.inf: + self._advance2_ready_since = current_time + logger.debug("Advance 2 countdown started (%s)", self.command.name) + elif (current_time - self._advance2_ready_since) >= _AUTO_ADVANCE_DELAY: + logger.info( + "Kicker in centre circle — auto-advancing %s → NORMAL_START", + self.command.name, + ) + self.command = RefereeCommand.NORMAL_START + self.command_counter += 1 + self.command_timestamp = current_time + self.next_command = None + self._normal_start_time = current_time + self._ball_pos_at_normal_start = ( + (game_frame.ball.p.x, game_frame.ball.p.y) if game_frame.ball is not None else None + ) + self._advance2_ready_since = math.inf + self._last_transition_time = current_time + else: + self._advance2_ready_since = math.inf + + # ---------------------------------------------------------------- + # Auto-advance 3: DIRECT_FREE_* → NORMAL_START + # Fires when the kicker is within _KICKER_READY_DIST of the ball + # AND all defending robots are ≥ _BALL_CLEAR_DIST away, sustained + # for _AUTO_ADVANCE_DELAY seconds. + # ---------------------------------------------------------------- + elif self._auto_advance.direct_free_to_normal and self.command in self._DIRECT_FREE_COMMANDS: + ready = game_frame is not None and self._free_kick_ready(self.command, game_frame) + if ready: + if self._advance3_ready_since == math.inf: + self._advance3_ready_since = current_time + logger.debug("Advance 3 countdown started (%s)", self.command.name) + elif (current_time - self._advance3_ready_since) >= _AUTO_ADVANCE_DELAY: + logger.info("Free kick ready — auto-advancing %s → NORMAL_START", self.command.name) + self.command = RefereeCommand.NORMAL_START + self.command_counter += 1 + self.command_timestamp = current_time + self.next_command = None + self._normal_start_time = current_time + self._ball_pos_at_normal_start = ( + (game_frame.ball.p.x, game_frame.ball.p.y) if game_frame.ball is not None else None + ) + self._advance3_ready_since = math.inf + self._last_transition_time = current_time + else: + self._advance3_ready_since = math.inf + + # ---------------------------------------------------------------- + # Auto-advance 4: BALL_PLACEMENT_* → next_command + # Fires when ball reaches within _PLACEMENT_DONE_DIST of target, + # sustained for _AUTO_ADVANCE_DELAY seconds. + # ---------------------------------------------------------------- + elif self._auto_advance.ball_placement_to_next and self.command in self._BALL_PLACEMENT_COMMANDS: + ready = self.next_command is not None and game_frame is not None and self._ball_placement_done(game_frame) + if ready: + if self._advance4_ready_since == math.inf: + self._advance4_ready_since = current_time + logger.debug("Advance 4 countdown started (%s)", self.command.name) + elif (current_time - self._advance4_ready_since) >= _AUTO_ADVANCE_DELAY: + logger.info( + "Ball placement complete — auto-advancing %s → %s", + self.command.name, + self.next_command.name, + ) + self.command = self.next_command + self.command_counter += 1 + self.command_timestamp = current_time + self.next_command = None + self._advance4_ready_since = math.inf + self._last_transition_time = current_time + else: + self._advance4_ready_since = math.inf + + # ---------------------------------------------------------------- + # Auto-advance 5: NORMAL_START → FORCE_START + # Fires after kickoff_timeout_seconds if the ball hasn't moved ≥5 cm. + # ---------------------------------------------------------------- + elif ( + self._auto_advance.normal_start_to_force + and self.command == RefereeCommand.NORMAL_START + and self._ball_pos_at_normal_start is not None + and (current_time - self._normal_start_time) >= self._kickoff_timeout_seconds + and game_frame is not None + and game_frame.ball is not None + and not self._ball_has_moved(game_frame) + ): + logger.info("Kickoff/free-kick timeout — auto-advancing NORMAL_START → FORCE_START") + self.command = RefereeCommand.FORCE_START + self.command_counter += 1 + self.command_timestamp = current_time + self.next_command = None + self._ball_pos_at_normal_start = None + self._last_transition_time = current_time + + # ---------------------------------------------------------------- + # Legacy force-start path: STOP → FORCE_START after goal + # ---------------------------------------------------------------- + elif ( + self._force_start_after_goal + and self.command == RefereeCommand.STOP + and self.next_command in self._PREPARE_KICKOFF_COMMANDS + and (current_time - self._stop_entered_time) >= self._stop_duration_seconds + ): + self.command = RefereeCommand.FORCE_START + self.command_counter += 1 + self.command_timestamp = current_time + self.next_command = None + self._last_transition_time = current_time + logger.info("Auto-advanced STOP → FORCE_START after goal (force-start profile mode)") + + return self._generate_referee_data(current_time) + + def _all_robots_clear(self, game_frame: "GameFrame") -> bool: + """Return True if every robot on both teams is ≥ _BALL_CLEAR_DIST from the ball.""" + ball = game_frame.ball + if ball is None: + return True + bx, by = ball.p.x, ball.p.y + for r in list(game_frame.friendly_robots.values()) + list(game_frame.enemy_robots.values()): + if math.hypot(r.p.x - bx, r.p.y - by) < _BALL_CLEAR_DIST: + return False + return True + + def _kicker_in_centre_circle(self, command: RefereeCommand, game_frame: "GameFrame") -> bool: + """Return True if at least one robot of the attacking team is inside the centre circle.""" + r = self._geometry.center_circle_radius if self._geometry is not None else 0.5 + kicking_is_yellow = command == RefereeCommand.PREPARE_KICKOFF_YELLOW + attackers = ( + game_frame.friendly_robots if kicking_is_yellow == game_frame.my_team_is_yellow else game_frame.enemy_robots + ) + return any(math.hypot(robot.p.x, robot.p.y) <= r for robot in attackers.values()) + + def _free_kick_ready(self, command: RefereeCommand, game_frame: "GameFrame") -> bool: + """Return True when a free kick is ready to start: + - The kicker (closest attacker to ball) is within _KICKER_READY_DIST of the ball. + - All defending robots are ≥ _BALL_CLEAR_DIST from the ball. + """ + ball = game_frame.ball + if ball is None: + return False + bx, by = ball.p.x, ball.p.y + + kicking_is_yellow = command == RefereeCommand.DIRECT_FREE_YELLOW + attackers = ( + game_frame.friendly_robots if kicking_is_yellow == game_frame.my_team_is_yellow else game_frame.enemy_robots + ) + defenders = ( + game_frame.enemy_robots if kicking_is_yellow == game_frame.my_team_is_yellow else game_frame.friendly_robots + ) + + # Check defending robots are all clear. + if any(math.hypot(r.p.x - bx, r.p.y - by) < _BALL_CLEAR_DIST for r in defenders.values()): + return False + + # Check at least one attacker is close to the ball (kicker in position). + if not attackers: + return False + closest = min(math.hypot(r.p.x - bx, r.p.y - by) for r in attackers.values()) + return closest <= _KICKER_READY_DIST + + def _ball_has_moved(self, game_frame: "GameFrame") -> bool: + """Return True if the ball has moved ≥ 0.05 m since NORMAL_START.""" + if self._ball_pos_at_normal_start is None or game_frame.ball is None: + return False + ox, oy = self._ball_pos_at_normal_start + return math.hypot(game_frame.ball.p.x - ox, game_frame.ball.p.y - oy) >= 0.05 + + def _ball_placement_done(self, game_frame: "GameFrame") -> bool: + """Return True when the ball is within _PLACEMENT_DONE_DIST of the placement target.""" + if self.ball_placement_target is None or game_frame.ball is None: + return False + tx, ty = self.ball_placement_target + return math.hypot(game_frame.ball.p.x - tx, game_frame.ball.p.y - ty) <= _PLACEMENT_DONE_DIST + + # Commands that require robots to clear the ball before they take effect. + # In a real match these are always preceded by STOP. + _NEEDS_STOP_FIRST = frozenset( + { + RefereeCommand.PREPARE_KICKOFF_YELLOW, + RefereeCommand.PREPARE_KICKOFF_BLUE, + RefereeCommand.DIRECT_FREE_YELLOW, + RefereeCommand.DIRECT_FREE_BLUE, + RefereeCommand.PREPARE_PENALTY_YELLOW, + RefereeCommand.PREPARE_PENALTY_BLUE, + RefereeCommand.BALL_PLACEMENT_YELLOW, + RefereeCommand.BALL_PLACEMENT_BLUE, + } + ) + + def set_command(self, command: RefereeCommand, timestamp: float) -> None: + """Manual override — for operator use or test scripting. + + If *command* is a set-piece command (kickoff, free kick, penalty, + ball placement) and the game is not already in STOP or HALT, a STOP + is issued first and the requested command is stored as ``next_command`` + so the operator (or a script) can advance to it after robots have + cleared the ball. This mirrors real-match game-controller behaviour + and prevents robots from receiving a PREPARE_KICKOFF while they are + still within the keep-out zone around the ball. + """ + _ALREADY_STOPPED = (RefereeCommand.STOP, RefereeCommand.HALT) + + if command in self._NEEDS_STOP_FIRST and self.command not in _ALREADY_STOPPED: + # Insert STOP; park the real command as next_command. + logger.info("Inserting STOP before %s so robots can clear the ball", command.name) + self.command = RefereeCommand.STOP + self.command_counter += 1 + self.command_timestamp = timestamp + self.next_command = command + self._stop_entered_time = timestamp + return + + # NORMAL_START while in STOP with a pending set-piece: advance to the + # set-piece first so robots can form up. Auto-advance will then issue + # NORMAL_START after prepare_duration_seconds. + if ( + command == RefereeCommand.NORMAL_START + and self.command == RefereeCommand.STOP + and self.next_command in self._NEEDS_STOP_FIRST + ): + logger.info( + "Manually advancing STOP → %s (auto NORMAL_START in %.1f s)", + self.next_command.name, + self._prepare_duration_seconds, + ) + self.command = self.next_command + self.command_counter += 1 + self.command_timestamp = timestamp + self.next_command = RefereeCommand.NORMAL_START + self._prepare_entered_time = timestamp + return + + self.command = command + self.command_counter += 1 + self.command_timestamp = timestamp + self._advance2_ready_since = math.inf + self._advance3_ready_since = math.inf + self._advance4_ready_since = math.inf + + # Advance PRE stages to their active counterpart when play begins. + _PRE_TO_ACTIVE = { + Stage.NORMAL_FIRST_HALF_PRE: Stage.NORMAL_FIRST_HALF, + Stage.NORMAL_SECOND_HALF_PRE: Stage.NORMAL_SECOND_HALF, + Stage.EXTRA_FIRST_HALF_PRE: Stage.EXTRA_FIRST_HALF, + Stage.EXTRA_SECOND_HALF_PRE: Stage.EXTRA_SECOND_HALF, + } + if command in (RefereeCommand.NORMAL_START, RefereeCommand.FORCE_START): + active = _PRE_TO_ACTIVE.get(self.stage) + if active is not None: + self.advance_stage(active, timestamp) + + logger.info("Referee command manually set to: %s", command.name) + + def advance_stage(self, new_stage: Stage, timestamp: float) -> None: + """Advance the game stage.""" + logger.info("Stage %s → %s", self.stage.name, new_stage.name) + self.stage = new_stage + self.stage_start_time = timestamp + + # ------------------------------------------------------------------ + # Internal helpers + # ------------------------------------------------------------------ + + def _can_transition(self, current_time: float) -> bool: + return (current_time - self._last_transition_time) >= _TRANSITION_COOLDOWN + + def _apply_violation(self, violation: RuleViolation, current_time: float) -> None: + """Update state in response to a detected violation.""" + if violation.rule_name == "goal": + self._handle_goal(violation, current_time) + else: + self._handle_foul(violation, current_time) + + self._last_transition_time = current_time + + def _handle_goal(self, violation: RuleViolation, current_time: float) -> None: + # Determine scorer from next_command (loser gets the kickoff). + if violation.next_command == RefereeCommand.PREPARE_KICKOFF_BLUE: + # Blue gets kickoff → yellow scored. + self.yellow_team.increment_score() + logger.info( + "Goal by Yellow! Score: Yellow %d – Blue %d", + self.yellow_team.score, + self.blue_team.score, + ) + elif violation.next_command == RefereeCommand.PREPARE_KICKOFF_YELLOW: + # Yellow gets kickoff → blue scored. + self.blue_team.increment_score() + logger.info( + "Goal by Blue! Score: Yellow %d – Blue %d", + self.yellow_team.score, + self.blue_team.score, + ) + + self.command = RefereeCommand.STOP + self.command_counter += 1 + self.command_timestamp = current_time + self.next_command = violation.next_command + self.ball_placement_target = (0.0, 0.0) + self._stop_entered_time = current_time + + def _handle_foul(self, violation: RuleViolation, current_time: float) -> None: + self.command = violation.suggested_command + self.command_counter += 1 + self.command_timestamp = current_time + self.next_command = violation.next_command + self.ball_placement_target = violation.designated_position + logger.info( + "Foul detected: %s → %s (next: %s)", + violation.rule_name, + violation.suggested_command.name, + violation.next_command.name if violation.next_command else "None", + ) + + def _generate_referee_data(self, current_time: float) -> RefereeData: + stage_time_left = max(0.0, self.stage_duration - (current_time - self.stage_start_time)) + return RefereeData( + source_identifier="custom_referee", + time_sent=current_time, + time_received=current_time, + referee_command=self.command, + referee_command_timestamp=self.command_timestamp, + stage=self.stage, + stage_time_left=stage_time_left, + blue_team=self.blue_team, + yellow_team=self.yellow_team, + designated_position=self.ball_placement_target, + blue_team_on_positive_half=None, + next_command=self.next_command, + current_action_time_remaining=None, + ) diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index e0c916ea..1717eeba 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -6,7 +6,7 @@ import warnings from collections import deque from dataclasses import dataclass, field -from typing import List, Optional, Tuple +from typing import TYPE_CHECKING, List, Optional, Tuple from rich.live import Live from rich.text import Text @@ -31,6 +31,7 @@ from utama_core.entities.data.raw_vision import RawVisionData from utama_core.entities.game import Game, GameFrame, GameHistory from utama_core.entities.game.field import Field, FieldBounds +from utama_core.entities.referee.referee_command import RefereeCommand from utama_core.global_utils.mapping_utils import ( map_friendly_enemy_to_colors, map_left_right_to_colors, @@ -57,6 +58,9 @@ TestingStatus, ) +if TYPE_CHECKING: + from utama_core.custom_referee import CustomReferee + logging.basicConfig( filename="Utama.log", level=logging.CRITICAL, @@ -108,7 +112,10 @@ class StrategyRunner: control_scheme (str, optional): Name of the motion control scheme to use. opp_control_scheme (str, optional): Name of the opponent motion control scheme to use. If not set, uses same as friendly. replay_writer_config (ReplayWriterConfig, optional): Configuration for the replay writer. If unset, replay is disabled. - print_real_fps (bool, optional): Whether to print real FPS. Defaults to False. + show_live_status (bool, optional): Whether to show the live terminal status panel. + This panel includes FPS, referee command, stage, score, time remaining, + and optional status text. Defaults to False. + print_real_fps (bool, optional): Deprecated alias for `show_live_status`. profiler_name (Optional[str], optional): Enables and sets profiler name. Defaults to None which disables profiler. rsim_noise (RsimGaussianNoise, optional): When running in rsim, add Gaussian noise to balls and robots with the given standard deviation. The 3 parameters are for x (in m), y (in m), and orientation (in degrees) respectively. @@ -116,6 +123,13 @@ class StrategyRunner: rsim_vanishing (float, optional): When running in rsim, cause robots and ball to vanish with the given probability. Defaults to 0. filtering (bool, optional): Turn on Kalman filtering. Defaults to false. + referee_system (str, optional): Referee source selector. Valid values are + `"none"`, `"official"`, and `"custom"`. When omitted, it defaults to + `"none"` and no referee input is consumed unless an explicit referee + system is selected. + custom_referee (CustomReferee, optional): In-process referee source used instead of the + network referee receiver. Works across rsim, grsim, and real modes by pushing RefereeData + into ref_buffer each tick before the strategy step. """ def __init__( @@ -132,14 +146,19 @@ def __init__( control_scheme: str = "pid", # This is also the default control scheme used in the motion planning tests opp_control_scheme: Optional[str] = None, replay_writer_config: Optional[ReplayWriterConfig] = None, - print_real_fps: bool = False, # Turn this on for RSim + show_live_status: bool = False, # Turn this on for simulator debugging + print_real_fps: Optional[bool] = None, profiler_name: Optional[str] = None, rsim_noise: RsimGaussianNoise = RsimGaussianNoise(), rsim_vanishing: float = 0, filtering: bool = False, + referee_system: Optional[str] = None, + custom_referee: Optional["CustomReferee"] = None, ): self.logger = logging.getLogger(__name__) + self.custom_referee = custom_referee + self._prev_custom_ref_command: Optional[RefereeCommand] = None self.my_team_is_yellow = my_team_is_yellow self.my_team_is_right = my_team_is_right self.mode: Mode = self._load_mode(mode) @@ -147,6 +166,7 @@ def __init__( self.exp_enemy = exp_enemy self.exp_ball = exp_ball self.field_bounds = field_bounds + self.referee_system = self._resolve_referee_system(self.mode, referee_system, custom_referee) self.vision_buffers, self.ref_buffer = self._setup_vision_and_referee() @@ -177,6 +197,14 @@ def __init__( self.toggle_opp_first = False # used to alternate the order of opp and friendly in run + if print_real_fps is not None: + warnings.warn( + "`print_real_fps` is deprecated; use `show_live_status` instead.", + DeprecationWarning, + stacklevel=2, + ) + show_live_status = print_real_fps + # Replay Writer self.replay_writer = ( ReplayWriter(replay_writer_config, my_team_is_yellow, exp_friendly, exp_enemy) @@ -184,11 +212,12 @@ def __init__( else None ) - # FPS Printing + # Live terminal status panel self.num_frames_elapsed = 0 self.elapsed_time = 0.0 - self.print_real_fps = print_real_fps - if print_real_fps: + self.show_live_status = show_live_status + self.print_real_fps = show_live_status + if show_live_status: self._fps_live = Live(auto_refresh=False) self._fps_live.start() # manually control it so it never overrides prints else: @@ -223,6 +252,38 @@ def _load_mode(self, mode_str: str) -> Mode: raise ValueError(f"Unknown mode: {mode_str}. Choose from 'rsim', 'grsim', or 'real'.") return mode + @staticmethod + def _resolve_referee_system( + mode: Mode, + referee_system: Optional[str], + custom_referee: Optional["CustomReferee"], + ) -> str: + """Resolve and validate referee source selection. + + Default behavior: + - omitted -> "none" + """ + if referee_system is None: + referee_system = "none" + + system = referee_system.lower() + if system not in {"none", "official", "custom"}: + raise ValueError(f"Unknown referee_system: {referee_system}. Choose from 'none', 'official', or 'custom'.") + + if system == "custom" and custom_referee is None: + raise ValueError("referee_system='custom' requires a custom_referee instance.") + + if system != "custom" and custom_referee is not None: + raise ValueError( + "custom_referee was provided, but referee_system is not 'custom'. " + "Use referee_system='custom' or remove custom_referee." + ) + + if system == "official" and mode == Mode.RSIM: + raise ValueError("referee_system='official' is not supported in rsim. Use 'none' or 'custom'.") + + return system + def data_update_listener(self, receiver: VisionReceiver): """Listener function to pull vision data from a VisionReceiver. @@ -396,7 +457,7 @@ def _setup_vision_and_referee(self) -> Tuple[deque, deque]: vision_buffers = [deque(maxlen=1) for _ in range(MAX_CAMERAS)] ref_buffer = deque(maxlen=1) vision_receiver = VisionReceiver(vision_buffers) - if self.mode != Mode.RSIM: + if self.referee_system == "official": referee_receiver = RefereeMessageReceiver(ref_buffer) self.start_threads(vision_receiver, referee_receiver) @@ -773,14 +834,29 @@ def _run_step(self): No return value; updates internal game state and controllers. """ frame_start = time.perf_counter() + + if self.referee_system == "custom": + ref_data = self.custom_referee.step(self.my.current_game_frame, time.time()) + self.ref_buffer.append(ref_data) + if ( + self.sim_controller is not None + and ref_data.referee_command == RefereeCommand.STOP + and ref_data.designated_position is not None + and self._prev_custom_ref_command != RefereeCommand.STOP + ): + x, y = ref_data.designated_position + self.sim_controller.teleport_ball(x, y) + self._prev_custom_ref_command = ref_data.referee_command + if self.mode == Mode.RSIM: obs = self.rsim_env._frame_to_observations() - if len(obs) == 4: + if len(obs) == 4 and self.referee_system != "custom": # New format with referee embedded in observations vision_frames = [obs[0]] referee_data = obs[3] else: - # Standard format — check ref_buffer for externally injected referee data + # custom_referee already pushed data into ref_buffer above; + # otherwise read externally injected referee data. vision_frames = [obs[0]] referee_data = self.ref_buffer.popleft() if self.ref_buffer else None else: @@ -805,7 +881,7 @@ def _run_step(self): time.sleep(wait_time) # --- end of frame --- - if self.print_real_fps: + if self.show_live_status: frame_end = time.perf_counter() frame_dt = frame_end - frame_start diff --git a/utama_core/strategy/referee/actions.py b/utama_core/strategy/referee/actions.py index a2d5f049..8b8f6d60 100644 --- a/utama_core/strategy/referee/actions.py +++ b/utama_core/strategy/referee/actions.py @@ -26,6 +26,7 @@ _BALL_KEEP_DIST = 0.55 # ≥0.5 m required; 5 cm buffer _PENALTY_BEHIND_OFFSET = 0.4 # robots must be ≥0.4 m behind penalty mark _OPP_DEF_AREA_KEEP_DIST = 0.25 # ≥0.2 m from opponent defence area; 5 cm buffer +_PLACEMENT_DONE_DIST = 0.15 # ball within this dist of target → placement complete def _all_stop(blackboard) -> py_trees.common.Status: @@ -73,12 +74,11 @@ def update(self) -> py_trees.common.Status: class BallPlacementOursStep(AbstractBehaviour): - """Moves the closest friendly robot to the designated_position to place the ball. + """Moves the closest friendly robot to place the ball at designated_position. - All other robots stop in place. If can_place_ball is False, all robots stop. - - The placing robot drives toward designated_position using the move() skill. - Ball capture and release are handled by the dribbler (future: dribble_subtree). + If the chosen placer does not yet have the ball, it first drives to the ball + with the dribbler on. Once it has possession, it carries the ball to the + designated position. All other robots stop in place. """ def update(self) -> py_trees.common.Status: @@ -88,7 +88,7 @@ def update(self) -> py_trees.common.Status: # Determine which team is ours our_team = ref.yellow_team if game.my_team_is_yellow else ref.blue_team - if not getattr(our_team, "can_place_ball", True): + if getattr(our_team, "can_place_ball", None) is False: return _all_stop(self.blackboard) target = ref.designated_position @@ -97,20 +97,28 @@ def update(self) -> py_trees.common.Status: target_pos = Vector2D(target[0], target[1]) ball = game.ball + if ball is None: + return _all_stop(self.blackboard) + + if ball.p.distance_to(target_pos) <= _PLACEMENT_DONE_DIST: + return _all_stop(self.blackboard) # Pick the placer: robot closest to the ball placer_id = min( game.friendly_robots, - key=lambda rid: game.friendly_robots[rid].p.distance_to(ball.p) if ball else float("inf"), + key=lambda rid: game.friendly_robots[rid].p.distance_to(ball.p), ) for robot_id in game.friendly_robots: if robot_id == placer_id: - # Face the target while approaching robot = game.friendly_robots[robot_id] - oren = robot.p.angle_to(target_pos) + if robot.has_ball: + target_for_move = target_pos + else: + target_for_move = ball.p + oren = robot.p.angle_to(target_for_move) self.blackboard.cmd_map[robot_id] = move( - game, motion_controller, robot_id, target_pos, oren, dribbling=True + game, motion_controller, robot_id, target_for_move, oren, dribbling=True ) else: self.blackboard.cmd_map[robot_id] = empty_command(False) diff --git a/utama_core/tests/custom_referee/__init__.py b/utama_core/tests/custom_referee/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/utama_core/tests/custom_referee/test_custom_referee.py b/utama_core/tests/custom_referee/test_custom_referee.py new file mode 100644 index 00000000..46918980 --- /dev/null +++ b/utama_core/tests/custom_referee/test_custom_referee.py @@ -0,0 +1,444 @@ +"""Unit tests for the CustomReferee system.""" + +from __future__ import annotations + +import math +from unittest.mock import MagicMock + +import pytest + +from utama_core.custom_referee.custom_referee import CustomReferee +from utama_core.custom_referee.geometry import RefereeGeometry +from utama_core.custom_referee.profiles.profile_loader import load_profile +from utama_core.custom_referee.rules.defense_area_rule import DefenseAreaRule +from utama_core.custom_referee.rules.goal_rule import GoalRule +from utama_core.custom_referee.rules.keep_out_rule import KeepOutRule +from utama_core.custom_referee.rules.out_of_bounds_rule import OutOfBoundsRule +from utama_core.custom_referee.state_machine import GameStateMachine +from utama_core.entities.data.referee import RefereeData +from utama_core.entities.data.vector import Vector2D, Vector3D +from utama_core.entities.game.ball import Ball +from utama_core.entities.game.game_frame import GameFrame +from utama_core.entities.game.robot import Robot +from utama_core.entities.referee.referee_command import RefereeCommand +from utama_core.entities.referee.stage import Stage + +# --------------------------------------------------------------------------- +# Helpers +# --------------------------------------------------------------------------- + +GEO = RefereeGeometry.from_standard_div_b() + + +def _ball(x: float, y: float, z: float = 0.0) -> Ball: + return Ball(p=Vector3D(x, y, z), v=Vector3D(0, 0, 0), a=Vector3D(0, 0, 0)) + + +def _robot(robot_id: int, x: float, y: float, is_friendly: bool, has_ball: bool = False) -> Robot: + return Robot( + id=robot_id, + is_friendly=is_friendly, + has_ball=has_ball, + p=Vector2D(x, y), + v=Vector2D(0, 0), + a=Vector2D(0, 0), + orientation=0.0, + ) + + +def _frame( + ball: Ball, + friendly_robots: dict | None = None, + enemy_robots: dict | None = None, + my_team_is_yellow: bool = True, + my_team_is_right: bool = False, + ts: float = 10.0, +) -> GameFrame: + return GameFrame( + ts=ts, + my_team_is_yellow=my_team_is_yellow, + my_team_is_right=my_team_is_right, + friendly_robots=friendly_robots or {}, + enemy_robots=enemy_robots or {}, + ball=ball, + referee=None, + ) + + +def _state_machine() -> GameStateMachine: + return GameStateMachine( + half_duration_seconds=300.0, + kickoff_team="yellow", + n_robots_yellow=3, + n_robots_blue=3, + initial_command=RefereeCommand.NORMAL_START, + ) + + +# --------------------------------------------------------------------------- +# GoalRule +# --------------------------------------------------------------------------- + + +class TestGoalRule: + def test_right_goal_blue_scores_when_yellow_is_right(self): + # Yellow defends right goal → ball in right goal → blue scored → yellow kicks off. + rule = GoalRule(cooldown_seconds=1.0) + frame = _frame(ball=_ball(5.0, 0.0), my_team_is_yellow=True, my_team_is_right=True) + violation = rule.check(frame, GEO, RefereeCommand.NORMAL_START) + assert violation is not None + assert violation.rule_name == "goal" + assert violation.status_message == "Goal by Blue" + assert violation.next_command == RefereeCommand.PREPARE_KICKOFF_YELLOW + + def test_left_goal_yellow_scores_when_yellow_is_right(self): + # Blue defends left goal → ball in left goal → yellow scored → blue kicks off. + rule = GoalRule(cooldown_seconds=1.0) + frame = _frame(ball=_ball(-5.0, 0.0), my_team_is_yellow=True, my_team_is_right=True) + violation = rule.check(frame, GEO, RefereeCommand.NORMAL_START) + assert violation is not None + assert violation.status_message == "Goal by Yellow" + assert violation.next_command == RefereeCommand.PREPARE_KICKOFF_BLUE + + def test_right_goal_yellow_scores_when_yellow_is_left(self): + # Blue defends right goal → ball in right goal → yellow scored → blue kicks off. + rule = GoalRule(cooldown_seconds=1.0) + frame = _frame(ball=_ball(5.0, 0.0), my_team_is_yellow=True, my_team_is_right=False) + violation = rule.check(frame, GEO, RefereeCommand.NORMAL_START) + assert violation is not None + assert violation.status_message == "Goal by Yellow" + assert violation.next_command == RefereeCommand.PREPARE_KICKOFF_BLUE + + def test_no_goal_wide_shot(self): + rule = GoalRule() + frame = _frame(ball=_ball(5.0, 1.0)) # y=1.0 > half_goal_width=0.5 + assert rule.check(frame, GEO, RefereeCommand.NORMAL_START) is None + + def test_goal_respects_cooldown(self): + rule = GoalRule(cooldown_seconds=2.0) + frame1 = _frame(ball=_ball(5.0, 0.0), my_team_is_right=True, ts=10.0) + v1 = rule.check(frame1, GEO, RefereeCommand.NORMAL_START) + assert v1 is not None + + # Second detection within cooldown window — must be suppressed. + frame2 = _frame(ball=_ball(5.0, 0.0), my_team_is_right=True, ts=10.5) + v2 = rule.check(frame2, GEO, RefereeCommand.NORMAL_START) + assert v2 is None + + # After cooldown expires — should fire again. + frame3 = _frame(ball=_ball(5.0, 0.0), my_team_is_right=True, ts=13.0) + v3 = rule.check(frame3, GEO, RefereeCommand.NORMAL_START) + assert v3 is not None + + def test_no_detection_during_stop(self): + rule = GoalRule() + frame = _frame(ball=_ball(5.0, 0.0)) + assert rule.check(frame, GEO, RefereeCommand.STOP) is None + + +# --------------------------------------------------------------------------- +# OutOfBoundsRule +# --------------------------------------------------------------------------- + + +class TestOutOfBoundsRule: + def test_ball_out_top(self): + rule = OutOfBoundsRule() + frame = _frame(ball=_ball(0.0, 3.5), my_team_is_yellow=True) + violation = rule.check(frame, GEO, RefereeCommand.NORMAL_START) + assert violation is not None + assert violation.rule_name == "out_of_bounds" + + def test_ball_out_right_side(self): + rule = OutOfBoundsRule() + frame = _frame(ball=_ball(5.0, 1.0)) # wide — not in goal (y=1.0 > 0.5) + violation = rule.check(frame, GEO, RefereeCommand.NORMAL_START) + assert violation is not None + + def test_ball_in_field_no_violation(self): + rule = OutOfBoundsRule() + frame = _frame(ball=_ball(0.0, 0.0)) + assert rule.check(frame, GEO, RefereeCommand.NORMAL_START) is None + + def test_ball_in_goal_no_out_of_bounds(self): + rule = OutOfBoundsRule() + frame = _frame(ball=_ball(5.0, 0.0)) # in right goal + # GoalRule handles this; OutOfBoundsRule must not also fire. + assert rule.check(frame, GEO, RefereeCommand.NORMAL_START) is None + + def test_free_kick_assigned_to_non_touching_team_friendly_yellow(self): + """Friendly (yellow) last touched → enemy (blue) gets free kick.""" + rule = OutOfBoundsRule() + friendly = {0: _robot(0, 4.4, 2.9, is_friendly=True, has_ball=True)} + frame_before = _frame(ball=_ball(4.4, 2.9), friendly_robots=friendly, my_team_is_yellow=True, ts=9.9) + rule.check(frame_before, GEO, RefereeCommand.NORMAL_START) + + frame_out = _frame(ball=_ball(0.0, 3.5), my_team_is_yellow=True, ts=10.0) + violation = rule.check(frame_out, GEO, RefereeCommand.NORMAL_START) + assert violation is not None + assert violation.next_command == RefereeCommand.DIRECT_FREE_BLUE + + def test_designated_position_is_infield(self): + rule = OutOfBoundsRule() + frame = _frame(ball=_ball(0.0, 3.5)) + violation = rule.check(frame, GEO, RefereeCommand.NORMAL_START) + assert violation is not None + px, py = violation.designated_position + assert abs(py) < GEO.half_width # placed infield + + +# --------------------------------------------------------------------------- +# DefenseAreaRule +# --------------------------------------------------------------------------- + + +class TestDefenseAreaRule: + def _frame_with_attacker_in_defense(self, my_team_is_right: bool = False) -> GameFrame: + # Enemy robot inside my (left) defense area. + enemy = {0: _robot(0, -4.3, 0.5, is_friendly=False)} + return _frame( + ball=_ball(0, 0), + enemy_robots=enemy, + my_team_is_right=my_team_is_right, + ) + + def test_fires_during_normal_start(self): + rule = DefenseAreaRule() + frame = self._frame_with_attacker_in_defense(my_team_is_right=False) + v = rule.check(frame, GEO, RefereeCommand.NORMAL_START) + assert v is not None + assert v.rule_name == "defense_area" + + def test_does_not_fire_during_stop(self): + rule = DefenseAreaRule() + frame = self._frame_with_attacker_in_defense() + assert rule.check(frame, GEO, RefereeCommand.STOP) is None + + def test_does_not_fire_during_force_start_no_actually_fires(self): + rule = DefenseAreaRule() + frame = self._frame_with_attacker_in_defense(my_team_is_right=False) + v = rule.check(frame, GEO, RefereeCommand.FORCE_START) + assert v is not None + + def test_too_many_defenders(self): + rule = DefenseAreaRule(max_defenders=1) + # Two friendly robots in own (left) defense area. + friendly = { + 0: _robot(0, -4.3, 0.0, is_friendly=True), + 1: _robot(1, -4.3, 0.5, is_friendly=True), + } + frame = _frame(ball=_ball(0, 0), friendly_robots=friendly, my_team_is_right=False, my_team_is_yellow=True) + v = rule.check(frame, GEO, RefereeCommand.NORMAL_START) + assert v is not None + assert v.next_command == RefereeCommand.DIRECT_FREE_BLUE + + +# --------------------------------------------------------------------------- +# KeepOutRule +# --------------------------------------------------------------------------- + + +class TestKeepOutRule: + def test_no_trigger_before_persistence_threshold(self): + rule = KeepOutRule(radius_meters=0.5, violation_persistence_frames=5) + friendly = {0: _robot(0, 0.2, 0.0, is_friendly=True)} + # Enemy is kicking → check friendly. + for _ in range(4): + frame = _frame(ball=_ball(0.0, 0.0), friendly_robots=friendly) + v = rule.check(frame, GEO, RefereeCommand.DIRECT_FREE_BLUE) + assert v is None + + def test_triggers_after_persistence_threshold(self): + rule = KeepOutRule(radius_meters=0.5, violation_persistence_frames=5) + friendly = {0: _robot(0, 0.2, 0.0, is_friendly=True)} + v = None + for _ in range(5): + frame = _frame(ball=_ball(0.0, 0.0), friendly_robots=friendly) + v = rule.check(frame, GEO, RefereeCommand.DIRECT_FREE_BLUE) + assert v is not None + assert v.rule_name == "keep_out" + + def test_resets_on_non_violation_frame(self): + rule = KeepOutRule(radius_meters=0.5, violation_persistence_frames=5) + friendly = {0: _robot(0, 0.2, 0.0, is_friendly=True)} + for _ in range(4): + frame = _frame(ball=_ball(0.0, 0.0), friendly_robots=friendly) + rule.check(frame, GEO, RefereeCommand.DIRECT_FREE_BLUE) + + # Robot moves away — count resets. + far_frame = _frame( + ball=_ball(0.0, 0.0), + friendly_robots={0: _robot(0, 2.0, 0.0, is_friendly=True)}, + ) + rule.check(far_frame, GEO, RefereeCommand.DIRECT_FREE_BLUE) + + # Needs another full persistence run to trigger. + v = None + for _ in range(5): + frame = _frame(ball=_ball(0.0, 0.0), friendly_robots=friendly) + v = rule.check(frame, GEO, RefereeCommand.DIRECT_FREE_BLUE) + assert v is not None + + def test_inactive_during_normal_start(self): + rule = KeepOutRule(radius_meters=0.5, violation_persistence_frames=1) + friendly = {0: _robot(0, 0.1, 0.0, is_friendly=True)} + frame = _frame(ball=_ball(0.0, 0.0), friendly_robots=friendly) + assert rule.check(frame, GEO, RefereeCommand.NORMAL_START) is None + + +# --------------------------------------------------------------------------- +# GameStateMachine +# --------------------------------------------------------------------------- + + +class TestGameStateMachine: + def test_goal_increments_yellow_score(self): + from utama_core.custom_referee.rules.base_rule import RuleViolation + + sm = _state_machine() + violation = RuleViolation( + rule_name="goal", + suggested_command=RefereeCommand.STOP, + next_command=RefereeCommand.PREPARE_KICKOFF_BLUE, + status_message="Goal by Yellow", + ) + data = sm.step(current_time=10.0, violation=violation) + assert sm.yellow_team.score == 1 + assert sm.blue_team.score == 0 + assert data.referee_command == RefereeCommand.STOP + assert data.next_command == RefereeCommand.PREPARE_KICKOFF_BLUE + + def test_goal_increments_blue_score(self): + from utama_core.custom_referee.rules.base_rule import RuleViolation + + sm = _state_machine() + violation = RuleViolation( + rule_name="goal", + suggested_command=RefereeCommand.STOP, + next_command=RefereeCommand.PREPARE_KICKOFF_YELLOW, + status_message="Goal by Blue", + ) + sm.step(current_time=10.0, violation=violation) + assert sm.blue_team.score == 1 + assert sm.yellow_team.score == 0 + + def test_transition_cooldown_suppresses_duplicate(self): + from utama_core.custom_referee.rules.base_rule import RuleViolation + + sm = _state_machine() + violation = RuleViolation( + rule_name="goal", + suggested_command=RefereeCommand.STOP, + next_command=RefereeCommand.PREPARE_KICKOFF_BLUE, + status_message="Goal", + ) + sm.step(current_time=10.0, violation=violation) + assert sm.yellow_team.score == 1 + + # Second goal within cooldown window — must be suppressed. + sm.step(current_time=10.1, violation=violation) + assert sm.yellow_team.score == 1 # still 1 + + def test_goal_sets_designated_position_to_centre(self): + from utama_core.custom_referee.rules.base_rule import RuleViolation + + sm = _state_machine() + violation = RuleViolation( + rule_name="goal", + suggested_command=RefereeCommand.STOP, + next_command=RefereeCommand.PREPARE_KICKOFF_BLUE, + status_message="Goal by Yellow", + ) + data = sm.step(current_time=10.0, violation=violation) + assert data.designated_position == (0.0, 0.0) + + def test_manual_set_command(self): + sm = _state_machine() + sm.set_command(RefereeCommand.NORMAL_START, timestamp=5.0) + assert sm.command == RefereeCommand.NORMAL_START + + +# --------------------------------------------------------------------------- +# CustomReferee integration +# --------------------------------------------------------------------------- + + +class TestCustomReferee: + def test_returns_valid_referee_data(self): + referee = CustomReferee.from_profile_name("simulation") + frame = _frame(ball=_ball(0.0, 0.0)) + data = referee.step(frame, current_time=10.0) + assert isinstance(data, RefereeData) + assert data.source_identifier == "custom_referee" + + def test_simulation_goal_auto_advances_to_prepare_kickoff_and_scores(self): + referee = CustomReferee.from_profile_name("simulation") + referee.set_command(RefereeCommand.NORMAL_START, timestamp=0.0) + + # Yellow is on the RIGHT — ball in right goal means yellow conceded, blue scored. + frame = _frame(ball=_ball(5.0, 0.0), my_team_is_yellow=True, my_team_is_right=True, ts=10.0) + data = referee.step(frame, current_time=10.0) + + assert data.referee_command == RefereeCommand.PREPARE_KICKOFF_YELLOW + assert data.blue_team.score == 1 + assert data.yellow_team.score == 0 + assert data.next_command == RefereeCommand.NORMAL_START + + def test_human_profile_no_oob(self): + """Human profile disables out-of-bounds — ball outside must not trigger.""" + referee = CustomReferee.from_profile_name("human") + referee.set_command(RefereeCommand.NORMAL_START, timestamp=0.0) + frame = _frame(ball=_ball(0.0, 4.0), ts=10.0) # ball outside field width + data = referee.step(frame, current_time=10.0) + assert data.referee_command == RefereeCommand.NORMAL_START + + def test_human_stays_in_stop_after_goal_until_operator_advances(self): + """Human mode keeps the game in STOP after a goal for operator control.""" + referee = CustomReferee.from_profile_name("human") + referee.set_command(RefereeCommand.NORMAL_START, timestamp=0.0) + + # Score a goal (yellow on right, blue scores). + goal_frame = _frame(ball=_ball(5.0, 0.0), my_team_is_yellow=True, my_team_is_right=True, ts=10.0) + data = referee.step(goal_frame, current_time=10.0) + assert data.referee_command == RefereeCommand.STOP + assert data.next_command == RefereeCommand.PREPARE_KICKOFF_YELLOW + + # Still in STOP later — operator must choose the next command. + still_stop = referee.step(_frame(ball=_ball(0.0, 0.0), ts=70.0), current_time=70.0) + assert still_stop.referee_command == RefereeCommand.STOP + + def test_simulation_stays_in_prepare_kickoff_after_goal_without_ready_kicker(self): + """Simulation mode auto-advances into PREPARE_KICKOFF and waits there until ready.""" + referee = CustomReferee.from_profile_name("simulation") + referee.set_command(RefereeCommand.NORMAL_START, timestamp=0.0) + + goal_frame = _frame(ball=_ball(5.0, 0.0), my_team_is_yellow=True, my_team_is_right=True, ts=10.0) + referee.step(goal_frame, current_time=10.0) + + # With no kicker in the centre circle, the state remains in PREPARE_KICKOFF. + data = referee.step(_frame(ball=_ball(0.0, 0.0), ts=70.0), current_time=70.0) + assert data.referee_command == RefereeCommand.PREPARE_KICKOFF_YELLOW + + +# --------------------------------------------------------------------------- +# Profile loader +# --------------------------------------------------------------------------- + + +class TestProfileLoader: + def test_simulation_loads(self): + profile = load_profile("simulation") + assert profile.profile_name == "simulation" + assert profile.rules.goal_detection.enabled is True + assert profile.rules.keep_out.radius_meters == 0.5 + + def test_human_loads(self): + profile = load_profile("human") + assert profile.profile_name == "human" + assert profile.rules.out_of_bounds.enabled is False + assert profile.game.force_start_after_goal is False + assert profile.game.auto_advance.stop_to_prepare_kickoff is False + + def test_unknown_profile_raises(self): + with pytest.raises(FileNotFoundError): + load_profile("nonexistent_profile") diff --git a/utama_core/tests/referee/demo_referee_gui_rsim.py b/utama_core/tests/referee/demo_referee_gui_rsim.py new file mode 100644 index 00000000..96a68d57 --- /dev/null +++ b/utama_core/tests/referee/demo_referee_gui_rsim.py @@ -0,0 +1,74 @@ +"""demo_referee_gui_rsim.py — CustomReferee + web GUI + StrategyRunner (RSim). + +Run: + pixi run python utama_core/tests/referee/demo_referee_gui_rsim.py + # RSim window opens; open http://localhost:8080 in a browser + +What it does: + - Creates a CustomReferee (human profile) with enable_gui=True so the + browser panel starts automatically. + - Passes the referee to StrategyRunner via custom_referee=. StrategyRunner + calls referee.step() on every tick and handles ball teleports on STOP + automatically — no patching required. + - WanderingStrategy is used as the base strategy so robots visibly move and + you can watch the RefereeOverride tree interrupt them when you issue + commands from the GUI (Halt, Kickoff Yellow, etc.). + +Operator workflow: + 1. Open http://localhost:8080 in a browser. + 2. Robots start moving under WanderingStrategy. + 3. Click any command button (Halt, Stop, Kickoff Yellow…) — robots reposition. + 4. Click Normal Start to resume free play. + 5. With the human profile, the referee stays in STOP after a goal until the operator advances play. +""" + +from utama_core.custom_referee import CustomReferee +from utama_core.custom_referee.profiles.profile_loader import load_profile +from utama_core.run import StrategyRunner +from utama_core.tests.referee.wandering_strategy import WanderingStrategy + +# --------------------------------------------------------------------------- +# Configuration +# --------------------------------------------------------------------------- + +PROFILE = "human" # "human" or "simulation" +GUI_PORT = 8080 +N_ROBOTS = 3 # robots per side +MY_TEAM_IS_YELLOW = True +MY_TEAM_IS_RIGHT = True + +# --------------------------------------------------------------------------- +# Entry point +# --------------------------------------------------------------------------- + + +def main() -> None: + profile = load_profile(PROFILE) + + # enable_gui=True starts the HTTP server in a background daemon thread. + # referee.step() is called by StrategyRunner on every tick; the GUI + # receives state automatically after each call. + referee = CustomReferee( + profile, + n_robots_yellow=N_ROBOTS, + n_robots_blue=N_ROBOTS, + enable_gui=True, + gui_port=GUI_PORT, + ) + + runner = StrategyRunner( + strategy=WanderingStrategy(), + my_team_is_yellow=MY_TEAM_IS_YELLOW, + my_team_is_right=MY_TEAM_IS_RIGHT, + mode="rsim", + exp_friendly=N_ROBOTS, + exp_enemy=N_ROBOTS, + custom_referee=referee, # StrategyRunner drives referee.step() each tick + show_live_status=True, + ) + + runner.run() + + +if __name__ == "__main__": + main() diff --git a/utama_core/tests/referee/referee_sim.py b/utama_core/tests/referee/referee_sim.py index 8f2ea5c3..4bbf526c 100644 --- a/utama_core/tests/referee/referee_sim.py +++ b/utama_core/tests/referee/referee_sim.py @@ -142,7 +142,7 @@ def main(): mode="rsim", exp_friendly=N_ROBOTS, exp_enemy=N_ROBOTS, - print_real_fps=True, + show_live_status=True, ) # Patch _run_step to push scripted RefereeData into ref_buffer before each diff --git a/utama_core/tests/referee/test_referee_unit.py b/utama_core/tests/referee/test_referee_unit.py index fd6f40af..6f772d10 100644 --- a/utama_core/tests/referee/test_referee_unit.py +++ b/utama_core/tests/referee/test_referee_unit.py @@ -34,7 +34,7 @@ # --------------------------------------------------------------------------- -def _team_info(goalkeeper: int = 0) -> TeamInfo: +def _team_info(goalkeeper: int = 0, can_place_ball: bool = True) -> TeamInfo: return TeamInfo( name="TestTeam", score=0, @@ -44,6 +44,7 @@ def _team_info(goalkeeper: int = 0) -> TeamInfo: timeouts=0, timeout_time=0, goalkeeper=goalkeeper, + can_place_ball=can_place_ball, ) @@ -385,6 +386,104 @@ def test_stop_writes_to_all_robots(self): assert set(cmd_map.keys()) == {0, 1, 2} +# --------------------------------------------------------------------------- +# BallPlacementOursStep — fetch ball before target placement +# --------------------------------------------------------------------------- + + +class TestBallPlacementOursStep: + def test_robot_without_ball_moves_to_ball_first(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords, dribbling)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = { + 0: _robot(0, 0.0, 0.0), + 1: _robot(1, 2.0, 2.0), + } + referee = _make_referee_data( + command=RefereeCommand.BALL_PLACEMENT_YELLOW, + ) + referee.designated_position = (1.5, 1.5) + frame = GameFrame( + ts=0.0, + my_team_is_yellow=True, + my_team_is_right=True, + friendly_robots=robots, + enemy_robots={}, + ball=_ball(0.2, 0.0), + referee=referee, + ) + game = Game(past=GameHistory(10), current=frame, field=Field.FULL_FIELD_BOUNDS) + + cmd_map = _make_cmd_map(game) + node = referee_actions.BallPlacementOursStep(name="BallPlacementOurs") + node.blackboard = _make_blackboard(game, cmd_map) + + status = node.update() + + assert status == py_trees.common.Status.RUNNING + assert captured[0][0] == 0 + assert captured[0][1].x == game.ball.p.x + assert captured[0][1].y == game.ball.p.y + assert captured[0][2] is True + assert cmd_map[1] is not None + + def test_robot_with_ball_moves_to_designated_position(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords, dribbling)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = { + 0: Robot( + id=0, + is_friendly=True, + has_ball=True, + p=Vector2D(0.0, 0.0), + v=Vector2D(0.0, 0.0), + a=Vector2D(0.0, 0.0), + orientation=0.0, + ) + } + referee = _make_referee_data( + command=RefereeCommand.BALL_PLACEMENT_YELLOW, + ) + referee.designated_position = (1.5, -0.5) + frame = GameFrame( + ts=0.0, + my_team_is_yellow=True, + my_team_is_right=True, + friendly_robots=robots, + enemy_robots={}, + ball=_ball(0.0, 0.0), + referee=referee, + ) + game = Game(past=GameHistory(10), current=frame, field=Field.FULL_FIELD_BOUNDS) + + cmd_map = _make_cmd_map(game) + node = referee_actions.BallPlacementOursStep(name="BallPlacementOurs") + node.blackboard = _make_blackboard(game, cmd_map) + + status = node.update() + + assert status == py_trees.common.Status.RUNNING + assert captured[0][0] == 0 + assert captured[0][1] == Vector2D(1.5, -0.5) + assert captured[0][2] is True + + # --------------------------------------------------------------------------- # build_referee_override_tree — structure checks # --------------------------------------------------------------------------- diff --git a/utama_core/tests/strategy_runner/test_runner_misconfig.py b/utama_core/tests/strategy_runner/test_runner_misconfig.py index 417e4a1a..6b2ade4d 100644 --- a/utama_core/tests/strategy_runner/test_runner_misconfig.py +++ b/utama_core/tests/strategy_runner/test_runner_misconfig.py @@ -29,6 +29,44 @@ def test_load_mode_invalid(base_runner): base_runner._load_mode("invalid_mode") +def test_resolve_referee_system_defaults_to_none_in_rsim(): + assert StrategyRunner._resolve_referee_system(Mode.RSIM, None, None) == "none" + + +def test_resolve_referee_system_defaults_to_none_in_grsim(): + assert StrategyRunner._resolve_referee_system(Mode.GRSIM, None, None) == "none" + + +def test_resolve_referee_system_defaults_to_none_even_when_custom_referee_is_provided(): + with pytest.raises(ValueError, match="custom_referee"): + StrategyRunner._resolve_referee_system(Mode.RSIM, None, object()) + + +def test_resolve_referee_system_rejects_invalid_name(): + with pytest.raises(ValueError, match="Unknown referee_system"): + StrategyRunner._resolve_referee_system(Mode.RSIM, "auto", None) + + +def test_resolve_referee_system_rejects_official_in_rsim(): + with pytest.raises(ValueError, match="official"): + StrategyRunner._resolve_referee_system(Mode.RSIM, "official", None) + + +def test_resolve_referee_system_requires_custom_referee_for_custom_mode(): + with pytest.raises(ValueError, match="custom_referee"): + StrategyRunner._resolve_referee_system(Mode.RSIM, "custom", None) + + +def test_resolve_referee_system_rejects_custom_referee_with_none_mode(): + with pytest.raises(ValueError, match="custom_referee"): + StrategyRunner._resolve_referee_system(Mode.RSIM, "none", object()) + + +def test_resolve_referee_system_rejects_custom_referee_with_official_mode(): + with pytest.raises(ValueError, match="custom_referee"): + StrategyRunner._resolve_referee_system(Mode.GRSIM, "official", object()) + + def test_assert_exp_robots_valid(base_runner): base_runner._assert_exp_robots_and_ball(3, 3, True) # Should not raise From 5c0b05a8219353e68a49921dddd2ff011d18f9e9 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Tue, 31 Mar 2026 22:22:48 +0100 Subject: [PATCH 007/121] Fix referee runner startup and keep-out behavior --- docs/referee_integration.md | 2 +- utama_core/run/strategy_runner.py | 28 ++-- utama_core/strategy/referee/actions.py | 88 +++++++--- utama_core/tests/referee/test_referee_unit.py | 155 +++++++++++++++++- .../strategy_runner/test_runner_misconfig.py | 97 +++++++++++ 5 files changed, 331 insertions(+), 39 deletions(-) diff --git a/docs/referee_integration.md b/docs/referee_integration.md index d4a3d49e..2570fa3f 100644 --- a/docs/referee_integration.md +++ b/docs/referee_integration.md @@ -49,7 +49,7 @@ Rules sourced from the [SSL Rulebook](https://robocup-ssl.github.io/ssl-rules/ss | **PREPARE_KICKOFF (theirs)** | All robots to own half, outside centre circle. | Same zone constraint. | | **NORMAL_START** (after kickoff / free kick) | Game live — pass to strategy tree. | Ball is now in play. | | **FORCE_START** | Game live — pass to strategy tree. | Ball at current position; no placement needed. | -| **PREPARE_PENALTY (ours)** | Kicker: approach penalty mark, do not touch. Our other robots: ≥ 0.4 m behind penalty mark line. | Penalty mark: 6 m from goal centre (Div B). | +| **PREPARE_PENALTY (ours)** | Kicker: approach penalty mark, do not touch. Our other robots: ≥ 0.4 m behind penalty mark line. | Penalty mark: halfway between centre line and attacked goal in Utama's field model. | | **PREPARE_PENALTY (theirs)** | Our goalkeeper: touch own goal line. All other our robots: ≥ 0.4 m behind the penalty mark (on our side). | Goalkeeper ID from `referee.{our_team}.goalkeeper`. | | **DIRECT_FREE (ours)** | One robot (kicker) approaches ball. Others position freely. After NORMAL_START the kicker may shoot directly. | Ball must move ≥ 0.05 m to be in play. | | **DIRECT_FREE (theirs)** | All our robots ≥ 0.5 m from ball. Full speed allowed (unlike STOP). | Same distance as STOP but no speed cap. | diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index 1717eeba..54ab906b 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -296,23 +296,28 @@ def data_update_listener(self, receiver: VisionReceiver): # Start receiving game data; this will run in a separate thread. receiver.pull_game_data() - def start_threads(self, vision_receiver: VisionReceiver, referee_receiver: RefereeMessageReceiver): - """Start background threads for receiving vision and referee data. + def start_threads( + self, + vision_receiver: VisionReceiver, + referee_receiver: Optional[RefereeMessageReceiver] = None, + ): + """Start background threads for receiving vision and optionally referee data. Starts daemon threads so they do not prevent process exit. Args: vision_receiver: VisionReceiver to run in a background thread. - referee_receiver: RefereeMessageReceiver to run in a background thread. + referee_receiver: Optional RefereeMessageReceiver to run in a background thread. """ vision_thread = threading.Thread(target=vision_receiver.pull_game_data) - referee_thread = threading.Thread(target=referee_receiver.pull_referee_data) vision_thread.daemon = True - referee_thread.daemon = True vision_thread.start() - referee_thread.start() + if referee_receiver is not None: + referee_thread = threading.Thread(target=referee_receiver.pull_referee_data) + referee_thread.daemon = True + referee_thread.start() def _setup_sides_data( self, @@ -456,10 +461,13 @@ def _setup_vision_and_referee(self) -> Tuple[deque, deque]: """ vision_buffers = [deque(maxlen=1) for _ in range(MAX_CAMERAS)] ref_buffer = deque(maxlen=1) - vision_receiver = VisionReceiver(vision_buffers) - if self.referee_system == "official": - referee_receiver = RefereeMessageReceiver(ref_buffer) - self.start_threads(vision_receiver, referee_receiver) + if self.mode != Mode.RSIM: + vision_receiver = VisionReceiver(vision_buffers) + if self.referee_system == "official": + referee_receiver = RefereeMessageReceiver(ref_buffer) + self.start_threads(vision_receiver, referee_receiver) + else: + self.start_threads(vision_receiver) return vision_buffers, ref_buffer diff --git a/utama_core/strategy/referee/actions.py b/utama_core/strategy/referee/actions.py index 8b8f6d60..920664db 100644 --- a/utama_core/strategy/referee/actions.py +++ b/utama_core/strategy/referee/actions.py @@ -19,8 +19,11 @@ from utama_core.skills.src.utils.move_utils import empty_command, move from utama_core.strategy.common.abstract_behaviour import AbstractBehaviour -# SSL Div B field constants (metres) -_PENALTY_MARK_DIST = 6.0 # distance from goal centre to penalty mark +# SSL field constants / heuristics (metres) +# Utama's standard field model is 9m x 6m. For penalty setup we place the +# penalty mark halfway between the centre line and the relevant goal line so +# it always lies on the correct half, including custom field bounds. +_PENALTY_MARK_HALF_FIELD_RATIO = 0.5 _HALF_FIELD_X = 4.5 # half field length _CENTRE_CIRCLE_R = 0.5 # centre circle radius _BALL_KEEP_DIST = 0.55 # ≥0.5 m required; 5 cm buffer @@ -36,6 +39,48 @@ def _all_stop(blackboard) -> py_trees.common.Status: return py_trees.common.Status.RUNNING +def _field_half_length(game) -> float: + """Return the current field half-length, supporting Field and FieldBounds alike.""" + field = game.field + if hasattr(field, "half_length"): + return field.half_length + return (field.bottom_right[0] - field.top_left[0]) / 2.0 + + +def _penalty_mark_x(goal_x: float) -> float: + """Place the penalty mark midway between centre and goal line.""" + return goal_x * _PENALTY_MARK_HALF_FIELD_RATIO + + +def _clear_from_ball(blackboard, keep_dist: float = _BALL_KEEP_DIST) -> py_trees.common.Status: + """Move encroaching robots out beyond the keep-out radius and stop the rest.""" + game = blackboard.game + ball = game.ball + motion_controller = blackboard.motion_controller + if ball is None: + return _all_stop(blackboard) + + bx, by = ball.p.x, ball.p.y + for robot_id, robot in game.friendly_robots.items(): + dx = robot.p.x - bx + dy = robot.p.y - by + dist = math.hypot(dx, dy) + if dist >= keep_dist: + blackboard.cmd_map[robot_id] = empty_command(False) + continue + + if dist == 0.0: + ux, uy = 1.0, 0.0 + else: + ux, uy = dx / dist, dy / dist + + target = Vector2D(bx + ux * keep_dist, by + uy * keep_dist) + oren = robot.p.angle_to(target) + blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, target, oren) + + return py_trees.common.Status.RUNNING + + # --------------------------------------------------------------------------- # HALT — zero velocity, highest priority # --------------------------------------------------------------------------- @@ -58,14 +103,10 @@ def update(self) -> py_trees.common.Status: class StopStep(AbstractBehaviour): - """Sends zero-velocity commands to all friendly robots. - - Complies with STOP: robots are stationary, so speed = 0 m/s ≤ 1.5 m/s - and they do not approach the ball. - """ + """Moves encroaching robots out of the keep-out radius and stops the rest.""" def update(self) -> py_trees.common.Status: - return _all_stop(self.blackboard) + return _clear_from_ball(self.blackboard) # --------------------------------------------------------------------------- @@ -132,15 +173,10 @@ def update(self) -> py_trees.common.Status: class BallPlacementTheirsStep(AbstractBehaviour): - """Stops all friendly robots during the opponent's ball placement. - - Robots stopped in place are guaranteed not to approach the ball or interfere - with the placement. Active clearance (move ≥0.5 m from ball) is a future - enhancement. - """ + """Actively clear our robots away from the ball during their placement.""" def update(self) -> py_trees.common.Status: - return _all_stop(self.blackboard) + return _clear_from_ball(self.blackboard) # --------------------------------------------------------------------------- @@ -236,7 +272,7 @@ class PreparePenaltyOursStep(AbstractBehaviour): Kicker (lowest non-keeper ID): moves to our penalty mark, faces goal. All others: stop on a line 0.4 m behind the penalty mark (on own side). - Penalty mark is at (opp_goal_x ∓ 6.0, 0), sign depends on which side we attack. + Penalty mark is placed halfway between the centre line and the target goal line. """ def update(self) -> py_trees.common.Status: @@ -249,9 +285,10 @@ def update(self) -> py_trees.common.Status: keeper_id = our_team_info.goalkeeper # Opponent goal is on the right if we are on the right, else on the left - opp_goal_x = _HALF_FIELD_X if not game.my_team_is_right else -_HALF_FIELD_X + field_half_length = _field_half_length(game) + opp_goal_x = field_half_length if not game.my_team_is_right else -field_half_length sign = 1 if not game.my_team_is_right else -1 - penalty_mark = Vector2D(opp_goal_x - sign * _PENALTY_MARK_DIST, 0.0) + penalty_mark = Vector2D(_penalty_mark_x(opp_goal_x), 0.0) behind_line_x = penalty_mark.x - sign * _PENALTY_BEHIND_OFFSET goal_oren = math.atan2(0.0, opp_goal_x - penalty_mark.x) @@ -296,11 +333,12 @@ def update(self) -> py_trees.common.Status: keeper_id = our_team_info.goalkeeper # Our goal is on the right if my_team_is_right, else on the left - our_goal_x = _HALF_FIELD_X if game.my_team_is_right else -_HALF_FIELD_X + field_half_length = _field_half_length(game) + our_goal_x = field_half_length if game.my_team_is_right else -field_half_length sign = 1 if game.my_team_is_right else -1 - # Opponent's penalty mark is in their half attacking our goal - opp_penalty_mark_x = our_goal_x - sign * _PENALTY_MARK_DIST + # Opponent's penalty mark is in our half, between centre and our goal line. + opp_penalty_mark_x = _penalty_mark_x(our_goal_x) behind_line_x = opp_penalty_mark_x + sign * _PENALTY_BEHIND_OFFSET robot_ids = sorted(game.friendly_robots.keys()) @@ -363,14 +401,10 @@ def update(self) -> py_trees.common.Status: class DirectFreeTheirsStep(AbstractBehaviour): - """Stops all our robots during the opponent's direct free kick. - - All robots must remain ≥ 0.5 m from the ball. Stopping in place satisfies this - assuming robots are not already within 0.5 m (future: add active clearance). - """ + """Actively clear our robots out of the ball keep-out radius.""" def update(self) -> py_trees.common.Status: - return _all_stop(self.blackboard) + return _clear_from_ball(self.blackboard) # --------------------------------------------------------------------------- diff --git a/utama_core/tests/referee/test_referee_unit.py b/utama_core/tests/referee/test_referee_unit.py index 6f772d10..50fd30fb 100644 --- a/utama_core/tests/referee/test_referee_unit.py +++ b/utama_core/tests/referee/test_referee_unit.py @@ -116,7 +116,7 @@ def _make_blackboard(game: Game, cmd_map=None): bb = SimpleNamespace() bb.game = game bb.cmd_map = cmd_map if cmd_map is not None else {} - bb.motion_controller = None + bb.motion_controller = SimpleNamespace(calculate=lambda **kwargs: (Vector2D(0.0, 0.0), 0.0)) return bb @@ -484,6 +484,159 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri assert captured[0][2] is True +# --------------------------------------------------------------------------- +# Keep-out retreat and penalty positioning +# --------------------------------------------------------------------------- + + +class TestRefereeKeepOutRetreat: + def test_stop_moves_only_robots_inside_keep_out_radius(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords, dribbling)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = { + 0: _robot(0, 0.0, 0.0), + 1: _robot(1, 1.0, 0.0), + } + game = _make_game(friendly_robots=robots, referee=_make_referee_data(command=RefereeCommand.STOP)) + cmd_map = _make_cmd_map(game) + node = referee_actions.StopStep(name="Stop") + node.blackboard = _make_blackboard(game, cmd_map) + + status = node.update() + + assert status == py_trees.common.Status.RUNNING + assert len(captured) == 1 + assert captured[0][0] == 0 + assert captured[0][1] == Vector2D(0.55, 0.0) + assert cmd_map[1] is not None + + def test_ball_placement_theirs_clears_encroaching_robot(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = { + 0: _robot(0, 0.1, 0.0), + 1: _robot(1, 1.0, 0.0), + } + referee = _make_referee_data(command=RefereeCommand.BALL_PLACEMENT_BLUE) + game = _make_game(friendly_robots=robots, referee=referee) + cmd_map = _make_cmd_map(game) + node = referee_actions.BallPlacementTheirsStep(name="BallPlacementTheirs") + node.blackboard = _make_blackboard(game, cmd_map) + + status = node.update() + + assert status == py_trees.common.Status.RUNNING + assert len(captured) == 1 + assert captured[0][0] == 0 + assert captured[0][1] == Vector2D(0.55, 0.0) + + def test_direct_free_theirs_clears_encroaching_robot(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = { + 0: _robot(0, 0.2, 0.0), + 1: _robot(1, -1.0, 0.0), + } + referee = _make_referee_data(command=RefereeCommand.DIRECT_FREE_BLUE) + game = _make_game(friendly_robots=robots, referee=referee) + cmd_map = _make_cmd_map(game) + node = referee_actions.DirectFreeTheirsStep(name="DirectFreeTheirs") + node.blackboard = _make_blackboard(game, cmd_map) + + status = node.update() + + assert status == py_trees.common.Status.RUNNING + assert len(captured) == 1 + assert captured[0][0] == 0 + assert captured[0][1] == Vector2D(0.55, 0.0) + + +class TestPenaltyPositioning: + def test_prepare_penalty_ours_kicker_stays_on_attacking_half(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = { + 0: _robot(0, 0.0, 0.0), + 1: _robot(1, 1.0, 0.0), + } + referee = _make_referee_data(command=RefereeCommand.PREPARE_PENALTY_YELLOW) + referee.yellow_team.goalkeeper = 1 + game = _make_game(friendly_robots=robots, referee=referee, my_team_is_yellow=True, my_team_is_right=True) + cmd_map = _make_cmd_map(game) + node = referee_actions.PreparePenaltyOursStep(name="PreparePenaltyOurs") + node.blackboard = _make_blackboard(game, cmd_map) + + status = node.update() + kicker_target = next(target for robot_id, target in captured if robot_id == 0) + + assert status == py_trees.common.Status.RUNNING + assert kicker_target.x == pytest.approx(-2.25) + assert kicker_target.x < 0.0 + + def test_prepare_penalty_theirs_support_robots_stay_on_our_half(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = { + 0: _robot(0, 0.0, 0.0), + 1: _robot(1, 0.5, 0.0), + 2: _robot(2, -0.5, 0.0), + } + referee = _make_referee_data(command=RefereeCommand.PREPARE_PENALTY_BLUE) + referee.yellow_team.goalkeeper = 1 + game = _make_game(friendly_robots=robots, referee=referee, my_team_is_yellow=True, my_team_is_right=True) + cmd_map = _make_cmd_map(game) + node = referee_actions.PreparePenaltyTheirsStep(name="PreparePenaltyTheirs") + node.blackboard = _make_blackboard(game, cmd_map) + + status = node.update() + keeper_target = next(target for robot_id, target in captured if robot_id == 1) + support_targets = [target for robot_id, target in captured if robot_id != 1] + + assert status == py_trees.common.Status.RUNNING + assert keeper_target.x == pytest.approx(4.5) + assert all(target.x > 0.0 for target in support_targets) + + # --------------------------------------------------------------------------- # build_referee_override_tree — structure checks # --------------------------------------------------------------------------- diff --git a/utama_core/tests/strategy_runner/test_runner_misconfig.py b/utama_core/tests/strategy_runner/test_runner_misconfig.py index 6b2ade4d..13487df6 100644 --- a/utama_core/tests/strategy_runner/test_runner_misconfig.py +++ b/utama_core/tests/strategy_runner/test_runner_misconfig.py @@ -1,3 +1,5 @@ +from types import SimpleNamespace + import pytest from utama_core.config.enums import Mode @@ -67,6 +69,101 @@ def test_resolve_referee_system_rejects_custom_referee_with_official_mode(): StrategyRunner._resolve_referee_system(Mode.GRSIM, "official", object()) +def test_setup_vision_and_referee_starts_vision_only_when_referee_none(monkeypatch): + from utama_core.run import strategy_runner as runner_mod + + started = [] + + class DummyVisionReceiver: + def __init__(self, buffers): + self.buffers = buffers + + class DummyRefereeReceiver: + def __init__(self, buffer): + self.buffer = buffer + + monkeypatch.setattr(runner_mod, "VisionReceiver", DummyVisionReceiver) + monkeypatch.setattr(runner_mod, "RefereeMessageReceiver", DummyRefereeReceiver) + + fake_runner = SimpleNamespace( + mode=Mode.GRSIM, + referee_system="none", + start_threads=lambda vision_receiver, referee_receiver=None: started.append( + (vision_receiver, referee_receiver) + ), + ) + + vision_buffers, ref_buffer = StrategyRunner._setup_vision_and_referee(fake_runner) + + assert len(vision_buffers) > 0 + assert ref_buffer.maxlen == 1 + assert len(started) == 1 + assert isinstance(started[0][0], DummyVisionReceiver) + assert started[0][1] is None + + +def test_setup_vision_and_referee_starts_vision_only_when_referee_custom(monkeypatch): + from utama_core.run import strategy_runner as runner_mod + + started = [] + + class DummyVisionReceiver: + def __init__(self, buffers): + self.buffers = buffers + + class DummyRefereeReceiver: + def __init__(self, buffer): + self.buffer = buffer + + monkeypatch.setattr(runner_mod, "VisionReceiver", DummyVisionReceiver) + monkeypatch.setattr(runner_mod, "RefereeMessageReceiver", DummyRefereeReceiver) + + fake_runner = SimpleNamespace( + mode=Mode.REAL, + referee_system="custom", + start_threads=lambda vision_receiver, referee_receiver=None: started.append( + (vision_receiver, referee_receiver) + ), + ) + + StrategyRunner._setup_vision_and_referee(fake_runner) + + assert len(started) == 1 + assert isinstance(started[0][0], DummyVisionReceiver) + assert started[0][1] is None + + +def test_setup_vision_and_referee_starts_both_receivers_when_referee_official(monkeypatch): + from utama_core.run import strategy_runner as runner_mod + + started = [] + + class DummyVisionReceiver: + def __init__(self, buffers): + self.buffers = buffers + + class DummyRefereeReceiver: + def __init__(self, buffer): + self.buffer = buffer + + monkeypatch.setattr(runner_mod, "VisionReceiver", DummyVisionReceiver) + monkeypatch.setattr(runner_mod, "RefereeMessageReceiver", DummyRefereeReceiver) + + fake_runner = SimpleNamespace( + mode=Mode.GRSIM, + referee_system="official", + start_threads=lambda vision_receiver, referee_receiver=None: started.append( + (vision_receiver, referee_receiver) + ), + ) + + StrategyRunner._setup_vision_and_referee(fake_runner) + + assert len(started) == 1 + assert isinstance(started[0][0], DummyVisionReceiver) + assert isinstance(started[0][1], DummyRefereeReceiver) + + def test_assert_exp_robots_valid(base_runner): base_runner._assert_exp_robots_and_ball(3, 3, True) # Should not raise From 626ef221ae9bdc1a3891e5daeff7b40fb2e868d6 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Tue, 31 Mar 2026 22:29:12 +0100 Subject: [PATCH 008/121] Scale referee actions with field geometry --- utama_core/config/referee_constants.py | 26 ++++ utama_core/entities/game/field.py | 13 ++ utama_core/strategy/referee/actions.py | 112 ++++++++++-------- utama_core/tests/referee/test_referee_unit.py | 96 ++++++++++++++- 4 files changed, 195 insertions(+), 52 deletions(-) create mode 100644 utama_core/config/referee_constants.py diff --git a/utama_core/config/referee_constants.py b/utama_core/config/referee_constants.py new file mode 100644 index 00000000..7a584099 --- /dev/null +++ b/utama_core/config/referee_constants.py @@ -0,0 +1,26 @@ +from utama_core.entities.game.field import Field + +BALL_KEEP_OUT_DISTANCE = 0.55 +BALL_PLACEMENT_DONE_DISTANCE = 0.15 +PENALTY_BEHIND_MARK_DISTANCE = 0.4 +PENALTY_MARK_HALF_FIELD_RATIO = 0.5 +CLEARANCE_FALLBACK_DIRECTION = (1.0, 0.0) + +PENALTY_LINE_Y_STEP_RATIO = 0.35 / Field.FULL_FIELD_HALF_WIDTH + +KICKOFF_SUPPORT_POSITION_RATIOS_RIGHT = ( + (-0.8 / Field.FULL_FIELD_HALF_LENGTH, 0.5 / Field.FULL_FIELD_HALF_WIDTH), + (-0.8 / Field.FULL_FIELD_HALF_LENGTH, -0.5 / Field.FULL_FIELD_HALF_WIDTH), + (-1.5 / Field.FULL_FIELD_HALF_LENGTH, 0.8 / Field.FULL_FIELD_HALF_WIDTH), + (-1.5 / Field.FULL_FIELD_HALF_LENGTH, -0.8 / Field.FULL_FIELD_HALF_WIDTH), + (-2.5 / Field.FULL_FIELD_HALF_LENGTH, 0.0), +) + +KICKOFF_DEFENCE_POSITION_RATIOS_RIGHT = ( + (-0.8 / Field.FULL_FIELD_HALF_LENGTH, 0.4 / Field.FULL_FIELD_HALF_WIDTH), + (-0.8 / Field.FULL_FIELD_HALF_LENGTH, -0.4 / Field.FULL_FIELD_HALF_WIDTH), + (-1.5 / Field.FULL_FIELD_HALF_LENGTH, 0.6 / Field.FULL_FIELD_HALF_WIDTH), + (-1.5 / Field.FULL_FIELD_HALF_LENGTH, -0.6 / Field.FULL_FIELD_HALF_WIDTH), + (-2.5 / Field.FULL_FIELD_HALF_LENGTH, 0.0), + (-1.5 / Field.FULL_FIELD_HALF_LENGTH, 0.0), +) diff --git a/utama_core/entities/game/field.py b/utama_core/entities/game/field.py index 5e9692db..14d79574 100644 --- a/utama_core/entities/game/field.py +++ b/utama_core/entities/game/field.py @@ -32,6 +32,7 @@ class Field: # Class constants refer to the standard SSL field (9m x 6m) + _CENTER_CIRCLE_RADIUS = 0.5 _HALF_GOAL_WIDTH = 0.5 _HALF_DEFENSE_AREA_LENGTH = 0.5 _HALF_DEFENSE_AREA_WIDTH = 1 @@ -180,6 +181,18 @@ def center(self) -> tuple[float, float]: def HALF_GOAL_WIDTH(cls) -> float: return cls._HALF_GOAL_WIDTH + @ClassProperty + def HALF_DEFENSE_AREA_LENGTH(cls) -> float: + return cls._HALF_DEFENSE_AREA_LENGTH + + @ClassProperty + def HALF_DEFENSE_AREA_WIDTH(cls) -> float: + return cls._HALF_DEFENSE_AREA_WIDTH + + @ClassProperty + def CENTER_CIRCLE_RADIUS(cls) -> float: + return cls._CENTER_CIRCLE_RADIUS + @ClassProperty def LEFT_GOAL_LINE(cls) -> np.ndarray: return cls._LEFT_GOAL_LINE diff --git a/utama_core/strategy/referee/actions.py b/utama_core/strategy/referee/actions.py index 920664db..b423c0c1 100644 --- a/utama_core/strategy/referee/actions.py +++ b/utama_core/strategy/referee/actions.py @@ -1,4 +1,4 @@ -"""Hardcoded action nodes for each referee game state. +"""Referee action nodes for each referee game state. Each node: - Reads game state from blackboard.game @@ -14,23 +14,22 @@ import py_trees +from utama_core.config.referee_constants import ( + BALL_KEEP_OUT_DISTANCE, + BALL_PLACEMENT_DONE_DISTANCE, + CLEARANCE_FALLBACK_DIRECTION, + KICKOFF_DEFENCE_POSITION_RATIOS_RIGHT, + KICKOFF_SUPPORT_POSITION_RATIOS_RIGHT, + PENALTY_BEHIND_MARK_DISTANCE, + PENALTY_LINE_Y_STEP_RATIO, + PENALTY_MARK_HALF_FIELD_RATIO, +) from utama_core.entities.data.vector import Vector2D +from utama_core.entities.game.field import Field from utama_core.entities.referee.referee_command import RefereeCommand from utama_core.skills.src.utils.move_utils import empty_command, move from utama_core.strategy.common.abstract_behaviour import AbstractBehaviour -# SSL field constants / heuristics (metres) -# Utama's standard field model is 9m x 6m. For penalty setup we place the -# penalty mark halfway between the centre line and the relevant goal line so -# it always lies on the correct half, including custom field bounds. -_PENALTY_MARK_HALF_FIELD_RATIO = 0.5 -_HALF_FIELD_X = 4.5 # half field length -_CENTRE_CIRCLE_R = 0.5 # centre circle radius -_BALL_KEEP_DIST = 0.55 # ≥0.5 m required; 5 cm buffer -_PENALTY_BEHIND_OFFSET = 0.4 # robots must be ≥0.4 m behind penalty mark -_OPP_DEF_AREA_KEEP_DIST = 0.25 # ≥0.2 m from opponent defence area; 5 cm buffer -_PLACEMENT_DONE_DIST = 0.15 # ball within this dist of target → placement complete - def _all_stop(blackboard) -> py_trees.common.Status: """Send empty_command to every friendly robot and return RUNNING.""" @@ -47,12 +46,44 @@ def _field_half_length(game) -> float: return (field.bottom_right[0] - field.top_left[0]) / 2.0 +def _field_half_width(game) -> float: + """Return the current field half-width, supporting Field and FieldBounds alike.""" + field = game.field + if hasattr(field, "half_width"): + return field.half_width + return (field.top_left[1] - field.bottom_right[1]) / 2.0 + + def _penalty_mark_x(goal_x: float) -> float: """Place the penalty mark midway between centre and goal line.""" - return goal_x * _PENALTY_MARK_HALF_FIELD_RATIO + return goal_x * PENALTY_MARK_HALF_FIELD_RATIO + + +def _scaled_position(game, x_ratio: float, y_ratio: float) -> Vector2D: + """Scale a normalized formation coordinate to the current field dimensions.""" + return Vector2D(x_ratio * _field_half_length(game), y_ratio * _field_half_width(game)) + +def _ensure_outside_center_circle(target: Vector2D) -> Vector2D: + """Project kickoff support points to the centre-circle boundary when needed.""" + dist = math.hypot(target.x, target.y) + keep_radius = Field.CENTER_CIRCLE_RADIUS + if dist == 0.0 or dist >= keep_radius: + return target + scale = keep_radius / dist + return Vector2D(target.x * scale, target.y * scale) -def _clear_from_ball(blackboard, keep_dist: float = _BALL_KEEP_DIST) -> py_trees.common.Status: + +def _formation_positions(game, ratios: tuple[tuple[float, float], ...], mirror_x: bool) -> list[Vector2D]: + """Build field-scaled formation positions, mirroring x when we defend the left goal.""" + positions = [] + for x_ratio, y_ratio in ratios: + scaled_x_ratio = -x_ratio if mirror_x else x_ratio + positions.append(_ensure_outside_center_circle(_scaled_position(game, scaled_x_ratio, y_ratio))) + return positions + + +def _clear_from_ball(blackboard, keep_dist: float = BALL_KEEP_OUT_DISTANCE) -> py_trees.common.Status: """Move encroaching robots out beyond the keep-out radius and stop the rest.""" game = blackboard.game ball = game.ball @@ -70,7 +101,7 @@ def _clear_from_ball(blackboard, keep_dist: float = _BALL_KEEP_DIST) -> py_trees continue if dist == 0.0: - ux, uy = 1.0, 0.0 + ux, uy = CLEARANCE_FALLBACK_DIRECTION else: ux, uy = dx / dist, dy / dist @@ -141,7 +172,7 @@ def update(self) -> py_trees.common.Status: if ball is None: return _all_stop(self.blackboard) - if ball.p.distance_to(target_pos) <= _PLACEMENT_DONE_DIST: + if ball.p.distance_to(target_pos) <= BALL_PLACEMENT_DONE_DISTANCE: return _all_stop(self.blackboard) # Pick the placer: robot closest to the ball @@ -183,17 +214,6 @@ def update(self) -> py_trees.common.Status: # PREPARE_KICKOFF — ours # --------------------------------------------------------------------------- -# Kickoff formation positions (own half, outside centre circle). -# Relative x is negative = own half when we are on the right; sign is flipped below. -_KICKOFF_SUPPORT_POSITIONS_RIGHT = [ - Vector2D(-0.8, 0.5), - Vector2D(-0.8, -0.5), - Vector2D(-1.5, 0.8), - Vector2D(-1.5, -0.8), - Vector2D(-2.5, 0.0), -] -_KICKOFF_SUPPORT_POSITIONS_LEFT = [Vector2D(-p.x, p.y) for p in _KICKOFF_SUPPORT_POSITIONS_RIGHT] - class PrepareKickoffOursStep(AbstractBehaviour): """Positions robots for our kickoff. @@ -210,8 +230,10 @@ def update(self) -> py_trees.common.Status: kicker_id = robot_ids[0] # Support positions depend on which side we defend - support_positions = ( - _KICKOFF_SUPPORT_POSITIONS_RIGHT if game.my_team_is_right else _KICKOFF_SUPPORT_POSITIONS_LEFT + support_positions = _formation_positions( + game, + KICKOFF_SUPPORT_POSITION_RATIOS_RIGHT, + mirror_x=not game.my_team_is_right, ) support_idx = 0 @@ -219,7 +241,7 @@ def update(self) -> py_trees.common.Status: if robot_id == kicker_id: # Approach the ball at centre, face the opponent goal target = Vector2D(0.0, 0.0) - goal_x = _HALF_FIELD_X if not game.my_team_is_right else -_HALF_FIELD_X + goal_x = _field_half_length(game) if not game.my_team_is_right else -_field_half_length(game) oren = math.atan2(0.0 - target.y, goal_x - target.x) self.blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, target, oren) else: @@ -234,16 +256,6 @@ def update(self) -> py_trees.common.Status: # PREPARE_KICKOFF — theirs # --------------------------------------------------------------------------- -_KICKOFF_DEFENCE_POSITIONS_RIGHT = [ - Vector2D(-0.8, 0.4), - Vector2D(-0.8, -0.4), - Vector2D(-1.5, 0.6), - Vector2D(-1.5, -0.6), - Vector2D(-2.5, 0.0), - Vector2D(-1.5, 0.0), -] -_KICKOFF_DEFENCE_POSITIONS_LEFT = [Vector2D(-p.x, p.y) for p in _KICKOFF_DEFENCE_POSITIONS_RIGHT] - class PrepareKickoffTheirsStep(AbstractBehaviour): """Moves all our robots to own half, outside the centre circle, for the opponent kickoff.""" @@ -252,7 +264,11 @@ def update(self) -> py_trees.common.Status: game = self.blackboard.game motion_controller = self.blackboard.motion_controller - positions = _KICKOFF_DEFENCE_POSITIONS_RIGHT if game.my_team_is_right else _KICKOFF_DEFENCE_POSITIONS_LEFT + positions = _formation_positions( + game, + KICKOFF_DEFENCE_POSITION_RATIOS_RIGHT, + mirror_x=not game.my_team_is_right, + ) for idx, robot_id in enumerate(sorted(game.friendly_robots.keys())): pos = positions[idx % len(positions)] @@ -270,7 +286,7 @@ class PreparePenaltyOursStep(AbstractBehaviour): """Positions robots for our penalty kick. Kicker (lowest non-keeper ID): moves to our penalty mark, faces goal. - All others: stop on a line 0.4 m behind the penalty mark (on own side). + All others: stop on a line behind the penalty mark on our side. Penalty mark is placed halfway between the centre line and the target goal line. """ @@ -289,7 +305,7 @@ def update(self) -> py_trees.common.Status: opp_goal_x = field_half_length if not game.my_team_is_right else -field_half_length sign = 1 if not game.my_team_is_right else -1 penalty_mark = Vector2D(_penalty_mark_x(opp_goal_x), 0.0) - behind_line_x = penalty_mark.x - sign * _PENALTY_BEHIND_OFFSET + behind_line_x = penalty_mark.x - sign * PENALTY_BEHIND_MARK_DISTANCE goal_oren = math.atan2(0.0, opp_goal_x - penalty_mark.x) @@ -298,7 +314,7 @@ def update(self) -> py_trees.common.Status: kicker_id = non_keeper_ids[0] if non_keeper_ids else robot_ids[0] behind_idx = 0 - behind_y_step = 0.35 + behind_y_step = PENALTY_LINE_Y_STEP_RATIO * _field_half_width(game) for robot_id in robot_ids: if robot_id == kicker_id: self.blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, penalty_mark, goal_oren) @@ -321,7 +337,7 @@ class PreparePenaltyTheirsStep(AbstractBehaviour): """Positions our robots for the opponent's penalty kick. Goalkeeper: moves to our goal line centre. - All others: move to a line 0.4 m behind the penalty mark on our half. + All others: move to a line behind the penalty mark on our half. """ def update(self) -> py_trees.common.Status: @@ -339,11 +355,11 @@ def update(self) -> py_trees.common.Status: # Opponent's penalty mark is in our half, between centre and our goal line. opp_penalty_mark_x = _penalty_mark_x(our_goal_x) - behind_line_x = opp_penalty_mark_x + sign * _PENALTY_BEHIND_OFFSET + behind_line_x = opp_penalty_mark_x + sign * PENALTY_BEHIND_MARK_DISTANCE robot_ids = sorted(game.friendly_robots.keys()) behind_idx = 0 - behind_y_step = 0.35 + behind_y_step = PENALTY_LINE_Y_STEP_RATIO * _field_half_width(game) for robot_id in robot_ids: if robot_id == keeper_id: diff --git a/utama_core/tests/referee/test_referee_unit.py b/utama_core/tests/referee/test_referee_unit.py index 50fd30fb..55e8f2d0 100644 --- a/utama_core/tests/referee/test_referee_unit.py +++ b/utama_core/tests/referee/test_referee_unit.py @@ -18,7 +18,7 @@ from utama_core.entities.data.referee import RefereeData from utama_core.entities.data.vector import Vector2D, Vector3D from utama_core.entities.game.ball import Ball -from utama_core.entities.game.field import Field +from utama_core.entities.game.field import Field, FieldBounds from utama_core.entities.game.game import Game from utama_core.entities.game.game_frame import GameFrame from utama_core.entities.game.game_history import GameHistory @@ -105,10 +105,15 @@ def _make_game( referee=None, my_team_is_yellow: bool = True, my_team_is_right: bool = True, + field_bounds: FieldBounds = Field.FULL_FIELD_BOUNDS, ) -> Game: frame = _make_game_frame(friendly_robots, referee, my_team_is_yellow, my_team_is_right) history = GameHistory(10) - return Game(past=history, current=frame, field=Field.FULL_FIELD_BOUNDS) + return Game( + past=history, + current=frame, + field=Field(my_team_is_right=my_team_is_right, field_bounds=field_bounds), + ) def _make_blackboard(game: Game, cmd_map=None): @@ -420,7 +425,11 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri ball=_ball(0.2, 0.0), referee=referee, ) - game = Game(past=GameHistory(10), current=frame, field=Field.FULL_FIELD_BOUNDS) + game = Game( + past=GameHistory(10), + current=frame, + field=Field(my_team_is_right=True, field_bounds=Field.FULL_FIELD_BOUNDS), + ) cmd_map = _make_cmd_map(game) node = referee_actions.BallPlacementOursStep(name="BallPlacementOurs") @@ -470,7 +479,11 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri ball=_ball(0.0, 0.0), referee=referee, ) - game = Game(past=GameHistory(10), current=frame, field=Field.FULL_FIELD_BOUNDS) + game = Game( + past=GameHistory(10), + current=frame, + field=Field(my_team_is_right=True, field_bounds=Field.FULL_FIELD_BOUNDS), + ) cmd_map = _make_cmd_map(game) node = referee_actions.BallPlacementOursStep(name="BallPlacementOurs") @@ -637,6 +650,81 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri assert all(target.x > 0.0 for target in support_targets) +class TestVariableFieldScaling: + def test_prepare_kickoff_ours_scales_support_positions_with_field_bounds(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = { + 0: _robot(0, 0.0, 0.0), + 1: _robot(1, 1.0, 0.0), + 2: _robot(2, 2.0, 0.0), + } + custom_bounds = FieldBounds(top_left=(-6.0, 4.0), bottom_right=(6.0, -4.0)) + referee = _make_referee_data(command=RefereeCommand.PREPARE_KICKOFF_YELLOW) + game = _make_game( + friendly_robots=robots, + referee=referee, + my_team_is_yellow=True, + my_team_is_right=True, + field_bounds=custom_bounds, + ) + cmd_map = _make_cmd_map(game) + node = referee_actions.PrepareKickoffOursStep(name="PrepareKickoffOurs") + node.blackboard = _make_blackboard(game, cmd_map) + + status = node.update() + first_support_target = next(target for robot_id, target in captured if robot_id == 1) + + assert status == py_trees.common.Status.RUNNING + assert first_support_target.x == pytest.approx(-6.0 * (0.8 / 4.5)) + assert first_support_target.y == pytest.approx(4.0 * (0.5 / 3.0)) + assert first_support_target.distance_to(Vector2D(0.0, 0.0)) >= Field.CENTER_CIRCLE_RADIUS + + def test_prepare_penalty_ours_scales_penalty_mark_with_field_bounds(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = { + 0: _robot(0, 0.0, 0.0), + 1: _robot(1, 1.0, 0.0), + } + custom_bounds = FieldBounds(top_left=(-6.0, 4.0), bottom_right=(6.0, -4.0)) + referee = _make_referee_data(command=RefereeCommand.PREPARE_PENALTY_YELLOW) + referee.yellow_team.goalkeeper = 1 + game = _make_game( + friendly_robots=robots, + referee=referee, + my_team_is_yellow=True, + my_team_is_right=True, + field_bounds=custom_bounds, + ) + cmd_map = _make_cmd_map(game) + node = referee_actions.PreparePenaltyOursStep(name="PreparePenaltyOurs") + node.blackboard = _make_blackboard(game, cmd_map) + + status = node.update() + kicker_target = next(target for robot_id, target in captured if robot_id == 0) + + assert status == py_trees.common.Status.RUNNING + assert kicker_target.x == pytest.approx(-3.0) + assert kicker_target.y == pytest.approx(0.0) + + # --------------------------------------------------------------------------- # build_referee_override_tree — structure checks # --------------------------------------------------------------------------- From d4adaeb39851a0d2b6da25eb4fd2c445545471d1 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Tue, 31 Mar 2026 22:47:10 +0100 Subject: [PATCH 009/121] Fix referee restart progression and clearance --- docs/custom_referee.md | 37 +++-- docs/custom_referee_gui.md | 29 ++-- docs/referee_integration.md | 9 +- utama_core/config/referee_constants.py | 27 ++-- utama_core/custom_referee/gui.py | 6 +- utama_core/custom_referee/profiles/human.yaml | 3 +- .../custom_referee/profiles/profile_loader.py | 11 +- .../custom_referee/profiles/simulation.yaml | 3 +- utama_core/custom_referee/state_machine.py | 86 ++++++++-- utama_core/strategy/referee/actions.py | 136 +++++++++++----- .../custom_referee/test_custom_referee.py | 100 +++++++++++- utama_core/tests/referee/test_referee_unit.py | 153 +++++++++++++++++- 12 files changed, 498 insertions(+), 102 deletions(-) diff --git a/docs/custom_referee.md b/docs/custom_referee.md index e71b6c09..43a9221c 100644 --- a/docs/custom_referee.md +++ b/docs/custom_referee.md @@ -64,7 +64,7 @@ The one-frame lag (the `GameFrame` used is from the previous step) is acceptable ## State Machine -The `GameStateMachine` owns all mutable state: command, score, stage, and next command. It does **not** auto-advance from `STOP` to `NORMAL_START` — that transition is always explicit (operator input or a fixed-delay script). This keeps control predictable. +The `GameStateMachine` owns all mutable state: command, score, stage, and next command. In the `simulation` profile it can auto-advance from `STOP` into the queued restart command once robots have cleared the ball, then continue through restart-specific readiness checks. In the `human` profile those auto-advances are disabled so an operator stays in control. ```mermaid stateDiagram-v2 @@ -75,11 +75,14 @@ stateDiagram-v2 HALT --> STOP HALT --> NORMAL_START - STOP --> NORMAL_START\n[operator / script] STOP --> PREPARE_KICKOFF_YELLOW STOP --> PREPARE_KICKOFF_BLUE STOP --> DIRECT_FREE_YELLOW STOP --> DIRECT_FREE_BLUE + STOP --> PREPARE_PENALTY_YELLOW + STOP --> PREPARE_PENALTY_BLUE + STOP --> BALL_PLACEMENT_YELLOW + STOP --> BALL_PLACEMENT_BLUE NORMAL_START --> STOP : GoalRule fires\n[score++, next_cmd set] NORMAL_START --> STOP : OutOfBoundsRule fires\n[designated_position set] @@ -92,15 +95,18 @@ stateDiagram-v2 PREPARE_KICKOFF_YELLOW --> NORMAL_START PREPARE_KICKOFF_BLUE --> NORMAL_START + PREPARE_PENALTY_YELLOW --> NORMAL_START + PREPARE_PENALTY_BLUE --> NORMAL_START DIRECT_FREE_YELLOW --> NORMAL_START DIRECT_FREE_BLUE --> NORMAL_START + BALL_PLACEMENT_YELLOW --> NORMAL_START + BALL_PLACEMENT_BLUE --> NORMAL_START NORMAL_START --> FORCE_START FORCE_START --> NORMAL_START ``` -> **Key design principle:** `CustomReferee` only ever *moves into* `STOP` automatically. All transitions *out of* `STOP` require an explicit `set_command()` call. This matches how a human operator interacts with a real game controller. -> More thoughts on this, in RL loop / automated testing, we do want the referee system to resume the game after our system is ready, e.g. putting ball at designated location and ready to start. +> **Key design principle:** profile choice controls restart ownership. `simulation` auto-progresses through queued restarts when readiness checks are satisfied; `human` keeps those transitions manual for operator control. ### Transition cooldown @@ -195,14 +201,14 @@ referee = CustomReferee.from_profile_name("simulation") referee = CustomReferee.from_profile_name("/path/to/my_profile.yaml") ``` -| Setting | `simulation` | `exhibition` | `human` | -|---|---|---|---| -| Goal detection | ✅ 1.0 s cooldown | ✅ 1.0 s cooldown | ✅ 1.0 s cooldown | -| Out of bounds | ✅ | ✅ | ❌ | -| Defence area | ✅ max 1 defender | ✅ max 1 defender | ❌ | -| Keep-out radius | ✅ 0.5 m | ✅ 0.2 m | ❌ | -| Force start after goal | ❌ | ❌ | ❌ | -| Half duration | 300 s | 300 s | 300 s | +| Setting | `simulation` | `human` | +|---|---|---| +| Goal detection | ✅ 1.0 s cooldown | ✅ 1.0 s cooldown | +| Out of bounds | ✅ | ❌ | +| Defence area | ✅ max 1 defender | ❌ | +| Keep-out radius | ✅ 0.5 m | ❌ | +| Restart progression | Auto when readiness criteria are met | Manual operator control | +| Half duration | 300 s | 300 s | **`simulation`** — Full SSL-compatible rule set with auto-advance enabled for most restarts. Use for simulator testing, AI-vs-AI development, and RL training. @@ -238,6 +244,13 @@ game: half_duration_seconds: 300.0 kickoff_team: "yellow" force_start_after_goal: false + auto_advance: + stop_to_next_command: true + prepare_kickoff_to_normal: true + prepare_penalty_to_normal: true + direct_free_to_normal: true + ball_placement_to_next: true + normal_start_to_force: true ``` --- diff --git a/docs/custom_referee_gui.md b/docs/custom_referee_gui.md index b3b28534..29a444ec 100644 --- a/docs/custom_referee_gui.md +++ b/docs/custom_referee_gui.md @@ -92,7 +92,7 @@ Standard half start: Halt → Stop → Kickoff Yellow → Normal Start ``` -After goal (human profile — auto-restart): +After goal (human profile — operator-controlled): ``` (Goal auto-detected) → Stop → (auto Force Start after stop_duration_seconds) ``` @@ -200,8 +200,9 @@ Every tuneable parameter and its effect: | `game.kickoff_team` | `"yellow"` or `"blue"` | Which team kicks off at the start | | `game.force_start_after_goal` | bool | Legacy human fast-path; superseded by `auto_advance` flags | | `game.stop_duration_seconds` | float | STOP hold time before auto FORCE START (legacy human path) | -| `game.auto_advance.stop_to_prepare_kickoff` | bool | Auto STOP → PREPARE_KICKOFF when all robots clear | +| `game.auto_advance.stop_to_next_command` | bool | Auto STOP → queued restart when all robots clear | | `game.auto_advance.prepare_kickoff_to_normal` | bool | Auto PREPARE_KICKOFF → NORMAL_START when kicker in position (2 s delay) | +| `game.auto_advance.prepare_penalty_to_normal` | bool | Auto PREPARE_PENALTY → NORMAL_START when kicker reaches the mark (2 s delay) | | `game.auto_advance.direct_free_to_normal` | bool | Auto DIRECT_FREE → NORMAL_START when kicker ready (2 s delay) | | `game.auto_advance.ball_placement_to_next` | bool | Auto BALL_PLACEMENT → next command when ball at target (2 s delay) | | `game.auto_advance.normal_start_to_force` | bool | Auto NORMAL_START → FORCE_START after kickoff timeout if ball hasn't moved | @@ -213,17 +214,18 @@ Every tuneable parameter and its effect: The state machine can automatically advance through referee states when certain conditions are met. Each transition is independently configurable via the `auto_advance` block in the profile. -### The five auto-advances +### The six auto-advances | # | Transition | Trigger | Delay | |---|---|---|---| -| 1 | `STOP` → `PREPARE_KICKOFF_*` | All robots ≥ 0.5 m from ball | None | +| 1 | `STOP` → queued restart | All robots ≥ 0.5 m from ball | None | | 2 | `PREPARE_KICKOFF_*` → `NORMAL_START` | Timer elapsed + kicker inside centre circle | **2 s** | -| 3 | `DIRECT_FREE_*` → `NORMAL_START` | Kicker ≤ 0.3 m from ball + defenders ≥ 0.5 m away | **2 s** | -| 4 | `BALL_PLACEMENT_*` → next command | Ball ≤ 0.15 m from placement target | **2 s** | -| 5 | `NORMAL_START` → `FORCE_START` | Kickoff timeout elapsed + ball hasn't moved | None (uses `kickoff_timeout_seconds`) | +| 3 | `PREPARE_PENALTY_*` → `NORMAL_START` | Timer elapsed + kicker reaches the penalty mark | **2 s** | +| 4 | `DIRECT_FREE_*` → `NORMAL_START` | Kicker ≤ 0.3 m from ball + defenders ≥ 0.5 m away | **2 s** | +| 5 | `BALL_PLACEMENT_*` → next command | Ball ≤ 0.15 m from placement target | **2 s** | +| 6 | `NORMAL_START` → `FORCE_START` | Kickoff timeout elapsed + ball hasn't moved | None (uses `kickoff_timeout_seconds`) | -Advances 2, 3, and 4 require the readiness condition to be **sustained for 2 seconds** before +Advances 2, 3, 4, and 5 require the readiness condition to be **sustained for 2 seconds** before firing. If the condition drops out during that window (e.g. kicker steps back), the countdown resets. This gives robots time to settle before play begins. @@ -234,8 +236,9 @@ resets. This gives robots time to settle before play begins. ```yaml game: auto_advance: - stop_to_prepare_kickoff: true + stop_to_next_command: true prepare_kickoff_to_normal: true + prepare_penalty_to_normal: true direct_free_to_normal: true ball_placement_to_next: true normal_start_to_force: true @@ -248,8 +251,9 @@ nobody is on the field when play begins. ```yaml game: auto_advance: - stop_to_prepare_kickoff: false + stop_to_next_command: false prepare_kickoff_to_normal: false + prepare_penalty_to_normal: false direct_free_to_normal: false ball_placement_to_next: false normal_start_to_force: false @@ -309,8 +313,9 @@ game: force_start_after_goal: false stop_duration_seconds: 3.0 auto_advance: - stop_to_prepare_kickoff: true # set false for physical/operator-driven environments + stop_to_next_command: true # set false for physical/operator-driven environments prepare_kickoff_to_normal: true + prepare_penalty_to_normal: true direct_free_to_normal: true ball_placement_to_next: true normal_start_to_force: true @@ -351,7 +356,7 @@ game: force_start_after_goal: true stop_duration_seconds: 2.0 auto_advance: - stop_to_prepare_kickoff: true + stop_to_next_command: true prepare_kickoff_to_normal: true direct_free_to_normal: true ball_placement_to_next: true diff --git a/docs/referee_integration.md b/docs/referee_integration.md index 2570fa3f..6f9fc789 100644 --- a/docs/referee_integration.md +++ b/docs/referee_integration.md @@ -439,7 +439,7 @@ Standard half start: Halt → Stop → Kickoff Yellow → Normal Start ``` -After goal (human profile — auto-restart): +After goal (human profile — operator-controlled): ``` (Goal auto-detected) → Stop → (auto Force Start after stop_duration_seconds) ``` @@ -482,8 +482,8 @@ The **Event Log** panel shows the 20 most recent events, newest first. ## 9. Open Questions / Future Work -- **Active distance-keeping during STOP/free kicks**: Currently we stop in place. - A better implementation moves robots away from the ball if they are within 0.5 m. +- **Active distance-keeping during STOP/free kicks**: + Implemented for built-in referee nodes: STOP, opponent free kicks, and both ball-placement variants now actively clear illegal positions. Future work is mainly smarter pre-positioning, not basic compliance. - **Ball placement precision**: `BallPlacementOursStep` uses `move()` which will stop the ball near (not exactly at) `designated_position`. The tolerance is ±0.15 m per the rules. @@ -497,5 +497,4 @@ The **Event Log** panel shows the 20 most recent events, newest first. - **`can_place_ball` fallback**: If `TeamInfo.can_place_ball` is False (too many placement failures), `BallPlacementOursStep` must fall back to STOP behaviour. -- **Active ball-distance enforcement during DIRECT_FREE (theirs)**: Currently stops in place. - Should actively move away if within 0.5 m of ball. +- **Penalty / ball-placement readiness tuning**: `simulation` now auto-progresses these restarts, but the exact readiness heuristics may still need iteration as we gather more simulator coverage. diff --git a/utama_core/config/referee_constants.py b/utama_core/config/referee_constants.py index 7a584099..9d7309d2 100644 --- a/utama_core/config/referee_constants.py +++ b/utama_core/config/referee_constants.py @@ -2,25 +2,26 @@ BALL_KEEP_OUT_DISTANCE = 0.55 BALL_PLACEMENT_DONE_DISTANCE = 0.15 +OPPONENT_DEFENSE_AREA_KEEP_DISTANCE = 0.25 PENALTY_BEHIND_MARK_DISTANCE = 0.4 PENALTY_MARK_HALF_FIELD_RATIO = 0.5 CLEARANCE_FALLBACK_DIRECTION = (1.0, 0.0) PENALTY_LINE_Y_STEP_RATIO = 0.35 / Field.FULL_FIELD_HALF_WIDTH -KICKOFF_SUPPORT_POSITION_RATIOS_RIGHT = ( - (-0.8 / Field.FULL_FIELD_HALF_LENGTH, 0.5 / Field.FULL_FIELD_HALF_WIDTH), - (-0.8 / Field.FULL_FIELD_HALF_LENGTH, -0.5 / Field.FULL_FIELD_HALF_WIDTH), - (-1.5 / Field.FULL_FIELD_HALF_LENGTH, 0.8 / Field.FULL_FIELD_HALF_WIDTH), - (-1.5 / Field.FULL_FIELD_HALF_LENGTH, -0.8 / Field.FULL_FIELD_HALF_WIDTH), - (-2.5 / Field.FULL_FIELD_HALF_LENGTH, 0.0), +KICKOFF_SUPPORT_POSITION_RATIOS_OWN_HALF = ( + (0.8 / Field.FULL_FIELD_HALF_LENGTH, 0.5 / Field.FULL_FIELD_HALF_WIDTH), + (0.8 / Field.FULL_FIELD_HALF_LENGTH, -0.5 / Field.FULL_FIELD_HALF_WIDTH), + (1.5 / Field.FULL_FIELD_HALF_LENGTH, 0.8 / Field.FULL_FIELD_HALF_WIDTH), + (1.5 / Field.FULL_FIELD_HALF_LENGTH, -0.8 / Field.FULL_FIELD_HALF_WIDTH), + (2.5 / Field.FULL_FIELD_HALF_LENGTH, 0.0), ) -KICKOFF_DEFENCE_POSITION_RATIOS_RIGHT = ( - (-0.8 / Field.FULL_FIELD_HALF_LENGTH, 0.4 / Field.FULL_FIELD_HALF_WIDTH), - (-0.8 / Field.FULL_FIELD_HALF_LENGTH, -0.4 / Field.FULL_FIELD_HALF_WIDTH), - (-1.5 / Field.FULL_FIELD_HALF_LENGTH, 0.6 / Field.FULL_FIELD_HALF_WIDTH), - (-1.5 / Field.FULL_FIELD_HALF_LENGTH, -0.6 / Field.FULL_FIELD_HALF_WIDTH), - (-2.5 / Field.FULL_FIELD_HALF_LENGTH, 0.0), - (-1.5 / Field.FULL_FIELD_HALF_LENGTH, 0.0), +KICKOFF_DEFENCE_POSITION_RATIOS_OWN_HALF = ( + (0.8 / Field.FULL_FIELD_HALF_LENGTH, 0.4 / Field.FULL_FIELD_HALF_WIDTH), + (0.8 / Field.FULL_FIELD_HALF_LENGTH, -0.4 / Field.FULL_FIELD_HALF_WIDTH), + (1.5 / Field.FULL_FIELD_HALF_LENGTH, 0.6 / Field.FULL_FIELD_HALF_WIDTH), + (1.5 / Field.FULL_FIELD_HALF_LENGTH, -0.6 / Field.FULL_FIELD_HALF_WIDTH), + (2.5 / Field.FULL_FIELD_HALF_LENGTH, 0.0), + (1.5 / Field.FULL_FIELD_HALF_LENGTH, 0.0), ) diff --git a/utama_core/custom_referee/gui.py b/utama_core/custom_referee/gui.py index 16571750..e379a176 100644 --- a/utama_core/custom_referee/gui.py +++ b/utama_core/custom_referee/gui.py @@ -352,8 +352,9 @@ def _build_config_json(profile: "RefereeProfile") -> str: "force_start_after_goal": gm.force_start_after_goal, "stop_duration_seconds": gm.stop_duration_seconds, "auto_advance": { - "stop_to_prepare_kickoff": gm.auto_advance.stop_to_prepare_kickoff, + "stop_to_next_command": gm.auto_advance.stop_to_next_command, "prepare_kickoff_to_normal": gm.auto_advance.prepare_kickoff_to_normal, + "prepare_penalty_to_normal": gm.auto_advance.prepare_penalty_to_normal, "direct_free_to_normal": gm.auto_advance.direct_free_to_normal, "ball_placement_to_next": gm.auto_advance.ball_placement_to_next, "normal_start_to_force": gm.auto_advance.normal_start_to_force, @@ -976,8 +977,9 @@ def _build_config_json(profile: "RefereeProfile") -> str: const aa = gm.auto_advance || {}; const aaRows = - cfgRow('stop → prepare kickoff', aa.stop_to_prepare_kickoff) + + cfgRow('stop → next command', aa.stop_to_next_command) + cfgRow('prepare kickoff → normal', aa.prepare_kickoff_to_normal) + + cfgRow('prepare penalty → normal', aa.prepare_penalty_to_normal) + cfgRow('direct free → normal', aa.direct_free_to_normal) + cfgRow('ball placement → next', aa.ball_placement_to_next) + cfgRow('normal start → force', aa.normal_start_to_force); diff --git a/utama_core/custom_referee/profiles/human.yaml b/utama_core/custom_referee/profiles/human.yaml index 24ed3c4d..a531fd26 100644 --- a/utama_core/custom_referee/profiles/human.yaml +++ b/utama_core/custom_referee/profiles/human.yaml @@ -29,8 +29,9 @@ game: prepare_duration_seconds: 2.0 kickoff_timeout_seconds: 10.0 auto_advance: - stop_to_prepare_kickoff: false # Operator advances restarts manually + stop_to_next_command: false # Operator advances restarts manually prepare_kickoff_to_normal: false + prepare_penalty_to_normal: false direct_free_to_normal: false ball_placement_to_next: false normal_start_to_force: false diff --git a/utama_core/custom_referee/profiles/profile_loader.py b/utama_core/custom_referee/profiles/profile_loader.py index 97ff9888..a9eec66b 100644 --- a/utama_core/custom_referee/profiles/profile_loader.py +++ b/utama_core/custom_referee/profiles/profile_loader.py @@ -67,11 +67,14 @@ class AutoAdvanceConfig: explicitly advance the state to prevent robots from moving unexpectedly. """ - # STOP → PREPARE_KICKOFF_* when all robots have cleared the ball. - stop_to_prepare_kickoff: bool = True + # STOP → queued restart command when all robots have cleared the ball. + stop_to_next_command: bool = True # PREPARE_KICKOFF_* → NORMAL_START after prepare_duration_seconds when # the kicker is inside the centre circle. prepare_kickoff_to_normal: bool = True + # PREPARE_PENALTY_* → NORMAL_START after prepare_duration_seconds when + # the kicker reaches the penalty mark. + prepare_penalty_to_normal: bool = True # DIRECT_FREE_* → NORMAL_START when kicker is in position and defenders # have cleared. direct_free_to_normal: bool = True @@ -198,9 +201,11 @@ def _parse_profile(data: dict) -> RefereeProfile: game_d = data.get("game", {}) aa = game_d.get("auto_advance", {}) + stop_to_next_command = aa.get("stop_to_next_command", aa.get("stop_to_prepare_kickoff", True)) auto_advance = AutoAdvanceConfig( - stop_to_prepare_kickoff=aa.get("stop_to_prepare_kickoff", True), + stop_to_next_command=stop_to_next_command, prepare_kickoff_to_normal=aa.get("prepare_kickoff_to_normal", True), + prepare_penalty_to_normal=aa.get("prepare_penalty_to_normal", True), direct_free_to_normal=aa.get("direct_free_to_normal", True), ball_placement_to_next=aa.get("ball_placement_to_next", True), normal_start_to_force=aa.get("normal_start_to_force", True), diff --git a/utama_core/custom_referee/profiles/simulation.yaml b/utama_core/custom_referee/profiles/simulation.yaml index c1c4b119..66809f8e 100644 --- a/utama_core/custom_referee/profiles/simulation.yaml +++ b/utama_core/custom_referee/profiles/simulation.yaml @@ -28,8 +28,9 @@ game: prepare_duration_seconds: 3.0 # seconds in PREPARE_KICKOFF before NORMAL_START is auto-issued kickoff_timeout_seconds: 10.0 # seconds after NORMAL_START before FORCE_START if ball hasn't moved auto_advance: - stop_to_prepare_kickoff: true # STOP → PREPARE_KICKOFF_* when all robots clear + stop_to_next_command: true # STOP → queued restart when all robots clear prepare_kickoff_to_normal: true # PREPARE_KICKOFF_* → NORMAL_START when kicker in circle + prepare_penalty_to_normal: true # PREPARE_PENALTY_* → NORMAL_START when kicker reaches the mark direct_free_to_normal: true # DIRECT_FREE_* → NORMAL_START when kicker ready ball_placement_to_next: true # BALL_PLACEMENT_* → next_command when ball at target normal_start_to_force: true # NORMAL_START → FORCE_START on kickoff timeout diff --git a/utama_core/custom_referee/state_machine.py b/utama_core/custom_referee/state_machine.py index 13140e02..bac80a6d 100644 --- a/utama_core/custom_referee/state_machine.py +++ b/utama_core/custom_referee/state_machine.py @@ -19,7 +19,7 @@ logger = logging.getLogger(__name__) _TRANSITION_COOLDOWN = 0.3 # seconds — prevents command oscillation -_BALL_CLEAR_DIST = 0.5 # metres — all robots must be this far from ball before PREPARE_KICKOFF +_BALL_CLEAR_DIST = 0.5 # metres — all robots must be this far from ball before queued restart _KICKER_READY_DIST = 0.3 # metres — kicker must be within this distance to trigger free kick start _PLACEMENT_DONE_DIST = 0.15 # metres — ball within this dist of target → placement complete _AUTO_ADVANCE_DELAY = 2.0 # seconds — readiness must be sustained this long before play starts @@ -109,7 +109,7 @@ def __init__( # Timestamps for sustained-readiness countdown before play-starting advances. # Set to math.inf when condition is not yet met; fire when elapsed >= _AUTO_ADVANCE_DELAY. - self._advance2_ready_since: float = math.inf # PREPARE_KICKOFF_* → NORMAL_START + self._advance2_ready_since: float = math.inf # PREPARE_* → NORMAL_START self._advance3_ready_since: float = math.inf # DIRECT_FREE_* → NORMAL_START self._advance4_ready_since: float = math.inf # BALL_PLACEMENT_* → next_command @@ -138,6 +138,12 @@ def __init__( RefereeCommand.DIRECT_FREE_BLUE, } ) + _PREPARE_PENALTY_COMMANDS = frozenset( + { + RefereeCommand.PREPARE_PENALTY_YELLOW, + RefereeCommand.PREPARE_PENALTY_BLUE, + } + ) _BALL_PLACEMENT_COMMANDS = frozenset( { RefereeCommand.BALL_PLACEMENT_YELLOW, @@ -156,13 +162,13 @@ def step( self._apply_violation(violation, current_time) # ---------------------------------------------------------------- - # Auto-advance 1: STOP → PREPARE_KICKOFF_* + # Auto-advance 1: STOP → next queued restart # Fires when all robots are ≥ _BALL_CLEAR_DIST from the ball. # ---------------------------------------------------------------- if ( - self._auto_advance.stop_to_prepare_kickoff + self._auto_advance.stop_to_next_command and self.command == RefereeCommand.STOP - and self.next_command in self._PREPARE_KICKOFF_COMMANDS + and self.next_command in self._NEEDS_STOP_FIRST and game_frame is not None and self._all_robots_clear(game_frame) ): @@ -170,15 +176,22 @@ def step( self.command = self.next_command self.command_counter += 1 self.command_timestamp = current_time - self.next_command = RefereeCommand.NORMAL_START - self._prepare_entered_time = current_time + if self.command in self._BALL_PLACEMENT_COMMANDS: + self.next_command = RefereeCommand.NORMAL_START + self._advance4_ready_since = math.inf + elif self.command in self._DIRECT_FREE_COMMANDS: + self.next_command = RefereeCommand.NORMAL_START + self._advance3_ready_since = math.inf + elif self.command in self._PREPARE_KICKOFF_COMMANDS or self.command in self._PREPARE_PENALTY_COMMANDS: + self.next_command = RefereeCommand.NORMAL_START + self._prepare_entered_time = current_time + self._advance2_ready_since = math.inf self._last_transition_time = current_time # ---------------------------------------------------------------- - # Auto-advance 2: PREPARE_KICKOFF_* → NORMAL_START + # Auto-advance 2a: PREPARE_KICKOFF_* → NORMAL_START # Fires after prepare_duration_seconds AND one attacker is inside - # the centre circle (i.e. kicker is in position), sustained for - # _AUTO_ADVANCE_DELAY seconds. + # the centre circle, sustained for _AUTO_ADVANCE_DELAY seconds. # ---------------------------------------------------------------- elif self._auto_advance.prepare_kickoff_to_normal and self.command in self._PREPARE_KICKOFF_COMMANDS: ready = ( @@ -208,6 +221,39 @@ def step( else: self._advance2_ready_since = math.inf + # ---------------------------------------------------------------- + # Auto-advance 2b: PREPARE_PENALTY_* → NORMAL_START + # Fires after prepare_duration_seconds when the kicker reaches the + # penalty mark, sustained for _AUTO_ADVANCE_DELAY seconds. + # ---------------------------------------------------------------- + elif self._auto_advance.prepare_penalty_to_normal and self.command in self._PREPARE_PENALTY_COMMANDS: + ready = ( + (current_time - self._prepare_entered_time) >= self._prepare_duration_seconds + and game_frame is not None + and self._penalty_kicker_ready(self.command, game_frame) + ) + if ready: + if self._advance2_ready_since == math.inf: + self._advance2_ready_since = current_time + logger.debug("Advance 2 countdown started (%s)", self.command.name) + elif (current_time - self._advance2_ready_since) >= _AUTO_ADVANCE_DELAY: + logger.info( + "Kicker at penalty mark — auto-advancing %s → NORMAL_START", + self.command.name, + ) + self.command = RefereeCommand.NORMAL_START + self.command_counter += 1 + self.command_timestamp = current_time + self.next_command = None + self._normal_start_time = current_time + self._ball_pos_at_normal_start = ( + (game_frame.ball.p.x, game_frame.ball.p.y) if game_frame.ball is not None else None + ) + self._advance2_ready_since = math.inf + self._last_transition_time = current_time + else: + self._advance2_ready_since = math.inf + # ---------------------------------------------------------------- # Auto-advance 3: DIRECT_FREE_* → NORMAL_START # Fires when the kicker is within _KICKER_READY_DIST of the ball @@ -320,6 +366,26 @@ def _kicker_in_centre_circle(self, command: RefereeCommand, game_frame: "GameFra ) return any(math.hypot(robot.p.x, robot.p.y) <= r for robot in attackers.values()) + def _penalty_kicker_ready(self, command: RefereeCommand, game_frame: "GameFrame") -> bool: + """Return True when an attacking robot is within the ready radius of the penalty mark.""" + kicking_is_yellow = command == RefereeCommand.PREPARE_PENALTY_YELLOW + attackers = ( + game_frame.friendly_robots if kicking_is_yellow == game_frame.my_team_is_yellow else game_frame.enemy_robots + ) + if not attackers: + return False + + half_length = self._geometry.half_length if self._geometry is not None else 4.5 + yellow_is_right = game_frame.my_team_is_right == game_frame.my_team_is_yellow + if kicking_is_yellow: + goal_sign = -1.0 if yellow_is_right else 1.0 + else: + goal_sign = 1.0 if yellow_is_right else -1.0 + penalty_mark_x = goal_sign * half_length * 0.5 + + closest = min(math.hypot(robot.p.x - penalty_mark_x, robot.p.y) for robot in attackers.values()) + return closest <= _KICKER_READY_DIST + def _free_kick_ready(self, command: RefereeCommand, game_frame: "GameFrame") -> bool: """Return True when a free kick is ready to start: - The kicker (closest attacker to ball) is within _KICKER_READY_DIST of the ball. diff --git a/utama_core/strategy/referee/actions.py b/utama_core/strategy/referee/actions.py index b423c0c1..05a651b2 100644 --- a/utama_core/strategy/referee/actions.py +++ b/utama_core/strategy/referee/actions.py @@ -18,8 +18,9 @@ BALL_KEEP_OUT_DISTANCE, BALL_PLACEMENT_DONE_DISTANCE, CLEARANCE_FALLBACK_DIRECTION, - KICKOFF_DEFENCE_POSITION_RATIOS_RIGHT, - KICKOFF_SUPPORT_POSITION_RATIOS_RIGHT, + KICKOFF_DEFENCE_POSITION_RATIOS_OWN_HALF, + KICKOFF_SUPPORT_POSITION_RATIOS_OWN_HALF, + OPPONENT_DEFENSE_AREA_KEEP_DISTANCE, PENALTY_BEHIND_MARK_DISTANCE, PENALTY_LINE_Y_STEP_RATIO, PENALTY_MARK_HALF_FIELD_RATIO, @@ -74,38 +75,87 @@ def _ensure_outside_center_circle(target: Vector2D) -> Vector2D: return Vector2D(target.x * scale, target.y * scale) -def _formation_positions(game, ratios: tuple[tuple[float, float], ...], mirror_x: bool) -> list[Vector2D]: - """Build field-scaled formation positions, mirroring x when we defend the left goal.""" +def _formation_positions(game, ratios: tuple[tuple[float, float], ...]) -> list[Vector2D]: + """Build own-half field-scaled formation positions for the current defended side.""" positions = [] + own_half_sign = 1.0 if game.my_team_is_right else -1.0 for x_ratio, y_ratio in ratios: - scaled_x_ratio = -x_ratio if mirror_x else x_ratio - positions.append(_ensure_outside_center_circle(_scaled_position(game, scaled_x_ratio, y_ratio))) + positions.append(_ensure_outside_center_circle(_scaled_position(game, own_half_sign * x_ratio, y_ratio))) return positions -def _clear_from_ball(blackboard, keep_dist: float = BALL_KEEP_OUT_DISTANCE) -> py_trees.common.Status: - """Move encroaching robots out beyond the keep-out radius and stop the rest.""" +def _project_outside_circle(point: Vector2D, center: Vector2D, keep_dist: float) -> Vector2D: + """Project a point to the circle boundary if it lies inside the keep-out radius.""" + offset = point - center + dist = offset.mag() + if dist >= keep_dist: + return point + if dist == 0.0: + ux, uy = CLEARANCE_FALLBACK_DIRECTION + return Vector2D(center.x + ux * keep_dist, center.y + uy * keep_dist) + scale = keep_dist / dist + return Vector2D(center.x + offset.x * scale, center.y + offset.y * scale) + + +def _project_outside_opp_defense_area(game, point: Vector2D, keep_dist: float) -> Vector2D: + """Project a point out of the opponent defense area plus the required keep distance.""" + field_half_length = _field_half_length(game) + opp_goal_sign = -1.0 if game.my_team_is_right else 1.0 + defense_width = Field.HALF_DEFENSE_AREA_WIDTH + keep_dist + defense_inner_x = opp_goal_sign * (field_half_length - 2.0 * Field.HALF_DEFENSE_AREA_LENGTH) + safe_x = defense_inner_x - opp_goal_sign * keep_dist + + if abs(point.y) > defense_width: + return point + + if opp_goal_sign < 0.0: + if point.x >= safe_x: + return point + else: + if point.x <= safe_x: + return point + + return Vector2D(safe_x, point.y) + + +def _clear_to_legal_positions( + blackboard, + *, + ball_keep_dist: float | None = None, + designated_keep_dist: float | None = None, + clear_opp_defense_area: bool = False, + exempt_robot_ids: set[int] | None = None, +) -> py_trees.common.Status: + """Move encroaching robots to the nearest legal location and stop the rest.""" game = blackboard.game - ball = game.ball motion_controller = blackboard.motion_controller - if ball is None: - return _all_stop(blackboard) + exempt_robot_ids = exempt_robot_ids or set() + + ball_center = None + if ball_keep_dist is not None and game.ball is not None: + ball_center = Vector2D(game.ball.p.x, game.ball.p.y) + + designated_center = None + ref = game.referee + if designated_keep_dist is not None and ref is not None and ref.designated_position is not None: + designated_center = Vector2D(ref.designated_position[0], ref.designated_position[1]) - bx, by = ball.p.x, ball.p.y for robot_id, robot in game.friendly_robots.items(): - dx = robot.p.x - bx - dy = robot.p.y - by - dist = math.hypot(dx, dy) - if dist >= keep_dist: - blackboard.cmd_map[robot_id] = empty_command(False) + if robot_id in exempt_robot_ids: continue - if dist == 0.0: - ux, uy = CLEARANCE_FALLBACK_DIRECTION - else: - ux, uy = dx / dist, dy / dist + target = Vector2D(robot.p.x, robot.p.y) + if ball_center is not None: + target = _project_outside_circle(target, ball_center, ball_keep_dist) + if designated_center is not None: + target = _project_outside_circle(target, designated_center, designated_keep_dist) + if clear_opp_defense_area: + target = _project_outside_opp_defense_area(game, target, OPPONENT_DEFENSE_AREA_KEEP_DISTANCE) + + if target == robot.p: + blackboard.cmd_map[robot_id] = empty_command(False) + continue - target = Vector2D(bx + ux * keep_dist, by + uy * keep_dist) oren = robot.p.angle_to(target) blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, target, oren) @@ -137,7 +187,11 @@ class StopStep(AbstractBehaviour): """Moves encroaching robots out of the keep-out radius and stops the rest.""" def update(self) -> py_trees.common.Status: - return _clear_from_ball(self.blackboard) + return _clear_to_legal_positions( + self.blackboard, + ball_keep_dist=BALL_KEEP_OUT_DISTANCE, + clear_opp_defense_area=True, + ) # --------------------------------------------------------------------------- @@ -150,7 +204,7 @@ class BallPlacementOursStep(AbstractBehaviour): If the chosen placer does not yet have the ball, it first drives to the ball with the dribbler on. Once it has possession, it carries the ball to the - designated position. All other robots stop in place. + designated position. All other robots clear away from the ball. """ def update(self) -> py_trees.common.Status: @@ -192,10 +246,11 @@ def update(self) -> py_trees.common.Status: self.blackboard.cmd_map[robot_id] = move( game, motion_controller, robot_id, target_for_move, oren, dribbling=True ) - else: - self.blackboard.cmd_map[robot_id] = empty_command(False) - - return py_trees.common.Status.RUNNING + return _clear_to_legal_positions( + self.blackboard, + ball_keep_dist=BALL_KEEP_OUT_DISTANCE, + exempt_robot_ids={placer_id}, + ) # --------------------------------------------------------------------------- @@ -204,10 +259,14 @@ def update(self) -> py_trees.common.Status: class BallPlacementTheirsStep(AbstractBehaviour): - """Actively clear our robots away from the ball during their placement.""" + """Actively clear our robots away from the ball and target during their placement.""" def update(self) -> py_trees.common.Status: - return _clear_from_ball(self.blackboard) + return _clear_to_legal_positions( + self.blackboard, + ball_keep_dist=BALL_KEEP_OUT_DISTANCE, + designated_keep_dist=BALL_KEEP_OUT_DISTANCE, + ) # --------------------------------------------------------------------------- @@ -230,11 +289,7 @@ def update(self) -> py_trees.common.Status: kicker_id = robot_ids[0] # Support positions depend on which side we defend - support_positions = _formation_positions( - game, - KICKOFF_SUPPORT_POSITION_RATIOS_RIGHT, - mirror_x=not game.my_team_is_right, - ) + support_positions = _formation_positions(game, KICKOFF_SUPPORT_POSITION_RATIOS_OWN_HALF) support_idx = 0 for robot_id in robot_ids: @@ -264,11 +319,7 @@ def update(self) -> py_trees.common.Status: game = self.blackboard.game motion_controller = self.blackboard.motion_controller - positions = _formation_positions( - game, - KICKOFF_DEFENCE_POSITION_RATIOS_RIGHT, - mirror_x=not game.my_team_is_right, - ) + positions = _formation_positions(game, KICKOFF_DEFENCE_POSITION_RATIOS_OWN_HALF) for idx, robot_id in enumerate(sorted(game.friendly_robots.keys())): pos = positions[idx % len(positions)] @@ -420,7 +471,10 @@ class DirectFreeTheirsStep(AbstractBehaviour): """Actively clear our robots out of the ball keep-out radius.""" def update(self) -> py_trees.common.Status: - return _clear_from_ball(self.blackboard) + return _clear_to_legal_positions( + self.blackboard, + ball_keep_dist=BALL_KEEP_OUT_DISTANCE, + ) # --------------------------------------------------------------------------- diff --git a/utama_core/tests/custom_referee/test_custom_referee.py b/utama_core/tests/custom_referee/test_custom_referee.py index 46918980..5b6333d1 100644 --- a/utama_core/tests/custom_referee/test_custom_referee.py +++ b/utama_core/tests/custom_referee/test_custom_referee.py @@ -357,6 +357,38 @@ def test_manual_set_command(self): sm.set_command(RefereeCommand.NORMAL_START, timestamp=5.0) assert sm.command == RefereeCommand.NORMAL_START + def test_manual_ball_placement_auto_advances_from_stop_and_then_to_normal_start(self): + sm = _state_machine() + sm.set_command(RefereeCommand.BALL_PLACEMENT_YELLOW, timestamp=1.0) + sm.ball_placement_target = (0.0, 0.0) + + clear_frame = _frame(ball=_ball(2.0, 0.0), ts=10.0) + data = sm.step(current_time=10.0, violation=None, game_frame=clear_frame) + assert data.referee_command == RefereeCommand.BALL_PLACEMENT_YELLOW + assert data.next_command == RefereeCommand.NORMAL_START + + placed_frame = _frame(ball=_ball(0.0, 0.0), ts=20.0) + sm.step(current_time=20.0, violation=None, game_frame=placed_frame) + data = sm.step(current_time=23.0, violation=None, game_frame=placed_frame) + assert data.referee_command == RefereeCommand.NORMAL_START + assert data.next_command is None + + def test_manual_penalty_auto_advances_from_stop_and_then_to_normal_start(self): + sm = _state_machine() + sm.set_command(RefereeCommand.PREPARE_PENALTY_YELLOW, timestamp=1.0) + + clear_frame = _frame(ball=_ball(0.0, 0.0), ts=10.0) + data = sm.step(current_time=10.0, violation=None, game_frame=clear_frame) + assert data.referee_command == RefereeCommand.PREPARE_PENALTY_YELLOW + assert data.next_command == RefereeCommand.NORMAL_START + + ready_attackers = {0: _robot(0, 2.25, 0.0, is_friendly=True)} + ready_frame = _frame(ball=_ball(0.0, 0.0), friendly_robots=ready_attackers, ts=14.0) + sm.step(current_time=14.0, violation=None, game_frame=ready_frame) + data = sm.step(current_time=17.0, violation=None, game_frame=ready_frame) + assert data.referee_command == RefereeCommand.NORMAL_START + assert data.next_command is None + # --------------------------------------------------------------------------- # CustomReferee integration @@ -419,6 +451,55 @@ def test_simulation_stays_in_prepare_kickoff_after_goal_without_ready_kicker(sel data = referee.step(_frame(ball=_ball(0.0, 0.0), ts=70.0), current_time=70.0) assert data.referee_command == RefereeCommand.PREPARE_KICKOFF_YELLOW + def test_simulation_oob_auto_advances_to_direct_free_and_then_normal_start(self): + referee = CustomReferee.from_profile_name("simulation") + referee.set_command(RefereeCommand.NORMAL_START, timestamp=0.0) + + touch_frame = _frame( + ball=_ball(4.4, 2.9), + friendly_robots={0: _robot(0, 4.4, 2.9, is_friendly=True, has_ball=True)}, + my_team_is_yellow=True, + ts=9.9, + ) + referee.step(touch_frame, current_time=9.9) + + out_frame = _frame(ball=_ball(0.0, 3.5), my_team_is_yellow=True, ts=10.0) + data = referee.step(out_frame, current_time=10.0) + assert data.referee_command == RefereeCommand.DIRECT_FREE_BLUE + assert data.next_command == RefereeCommand.NORMAL_START + + ready_frame = _frame( + ball=_ball(0.0, 0.0), + friendly_robots={0: _robot(0, 1.0, 0.0, is_friendly=True)}, + enemy_robots={0: _robot(0, 0.1, 0.0, is_friendly=False)}, + my_team_is_yellow=True, + ts=20.0, + ) + referee.step(ready_frame, current_time=20.0) + data = referee.step(ready_frame, current_time=23.0) + assert data.referee_command == RefereeCommand.NORMAL_START + + def test_human_manual_direct_free_stays_in_stop_until_operator_advances(self): + referee = CustomReferee.from_profile_name("human") + referee.set_command(RefereeCommand.NORMAL_START, timestamp=0.0) + referee.set_command(RefereeCommand.DIRECT_FREE_BLUE, timestamp=1.0) + + data = referee.step(_frame(ball=_ball(0.0, 0.0), my_team_is_yellow=True, ts=10.0), current_time=10.0) + assert data.referee_command == RefereeCommand.STOP + assert data.next_command == RefereeCommand.DIRECT_FREE_BLUE + + still_stop = referee.step(_frame(ball=_ball(0.0, 0.0), ts=40.0), current_time=40.0) + assert still_stop.referee_command == RefereeCommand.STOP + + def test_human_manual_penalty_stays_in_stop_until_operator_advances(self): + referee = CustomReferee.from_profile_name("human") + referee.set_command(RefereeCommand.NORMAL_START, timestamp=0.0) + referee.set_command(RefereeCommand.PREPARE_PENALTY_YELLOW, timestamp=1.0) + + data = referee.step(_frame(ball=_ball(0.0, 0.0), ts=10.0), current_time=10.0) + assert data.referee_command == RefereeCommand.STOP + assert data.next_command == RefereeCommand.PREPARE_PENALTY_YELLOW + # --------------------------------------------------------------------------- # Profile loader @@ -437,7 +518,24 @@ def test_human_loads(self): assert profile.profile_name == "human" assert profile.rules.out_of_bounds.enabled is False assert profile.game.force_start_after_goal is False - assert profile.game.auto_advance.stop_to_prepare_kickoff is False + assert profile.game.auto_advance.stop_to_next_command is False + assert profile.game.auto_advance.prepare_penalty_to_normal is False + + def test_legacy_stop_to_prepare_kickoff_key_is_still_loaded(self, tmp_path): + profile_path = tmp_path / "legacy_profile.yaml" + profile_path.write_text( + """ +profile_name: "legacy" +geometry: {} +rules: {} +game: + auto_advance: + stop_to_prepare_kickoff: false +""".strip() + ) + + profile = load_profile(str(profile_path)) + assert profile.game.auto_advance.stop_to_next_command is False def test_unknown_profile_raises(self): with pytest.raises(FileNotFoundError): diff --git a/utama_core/tests/referee/test_referee_unit.py b/utama_core/tests/referee/test_referee_unit.py index 55e8f2d0..8e3f81d0 100644 --- a/utama_core/tests/referee/test_referee_unit.py +++ b/utama_core/tests/referee/test_referee_unit.py @@ -496,6 +496,39 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri assert captured[0][1] == Vector2D(1.5, -0.5) assert captured[0][2] is True + def test_non_placing_teammate_clears_from_ball(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords, dribbling)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = { + 0: _robot(0, 0.0, 0.0), + 1: _robot(1, 0.1, 0.0), + } + referee = _make_referee_data(command=RefereeCommand.BALL_PLACEMENT_YELLOW) + referee.designated_position = (1.5, 0.0) + game = _make_game(friendly_robots=robots, referee=referee, my_team_is_yellow=True, my_team_is_right=True) + + cmd_map = _make_cmd_map(game) + node = referee_actions.BallPlacementOursStep(name="BallPlacementOurs") + node.blackboard = _make_blackboard(game, cmd_map) + + status = node.update() + + assert status == py_trees.common.Status.RUNNING + assert len(captured) == 2 + placer_move = next(item for item in captured if item[0] == 0) + support_move = next(item for item in captured if item[0] == 1) + assert placer_move[1] == game.ball.p + assert support_move[1] == Vector2D(0.55, 0.0) + assert support_move[2] is False + # --------------------------------------------------------------------------- # Keep-out retreat and penalty positioning @@ -531,6 +564,47 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri assert captured[0][1] == Vector2D(0.55, 0.0) assert cmd_map[1] is not None + def test_stop_clears_robot_from_opponent_defense_area(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = { + 0: _robot(0, -4.3, 0.0), + 1: _robot(1, 1.0, 0.0), + } + referee = _make_referee_data(command=RefereeCommand.STOP) + frame = GameFrame( + ts=0.0, + my_team_is_yellow=True, + my_team_is_right=True, + friendly_robots=robots, + enemy_robots={}, + ball=_ball(2.0, 0.0), + referee=referee, + ) + game = Game( + past=GameHistory(10), + current=frame, + field=Field(my_team_is_right=True, field_bounds=Field.FULL_FIELD_BOUNDS), + ) + cmd_map = _make_cmd_map(game) + node = referee_actions.StopStep(name="Stop") + node.blackboard = _make_blackboard(game, cmd_map) + + status = node.update() + + assert status == py_trees.common.Status.RUNNING + assert len(captured) == 1 + assert captured[0][0] == 0 + assert captured[0][1] == Vector2D(-3.25, 0.0) + def test_ball_placement_theirs_clears_encroaching_robot(self, monkeypatch): from utama_core.strategy.referee import actions as referee_actions @@ -559,6 +633,48 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri assert captured[0][0] == 0 assert captured[0][1] == Vector2D(0.55, 0.0) + def test_ball_placement_theirs_clears_robot_from_designated_position(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = { + 0: _robot(0, 1.0, 1.0), + 1: _robot(1, -1.0, 0.0), + } + referee = _make_referee_data(command=RefereeCommand.BALL_PLACEMENT_BLUE) + referee.designated_position = (1.0, 1.0) + frame = GameFrame( + ts=0.0, + my_team_is_yellow=True, + my_team_is_right=True, + friendly_robots=robots, + enemy_robots={}, + ball=_ball(0.0, 0.0), + referee=referee, + ) + game = Game( + past=GameHistory(10), + current=frame, + field=Field(my_team_is_right=True, field_bounds=Field.FULL_FIELD_BOUNDS), + ) + cmd_map = _make_cmd_map(game) + node = referee_actions.BallPlacementTheirsStep(name="BallPlacementTheirs") + node.blackboard = _make_blackboard(game, cmd_map) + + status = node.update() + + assert status == py_trees.common.Status.RUNNING + assert len(captured) == 1 + assert captured[0][0] == 0 + assert captured[0][1] == Vector2D(1.55, 1.0) + def test_direct_free_theirs_clears_encroaching_robot(self, monkeypatch): from utama_core.strategy.referee import actions as referee_actions @@ -684,10 +800,45 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri first_support_target = next(target for robot_id, target in captured if robot_id == 1) assert status == py_trees.common.Status.RUNNING - assert first_support_target.x == pytest.approx(-6.0 * (0.8 / 4.5)) + assert first_support_target.x == pytest.approx(6.0 * (0.8 / 4.5)) assert first_support_target.y == pytest.approx(4.0 * (0.5 / 3.0)) assert first_support_target.distance_to(Vector2D(0.0, 0.0)) >= Field.CENTER_CIRCLE_RADIUS + def test_prepare_kickoff_ours_uses_own_half_when_defending_left(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = { + 0: _robot(0, 0.0, 0.0), + 1: _robot(1, 1.0, 0.0), + } + custom_bounds = FieldBounds(top_left=(-6.0, 4.0), bottom_right=(6.0, -4.0)) + referee = _make_referee_data(command=RefereeCommand.PREPARE_KICKOFF_YELLOW) + game = _make_game( + friendly_robots=robots, + referee=referee, + my_team_is_yellow=True, + my_team_is_right=False, + field_bounds=custom_bounds, + ) + cmd_map = _make_cmd_map(game) + node = referee_actions.PrepareKickoffOursStep(name="PrepareKickoffOurs") + node.blackboard = _make_blackboard(game, cmd_map) + + status = node.update() + first_support_target = next(target for robot_id, target in captured if robot_id == 1) + + assert status == py_trees.common.Status.RUNNING + assert first_support_target.x == pytest.approx(-6.0 * (0.8 / 4.5)) + assert first_support_target.distance_to(Vector2D(0.0, 0.0)) >= Field.CENTER_CIRCLE_RADIUS + def test_prepare_penalty_ours_scales_penalty_mark_with_field_bounds(self, monkeypatch): from utama_core.strategy.referee import actions as referee_actions From a0b120d36914cd4027e3cf98d946d8761156f875 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Tue, 31 Mar 2026 22:57:21 +0100 Subject: [PATCH 010/121] Fix custom referee demo wiring and status messages --- demo_referee_gui_rsim.py | 4 ++- docs/custom_referee.md | 3 +- utama_core/custom_referee/state_machine.py | 13 +++++++ .../custom_referee/test_custom_referee.py | 36 +++++++++++++++++++ .../tests/referee/demo_referee_gui_rsim.py | 4 ++- 5 files changed, 57 insertions(+), 3 deletions(-) diff --git a/demo_referee_gui_rsim.py b/demo_referee_gui_rsim.py index b3c6b04b..51d3f41a 100644 --- a/demo_referee_gui_rsim.py +++ b/demo_referee_gui_rsim.py @@ -7,7 +7,8 @@ What it does: - Creates a CustomReferee (human profile) with enable_gui=True so the browser panel starts automatically. - - Passes the referee to StrategyRunner via custom_referee=. StrategyRunner + - Passes the referee to StrategyRunner via custom_referee= with + referee_system="custom". StrategyRunner calls referee.step() on every tick and handles ball teleports on STOP automatically — no patching required. - WanderingStrategy is used as the base strategy so robots visibly move and @@ -64,6 +65,7 @@ def main() -> None: control_scheme="dwa", exp_friendly=N_ROBOTS, exp_enemy=N_ROBOTS, + referee_system="custom", custom_referee=referee, # StrategyRunner drives referee.step() each tick show_live_status=True, opp_strategy=WanderingStrategy(), diff --git a/docs/custom_referee.md b/docs/custom_referee.md index 43a9221c..5ca3d50b 100644 --- a/docs/custom_referee.md +++ b/docs/custom_referee.md @@ -277,6 +277,7 @@ runner = StrategyRunner( mode="rsim", exp_friendly=3, exp_enemy=3, + referee_system="custom", custom_referee=referee, ) runner.run() @@ -376,7 +377,7 @@ pixi run python demo_referee_gui_rsim.py ### What it does - Creates a `CustomReferee` with `enable_gui=True`, which starts an HTTP server on a background daemon thread. -- Passes the referee to `StrategyRunner` via `custom_referee=`. `StrategyRunner` calls `referee.step()` on every tick and handles ball teleports on `STOP` automatically. +- Passes the referee to `StrategyRunner` via `custom_referee=` with `referee_system="custom"`. `StrategyRunner` calls `referee.step()` on every tick and handles ball teleports on `STOP` automatically. - Uses `WanderingStrategy` so robots visibly move; the `RefereeOverride` behaviour tree interrupts them when you issue commands from the GUI. ### Operator workflow diff --git a/utama_core/custom_referee/state_machine.py b/utama_core/custom_referee/state_machine.py index bac80a6d..f2adda74 100644 --- a/utama_core/custom_referee/state_machine.py +++ b/utama_core/custom_referee/state_machine.py @@ -88,6 +88,7 @@ def __init__( self.next_command: Optional[RefereeCommand] = None self.ball_placement_target: Optional[tuple[float, float]] = None + self.status_message: Optional[str] = None # Kickoff team initialised from profile. self._kickoff_team_is_yellow = kickoff_team.lower() == "yellow" @@ -212,6 +213,7 @@ def step( self.command_counter += 1 self.command_timestamp = current_time self.next_command = None + self.status_message = None self._normal_start_time = current_time self._ball_pos_at_normal_start = ( (game_frame.ball.p.x, game_frame.ball.p.y) if game_frame.ball is not None else None @@ -245,6 +247,7 @@ def step( self.command_counter += 1 self.command_timestamp = current_time self.next_command = None + self.status_message = None self._normal_start_time = current_time self._ball_pos_at_normal_start = ( (game_frame.ball.p.x, game_frame.ball.p.y) if game_frame.ball is not None else None @@ -272,6 +275,7 @@ def step( self.command_counter += 1 self.command_timestamp = current_time self.next_command = None + self.status_message = None self._normal_start_time = current_time self._ball_pos_at_normal_start = ( (game_frame.ball.p.x, game_frame.ball.p.y) if game_frame.ball is not None else None @@ -303,6 +307,7 @@ def step( self.command_timestamp = current_time self.next_command = None self._advance4_ready_since = math.inf + self.status_message = None self._last_transition_time = current_time else: self._advance4_ready_since = math.inf @@ -325,6 +330,7 @@ def step( self.command_counter += 1 self.command_timestamp = current_time self.next_command = None + self.status_message = None self._ball_pos_at_normal_start = None self._last_transition_time = current_time @@ -341,6 +347,7 @@ def step( self.command_counter += 1 self.command_timestamp = current_time self.next_command = None + self.status_message = None self._last_transition_time = current_time logger.info("Auto-advanced STOP → FORCE_START after goal (force-start profile mode)") @@ -463,6 +470,7 @@ def set_command(self, command: RefereeCommand, timestamp: float) -> None: self.command_counter += 1 self.command_timestamp = timestamp self.next_command = command + self.status_message = None self._stop_entered_time = timestamp return @@ -483,12 +491,14 @@ def set_command(self, command: RefereeCommand, timestamp: float) -> None: self.command_counter += 1 self.command_timestamp = timestamp self.next_command = RefereeCommand.NORMAL_START + self.status_message = None self._prepare_entered_time = timestamp return self.command = command self.command_counter += 1 self.command_timestamp = timestamp + self.status_message = None self._advance2_ready_since = math.inf self._advance3_ready_since = math.inf self._advance4_ready_since = math.inf @@ -553,6 +563,7 @@ def _handle_goal(self, violation: RuleViolation, current_time: float) -> None: self.command_timestamp = current_time self.next_command = violation.next_command self.ball_placement_target = (0.0, 0.0) + self.status_message = violation.status_message self._stop_entered_time = current_time def _handle_foul(self, violation: RuleViolation, current_time: float) -> None: @@ -561,6 +572,7 @@ def _handle_foul(self, violation: RuleViolation, current_time: float) -> None: self.command_timestamp = current_time self.next_command = violation.next_command self.ball_placement_target = violation.designated_position + self.status_message = violation.status_message logger.info( "Foul detected: %s → %s (next: %s)", violation.rule_name, @@ -584,4 +596,5 @@ def _generate_referee_data(self, current_time: float) -> RefereeData: blue_team_on_positive_half=None, next_command=self.next_command, current_action_time_remaining=None, + status_message=self.status_message, ) diff --git a/utama_core/tests/custom_referee/test_custom_referee.py b/utama_core/tests/custom_referee/test_custom_referee.py index 5b6333d1..c7191c08 100644 --- a/utama_core/tests/custom_referee/test_custom_referee.py +++ b/utama_core/tests/custom_referee/test_custom_referee.py @@ -352,6 +352,35 @@ def test_goal_sets_designated_position_to_centre(self): data = sm.step(current_time=10.0, violation=violation) assert data.designated_position == (0.0, 0.0) + def test_goal_status_message_is_propagated_into_referee_data(self): + from utama_core.custom_referee.rules.base_rule import RuleViolation + + sm = _state_machine() + violation = RuleViolation( + rule_name="goal", + suggested_command=RefereeCommand.STOP, + next_command=RefereeCommand.PREPARE_KICKOFF_BLUE, + status_message="Goal by Yellow", + ) + data = sm.step(current_time=10.0, violation=violation) + assert data.status_message == "Goal by Yellow" + + def test_manual_command_clears_status_message(self): + from utama_core.custom_referee.rules.base_rule import RuleViolation + + sm = _state_machine() + violation = RuleViolation( + rule_name="goal", + suggested_command=RefereeCommand.STOP, + next_command=RefereeCommand.PREPARE_KICKOFF_BLUE, + status_message="Goal by Yellow", + ) + sm.step(current_time=10.0, violation=violation) + + sm.set_command(RefereeCommand.NORMAL_START, timestamp=11.0) + data = sm.step(current_time=11.0, violation=None) + assert data.status_message is None + def test_manual_set_command(self): sm = _state_machine() sm.set_command(RefereeCommand.NORMAL_START, timestamp=5.0) @@ -424,6 +453,13 @@ def test_human_profile_no_oob(self): data = referee.step(frame, current_time=10.0) assert data.referee_command == RefereeCommand.NORMAL_START + def test_simulation_oob_exposes_status_message(self): + referee = CustomReferee.from_profile_name("simulation") + referee.set_command(RefereeCommand.NORMAL_START, timestamp=0.0) + frame = _frame(ball=_ball(0.0, 4.0), ts=10.0) + data = referee.step(frame, current_time=10.0) + assert data.status_message == "Ball out of bounds" + def test_human_stays_in_stop_after_goal_until_operator_advances(self): """Human mode keeps the game in STOP after a goal for operator control.""" referee = CustomReferee.from_profile_name("human") diff --git a/utama_core/tests/referee/demo_referee_gui_rsim.py b/utama_core/tests/referee/demo_referee_gui_rsim.py index 96a68d57..fc7f962c 100644 --- a/utama_core/tests/referee/demo_referee_gui_rsim.py +++ b/utama_core/tests/referee/demo_referee_gui_rsim.py @@ -7,7 +7,8 @@ What it does: - Creates a CustomReferee (human profile) with enable_gui=True so the browser panel starts automatically. - - Passes the referee to StrategyRunner via custom_referee=. StrategyRunner + - Passes the referee to StrategyRunner via custom_referee= with + referee_system="custom". StrategyRunner calls referee.step() on every tick and handles ball teleports on STOP automatically — no patching required. - WanderingStrategy is used as the base strategy so robots visibly move and @@ -63,6 +64,7 @@ def main() -> None: mode="rsim", exp_friendly=N_ROBOTS, exp_enemy=N_ROBOTS, + referee_system="custom", custom_referee=referee, # StrategyRunner drives referee.step() each tick show_live_status=True, ) From 2250a9240804f88242c99c231e63be25cf7ac1a4 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Tue, 31 Mar 2026 23:00:47 +0100 Subject: [PATCH 011/121] Show referee source details in live status --- utama_core/custom_referee/custom_referee.py | 5 +++++ utama_core/run/strategy_runner.py | 11 ++++++++++- 2 files changed, 15 insertions(+), 1 deletion(-) diff --git a/utama_core/custom_referee/custom_referee.py b/utama_core/custom_referee/custom_referee.py index 8675b30a..ccec53ad 100644 --- a/utama_core/custom_referee/custom_referee.py +++ b/utama_core/custom_referee/custom_referee.py @@ -75,6 +75,7 @@ def __init__( enable_gui: bool = False, gui_port: int = 8080, ) -> None: + self._profile_name = profile.profile_name self._geometry: RefereeGeometry = profile.geometry self._rules: List[BaseRule] = _build_active_rules(profile.rules) self._state = GameStateMachine( @@ -161,3 +162,7 @@ def set_command(self, command: RefereeCommand, timestamp: float) -> None: @property def geometry(self) -> RefereeGeometry: return self._geometry + + @property + def profile_name(self) -> str: + return self._profile_name diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index 54ab906b..ba93d88c 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -903,11 +903,15 @@ def _run_step(self): stage_secs = ref.stage_time_left stage_min = int(stage_secs // 60) stage_sec = int(stage_secs % 60) + last_ref = self.referee_refiner._referee_records[-1] if self.referee_refiner._referee_records else None display = Text() display.append(f"FPS: {fps:.1f}", style="bold cyan") display.append(" | ") display.append(ref.last_command.name, style="bold yellow") + if last_ref and last_ref.next_command: + display.append(" -> ") + display.append(last_ref.next_command.name, style="yellow") display.append(" | ") display.append(ref.stage.name.replace("_", " ").title()) display.append(" | Blue ") @@ -916,8 +920,13 @@ def _run_step(self): display.append(str(ref.yellow_team.score), style="bold yellow") display.append(" Yellow") display.append(f" | {stage_min}:{stage_sec:02d} left") + display.append(" | Ref: ") + display.append(self.referee_system, style="bold magenta") + if self.referee_system == "custom" and self.custom_referee is not None: + display.append(" (") + display.append(self.custom_referee.profile_name, style="magenta") + display.append(")") - last_ref = self.referee_refiner._referee_records[-1] if self.referee_refiner._referee_records else None if last_ref and last_ref.status_message: display.append(f" | {last_ref.status_message}", style="dim") From 5d757c1dc05e6ff3e1fa04335a8f857847942797 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Fri, 3 Apr 2026 11:43:43 +0100 Subject: [PATCH 012/121] Add referee behaviour integration tests and unit test coverage - Add rsim integration tests for ball placement, direct free kick (ours and theirs), and kickoff positioning in test_referee_rsim.py - Add 15 unit tests covering PrepareKickoffTheirsStep, DirectFreeOursStep, and DirectFreeTheirsStep action nodes in test_referee_unit.py - Switch demo script control_scheme from dwa to pid Co-Authored-By: Claude Sonnet 4.6 --- demo_referee_gui_rsim.py | 2 +- utama_core/tests/referee/test_referee_unit.py | 385 +++++++++++++++++ .../strategy_runner/test_referee_rsim.py | 386 ++++++++++++++++++ 3 files changed, 772 insertions(+), 1 deletion(-) create mode 100644 utama_core/tests/strategy_runner/test_referee_rsim.py diff --git a/demo_referee_gui_rsim.py b/demo_referee_gui_rsim.py index 51d3f41a..a71d4407 100644 --- a/demo_referee_gui_rsim.py +++ b/demo_referee_gui_rsim.py @@ -62,7 +62,7 @@ def main() -> None: my_team_is_yellow=MY_TEAM_IS_YELLOW, my_team_is_right=MY_TEAM_IS_RIGHT, mode="rsim", - control_scheme="dwa", + control_scheme="pid", exp_friendly=N_ROBOTS, exp_enemy=N_ROBOTS, referee_system="custom", diff --git a/utama_core/tests/referee/test_referee_unit.py b/utama_core/tests/referee/test_referee_unit.py index 8e3f81d0..bb436360 100644 --- a/utama_core/tests/referee/test_referee_unit.py +++ b/utama_core/tests/referee/test_referee_unit.py @@ -1045,3 +1045,388 @@ def test_direct_free_blue_calls_ours_when_blue(self): self._tick_dispatcher(dispatcher, game) assert called == ["ours"] + + +# --------------------------------------------------------------------------- +# PrepareKickoffTheirsStep +# --------------------------------------------------------------------------- + + +class TestPrepareKickoffTheirsStep: + def test_returns_running(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + monkeypatch.setattr(referee_actions, "move", lambda *a, **kw: ("move",)) + + robots = {0: _robot(0, 0.0, 0.0)} + referee = _make_referee_data(command=RefereeCommand.PREPARE_KICKOFF_BLUE) + game = _make_game(friendly_robots=robots, referee=referee, my_team_is_yellow=True, my_team_is_right=True) + cmd_map = _make_cmd_map(game) + node = referee_actions.PrepareKickoffTheirsStep(name="PrepareKickoffTheirs") + node.blackboard = _make_blackboard(game, cmd_map) + + assert node.update() == py_trees.common.Status.RUNNING + + def test_all_robots_placed_on_own_half_right(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = {i: _robot(i, float(i), 0.0) for i in range(3)} + referee = _make_referee_data(command=RefereeCommand.PREPARE_KICKOFF_BLUE) + # my_team_is_right=True → own half is positive-x side + game = _make_game(friendly_robots=robots, referee=referee, my_team_is_yellow=True, my_team_is_right=True) + cmd_map = _make_cmd_map(game) + node = referee_actions.PrepareKickoffTheirsStep(name="PrepareKickoffTheirs") + node.blackboard = _make_blackboard(game, cmd_map) + + node.update() + + assert len(captured) == 3 + for _, target in captured: + assert target.x > 0.0, f"Expected positive-x (own half right), got {target}" + + def test_all_robots_placed_on_own_half_left(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = {i: _robot(i, float(i), 0.0) for i in range(3)} + referee = _make_referee_data(command=RefereeCommand.PREPARE_KICKOFF_YELLOW) + # my_team_is_right=False → own half is negative-x side + game = _make_game(friendly_robots=robots, referee=referee, my_team_is_yellow=True, my_team_is_right=False) + cmd_map = _make_cmd_map(game) + node = referee_actions.PrepareKickoffTheirsStep(name="PrepareKickoffTheirs") + node.blackboard = _make_blackboard(game, cmd_map) + + node.update() + + assert len(captured) == 3 + for _, target in captured: + assert target.x < 0.0, f"Expected negative-x (own half left), got {target}" + + def test_positions_outside_centre_circle(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = {i: _robot(i, 0.0, 0.0) for i in range(6)} + referee = _make_referee_data(command=RefereeCommand.PREPARE_KICKOFF_BLUE) + game = _make_game(friendly_robots=robots, referee=referee, my_team_is_yellow=True, my_team_is_right=True) + cmd_map = _make_cmd_map(game) + node = referee_actions.PrepareKickoffTheirsStep(name="PrepareKickoffTheirs") + node.blackboard = _make_blackboard(game, cmd_map) + + node.update() + + for _, target in captured: + dist = target.distance_to(Vector2D(0.0, 0.0)) + assert dist >= Field.CENTER_CIRCLE_RADIUS, f"Target {target} inside centre circle" + + def test_scales_with_custom_field_bounds(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = {0: _robot(0, 0.0, 0.0), 1: _robot(1, 0.0, 0.0)} + custom_bounds = FieldBounds(top_left=(-6.0, 4.0), bottom_right=(6.0, -4.0)) + referee = _make_referee_data(command=RefereeCommand.PREPARE_KICKOFF_BLUE) + game = _make_game( + friendly_robots=robots, + referee=referee, + my_team_is_yellow=True, + my_team_is_right=True, + field_bounds=custom_bounds, + ) + cmd_map = _make_cmd_map(game) + node = referee_actions.PrepareKickoffTheirsStep(name="PrepareKickoffTheirs") + node.blackboard = _make_blackboard(game, cmd_map) + + node.update() + + # Positions must be on own half and outside centre circle + for _, target in captured: + assert target.x > 0.0 + assert target.distance_to(Vector2D(0.0, 0.0)) >= Field.CENTER_CIRCLE_RADIUS + + +# --------------------------------------------------------------------------- +# DirectFreeOursStep +# --------------------------------------------------------------------------- + + +class TestDirectFreeOursStep: + def test_returns_running(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + monkeypatch.setattr(referee_actions, "move", lambda *a, **kw: ("move",)) + + robots = {0: _robot(0, 0.0, 0.0)} + referee = _make_referee_data(command=RefereeCommand.DIRECT_FREE_YELLOW) + game = _make_game(friendly_robots=robots, referee=referee) + cmd_map = _make_cmd_map(game) + node = referee_actions.DirectFreeOursStep(name="DirectFreeOurs") + node.blackboard = _make_blackboard(game, cmd_map) + + assert node.update() == py_trees.common.Status.RUNNING + + def test_kicker_is_closest_robot_to_ball(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + # Robot 1 is closer to the ball at (1.0, 0.0) + robots = { + 0: _robot(0, -2.0, 0.0), + 1: _robot(1, 1.2, 0.0), + } + frame = GameFrame( + ts=0.0, + my_team_is_yellow=True, + my_team_is_right=True, + friendly_robots=robots, + enemy_robots={}, + ball=_ball(1.0, 0.0), + referee=_make_referee_data(command=RefereeCommand.DIRECT_FREE_YELLOW), + ) + game = Game( + past=GameHistory(10), + current=frame, + field=Field(my_team_is_right=True, field_bounds=Field.FULL_FIELD_BOUNDS), + ) + cmd_map = _make_cmd_map(game) + node = referee_actions.DirectFreeOursStep(name="DirectFreeOurs") + node.blackboard = _make_blackboard(game, cmd_map) + + node.update() + + kicker_entries = [entry for entry in captured if entry[0] == 1] + assert len(kicker_entries) == 1 + assert kicker_entries[0][1].x == pytest.approx(1.0) + assert kicker_entries[0][1].y == pytest.approx(0.0) + + def test_kicker_moves_toward_ball(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + robots = {0: _robot(0, 0.5, 0.0)} + frame = GameFrame( + ts=0.0, + my_team_is_yellow=True, + my_team_is_right=True, + friendly_robots=robots, + enemy_robots={}, + ball=_ball(2.0, 1.0), + referee=_make_referee_data(command=RefereeCommand.DIRECT_FREE_YELLOW), + ) + game = Game( + past=GameHistory(10), + current=frame, + field=Field(my_team_is_right=True, field_bounds=Field.FULL_FIELD_BOUNDS), + ) + cmd_map = _make_cmd_map(game) + node = referee_actions.DirectFreeOursStep(name="DirectFreeOurs") + node.blackboard = _make_blackboard(game, cmd_map) + + node.update() + + assert len(captured) == 1 + assert captured[0][0] == 0 + assert captured[0][1].x == pytest.approx(2.0) + assert captured[0][1].y == pytest.approx(1.0) + + def test_non_kicker_robots_get_stop_command(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + monkeypatch.setattr(referee_actions, "move", lambda *a, **kw: ("move",)) + + # Robot 0 is closest to ball at (0.0, 0.0); robots 1 and 2 are farther + robots = { + 0: _robot(0, 0.0, 0.0), + 1: _robot(1, 2.0, 0.0), + 2: _robot(2, -3.0, 1.0), + } + game = _make_game( + friendly_robots=robots, + referee=_make_referee_data(command=RefereeCommand.DIRECT_FREE_YELLOW), + ) + cmd_map = _make_cmd_map(game) + node = referee_actions.DirectFreeOursStep(name="DirectFreeOurs") + node.blackboard = _make_blackboard(game, cmd_map) + + node.update() + + # Robots 1 and 2 must have been given the empty (stop) command, not a move + assert cmd_map[1] is not None + assert cmd_map[2] is not None + # The stop command is the empty_command tuple; move returns ("move", robot_id) + assert cmd_map[1] != ("move", 1) + assert cmd_map[2] != ("move", 2) + + def test_writes_command_for_every_robot(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + monkeypatch.setattr(referee_actions, "move", lambda *a, **kw: ("move",)) + + robots = {i: _robot(i, float(i), 0.0) for i in range(4)} + game = _make_game( + friendly_robots=robots, + referee=_make_referee_data(command=RefereeCommand.DIRECT_FREE_YELLOW), + ) + cmd_map = _make_cmd_map(game) + node = referee_actions.DirectFreeOursStep(name="DirectFreeOurs") + node.blackboard = _make_blackboard(game, cmd_map) + + node.update() + + assert set(cmd_map.keys()) == set(robots.keys()) + for v in cmd_map.values(): + assert v is not None + + +# --------------------------------------------------------------------------- +# DirectFreeTheirsStep — comprehensive keep-out coverage +# --------------------------------------------------------------------------- + + +class TestDirectFreeTheirsStep: + def test_returns_running(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + monkeypatch.setattr(referee_actions, "move", lambda *a, **kw: ("move",)) + + robots = {0: _robot(0, 2.0, 0.0)} + referee = _make_referee_data(command=RefereeCommand.DIRECT_FREE_BLUE) + game = _make_game(friendly_robots=robots, referee=referee) + cmd_map = _make_cmd_map(game) + node = referee_actions.DirectFreeTheirsStep(name="DirectFreeTheirs") + node.blackboard = _make_blackboard(game, cmd_map) + + assert node.update() == py_trees.common.Status.RUNNING + + def test_robot_outside_keep_out_stays_put(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + monkeypatch.setattr(referee_actions, "move", lambda *a, **kw: ("move",)) + + robots = {0: _robot(0, 2.0, 0.0)} # well outside 0.55 m from ball at (0,0) + referee = _make_referee_data(command=RefereeCommand.DIRECT_FREE_BLUE) + game = _make_game(friendly_robots=robots, referee=referee) + cmd_map = _make_cmd_map(game) + node = referee_actions.DirectFreeTheirsStep(name="DirectFreeTheirs") + node.blackboard = _make_blackboard(game, cmd_map) + + node.update() + + # No move was needed; cmd_map entry should be the empty (stop) command + assert cmd_map[0] is not None + assert cmd_map[0] != ("move", 0) + + def test_multiple_robots_only_encroaching_ones_move(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + # Ball at (0, 0); robot 0 inside keep-out, robots 1 & 2 outside + robots = { + 0: _robot(0, 0.1, 0.0), + 1: _robot(1, 1.0, 0.0), + 2: _robot(2, -1.5, 0.5), + } + referee = _make_referee_data(command=RefereeCommand.DIRECT_FREE_BLUE) + game = _make_game(friendly_robots=robots, referee=referee) + cmd_map = _make_cmd_map(game) + node = referee_actions.DirectFreeTheirsStep(name="DirectFreeTheirs") + node.blackboard = _make_blackboard(game, cmd_map) + + node.update() + + moved_ids = [rid for rid, _ in captured] + assert moved_ids == [0] + assert cmd_map[1] is not None + assert cmd_map[2] is not None + + def test_encroaching_robot_projected_to_keep_out_boundary(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + captured = [] + + def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): + captured.append((robot_id, target_coords)) + return ("move", robot_id) + + monkeypatch.setattr(referee_actions, "move", fake_move) + + # Ball at origin; robot dead on the x-axis at 0.3 m (inside 0.55) + robots = {0: _robot(0, 0.3, 0.0)} + referee = _make_referee_data(command=RefereeCommand.DIRECT_FREE_BLUE) + game = _make_game(friendly_robots=robots, referee=referee) + cmd_map = _make_cmd_map(game) + node = referee_actions.DirectFreeTheirsStep(name="DirectFreeTheirs") + node.blackboard = _make_blackboard(game, cmd_map) + + node.update() + + assert len(captured) == 1 + assert captured[0][1] == pytest.approx(Vector2D(0.55, 0.0)) + + def test_all_robots_get_commands(self, monkeypatch): + from utama_core.strategy.referee import actions as referee_actions + + monkeypatch.setattr(referee_actions, "move", lambda *a, **kw: ("move",)) + + robots = {i: _robot(i, float(i) * 0.5 - 1.0, 0.0) for i in range(5)} + referee = _make_referee_data(command=RefereeCommand.DIRECT_FREE_BLUE) + game = _make_game(friendly_robots=robots, referee=referee) + cmd_map = _make_cmd_map(game) + node = referee_actions.DirectFreeTheirsStep(name="DirectFreeTheirs") + node.blackboard = _make_blackboard(game, cmd_map) + + node.update() + + assert set(cmd_map.keys()) == set(robots.keys()) + for v in cmd_map.values(): + assert v is not None diff --git a/utama_core/tests/strategy_runner/test_referee_rsim.py b/utama_core/tests/strategy_runner/test_referee_rsim.py new file mode 100644 index 00000000..954f17b8 --- /dev/null +++ b/utama_core/tests/strategy_runner/test_referee_rsim.py @@ -0,0 +1,386 @@ +"""Referee behaviour integration tests using rsim + CustomReferee. + +Each test: + 1. Starts a full rsim session with a CustomReferee (simulation profile). + 2. Sets up a scenario via reset_field (ball position + velocity, robots placed). + 3. Waits for the referee to detect a violation and issue a command. + 4. Verifies that the robots respond correctly via eval_status. + +Scenarios covered: + - BALL_PLACEMENT_YELLOW issued directly → closest robot drives to designated target. + - Ball exits side boundary → DIRECT_FREE_YELLOW issued → kicker drives to ball. + - Ball exits side boundary, robot near ball → DIRECT_FREE_BLUE issued → robots clear keep-out zone. + - PREPARE_KICKOFF issued → robots reach own-half positions outside centre circle. + +Note on initial commands: + Out-of-bounds and goal rules only fire during NORMAL_START / FORCE_START, so the + manager issues FORCE_START in reset_field to put the game into active play before + the ball exits. The kickoff test issues PREPARE_KICKOFF_YELLOW directly. + +Note on last-touch tracking: + DIRECT_FREE_YELLOW (our free kick) is issued when the enemy last touched the ball. + DIRECT_FREE_BLUE (their free kick) is issued when we last touched the ball. + We control which fires by positioning a friendly robot next to the ball before + it exits (triggers friendly last-touch → DIRECT_FREE_BLUE, their kick). + With no robot near the ball, last-touch defaults to DIRECT_FREE_YELLOW (ours). +""" + +import math +import time +from typing import Optional + +import py_trees + +from utama_core.custom_referee import CustomReferee +from utama_core.entities.game import Game +from utama_core.entities.game.field import Field, FieldBounds +from utama_core.entities.referee.referee_command import RefereeCommand +from utama_core.run.strategy_runner import StrategyRunner +from utama_core.strategy.common.abstract_strategy import AbstractStrategy +from utama_core.team_controller.src.controllers import AbstractSimController +from utama_core.tests.common.abstract_test_manager import ( + AbstractTestManager, + TestingStatus, +) + +# SSL keep-out radius during opponent free kicks (must match referee_constants.py). +BALL_KEEP_OUT_DISTANCE = 0.55 + +# --------------------------------------------------------------------------- +# Minimal idle strategy — referee override tree handles all motion +# --------------------------------------------------------------------------- + +BALL_PLACEMENT_COMMANDS = { + RefereeCommand.BALL_PLACEMENT_YELLOW, + RefereeCommand.BALL_PLACEMENT_BLUE, +} +DIRECT_FREE_COMMANDS = { + RefereeCommand.DIRECT_FREE_YELLOW, + RefereeCommand.DIRECT_FREE_BLUE, +} +PREPARE_KICKOFF_COMMANDS = { + RefereeCommand.PREPARE_KICKOFF_YELLOW, + RefereeCommand.PREPARE_KICKOFF_BLUE, +} + + +class _IdleStrategy(AbstractStrategy): + """Does nothing in the strategy subtree — referee override layer handles all motion.""" + + exp_ball: bool = True + + def create_behaviour_tree(self) -> py_trees.behaviour.Behaviour: + return py_trees.behaviours.Running(name="Idle") + + def assert_exp_robots(self, n_runtime_friendly: int, n_runtime_enemy: int) -> bool: + return True + + def assert_exp_goals(self, includes_my_goal_line: bool, includes_opp_goal_line: bool) -> bool: + return True + + def get_min_bounding_zone(self) -> Optional[FieldBounds]: + return None + + +# --------------------------------------------------------------------------- +# Helper +# --------------------------------------------------------------------------- + + +def _make_runner(referee: CustomReferee, n_friendly: int = 3) -> StrategyRunner: + return StrategyRunner( + strategy=_IdleStrategy(), + my_team_is_yellow=True, + my_team_is_right=False, # defending left → own half is negative-x + mode="rsim", + exp_friendly=n_friendly, + exp_enemy=0, + exp_ball=True, + referee_system="custom", + custom_referee=referee, + ) + + +# --------------------------------------------------------------------------- +# Scenario 1: BALL_PLACEMENT — closest robot drives to designated target +# --------------------------------------------------------------------------- + + +class _BallPlacementManager(AbstractTestManager): + """BALL_PLACEMENT_YELLOW is issued directly via set_command. + + A robot is placed near the designated target so it is the obvious candidate + to reach the position quickly. We verify it gets within APPROACH_TOLERANCE. + """ + + n_episodes = 1 + TARGET = (1.0, 1.0) # designated placement position + APPROACH_TOLERANCE = 0.4 + + def __init__(self, referee: CustomReferee): + super().__init__() + self._referee = referee + self.placement_command_seen: bool = False + self.robot_reached_target: bool = False + + def reset_field(self, sim_controller: AbstractSimController, game: Game): + # Robot 0 starts close to the target so it is the clear closest candidate. + sim_controller.teleport_robot(game.my_team_is_yellow, 0, 0.5, 0.5) + sim_controller.teleport_robot(game.my_team_is_yellow, 1, -2.0, 0.5) + sim_controller.teleport_robot(game.my_team_is_yellow, 2, -2.0, -0.5) + # Ball far from the placement target + sim_controller.teleport_ball(-1.0, -1.0) + # Issue BALL_PLACEMENT directly and set the designated target + self._referee.set_command(RefereeCommand.BALL_PLACEMENT_YELLOW, time.time()) + self._referee._state.ball_placement_target = self.TARGET + + def eval_status(self, game: Game) -> TestingStatus: + ref = game.referee + if ref is None: + return TestingStatus.IN_PROGRESS + + if ref.referee_command in BALL_PLACEMENT_COMMANDS: + self.placement_command_seen = True + + if not self.placement_command_seen: + return TestingStatus.IN_PROGRESS + + target_x, target_y = self.TARGET + for robot in game.friendly_robots.values(): + dist = math.hypot(robot.p.x - target_x, robot.p.y - target_y) + if dist < self.APPROACH_TOLERANCE: + self.robot_reached_target = True + return TestingStatus.SUCCESS + + return TestingStatus.IN_PROGRESS + + +def test_ball_placement_robot_approaches_designated_position(headless): + """During BALL_PLACEMENT, the closest robot drives toward the designated target.""" + referee = CustomReferee.from_profile_name("simulation") + runner = _make_runner(referee) + tm = _BallPlacementManager(referee) + + passed = runner.run_test(tm, episode_timeout=20.0, rsim_headless=headless) + + assert tm.placement_command_seen, "CustomReferee never issued a BALL_PLACEMENT command" + assert tm.robot_reached_target, "No robot approached the ball placement designated position" + assert passed + + +# --------------------------------------------------------------------------- +# Scenario 2a: our direct free kick — kicker drives toward ball +# --------------------------------------------------------------------------- + + +class _DirectFreeOursManager(AbstractTestManager): + """Ball exits the side boundary with no friendly robot nearby → DIRECT_FREE_YELLOW (ours). + + With no robot close enough to the ball to register a friendly last-touch, + OutOfBoundsRule defaults to DIRECT_FREE_YELLOW. We verify the kicker + drives toward the (now out-of-bounds) ball. + """ + + n_episodes = 1 + APPROACH_TOLERANCE = 0.6 # slightly wider: ball may be just outside boundary + + def __init__(self, referee: CustomReferee): + super().__init__() + self._referee = referee + self.direct_free_seen: bool = False + self.robot_near_ball: bool = False + + def reset_field(self, sim_controller: AbstractSimController, game: Game): + # Keep all robots well away from the ball so last-touch is unknown → DIRECT_FREE_YELLOW + sim_controller.teleport_robot(game.my_team_is_yellow, 0, -1.5, 0.0) + sim_controller.teleport_robot(game.my_team_is_yellow, 1, -2.0, 0.5) + sim_controller.teleport_robot(game.my_team_is_yellow, 2, -2.0, -0.5) + # Ball heading out the top sideline + sim_controller.teleport_ball(0.0, 2.5, vx=0.0, vy=2.5) + self._referee.set_command(RefereeCommand.FORCE_START, time.time()) + + def eval_status(self, game: Game) -> TestingStatus: + ref = game.referee + if ref is None: + return TestingStatus.IN_PROGRESS + + if ref.referee_command == RefereeCommand.DIRECT_FREE_YELLOW: + self.direct_free_seen = True + + if not self.direct_free_seen: + return TestingStatus.IN_PROGRESS + + ball = game.ball + if ball is None: + return TestingStatus.IN_PROGRESS + + for robot in game.friendly_robots.values(): + dist = math.hypot(robot.p.x - ball.p.x, robot.p.y - ball.p.y) + if dist < self.APPROACH_TOLERANCE: + self.robot_near_ball = True + return TestingStatus.SUCCESS + + return TestingStatus.IN_PROGRESS + + +def test_direct_free_kick_ours_robot_drives_to_ball(headless): + """After our direct free kick, the kicker drives toward the ball.""" + referee = CustomReferee.from_profile_name("simulation") + runner = _make_runner(referee) + tm = _DirectFreeOursManager(referee) + + passed = runner.run_test(tm, episode_timeout=20.0, rsim_headless=headless) + + assert tm.direct_free_seen, "CustomReferee never issued DIRECT_FREE_YELLOW" + assert tm.robot_near_ball, "No robot drove toward the ball during our direct free kick" + assert passed + + +# --------------------------------------------------------------------------- +# Scenario 2b: their direct free kick — robots clear the keep-out zone +# --------------------------------------------------------------------------- + + +class _DirectFreeTheirsManager(AbstractTestManager): + """A robot starts inside the keep-out radius; DIRECT_FREE_BLUE (theirs) is issued. + + We place robot 0 right next to the ball before it exits so last-touch registers + as friendly → OutOfBoundsRule issues DIRECT_FREE_BLUE (opponent's free kick). + The test verifies that all robots end up outside the keep-out radius. + """ + + n_episodes = 1 + # All robots must clear beyond this radius from the ball position. + CLEAR_TOLERANCE = 0.1 # allowed margin inside keep-out (robots should be well clear) + + def __init__(self, referee: CustomReferee): + super().__init__() + self._referee = referee + self.direct_free_seen: bool = False + self.robots_cleared: bool = False + # We record the ball position when DIRECT_FREE_BLUE fires to check clearing. + self._ball_pos_at_call: Optional[tuple[float, float]] = None + + def reset_field(self, sim_controller: AbstractSimController, game: Game): + # Robot 0 is placed right next to the ball — it will register as last-toucher. + sim_controller.teleport_robot(game.my_team_is_yellow, 0, 0.0, 2.4) + # Robots 1 and 2 also start near the ball path — both inside keep-out. + sim_controller.teleport_robot(game.my_team_is_yellow, 1, 0.1, 2.3) + sim_controller.teleport_robot(game.my_team_is_yellow, 2, -0.1, 2.3) + # Ball heading out the top sideline; robot 0 is close enough for last-touch + sim_controller.teleport_ball(0.0, 2.5, vx=0.0, vy=2.5) + self._referee.set_command(RefereeCommand.FORCE_START, time.time()) + + def eval_status(self, game: Game) -> TestingStatus: + ref = game.referee + if ref is None: + return TestingStatus.IN_PROGRESS + + if ref.referee_command == RefereeCommand.DIRECT_FREE_BLUE: + self.direct_free_seen = True + if self._ball_pos_at_call is None and game.ball is not None: + self._ball_pos_at_call = (game.ball.p.x, game.ball.p.y) + + if not self.direct_free_seen or self._ball_pos_at_call is None: + return TestingStatus.IN_PROGRESS + + bx, by = self._ball_pos_at_call + threshold = BALL_KEEP_OUT_DISTANCE - self.CLEAR_TOLERANCE + + all_clear = all(math.hypot(r.p.x - bx, r.p.y - by) >= threshold for r in game.friendly_robots.values()) + if all_clear: + self.robots_cleared = True + return TestingStatus.SUCCESS + + return TestingStatus.IN_PROGRESS + + +def test_direct_free_kick_theirs_robots_clear_keep_out_zone(headless): + """During opponent direct free kick, all robots clear the keep-out radius around the ball.""" + referee = CustomReferee.from_profile_name("simulation") + runner = _make_runner(referee) + tm = _DirectFreeTheirsManager(referee) + + passed = runner.run_test(tm, episode_timeout=20.0, rsim_headless=headless) + + assert tm.direct_free_seen, "CustomReferee never issued DIRECT_FREE_BLUE" + assert tm.robots_cleared, "Robots did not clear the keep-out zone during opponent direct free kick" + assert passed + + +# --------------------------------------------------------------------------- +# Scenario 3: PREPARE_KICKOFF → robots on own half, outside centre circle +# --------------------------------------------------------------------------- + + +class _KickoffPositioningManager(AbstractTestManager): + """PREPARE_KICKOFF_YELLOW is issued in reset_field. + + Robots start near the centre circle so their clearing movement is visible. + eval_status verifies all robots reach and hold own-half positions outside + the centre circle for N_FRAMES_TO_CHECK consecutive frames. + my_team_is_right=False → own half is negative-x. + """ + + n_episodes = 1 + N_FRAMES_TO_CHECK = 100 + POSITION_TOLERANCE = 0.15 + + def __init__(self, referee: CustomReferee): + super().__init__() + self._referee = referee + self.kickoff_command_seen: bool = False + self.success_frame_count: int = 0 + + def reset_field(self, sim_controller: AbstractSimController, game: Game): + # Robots start near the centre circle so clearing movement is clearly visible. + sim_controller.teleport_robot(game.my_team_is_yellow, 0, -0.3, 0.0) + sim_controller.teleport_robot(game.my_team_is_yellow, 1, -0.2, 0.5) + sim_controller.teleport_robot(game.my_team_is_yellow, 2, -0.2, -0.5) + sim_controller.teleport_ball(0.0, 0.0) + self._referee.set_command(RefereeCommand.PREPARE_KICKOFF_YELLOW, time.time()) + + def eval_status(self, game: Game) -> TestingStatus: + ref = game.referee + if ref is None: + return TestingStatus.IN_PROGRESS + + if ref.referee_command in PREPARE_KICKOFF_COMMANDS: + self.kickoff_command_seen = True + + if not self.kickoff_command_seen: + return TestingStatus.IN_PROGRESS + + # my_team_is_right=False → own half is negative-x. + # Kicker (robot 0) targets (0,0) on the boundary — allow x <= 0.2. + # Support robots (1, 2) must be strictly on own half and outside centre circle. + support_robots = [r for rid, r in game.friendly_robots.items() if rid != 0] + kicker = game.friendly_robots.get(0) + + kicker_ok = kicker is not None and kicker.p.x <= 0.2 + supports_on_half = all(r.p.x <= self.POSITION_TOLERANCE for r in support_robots) + supports_outside_circle = all( + math.hypot(r.p.x, r.p.y) >= Field.CENTER_CIRCLE_RADIUS - self.POSITION_TOLERANCE for r in support_robots + ) + + if kicker_ok and supports_on_half and supports_outside_circle: + self.success_frame_count += 1 + else: + self.success_frame_count = 0 + + if self.success_frame_count >= self.N_FRAMES_TO_CHECK: + return TestingStatus.SUCCESS + + return TestingStatus.IN_PROGRESS + + +def test_prepare_kickoff_robots_form_on_own_half_outside_circle(headless): + """At kickoff, all robots reach and hold own-half positions outside the centre circle.""" + referee = CustomReferee.from_profile_name("simulation") + runner = _make_runner(referee) + tm = _KickoffPositioningManager(referee) + + passed = runner.run_test(tm, episode_timeout=30.0, rsim_headless=headless) + + assert tm.kickoff_command_seen, "CustomReferee never issued a PREPARE_KICKOFF command" + assert passed, "Robots did not sustain a legal kickoff formation for the required number of frames" From b683f39fa0641c946af49a1b8e0cd1a20bed343f Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Fri, 3 Apr 2026 11:46:45 +0100 Subject: [PATCH 013/121] Use public Field class properties instead of private constants Replace Field._UNDERSCORE_CONSTANTS with their public ClassProperty equivalents in math_utils.py and geometry.py. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/custom_referee/geometry.py | 16 ++++++++-------- utama_core/global_utils/math_utils.py | 2 +- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/utama_core/custom_referee/geometry.py b/utama_core/custom_referee/geometry.py index 5d714200..fa9a25cb 100644 --- a/utama_core/custom_referee/geometry.py +++ b/utama_core/custom_referee/geometry.py @@ -24,11 +24,11 @@ class RefereeGeometry: def from_standard_div_b(cls) -> "RefereeGeometry": """Return geometry matching the standard SSL Division B field.""" return cls( - half_length=Field._FULL_FIELD_HALF_LENGTH, # 4.5 - half_width=Field._FULL_FIELD_HALF_WIDTH, # 3.0 - half_goal_width=Field._HALF_GOAL_WIDTH, # 0.5 - half_defense_length=Field._HALF_DEFENSE_AREA_LENGTH, # 0.5 - half_defense_width=Field._HALF_DEFENSE_AREA_WIDTH, # 1.0 + half_length=Field.FULL_FIELD_HALF_LENGTH, # 4.5 + half_width=Field.FULL_FIELD_HALF_WIDTH, # 3.0 + half_goal_width=Field.HALF_GOAL_WIDTH, # 0.5 + half_defense_length=Field.HALF_DEFENSE_AREA_LENGTH, # 0.5 + half_defense_width=Field.HALF_DEFENSE_AREA_WIDTH, # 1.0 center_circle_radius=0.5, ) @@ -40,9 +40,9 @@ def from_field_bounds(cls, field_bounds: FieldBounds) -> "RefereeGeometry": return cls( half_length=half_length, half_width=half_width, - half_goal_width=Field._HALF_GOAL_WIDTH, - half_defense_length=Field._HALF_DEFENSE_AREA_LENGTH, - half_defense_width=Field._HALF_DEFENSE_AREA_WIDTH, + half_goal_width=Field.HALF_GOAL_WIDTH, + half_defense_length=Field.HALF_DEFENSE_AREA_LENGTH, + half_defense_width=Field.HALF_DEFENSE_AREA_WIDTH, center_circle_radius=0.5, ) diff --git a/utama_core/global_utils/math_utils.py b/utama_core/global_utils/math_utils.py index f0db48e0..eebb149e 100644 --- a/utama_core/global_utils/math_utils.py +++ b/utama_core/global_utils/math_utils.py @@ -132,7 +132,7 @@ def in_field_bounds(point: Tuple[float, float] | Vector2D, bounding_box: FieldBo def assert_valid_bounding_box(bb: FieldBounds): """Asserts that a FieldBounds object is valid, raising an AssertionError if not.""" - fx, fy = Field._FULL_FIELD_HALF_LENGTH, Field._FULL_FIELD_HALF_WIDTH + fx, fy = Field.FULL_FIELD_HALF_LENGTH, Field.FULL_FIELD_HALF_WIDTH x0, y0 = bb.top_left x1, y1 = bb.bottom_right From f6f1297b3d1a579b8ff8077757bc2d29b845ffda Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Fri, 3 Apr 2026 12:10:26 +0100 Subject: [PATCH 014/121] Default headless=True, skip ball teleport when placement pending, document future work - conftest.py: default --headless to True so tests don't open rsim window - strategy_runner.py: skip ball teleport on STOP when next_command is BALL_PLACEMENT so the robot must physically carry the ball - test_referee_rsim.py: replace broken full-sequence test with a comment documenting why it is deferred (ball placement carry mechanics not yet reliable in rsim) Co-Authored-By: Claude Sonnet 4.6 --- conftest.py | 2 +- utama_core/run/strategy_runner.py | 5 +++ .../strategy_runner/test_referee_rsim.py | 35 +++++++++++++++++++ 3 files changed, 41 insertions(+), 1 deletion(-) diff --git a/conftest.py b/conftest.py index 75dedc31..4196efed 100644 --- a/conftest.py +++ b/conftest.py @@ -12,7 +12,7 @@ def pytest_addoption(parser): parser.addoption( "--headless", action="store_true", - default=False, + default=True, help="Don't display any graphics (runs faster)", ) parser.addoption( diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index ba93d88c..47caea4e 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -846,11 +846,16 @@ def _run_step(self): if self.referee_system == "custom": ref_data = self.custom_referee.step(self.my.current_game_frame, time.time()) self.ref_buffer.append(ref_data) + _ball_placement_next = ref_data.next_command in ( + RefereeCommand.BALL_PLACEMENT_YELLOW, + RefereeCommand.BALL_PLACEMENT_BLUE, + ) if ( self.sim_controller is not None and ref_data.referee_command == RefereeCommand.STOP and ref_data.designated_position is not None and self._prev_custom_ref_command != RefereeCommand.STOP + and not _ball_placement_next ): x, y = ref_data.designated_position self.sim_controller.teleport_ball(x, y) diff --git a/utama_core/tests/strategy_runner/test_referee_rsim.py b/utama_core/tests/strategy_runner/test_referee_rsim.py index 954f17b8..83c4eda9 100644 --- a/utama_core/tests/strategy_runner/test_referee_rsim.py +++ b/utama_core/tests/strategy_runner/test_referee_rsim.py @@ -11,6 +11,7 @@ - Ball exits side boundary → DIRECT_FREE_YELLOW issued → kicker drives to ball. - Ball exits side boundary, robot near ball → DIRECT_FREE_BLUE issued → robots clear keep-out zone. - PREPARE_KICKOFF issued → robots reach own-half positions outside centre circle. + - Full out-of-bounds sequence: ball exits → STOP → BALL_PLACEMENT → DIRECT_FREE → NORMAL_START. Note on initial commands: Out-of-bounds and goal rules only fire during NORMAL_START / FORCE_START, so the @@ -23,6 +24,12 @@ We control which fires by positioning a friendly robot next to the ball before it exits (triggers friendly last-touch → DIRECT_FREE_BLUE, their kick). With no robot near the ball, last-touch defaults to DIRECT_FREE_YELLOW (ours). + +Note on ball placement in out-of-bounds: + OutOfBoundsRule issues STOP → DIRECT_FREE directly (no automatic ball placement). + Ball placement is only reachable via set_command(). The full-sequence test manually + injects BALL_PLACEMENT_YELLOW after the STOP fires, then lets auto-advance carry the + state machine through BALL_PLACEMENT → DIRECT_FREE → NORMAL_START. """ import math @@ -384,3 +391,31 @@ def test_prepare_kickoff_robots_form_on_own_half_outside_circle(headless): assert tm.kickoff_command_seen, "CustomReferee never issued a PREPARE_KICKOFF command" assert passed, "Robots did not sustain a legal kickoff formation for the required number of frames" + + +# --------------------------------------------------------------------------- +# Future work: full out-of-bounds sequence integration test +# +# Intended scenario: +# ball exits → STOP → BALL_PLACEMENT_YELLOW → robot physically carries ball +# to designated position → DIRECT_FREE_YELLOW → kicker drives to ball → +# NORMAL_START (play resumes) +# +# Why it is not implemented yet: +# BallPlacementOursStep relies on robot.has_ball (IR sensor) to switch from +# approach to carry mode. In rsim the robot drives to ball.p but decelerates +# to a stop AT the ball centre rather than past it, so the dribbler never +# properly captures the ball — the robot ends up pushing it instead of +# carrying it. Several approaches were tried: +# - Adding a behind-ball approach offset (robot stopped short with a gap) +# - Driving directly into ball.p with face-target orientation (pushed sideways) +# - Proximity fallback for has_ball (robot reached ball but pushed it away) +# Root cause: the motion controller targets and the dribbler capture +# mechanics need tighter integration (approach from behind, slower final +# approach speed, or a dedicated "get-behind-ball" skill) before ball +# placement via robot carry can be reliably tested end-to-end. +# +# Additionally, OutOfBoundsRule currently issues STOP → DIRECT_FREE directly +# (no automatic ball placement step). Ball placement must be injected manually +# via set_command(), which makes the test scenario somewhat artificial. +# --------------------------------------------------------------------------- From aa4974a6e59b51d288b97c84ef38a26324b729bd Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Fri, 3 Apr 2026 12:11:51 +0100 Subject: [PATCH 015/121] Document end-to-end ball placement test as future work Co-Authored-By: Claude Sonnet 4.6 --- docs/referee_integration.md | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/docs/referee_integration.md b/docs/referee_integration.md index 6f9fc789..43cbf993 100644 --- a/docs/referee_integration.md +++ b/docs/referee_integration.md @@ -498,3 +498,18 @@ The **Event Log** panel shows the 20 most recent events, newest first. failures), `BallPlacementOursStep` must fall back to STOP behaviour. - **Penalty / ball-placement readiness tuning**: `simulation` now auto-progresses these restarts, but the exact readiness heuristics may still need iteration as we gather more simulator coverage. + +- **End-to-end ball placement integration test**: The intended test scenario is: + ball exits field → `STOP` → `BALL_PLACEMENT_YELLOW` → robot physically carries ball to + `designated_position` → `DIRECT_FREE_YELLOW` → kicker drives to ball → `NORMAL_START`. + This was attempted in `utama_core/tests/strategy_runner/test_referee_rsim.py` but deferred + because `BallPlacementOursStep` cannot reliably carry the ball in RSim. The robot drives + to `ball.p` with the dribbler on, but the motion controller decelerates to a stop at the + ball centre rather than capturing it, causing the robot to push the ball instead of carrying + it. Approaches tried: behind-ball offset (robot stops short), direct drive to ball with + face-target orientation (hits ball side-on), proximity fallback for `has_ball` (still pushes). + Root cause: the approach, dribbler-capture, and carry phases need a dedicated + "get-behind-ball" skill with a slower final-approach speed before this can be tested + end-to-end. Additionally, `OutOfBoundsRule` currently issues `STOP → DIRECT_FREE` directly + (no automatic ball placement step), so `BALL_PLACEMENT` must be injected manually via + `set_command()` for this scenario. From 15aa391ae2f94030a31381497172a978c80b85f2 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Fri, 3 Apr 2026 12:13:19 +0100 Subject: [PATCH 016/121] Remove advanced controls (penalty & ball placement) from referee GUI Penalty and ball placement buttons are not in use; removing them keeps the operator panel focused on the commands we actually use. Co-Authored-By: Claude Sonnet 4.6 --- docs/referee_integration.md | 8 ++------ utama_core/custom_referee/gui.py | 24 ------------------------ 2 files changed, 2 insertions(+), 30 deletions(-) diff --git a/docs/referee_integration.md b/docs/referee_integration.md index 43cbf993..83a5351e 100644 --- a/docs/referee_integration.md +++ b/docs/referee_integration.md @@ -418,10 +418,6 @@ framework dependency — state updates arrive via `EventSource`, config is fetch | **Kickoff Blue** | `PREPARE_KICKOFF_BLUE` | After Yellow scores | Blue kicker approaches centre; others to own half | | **Free Kick Yellow** | `DIRECT_FREE_YELLOW` | Foul by Blue | Yellow kicker near ball; Blue ≥0.5 m away | | **Free Kick Blue** | `DIRECT_FREE_BLUE` | Foul by Yellow | Blue kicker near ball; Yellow ≥0.5 m away | -| **Penalty Yellow** *(adv)* | `PREPARE_PENALTY_YELLOW` | Usually auto-detected; manual override only | Yellow kicker at penalty mark; others behind line | -| **Penalty Blue** *(adv)* | `PREPARE_PENALTY_BLUE` | Usually auto-detected; manual override only | Blue kicker at penalty mark; others behind line | -| **Ball Placement Yellow** *(adv)* | `BALL_PLACEMENT_YELLOW` | Manual placement command | Yellow robot moves ball to `designated_position` | -| **Ball Placement Blue** *(adv)* | `BALL_PLACEMENT_BLUE` | Manual placement command | Blue robot moves ball to `designated_position` | #### Auto-detected vs manual @@ -429,8 +425,8 @@ framework dependency — state updates arrive via `EventSource`, config is fetch |---|---|---| | Goal → kickoff | Auto (GoalRule) | Operator sets kickoff team before half starts | | Out-of-bounds → free kick | Auto (OutOfBoundsRule) | `free_kick_assigner` in profile controls which team | -| Defense area → penalty | Auto (DefenseAreaRule, if enabled) | Penalty buttons are in **Advanced** row; hidden by default | -| Ball placement | Auto (OutOfBoundsRule, if enabled) | Manual override via Advanced row if auto fails | +| Defense area → penalty | Auto (DefenseAreaRule, if enabled) | Penalty and ball placement are not exposed in the GUI | +| Ball placement | Auto (OutOfBoundsRule, if enabled) | Use `set_command()` in code if manual override is needed | #### Typical sequences diff --git a/utama_core/custom_referee/gui.py b/utama_core/custom_referee/gui.py index e379a176..b61cc7b5 100644 --- a/utama_core/custom_referee/gui.py +++ b/utama_core/custom_referee/gui.py @@ -613,10 +613,6 @@ def _build_config_json(profile: "RefereeProfile") -> str: .log-cmd { color:var(--green); } .log-score{ color:var(--yellow); } .log-msg { color:var(--text); opacity:.8; } - .adv-toggle { display:flex; align-items:center; gap:8px; font-size:.75rem; color:var(--muted); padding:4px 0 0 0; cursor:pointer; user-select:none; } - .adv-toggle input { cursor:pointer; } - .adv-row { display:none; } - .adv-row.visible { display:flex; } @@ -683,22 +679,6 @@ def _build_config_json(profile: "RefereeProfile") -> str: - -
- - -
-
- - -
@@ -938,10 +918,6 @@ def _build_config_json(profile: "RefereeProfile") -> str: }).catch(err => console.error('command error:', err)); } -function toggleAdvanced(on) { - document.querySelectorAll('.adv-row').forEach(el => - el.classList.toggle('visible', on)); -} function pill(val) { if (val === true) return 'ON'; From c148b349a486d60dfe8f1815b1b196c92d512919 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Fri, 3 Apr 2026 12:17:04 +0100 Subject: [PATCH 017/121] Add three future work items to referee integration docs - Ball placement phase before free kick per SSL rulebook - BallPlacementOursStep carry mechanics investigation (two-robot kissing) - GUI suggested next action to reduce operator cognitive load Co-Authored-By: Claude Sonnet 4.6 --- docs/referee_integration.md | 26 ++++++++++++++++++++++++++ 1 file changed, 26 insertions(+) diff --git a/docs/referee_integration.md b/docs/referee_integration.md index 83a5351e..5ec71c46 100644 --- a/docs/referee_integration.md +++ b/docs/referee_integration.md @@ -509,3 +509,29 @@ The **Event Log** panel shows the 20 most recent events, newest first. end-to-end. Additionally, `OutOfBoundsRule` currently issues `STOP → DIRECT_FREE` directly (no automatic ball placement step), so `BALL_PLACEMENT` must be injected manually via `set_command()` for this scenario. + +- **Ball placement before free kick (SSL rule compliance)**: Per the official SSL rulebook, + after a ball-out-of-bounds event the correct sequence is `STOP → BALL_PLACEMENT_* → + DIRECT_FREE_* → NORMAL_START`, not `STOP → DIRECT_FREE_*` as `OutOfBoundsRule` currently + produces. `OutOfBoundsRule` should be updated to set `suggested_command=STOP` and + `next_command=BALL_PLACEMENT_*` (with `designated_position` set to the infield restart + spot), so the state machine progresses through ball placement before issuing the free kick. + This requires `BallPlacementOursStep` to be working reliably first (see item above). + +- **`BallPlacementOursStep` robot carry mechanics**: The current single-robot dribble + approach does not work reliably — the robot pushes the ball rather than carrying it. + Investigation needed. Most competitive SSL teams use a two-robot "kissing" technique: + one robot pushes from behind while a second robot lightly contacts the ball from the + front to stabilise it, allowing the pair to transport it as a unit. Alternatively, + a single-robot approach with a dedicated "get-behind-ball" skill (slower final approach, + approach vector aligned from behind relative to the target) may also be viable and is + worth evaluating first before adding multi-robot coordination complexity. + +- **GUI: suggested next action for human operators**: The current operator panel presents + all available command buttons simultaneously, which is overwhelming for operators who + are unfamiliar with SSL rules. A future improvement would display a highlighted + "suggested next step" banner or button based on the current referee command — for + example, after a goal the suggestion would be "Kickoff [team]", after `PREPARE_KICKOFF` + it would be "Normal Start (when robots are in position)". This shifts the operator's + job from deciding *what* to do next to simply deciding *when* it is safe to advance, + reducing cognitive load and operator error during matches. From cb6b1763faff1f8047ece9929df5b80900fb6ef4 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Tue, 7 Apr 2026 21:44:44 +0100 Subject: [PATCH 018/121] Fix three bugs identified in Copilot review - Delete dead RefereeStateMachine (never wired up, duplicated GameStateMachine with a broken _replace() call on a mutable class) - Remove dead len(obs)==4 branch in _run_step; RSim always reads from ref_buffer - Snapshot TeamInfo via copy.copy() in _generate_referee_data() to prevent score mutations retroactively corrupting stored RefereeRefiner records - Update docs and stale docstrings accordingly - Document TeamInfo frozen dataclass refactor as deferred follow-up work Co-Authored-By: Claude Sonnet 4.6 --- docs/custom_referee.md | 2 +- docs/custom_referee_design_decisions.md | 15 + docs/referee_integration.md | 4 +- utama_core/custom_referee/state_machine.py | 5 +- .../src/ssl/envs/standard_ssl.py | 3 +- .../src/ssl/referee_state_machine.py | 289 ------------------ utama_core/run/strategy_runner.py | 11 +- 7 files changed, 24 insertions(+), 305 deletions(-) delete mode 100644 utama_core/rsoccer_simulator/src/ssl/referee_state_machine.py diff --git a/docs/custom_referee.md b/docs/custom_referee.md index 5ca3d50b..1d054c22 100644 --- a/docs/custom_referee.md +++ b/docs/custom_referee.md @@ -58,7 +58,7 @@ GameStateMachine.step(current_time, violation) RefereeData (source_identifier="custom_referee") ``` -The one-frame lag (the `GameFrame` used is from the previous step) is acceptable and matches how the existing RSim `RefereeStateMachine` works. +The one-frame lag (the `GameFrame` used is from the previous step) is acceptable for all supported modes. --- diff --git a/docs/custom_referee_design_decisions.md b/docs/custom_referee_design_decisions.md index 47f12652..c585336a 100644 --- a/docs/custom_referee_design_decisions.md +++ b/docs/custom_referee_design_decisions.md @@ -102,3 +102,18 @@ placed at `y = ±3.0 m` (touch-line boundary) rather than spread across the fiel The x-coordinate (`behind_line_x`) is unchanged — robots remain behind the penalty mark. Full off-field placement (Option C) is deferred until the simulator supports it. Penalty kicks remain disabled in all built-in profiles. + +--- + +## 8. `TeamInfo` should be a frozen dataclass + +**File:** `utama_core/entities/game/team_info.py` + +**Current behaviour:** +`TeamInfo` is a mutable class. `GameStateMachine._generate_referee_data()` passes `self.blue_team` / `self.yellow_team` directly into `RefereeData`. `RefereeRefiner` stores these `RefereeData` objects in `_referee_records`. Because all stored records reference the same `TeamInfo` objects, a subsequent `increment_score()` call mutates the score retroactively across all historical records — which can cause `RefereeData.__eq__` to falsely consider a new record equal to the previous one, silently dropping it from `_referee_records`. + +**Workaround (applied 2026-04-07):** `_generate_referee_data()` now calls `copy.copy(self.blue_team)` / `copy.copy(self.yellow_team)` to snapshot team state at the time of record creation. This fixes the aliasing issue for the `CustomReferee` path without touching `TeamInfo` or the network referee path. + +**Long-term fix:** Convert `TeamInfo` to `@dataclass(frozen=True)`. Replace all in-place mutations (`increment_score()`, `parse_referee_packet()`, etc.) with `dataclasses.replace()` calls. This eliminates the aliasing hazard at the type level across the whole codebase, and gives `TeamInfo` a correct `__eq__` for free. The network referee path (`RefereeMessageReceiver` → `parse_referee_packet()`) will need updating too. + +**Why deferred:** The refactor touches the network referee path which is out of scope for the referee integration PR. diff --git a/docs/referee_integration.md b/docs/referee_integration.md index 5ec71c46..a0dcaaf1 100644 --- a/docs/referee_integration.md +++ b/docs/referee_integration.md @@ -208,8 +208,8 @@ Requires WSL `networkingMode=mirrored` in `.wslconfig` for multicast UDP to reac ### RSim mode (simulation) ``` -ref_buffer.append(RefereeData) ← pushed externally (e.g. referee_sim.py) - → strategy_runner._run_step reads ref_buffer (when _frame_to_observations returns 3-tuple) +ref_buffer.append(RefereeData) ← pushed by CustomReferee.step() each tick (or externally, e.g. referee_sim.py) + → strategy_runner._run_step reads ref_buffer → same pipeline as above ``` diff --git a/utama_core/custom_referee/state_machine.py b/utama_core/custom_referee/state_machine.py index f2adda74..064c6401 100644 --- a/utama_core/custom_referee/state_machine.py +++ b/utama_core/custom_referee/state_machine.py @@ -2,6 +2,7 @@ from __future__ import annotations +import copy import logging import math import time @@ -590,8 +591,8 @@ def _generate_referee_data(self, current_time: float) -> RefereeData: referee_command_timestamp=self.command_timestamp, stage=self.stage, stage_time_left=stage_time_left, - blue_team=self.blue_team, - yellow_team=self.yellow_team, + blue_team=copy.copy(self.blue_team), + yellow_team=copy.copy(self.yellow_team), designated_position=self.ball_placement_target, blue_team_on_positive_half=None, next_command=self.next_command, diff --git a/utama_core/rsoccer_simulator/src/ssl/envs/standard_ssl.py b/utama_core/rsoccer_simulator/src/ssl/envs/standard_ssl.py index 0ae38885..2691011a 100644 --- a/utama_core/rsoccer_simulator/src/ssl/envs/standard_ssl.py +++ b/utama_core/rsoccer_simulator/src/ssl/envs/standard_ssl.py @@ -174,11 +174,10 @@ def _frame_to_observations( ) -> Tuple[RawVisionData, RobotResponse, RobotResponse]: """Return observation data that aligns with grSim. There may be Gaussian noise and vanishing added. - Returns (vision_observation, yellow_robot_feedback, blue_robot_feedback, referee_data) + Returns (vision_observation, yellow_robot_feedback, blue_robot_feedback) vision_observation: closely aligned to SSLVision that returns a FramData object yellow_robots_info: feedback from individual yellow robots that returns a List[RobotInfo] blue_robots_info: feedback from individual blue robots that returns a List[RobotInfo] - referee_data: current referee state from embedded referee state machine """ if self.latest_observation[0] == self.steps: diff --git a/utama_core/rsoccer_simulator/src/ssl/referee_state_machine.py b/utama_core/rsoccer_simulator/src/ssl/referee_state_machine.py deleted file mode 100644 index caa8ec2a..00000000 --- a/utama_core/rsoccer_simulator/src/ssl/referee_state_machine.py +++ /dev/null @@ -1,289 +0,0 @@ -"""Embedded referee state machine for RSim environment. - -This module implements a referee system for the RSim SSL environment that -generates RefereeData synchronously with simulation steps, maintaining -interface compatibility with network-based referee systems. -""" - -import logging -from typing import Optional - -import numpy as np - -from utama_core.entities.data.referee import RefereeData -from utama_core.entities.game.team_info import TeamInfo -from utama_core.entities.referee.referee_command import RefereeCommand -from utama_core.entities.referee.stage import Stage -from utama_core.rsoccer_simulator.src.Entities import Frame - -logger = logging.getLogger(__name__) - - -class RefereeStateMachine: - """Manages referee state and generates RefereeData for RSim. - - This class detects game events from simulation state, tracks scores and - timers, and generates valid RefereeData objects compatible with the - network-based referee system used in GRSIM/REAL modes. - - Attributes: - stage: Current game stage (NORMAL_FIRST_HALF, etc.) - command: Current referee command (HALT, STOP, NORMAL_START, etc.) - command_counter: Increments each time command changes - command_timestamp: Timestamp when current command was issued - stage_start_time: When current stage started - stage_duration: Duration of current stage in seconds - yellow_team: Team info for yellow team (score, cards, etc.) - blue_team: Team info for blue team - """ - - def __init__( - self, - n_robots_blue: int, - n_robots_yellow: int, - field, - initial_stage: Stage = Stage.NORMAL_FIRST_HALF_PRE, - initial_command: RefereeCommand = RefereeCommand.HALT, - ): - """Initialize referee state machine. - - Args: - n_robots_blue: Number of blue robots - n_robots_yellow: Number of yellow robots - field: Field object with dimensions - initial_stage: Starting game stage - initial_command: Starting referee command - """ - self.n_robots_blue = n_robots_blue - self.n_robots_yellow = n_robots_yellow - self.field = field - - # Field dimensions (meters) - self.field_half_length = field.length / 2 - self.field_half_width = field.width / 2 - - # State tracking - self.stage = initial_stage - self.command = initial_command - self.command_counter = 0 - self.command_timestamp = 0.0 - - # Timers - self.stage_start_time = 0.0 - self.stage_duration = 300.0 # 5 minutes per half - self.action_timeout = None - - # Team info - self.yellow_team = TeamInfo( - name="Yellow", - score=0, - red_cards=0, - yellow_card_times=[], - yellow_cards=0, - timeouts=4, - timeout_time=300, - goalkeeper=0, - foul_counter=0, - ball_placement_failures=0, - can_place_ball=True, - max_allowed_bots=n_robots_yellow, - bot_substitution_intent=False, - bot_substitution_allowed=True, - bot_substitutions_left=5, - ) - - self.blue_team = TeamInfo( - name="Blue", - score=0, - red_cards=0, - yellow_card_times=[], - yellow_cards=0, - timeouts=4, - timeout_time=300, - goalkeeper=0, - foul_counter=0, - ball_placement_failures=0, - can_place_ball=True, - max_allowed_bots=n_robots_blue, - bot_substitution_intent=False, - bot_substitution_allowed=True, - bot_substitutions_left=5, - ) - - # Game state - self.ball_last_touched_by = None - self.ball_placement_target = None - self.next_command = None - self.goal_scored_by = None - - # Event detection state - self.last_ball_position = None - self.last_goal_time = 0.0 - self.goal_cooldown = 0.5 # seconds before detecting another goal - - logger.info( - "RefereeStateMachine initialized: stage=%s, command=%s", - self.stage.name, - self.command.name, - ) - - def update(self, frame: Frame, current_time: float) -> None: - """Update referee state based on simulation frame. - - This should be called every simulation step. - - Args: - frame: Current simulation frame with ball and robot positions - current_time: Current simulation time in seconds - """ - # Detect and process game events - self._detect_and_process_events(frame, current_time) - - # Update timers - self._update_timers(current_time) - - def _detect_and_process_events(self, frame: Frame, current_time: float) -> None: - """Detect game events and update state accordingly. - - Args: - frame: Current simulation frame - current_time: Current simulation time - """ - # Goal detection (with cooldown to prevent multiple detections) - if current_time - self.last_goal_time > self.goal_cooldown: - if self._is_goal(frame): - self._process_goal(current_time) - - def _is_goal(self, frame: Frame) -> bool: - """Detect if ball is in goal. - - Args: - frame: Current simulation frame - - Returns: - True if goal scored, False otherwise - """ - ball = frame.ball - # goal_depth = 0.2 # meters behind goal line - goal_width = self.field.goal_width / 2 # half width - - # Left goal (yellow defends) - negative x - if ball.x < -self.field_half_length and abs(ball.y) < goal_width: - self.goal_scored_by = "blue" - logger.info("Goal scored by blue team!") - return True - - # Right goal (blue defends) - positive x - if ball.x > self.field_half_length and abs(ball.y) < goal_width: - self.goal_scored_by = "yellow" - logger.info("Goal scored by yellow team!") - return True - - return False - - def _process_goal(self, current_time: float) -> None: - """Process a goal event. - - Updates score, sets STOP command, and prepares kickoff for opposite team. - - Args: - current_time: Time when goal was scored - """ - if self.goal_scored_by == "yellow": - self.yellow_team = self.yellow_team._replace(score=self.yellow_team.score + 1) - self.next_command = RefereeCommand.PREPARE_KICKOFF_BLUE - logger.info("Yellow scored! Score: Yellow %d - Blue %d", self.yellow_team.score, self.blue_team.score) - elif self.goal_scored_by == "blue": - self.blue_team = self.blue_team._replace(score=self.blue_team.score + 1) - self.next_command = RefereeCommand.PREPARE_KICKOFF_YELLOW - logger.info("Blue scored! Score: Yellow %d - Blue %d", self.yellow_team.score, self.blue_team.score) - - # Set STOP command after goal - self.command = RefereeCommand.STOP - self.command_counter += 1 - self.command_timestamp = current_time - self.last_goal_time = current_time - - logger.info( - "Referee command: STOP (after goal), next: %s", self.next_command.name if self.next_command else "None" - ) - - def _update_timers(self, current_time: float) -> None: - """Update stage and action timers. - - Args: - current_time: Current simulation time - """ - # Stage timer automatically counts down based on elapsed time - # No action needed here, calculated in _generate_referee_data() - pass - - def _generate_referee_data(self, current_time: float) -> RefereeData: - """Generate RefereeData from current state. - - Args: - current_time: Current simulation time - - Returns: - RefereeData object with current referee state - """ - stage_time_left = max(0, self.stage_duration - (current_time - self.stage_start_time)) - - return RefereeData( - source_identifier="rsim-embedded", - time_sent=current_time, - time_received=current_time, - referee_command=self.command, - referee_command_timestamp=self.command_timestamp, - stage=self.stage, - stage_time_left=stage_time_left, - blue_team=self.blue_team, - yellow_team=self.yellow_team, - designated_position=self.ball_placement_target, - blue_team_on_positive_half=None, - next_command=self.next_command, - current_action_time_remaining=self.action_timeout, - ) - - def get_referee_data(self, current_time: float) -> RefereeData: - """Get current referee data without updating state. - - Args: - current_time: Current simulation time - - Returns: - RefereeData object with current referee state - """ - return self._generate_referee_data(current_time) - - def set_command(self, command: RefereeCommand, timestamp: float = None) -> None: - """Manually set referee command (for testing/scenarios). - - Args: - command: Referee command to set - timestamp: Optional timestamp, uses current command timestamp if None - """ - self.command = command - self.command_counter += 1 - if timestamp is not None: - self.command_timestamp = timestamp - logger.info("Referee command manually set to: %s", command.name) - - def advance_stage(self, new_stage: Stage, timestamp: float) -> None: - """Manually advance to a new stage. - - Args: - new_stage: Stage to advance to - timestamp: Timestamp when stage change occurs - """ - logger.info("Stage advancing from %s to %s", self.stage.name, new_stage.name) - self.stage = new_stage - self.stage_start_time = timestamp - - # Set appropriate duration for new stage - if new_stage in [Stage.NORMAL_FIRST_HALF, Stage.NORMAL_SECOND_HALF]: - self.stage_duration = 300.0 # 5 minutes - elif new_stage in [Stage.EXTRA_FIRST_HALF, Stage.EXTRA_SECOND_HALF]: - self.stage_duration = 150.0 # 2.5 minutes - else: - self.stage_duration = 0.0 diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index 47caea4e..12699f78 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -863,15 +863,8 @@ def _run_step(self): if self.mode == Mode.RSIM: obs = self.rsim_env._frame_to_observations() - if len(obs) == 4 and self.referee_system != "custom": - # New format with referee embedded in observations - vision_frames = [obs[0]] - referee_data = obs[3] - else: - # custom_referee already pushed data into ref_buffer above; - # otherwise read externally injected referee data. - vision_frames = [obs[0]] - referee_data = self.ref_buffer.popleft() if self.ref_buffer else None + vision_frames = [obs[0]] + referee_data = self.ref_buffer.popleft() if self.ref_buffer else None else: vision_frames = [buffer.popleft() if buffer else None for buffer in self.vision_buffers] referee_data = self.ref_buffer.popleft() if self.ref_buffer else None From 5282cc274d8479ac17e49a832e6483b56b136756 Mon Sep 17 00:00:00 2001 From: Isaac Yong <72080621+isaac0804@users.noreply.github.com> Date: Tue, 7 Apr 2026 22:01:53 +0100 Subject: [PATCH 019/121] Update utama_core/custom_referee/state_machine.py Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> --- utama_core/custom_referee/state_machine.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/utama_core/custom_referee/state_machine.py b/utama_core/custom_referee/state_machine.py index 064c6401..451af006 100644 --- a/utama_core/custom_referee/state_machine.py +++ b/utama_core/custom_referee/state_machine.py @@ -43,13 +43,16 @@ def __init__( kickoff_timeout_seconds: float = 10.0, geometry: Optional[RefereeGeometry] = None, auto_advance: Optional[AutoAdvanceConfig] = None, + initial_time: Optional[float] = None, ) -> None: self.command = initial_command self.command_counter = 0 self.command_timestamp = 0.0 self.stage = initial_stage - self.stage_start_time = time.time() # initialise to now so timer is correct immediately + self.stage_start_time = ( + time.time() if initial_time is None else initial_time + ) self.stage_duration = half_duration_seconds self.yellow_team = TeamInfo( From cc1b1874f7af1311147e0bab147c9765078d158b Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Tue, 7 Apr 2026 22:20:02 +0100 Subject: [PATCH 020/121] Address second round of Copilot review comments MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Fix CustomReferee.step() to reset rules only on actual command transition, not when the state machine ignores the violation due to the cooldown - Remove dead STOP branch and unused my_team_is_yellow param from KeepOutRule - Add last_status_message and last_next_command properties to RefereeRefiner; remove direct _referee_records[-1] access from StrategyRunner - Fix designated_position type annotation: Tuple[float] → Tuple[float, float] - Import BALL_KEEP_OUT_DISTANCE from referee_constants in test file instead of duplicating the literal Co-Authored-By: Claude Sonnet 4.6 --- utama_core/custom_referee/custom_referee.py | 10 +++-- .../custom_referee/rules/keep_out_rule.py | 38 ++++++------------- .../data_processing/refiners/referee.py | 8 ++++ utama_core/entities/data/referee.py | 2 +- utama_core/run/strategy_runner.py | 10 ++--- .../strategy_runner/test_referee_rsim.py | 4 +- 6 files changed, 32 insertions(+), 40 deletions(-) diff --git a/utama_core/custom_referee/custom_referee.py b/utama_core/custom_referee/custom_referee.py index ccec53ad..79c666e3 100644 --- a/utama_core/custom_referee/custom_referee.py +++ b/utama_core/custom_referee/custom_referee.py @@ -141,12 +141,14 @@ def step(self, game_frame: GameFrame, current_time: float) -> RefereeData: violation = result break - # Notify rules of any command transition so they can reset internal state. - if violation is not None: + previous_command = self._state.command + result = self._state.step(current_time, violation, game_frame) + + # Notify rules only when the command actually changed (not when the + # state machine ignored the violation due to the transition cooldown). + if self._state.command != previous_command: for rule in self._rules: rule.reset() - - result = self._state.step(current_time, violation, game_frame) if self._gui_server is not None: self._gui_server.notify(result, game_frame) return result diff --git a/utama_core/custom_referee/rules/keep_out_rule.py b/utama_core/custom_referee/rules/keep_out_rule.py index 549a9e51..514d33d6 100644 --- a/utama_core/custom_referee/rules/keep_out_rule.py +++ b/utama_core/custom_referee/rules/keep_out_rule.py @@ -3,7 +3,7 @@ from __future__ import annotations import math -from typing import Optional +from typing import Optional # used by BaseRule.check return type from utama_core.custom_referee.geometry import RefereeGeometry from utama_core.custom_referee.rules.base_rule import BaseRule, RuleViolation @@ -57,26 +57,19 @@ def check( return None bx, by = ball.p.x, ball.p.y - my_team_is_yellow = game_frame.my_team_is_yellow # Determine which team is the *kicking* team (they are exempt). - # During DIRECT_FREE_*, the kicking team is indicated by the command. - kicking_team_is_yellow = _kicking_team_is_yellow(current_command, my_team_is_yellow) + # current_command is always in _STOPPAGE_COMMANDS here, so + # kicking_team_is_yellow is always True or False (never None). + kicking_team_is_yellow = _kicking_team_is_yellow(current_command) # Check non-kicking team robots for encroachment. - encroaching = False - if kicking_team_is_yellow is None: - # STOP: both teams must stay back. - encroaching = self._any_robot_encroaching( - game_frame.friendly_robots.values(), bx, by - ) or self._any_robot_encroaching(game_frame.enemy_robots.values(), bx, by) - elif kicking_team_is_yellow == my_team_is_yellow: + if kicking_team_is_yellow == game_frame.my_team_is_yellow: # Friendly is kicking — check enemy only. encroaching = self._any_robot_encroaching(game_frame.enemy_robots.values(), bx, by) else: # Enemy is kicking — check friendly only. encroaching = self._any_robot_encroaching(game_frame.friendly_robots.values(), bx, by) - if encroaching: self._violation_count += 1 else: @@ -85,8 +78,6 @@ def check( if self._violation_count >= self._persistence: self._violation_count = 0 # Reset after issuing. # Award free kick to the kicking team (they get to retry). - # kicking_team_is_yellow is always True or False here because STOP - # is excluded from _STOPPAGE_COMMANDS above. if kicking_team_is_yellow: next_cmd = RefereeCommand.DIRECT_FREE_YELLOW else: @@ -107,18 +98,13 @@ def _any_robot_encroaching(self, robots, bx: float, by: float) -> bool: return any(math.hypot(r.p.x - bx, r.p.y - by) < self._radius for r in robots) -def _kicking_team_is_yellow(command: RefereeCommand, my_team_is_yellow: bool) -> Optional[bool]: - """Return True if the kicking team is yellow, False if blue, None if STOP (both stop).""" - if command in ( +def _kicking_team_is_yellow(command: RefereeCommand) -> bool: + """Return True if the kicking team is yellow, False if blue. + + Only called when command is in _STOPPAGE_COMMANDS, so STOP is never passed. + """ + return command in ( RefereeCommand.DIRECT_FREE_YELLOW, RefereeCommand.PREPARE_KICKOFF_YELLOW, RefereeCommand.PREPARE_PENALTY_YELLOW, - ): - return True - if command in ( - RefereeCommand.DIRECT_FREE_BLUE, - RefereeCommand.PREPARE_KICKOFF_BLUE, - RefereeCommand.PREPARE_PENALTY_BLUE, - ): - return False - return None # STOP — no kicking team + ) diff --git a/utama_core/data_processing/refiners/referee.py b/utama_core/data_processing/refiners/referee.py index 788a0042..25dfa44e 100644 --- a/utama_core/data_processing/refiners/referee.py +++ b/utama_core/data_processing/refiners/referee.py @@ -112,6 +112,14 @@ def next_command(self) -> Optional[RefereeCommand]: def current_action_time_remaining(self) -> Optional[int]: return self._referee_records[-1].current_action_time_remaining if self._referee_records else None + @property + def last_status_message(self) -> Optional[str]: + return self._referee_records[-1].status_message if self._referee_records else None + + @property + def last_next_command(self) -> Optional[RefereeCommand]: + return self._referee_records[-1].next_command if self._referee_records else None + @property def is_halt(self) -> bool: return self.last_command == RefereeCommand.HALT diff --git a/utama_core/entities/data/referee.py b/utama_core/entities/data/referee.py index b97b6c2a..bd2230a7 100644 --- a/utama_core/entities/data/referee.py +++ b/utama_core/entities/data/referee.py @@ -23,7 +23,7 @@ class RefereeData: stage_time_left: float blue_team: TeamInfo yellow_team: TeamInfo - designated_position: Optional[Tuple[float]] = None + designated_position: Optional[Tuple[float, float]] = None # Information about the direction of play. # True, if the blue team will have it's goal on the positive x-axis of the ssl-vision coordinate system. diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index 12699f78..139ff266 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -901,15 +901,13 @@ def _run_step(self): stage_secs = ref.stage_time_left stage_min = int(stage_secs // 60) stage_sec = int(stage_secs % 60) - last_ref = self.referee_refiner._referee_records[-1] if self.referee_refiner._referee_records else None - display = Text() display.append(f"FPS: {fps:.1f}", style="bold cyan") display.append(" | ") display.append(ref.last_command.name, style="bold yellow") - if last_ref and last_ref.next_command: + if ref.last_next_command: display.append(" -> ") - display.append(last_ref.next_command.name, style="yellow") + display.append(ref.last_next_command.name, style="yellow") display.append(" | ") display.append(ref.stage.name.replace("_", " ").title()) display.append(" | Blue ") @@ -925,8 +923,8 @@ def _run_step(self): display.append(self.custom_referee.profile_name, style="magenta") display.append(")") - if last_ref and last_ref.status_message: - display.append(f" | {last_ref.status_message}", style="dim") + if ref.last_status_message: + display.append(f" | {ref.last_status_message}", style="dim") self._fps_live.update(display) self._fps_live.refresh() diff --git a/utama_core/tests/strategy_runner/test_referee_rsim.py b/utama_core/tests/strategy_runner/test_referee_rsim.py index 83c4eda9..b3d19aa6 100644 --- a/utama_core/tests/strategy_runner/test_referee_rsim.py +++ b/utama_core/tests/strategy_runner/test_referee_rsim.py @@ -38,6 +38,7 @@ import py_trees +from utama_core.config.referee_constants import BALL_KEEP_OUT_DISTANCE from utama_core.custom_referee import CustomReferee from utama_core.entities.game import Game from utama_core.entities.game.field import Field, FieldBounds @@ -50,9 +51,6 @@ TestingStatus, ) -# SSL keep-out radius during opponent free kicks (must match referee_constants.py). -BALL_KEEP_OUT_DISTANCE = 0.55 - # --------------------------------------------------------------------------- # Minimal idle strategy — referee override tree handles all motion # --------------------------------------------------------------------------- From 9d6b8ea8b5bdef7f2c5ebaabe90b7d5a3cce3acb Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Tue, 14 Apr 2026 22:42:14 +0100 Subject: [PATCH 021/121] fix: stage_time_left now updates every frame in RefereeRefiner RefereeData.__eq__ excludes stage_time_left to avoid spurious re-records, so the deduplication in add_new_referee_data() was discarding every frame's updated countdown. The stage_time_left property was reading from the stale cached record, causing the terminal display to freeze (e.g. always showing 4:59). Fix: track _latest_stage_time_left independently in refine(), updated on every call before the dedup check, and return it from the stage_time_left property. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/data_processing/refiners/referee.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/utama_core/data_processing/refiners/referee.py b/utama_core/data_processing/refiners/referee.py index 25dfa44e..27700f61 100644 --- a/utama_core/data_processing/refiners/referee.py +++ b/utama_core/data_processing/refiners/referee.py @@ -11,6 +11,7 @@ class RefereeRefiner(BaseRefiner): def __init__(self): self._referee_records = [] + self._latest_stage_time_left: float = 0.0 def refine(self, game_frame, data: Optional[RefereeData]): """Process referee data and update the game frame. @@ -25,6 +26,9 @@ def refine(self, game_frame, data: Optional[RefereeData]): if data is None: return game_frame + # Always track the latest countdown, even when deduplication skips the record + self._latest_stage_time_left = data.stage_time_left + # Add to history self.add_new_referee_data(data) @@ -60,7 +64,7 @@ def stage(self) -> Stage: @property def stage_time_left(self) -> float: - return self._referee_records[-1].stage_time_left if self._referee_records else 0.0 + return self._latest_stage_time_left @property def blue_team(self) -> TeamInfo: From 6c265abbfd8a9ae9afad83171e4d75462176935e Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Tue, 14 Apr 2026 23:14:33 +0100 Subject: [PATCH 022/121] fix: increase BALL_KEEP_OUT_DISTANCE to 0.8 m to prevent restart violation loop Action nodes were parking robots at 0.55 m from the ball while the KeepOutRule fires at < 0.5 m. A small ball nudge during restart would put defending robots inside the rule threshold, triggering another STOP and looping indefinitely. Increasing the action node clearance to 0.8 m gives enough buffer to absorb positioning inaccuracy. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/config/referee_constants.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/utama_core/config/referee_constants.py b/utama_core/config/referee_constants.py index 9d7309d2..15ffab76 100644 --- a/utama_core/config/referee_constants.py +++ b/utama_core/config/referee_constants.py @@ -1,6 +1,6 @@ from utama_core.entities.game.field import Field -BALL_KEEP_OUT_DISTANCE = 0.55 +BALL_KEEP_OUT_DISTANCE = 0.8 BALL_PLACEMENT_DONE_DISTANCE = 0.15 OPPONENT_DEFENSE_AREA_KEEP_DISTANCE = 0.25 PENALTY_BEHIND_MARK_DISTANCE = 0.4 From 2040685e7d2d841423760a1ad4f95d9f0cb80056 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 15 Apr 2026 00:09:30 +0100 Subject: [PATCH 023/121] fix: adapt referee code to FieldDimensions API and arbitrary field sizes MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Replace from_field_bounds with from_field_dims in RefereeGeometry so goal/defense dimensions scale with the actual field, not hardcoded to STANDARD_FIELD_DIMS - Fix Vector3D→Vector2D conversions in actions.py for fpp controller compatibility (DirectFreeOursStep, BallPlacementOursStep) - Rename get_min_bounding_zone→get_min_bounding_req in point_cycle_strategy and wandering_strategy to match abstract base class - Update test fixtures to use new Field(field_dims=...) constructor and correct BALL_KEEP_OUT_DISTANCE (0.8 m) Co-Authored-By: Claude Sonnet 4.6 --- utama_core/config/referee_constants.py | 26 +++---- utama_core/custom_referee/geometry.py | 37 ++++++---- .../strategy/examples/point_cycle_strategy.py | 2 +- utama_core/strategy/referee/actions.py | 55 ++++++++++++--- utama_core/tests/referee/test_referee_unit.py | 67 +++++++++++++------ .../tests/referee/wandering_strategy.py | 2 +- .../strategy_runner/test_referee_rsim.py | 8 +-- 7 files changed, 132 insertions(+), 65 deletions(-) diff --git a/utama_core/config/referee_constants.py b/utama_core/config/referee_constants.py index 15ffab76..beafc5ae 100644 --- a/utama_core/config/referee_constants.py +++ b/utama_core/config/referee_constants.py @@ -1,4 +1,4 @@ -from utama_core.entities.game.field import Field +from utama_core.config.field_params import STANDARD_FIELD_DIMS BALL_KEEP_OUT_DISTANCE = 0.8 BALL_PLACEMENT_DONE_DISTANCE = 0.15 @@ -7,21 +7,21 @@ PENALTY_MARK_HALF_FIELD_RATIO = 0.5 CLEARANCE_FALLBACK_DIRECTION = (1.0, 0.0) -PENALTY_LINE_Y_STEP_RATIO = 0.35 / Field.FULL_FIELD_HALF_WIDTH +PENALTY_LINE_Y_STEP_RATIO = 0.35 / STANDARD_FIELD_DIMS.full_field_half_width KICKOFF_SUPPORT_POSITION_RATIOS_OWN_HALF = ( - (0.8 / Field.FULL_FIELD_HALF_LENGTH, 0.5 / Field.FULL_FIELD_HALF_WIDTH), - (0.8 / Field.FULL_FIELD_HALF_LENGTH, -0.5 / Field.FULL_FIELD_HALF_WIDTH), - (1.5 / Field.FULL_FIELD_HALF_LENGTH, 0.8 / Field.FULL_FIELD_HALF_WIDTH), - (1.5 / Field.FULL_FIELD_HALF_LENGTH, -0.8 / Field.FULL_FIELD_HALF_WIDTH), - (2.5 / Field.FULL_FIELD_HALF_LENGTH, 0.0), + (0.8 / STANDARD_FIELD_DIMS.full_field_half_length, 0.5 / STANDARD_FIELD_DIMS.full_field_half_width), + (0.8 / STANDARD_FIELD_DIMS.full_field_half_length, -0.5 / STANDARD_FIELD_DIMS.full_field_half_width), + (1.5 / STANDARD_FIELD_DIMS.full_field_half_length, 0.8 / STANDARD_FIELD_DIMS.full_field_half_width), + (1.5 / STANDARD_FIELD_DIMS.full_field_half_length, -0.8 / STANDARD_FIELD_DIMS.full_field_half_width), + (2.5 / STANDARD_FIELD_DIMS.full_field_half_length, 0.0), ) KICKOFF_DEFENCE_POSITION_RATIOS_OWN_HALF = ( - (0.8 / Field.FULL_FIELD_HALF_LENGTH, 0.4 / Field.FULL_FIELD_HALF_WIDTH), - (0.8 / Field.FULL_FIELD_HALF_LENGTH, -0.4 / Field.FULL_FIELD_HALF_WIDTH), - (1.5 / Field.FULL_FIELD_HALF_LENGTH, 0.6 / Field.FULL_FIELD_HALF_WIDTH), - (1.5 / Field.FULL_FIELD_HALF_LENGTH, -0.6 / Field.FULL_FIELD_HALF_WIDTH), - (2.5 / Field.FULL_FIELD_HALF_LENGTH, 0.0), - (1.5 / Field.FULL_FIELD_HALF_LENGTH, 0.0), + (0.8 / STANDARD_FIELD_DIMS.full_field_half_length, 0.4 / STANDARD_FIELD_DIMS.full_field_half_width), + (0.8 / STANDARD_FIELD_DIMS.full_field_half_length, -0.4 / STANDARD_FIELD_DIMS.full_field_half_width), + (1.5 / STANDARD_FIELD_DIMS.full_field_half_length, 0.6 / STANDARD_FIELD_DIMS.full_field_half_width), + (1.5 / STANDARD_FIELD_DIMS.full_field_half_length, -0.6 / STANDARD_FIELD_DIMS.full_field_half_width), + (2.5 / STANDARD_FIELD_DIMS.full_field_half_length, 0.0), + (1.5 / STANDARD_FIELD_DIMS.full_field_half_length, 0.0), ) diff --git a/utama_core/custom_referee/geometry.py b/utama_core/custom_referee/geometry.py index fa9a25cb..572793ef 100644 --- a/utama_core/custom_referee/geometry.py +++ b/utama_core/custom_referee/geometry.py @@ -2,7 +2,11 @@ from dataclasses import dataclass -from utama_core.entities.game.field import Field, FieldBounds +from utama_core.config.field_params import ( + STANDARD_FIELD_DIMS, + FieldBounds, + FieldDimensions, +) @dataclass(frozen=True) @@ -24,25 +28,32 @@ class RefereeGeometry: def from_standard_div_b(cls) -> "RefereeGeometry": """Return geometry matching the standard SSL Division B field.""" return cls( - half_length=Field.FULL_FIELD_HALF_LENGTH, # 4.5 - half_width=Field.FULL_FIELD_HALF_WIDTH, # 3.0 - half_goal_width=Field.HALF_GOAL_WIDTH, # 0.5 - half_defense_length=Field.HALF_DEFENSE_AREA_LENGTH, # 0.5 - half_defense_width=Field.HALF_DEFENSE_AREA_WIDTH, # 1.0 + half_length=STANDARD_FIELD_DIMS.full_field_half_length, # 4.5 + half_width=STANDARD_FIELD_DIMS.full_field_half_width, # 3.0 + half_goal_width=STANDARD_FIELD_DIMS.half_goal_width, # 0.5 + half_defense_length=STANDARD_FIELD_DIMS.half_defense_area_depth, # 0.5 + half_defense_width=STANDARD_FIELD_DIMS.half_defense_area_width, # 1.0 center_circle_radius=0.5, ) @classmethod - def from_field_bounds(cls, field_bounds: FieldBounds) -> "RefereeGeometry": - """Derive half_length/width from a FieldBounds; use Field constants for the rest.""" - half_length = (field_bounds.bottom_right[0] - field_bounds.top_left[0]) / 2.0 - half_width = (field_bounds.top_left[1] - field_bounds.bottom_right[1]) / 2.0 + def from_field_dims(cls, field_dims: FieldDimensions, field_bounds: FieldBounds | None = None) -> "RefereeGeometry": + """Build geometry from a FieldDimensions instance. + + If field_bounds is provided (e.g. a sub-field play area), half_length and + half_width are derived from it; otherwise the full field extents are used. + All goal/defense dimensions are taken from field_dims so that non-standard + field sizes are fully supported. + """ + bounds = field_bounds or field_dims.full_field_bounds + half_length = (bounds.bottom_right[0] - bounds.top_left[0]) / 2.0 + half_width = (bounds.top_left[1] - bounds.bottom_right[1]) / 2.0 return cls( half_length=half_length, half_width=half_width, - half_goal_width=Field.HALF_GOAL_WIDTH, - half_defense_length=Field.HALF_DEFENSE_AREA_LENGTH, - half_defense_width=Field.HALF_DEFENSE_AREA_WIDTH, + half_goal_width=field_dims.half_goal_width, + half_defense_length=field_dims.half_defense_area_depth, + half_defense_width=field_dims.half_defense_area_width, center_circle_radius=0.5, ) diff --git a/utama_core/strategy/examples/point_cycle_strategy.py b/utama_core/strategy/examples/point_cycle_strategy.py index 0b725616..26eb8317 100644 --- a/utama_core/strategy/examples/point_cycle_strategy.py +++ b/utama_core/strategy/examples/point_cycle_strategy.py @@ -125,7 +125,7 @@ def assert_exp_robots(self, n_runtime_friendly: int, n_runtime_enemy: int): def assert_exp_goals(self, includes_my_goal_line: bool, includes_opp_goal_line: bool): return True - def get_min_bounding_zone(self) -> Optional[FieldBounds]: + def get_min_bounding_req(self) -> Optional[FieldBounds]: """Return the movement bounds.""" return self.field_bounds diff --git a/utama_core/strategy/referee/actions.py b/utama_core/strategy/referee/actions.py index 05a651b2..522e9530 100644 --- a/utama_core/strategy/referee/actions.py +++ b/utama_core/strategy/referee/actions.py @@ -26,7 +26,6 @@ PENALTY_MARK_HALF_FIELD_RATIO, ) from utama_core.entities.data.vector import Vector2D -from utama_core.entities.game.field import Field from utama_core.entities.referee.referee_command import RefereeCommand from utama_core.skills.src.utils.move_utils import empty_command, move from utama_core.strategy.common.abstract_behaviour import AbstractBehaviour @@ -68,7 +67,7 @@ def _scaled_position(game, x_ratio: float, y_ratio: float) -> Vector2D: def _ensure_outside_center_circle(target: Vector2D) -> Vector2D: """Project kickoff support points to the centre-circle boundary when needed.""" dist = math.hypot(target.x, target.y) - keep_radius = Field.CENTER_CIRCLE_RADIUS + keep_radius = 0.5 # standard SSL centre-circle radius if dist == 0.0 or dist >= keep_radius: return target scale = keep_radius / dist @@ -97,12 +96,23 @@ def _project_outside_circle(point: Vector2D, center: Vector2D, keep_dist: float) return Vector2D(center.x + offset.x * scale, center.y + offset.y * scale) +def _clamp_to_field(point: Vector2D, game) -> Vector2D: + """Clamp a position to within the field boundaries with a small inset margin.""" + margin = 0.1 + half_length = _field_half_length(game) - margin + half_width = _field_half_width(game) - margin + return Vector2D( + max(-half_length, min(half_length, point.x)), + max(-half_width, min(half_width, point.y)), + ) + + def _project_outside_opp_defense_area(game, point: Vector2D, keep_dist: float) -> Vector2D: """Project a point out of the opponent defense area plus the required keep distance.""" field_half_length = _field_half_length(game) opp_goal_sign = -1.0 if game.my_team_is_right else 1.0 - defense_width = Field.HALF_DEFENSE_AREA_WIDTH + keep_dist - defense_inner_x = opp_goal_sign * (field_half_length - 2.0 * Field.HALF_DEFENSE_AREA_LENGTH) + defense_width = game.field.half_defense_area_width + keep_dist + defense_inner_x = opp_goal_sign * (field_half_length - 2.0 * game.field.half_defense_area_depth) safe_x = defense_inner_x - opp_goal_sign * keep_dist if abs(point.y) > defense_width: @@ -152,6 +162,8 @@ def _clear_to_legal_positions( if clear_opp_defense_area: target = _project_outside_opp_defense_area(game, target, OPPONENT_DEFENSE_AREA_KEEP_DISTANCE) + target = _clamp_to_field(target, game) + if target == robot.p: blackboard.cmd_map[robot_id] = empty_command(False) continue @@ -241,7 +253,7 @@ def update(self) -> py_trees.common.Status: if robot.has_ball: target_for_move = target_pos else: - target_for_move = ball.p + target_for_move = Vector2D(ball.p.x, ball.p.y) oren = robot.p.angle_to(target_for_move) self.blackboard.cmd_map[robot_id] = move( game, motion_controller, robot_id, target_for_move, oren, dribbling=True @@ -325,7 +337,10 @@ def update(self) -> py_trees.common.Status: pos = positions[idx % len(positions)] self.blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, pos, 0.0) - return py_trees.common.Status.RUNNING + return _clear_to_legal_positions( + self.blackboard, + ball_keep_dist=BALL_KEEP_OUT_DISTANCE, + ) # --------------------------------------------------------------------------- @@ -436,11 +451,14 @@ def update(self) -> py_trees.common.Status: class DirectFreeOursStep(AbstractBehaviour): """Positions our robots for our direct free kick. - The robot closest to the ball becomes the kicker and drives toward the ball. - All other robots stop in place (they may be repositioned by the strategy tree - after NORMAL_START transitions the override layer to pass-through). + The robot closest to the ball becomes the kicker and approaches from the + field-inward side so it cannot push the ball out of bounds. + All other robots stop in place. """ + # How far infield from the ball the approach point is placed + _APPROACH_OFFSET = 0.15 + def update(self) -> py_trees.common.Status: game = self.blackboard.game motion_controller = self.blackboard.motion_controller @@ -454,8 +472,23 @@ def update(self) -> py_trees.common.Status: for robot_id in game.friendly_robots: if robot_id == kicker_id and ball: robot = game.friendly_robots[robot_id] - oren = robot.p.angle_to(ball.p) - self.blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, ball.p, oren) + ball_pos = Vector2D(ball.p.x, ball.p.y) + + # Compute an approach point offset inward from the nearest boundary, + # so the robot never drives through the ball toward the edge. + half_length = _field_half_length(game) + half_width = _field_half_width(game) + # Inward direction: push away from whichever boundary is closest + offset_x = 0.0 + offset_y = 0.0 + if abs(ball_pos.x) > half_length - 0.5: + offset_x = self._APPROACH_OFFSET * (-1.0 if ball_pos.x > 0 else 1.0) + if abs(ball_pos.y) > half_width - 0.5: + offset_y = self._APPROACH_OFFSET * (-1.0 if ball_pos.y > 0 else 1.0) + + approach = Vector2D(ball_pos.x + offset_x, ball_pos.y + offset_y) + oren = robot.p.angle_to(approach) + self.blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, approach, oren) else: self.blackboard.cmd_map[robot_id] = empty_command(False) diff --git a/utama_core/tests/referee/test_referee_unit.py b/utama_core/tests/referee/test_referee_unit.py index bb436360..95f0ed3f 100644 --- a/utama_core/tests/referee/test_referee_unit.py +++ b/utama_core/tests/referee/test_referee_unit.py @@ -14,6 +14,7 @@ import py_trees import pytest +from utama_core.config.field_params import STANDARD_FIELD_DIMS from utama_core.data_processing.refiners.referee import RefereeRefiner from utama_core.entities.data.referee import RefereeData from utama_core.entities.data.vector import Vector2D, Vector3D @@ -105,14 +106,14 @@ def _make_game( referee=None, my_team_is_yellow: bool = True, my_team_is_right: bool = True, - field_bounds: FieldBounds = Field.FULL_FIELD_BOUNDS, + field_bounds: FieldBounds = STANDARD_FIELD_DIMS.full_field_bounds, ) -> Game: frame = _make_game_frame(friendly_robots, referee, my_team_is_yellow, my_team_is_right) history = GameHistory(10) return Game( past=history, current=frame, - field=Field(my_team_is_right=my_team_is_right, field_bounds=field_bounds), + field=Field(my_team_is_right=my_team_is_right, field_dims=STANDARD_FIELD_DIMS, field_bounds=field_bounds), ) @@ -428,7 +429,11 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri game = Game( past=GameHistory(10), current=frame, - field=Field(my_team_is_right=True, field_bounds=Field.FULL_FIELD_BOUNDS), + field=Field( + my_team_is_right=True, + field_dims=STANDARD_FIELD_DIMS, + field_bounds=STANDARD_FIELD_DIMS.full_field_bounds, + ), ) cmd_map = _make_cmd_map(game) @@ -482,7 +487,11 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri game = Game( past=GameHistory(10), current=frame, - field=Field(my_team_is_right=True, field_bounds=Field.FULL_FIELD_BOUNDS), + field=Field( + my_team_is_right=True, + field_dims=STANDARD_FIELD_DIMS, + field_bounds=STANDARD_FIELD_DIMS.full_field_bounds, + ), ) cmd_map = _make_cmd_map(game) @@ -525,8 +534,8 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri assert len(captured) == 2 placer_move = next(item for item in captured if item[0] == 0) support_move = next(item for item in captured if item[0] == 1) - assert placer_move[1] == game.ball.p - assert support_move[1] == Vector2D(0.55, 0.0) + assert placer_move[1] == Vector2D(game.ball.p.x, game.ball.p.y) + assert support_move[1] == Vector2D(0.8, 0.0) assert support_move[2] is False @@ -561,7 +570,7 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri assert status == py_trees.common.Status.RUNNING assert len(captured) == 1 assert captured[0][0] == 0 - assert captured[0][1] == Vector2D(0.55, 0.0) + assert captured[0][1] == Vector2D(0.8, 0.0) assert cmd_map[1] is not None def test_stop_clears_robot_from_opponent_defense_area(self, monkeypatch): @@ -592,7 +601,11 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri game = Game( past=GameHistory(10), current=frame, - field=Field(my_team_is_right=True, field_bounds=Field.FULL_FIELD_BOUNDS), + field=Field( + my_team_is_right=True, + field_dims=STANDARD_FIELD_DIMS, + field_bounds=STANDARD_FIELD_DIMS.full_field_bounds, + ), ) cmd_map = _make_cmd_map(game) node = referee_actions.StopStep(name="Stop") @@ -631,7 +644,7 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri assert status == py_trees.common.Status.RUNNING assert len(captured) == 1 assert captured[0][0] == 0 - assert captured[0][1] == Vector2D(0.55, 0.0) + assert captured[0][1] == Vector2D(0.8, 0.0) def test_ball_placement_theirs_clears_robot_from_designated_position(self, monkeypatch): from utama_core.strategy.referee import actions as referee_actions @@ -662,7 +675,11 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri game = Game( past=GameHistory(10), current=frame, - field=Field(my_team_is_right=True, field_bounds=Field.FULL_FIELD_BOUNDS), + field=Field( + my_team_is_right=True, + field_dims=STANDARD_FIELD_DIMS, + field_bounds=STANDARD_FIELD_DIMS.full_field_bounds, + ), ) cmd_map = _make_cmd_map(game) node = referee_actions.BallPlacementTheirsStep(name="BallPlacementTheirs") @@ -673,7 +690,7 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri assert status == py_trees.common.Status.RUNNING assert len(captured) == 1 assert captured[0][0] == 0 - assert captured[0][1] == Vector2D(1.55, 1.0) + assert captured[0][1] == Vector2D(1.8, 1.0) def test_direct_free_theirs_clears_encroaching_robot(self, monkeypatch): from utama_core.strategy.referee import actions as referee_actions @@ -701,7 +718,7 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri assert status == py_trees.common.Status.RUNNING assert len(captured) == 1 assert captured[0][0] == 0 - assert captured[0][1] == Vector2D(0.55, 0.0) + assert captured[0][1] == Vector2D(0.8, 0.0) class TestPenaltyPositioning: @@ -802,7 +819,7 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri assert status == py_trees.common.Status.RUNNING assert first_support_target.x == pytest.approx(6.0 * (0.8 / 4.5)) assert first_support_target.y == pytest.approx(4.0 * (0.5 / 3.0)) - assert first_support_target.distance_to(Vector2D(0.0, 0.0)) >= Field.CENTER_CIRCLE_RADIUS + assert first_support_target.distance_to(Vector2D(0.0, 0.0)) >= 0.5 def test_prepare_kickoff_ours_uses_own_half_when_defending_left(self, monkeypatch): from utama_core.strategy.referee import actions as referee_actions @@ -837,7 +854,7 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri assert status == py_trees.common.Status.RUNNING assert first_support_target.x == pytest.approx(-6.0 * (0.8 / 4.5)) - assert first_support_target.distance_to(Vector2D(0.0, 0.0)) >= Field.CENTER_CIRCLE_RADIUS + assert first_support_target.distance_to(Vector2D(0.0, 0.0)) >= 0.5 def test_prepare_penalty_ours_scales_penalty_mark_with_field_bounds(self, monkeypatch): from utama_core.strategy.referee import actions as referee_actions @@ -1139,7 +1156,7 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri for _, target in captured: dist = target.distance_to(Vector2D(0.0, 0.0)) - assert dist >= Field.CENTER_CIRCLE_RADIUS, f"Target {target} inside centre circle" + assert dist >= 0.5, f"Target {target} inside centre circle" def test_scales_with_custom_field_bounds(self, monkeypatch): from utama_core.strategy.referee import actions as referee_actions @@ -1171,7 +1188,7 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri # Positions must be on own half and outside centre circle for _, target in captured: assert target.x > 0.0 - assert target.distance_to(Vector2D(0.0, 0.0)) >= Field.CENTER_CIRCLE_RADIUS + assert target.distance_to(Vector2D(0.0, 0.0)) >= 0.5 # --------------------------------------------------------------------------- @@ -1222,7 +1239,11 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri game = Game( past=GameHistory(10), current=frame, - field=Field(my_team_is_right=True, field_bounds=Field.FULL_FIELD_BOUNDS), + field=Field( + my_team_is_right=True, + field_dims=STANDARD_FIELD_DIMS, + field_bounds=STANDARD_FIELD_DIMS.full_field_bounds, + ), ) cmd_map = _make_cmd_map(game) node = referee_actions.DirectFreeOursStep(name="DirectFreeOurs") @@ -1259,7 +1280,11 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri game = Game( past=GameHistory(10), current=frame, - field=Field(my_team_is_right=True, field_bounds=Field.FULL_FIELD_BOUNDS), + field=Field( + my_team_is_right=True, + field_dims=STANDARD_FIELD_DIMS, + field_bounds=STANDARD_FIELD_DIMS.full_field_bounds, + ), ) cmd_map = _make_cmd_map(game) node = referee_actions.DirectFreeOursStep(name="DirectFreeOurs") @@ -1346,7 +1371,7 @@ def test_robot_outside_keep_out_stays_put(self, monkeypatch): monkeypatch.setattr(referee_actions, "move", lambda *a, **kw: ("move",)) - robots = {0: _robot(0, 2.0, 0.0)} # well outside 0.55 m from ball at (0,0) + robots = {0: _robot(0, 2.0, 0.0)} # well outside 0.8 m from ball at (0,0) referee = _make_referee_data(command=RefereeCommand.DIRECT_FREE_BLUE) game = _make_game(friendly_robots=robots, referee=referee) cmd_map = _make_cmd_map(game) @@ -1400,7 +1425,7 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri monkeypatch.setattr(referee_actions, "move", fake_move) - # Ball at origin; robot dead on the x-axis at 0.3 m (inside 0.55) + # Ball at origin; robot dead on the x-axis at 0.3 m (inside 0.8) robots = {0: _robot(0, 0.3, 0.0)} referee = _make_referee_data(command=RefereeCommand.DIRECT_FREE_BLUE) game = _make_game(friendly_robots=robots, referee=referee) @@ -1411,7 +1436,7 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri node.update() assert len(captured) == 1 - assert captured[0][1] == pytest.approx(Vector2D(0.55, 0.0)) + assert captured[0][1] == pytest.approx(Vector2D(0.8, 0.0)) def test_all_robots_get_commands(self, monkeypatch): from utama_core.strategy.referee import actions as referee_actions diff --git a/utama_core/tests/referee/wandering_strategy.py b/utama_core/tests/referee/wandering_strategy.py index 3680aa39..225a7f43 100644 --- a/utama_core/tests/referee/wandering_strategy.py +++ b/utama_core/tests/referee/wandering_strategy.py @@ -110,7 +110,7 @@ def assert_exp_robots(self, n_runtime_friendly: int, n_runtime_enemy: int) -> bo def assert_exp_goals(self, includes_my_goal_line: bool, includes_opp_goal_line: bool) -> bool: return True - def get_min_bounding_zone(self): + def get_min_bounding_req(self): return None def create_behaviour_tree(self) -> py_trees.behaviour.Behaviour: diff --git a/utama_core/tests/strategy_runner/test_referee_rsim.py b/utama_core/tests/strategy_runner/test_referee_rsim.py index b3d19aa6..3db63184 100644 --- a/utama_core/tests/strategy_runner/test_referee_rsim.py +++ b/utama_core/tests/strategy_runner/test_referee_rsim.py @@ -41,7 +41,7 @@ from utama_core.config.referee_constants import BALL_KEEP_OUT_DISTANCE from utama_core.custom_referee import CustomReferee from utama_core.entities.game import Game -from utama_core.entities.game.field import Field, FieldBounds +from utama_core.entities.game.field import FieldBounds from utama_core.entities.referee.referee_command import RefereeCommand from utama_core.run.strategy_runner import StrategyRunner from utama_core.strategy.common.abstract_strategy import AbstractStrategy @@ -83,7 +83,7 @@ def assert_exp_robots(self, n_runtime_friendly: int, n_runtime_enemy: int) -> bo def assert_exp_goals(self, includes_my_goal_line: bool, includes_opp_goal_line: bool) -> bool: return True - def get_min_bounding_zone(self) -> Optional[FieldBounds]: + def get_min_bounding_req(self) -> Optional[FieldBounds]: return None @@ -364,9 +364,7 @@ def eval_status(self, game: Game) -> TestingStatus: kicker_ok = kicker is not None and kicker.p.x <= 0.2 supports_on_half = all(r.p.x <= self.POSITION_TOLERANCE for r in support_robots) - supports_outside_circle = all( - math.hypot(r.p.x, r.p.y) >= Field.CENTER_CIRCLE_RADIUS - self.POSITION_TOLERANCE for r in support_robots - ) + supports_outside_circle = all(math.hypot(r.p.x, r.p.y) >= 0.5 - self.POSITION_TOLERANCE for r in support_robots) if kicker_ok and supports_on_half and supports_outside_circle: self.success_frame_count += 1 From 3d170b831ef8d7bdc4f7209d426beb8037412e78 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 15 Apr 2026 00:41:35 +0100 Subject: [PATCH 024/121] fix: use own-half fallback direction when robot is coincident with ball _project_outside_circle was using a hardcoded (1, 0) fallback when a robot sits exactly on the obstruction center (dist == 0), pushing it to positive-x regardless of which half the team defends. Now _clear_to_legal_ positions passes an own-half-aware fallback so coincident robots are always cleared toward their correct side. Also fix test_all_robots_placed_on_own_half_* to track final target per robot (dict keyed by robot_id) rather than a flat list, so the count assertion is robust against the clearing pass re-issuing a move command. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/strategy/referee/actions.py | 17 +++++++++++++---- utama_core/tests/referee/test_referee_unit.py | 12 ++++++------ 2 files changed, 19 insertions(+), 10 deletions(-) diff --git a/utama_core/strategy/referee/actions.py b/utama_core/strategy/referee/actions.py index 522e9530..cbac6e18 100644 --- a/utama_core/strategy/referee/actions.py +++ b/utama_core/strategy/referee/actions.py @@ -83,14 +83,19 @@ def _formation_positions(game, ratios: tuple[tuple[float, float], ...]) -> list[ return positions -def _project_outside_circle(point: Vector2D, center: Vector2D, keep_dist: float) -> Vector2D: +def _project_outside_circle( + point: Vector2D, + center: Vector2D, + keep_dist: float, + fallback_direction: tuple[float, float] = CLEARANCE_FALLBACK_DIRECTION, +) -> Vector2D: """Project a point to the circle boundary if it lies inside the keep-out radius.""" offset = point - center dist = offset.mag() if dist >= keep_dist: return point if dist == 0.0: - ux, uy = CLEARANCE_FALLBACK_DIRECTION + ux, uy = fallback_direction return Vector2D(center.x + ux * keep_dist, center.y + uy * keep_dist) scale = keep_dist / dist return Vector2D(center.x + offset.x * scale, center.y + offset.y * scale) @@ -150,15 +155,19 @@ def _clear_to_legal_positions( if designated_keep_dist is not None and ref is not None and ref.designated_position is not None: designated_center = Vector2D(ref.designated_position[0], ref.designated_position[1]) + # When a robot is exactly coincident with the obstruction, push it toward own half. + own_half_sign = 1.0 if game.my_team_is_right else -1.0 + own_half_fallback = (own_half_sign, 0.0) + for robot_id, robot in game.friendly_robots.items(): if robot_id in exempt_robot_ids: continue target = Vector2D(robot.p.x, robot.p.y) if ball_center is not None: - target = _project_outside_circle(target, ball_center, ball_keep_dist) + target = _project_outside_circle(target, ball_center, ball_keep_dist, own_half_fallback) if designated_center is not None: - target = _project_outside_circle(target, designated_center, designated_keep_dist) + target = _project_outside_circle(target, designated_center, designated_keep_dist, own_half_fallback) if clear_opp_defense_area: target = _project_outside_opp_defense_area(game, target, OPPONENT_DEFENSE_AREA_KEEP_DISTANCE) diff --git a/utama_core/tests/referee/test_referee_unit.py b/utama_core/tests/referee/test_referee_unit.py index 95f0ed3f..ce99eb69 100644 --- a/utama_core/tests/referee/test_referee_unit.py +++ b/utama_core/tests/referee/test_referee_unit.py @@ -1087,10 +1087,10 @@ def test_returns_running(self, monkeypatch): def test_all_robots_placed_on_own_half_right(self, monkeypatch): from utama_core.strategy.referee import actions as referee_actions - captured = [] + captured = {} def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): - captured.append((robot_id, target_coords)) + captured[robot_id] = target_coords return ("move", robot_id) monkeypatch.setattr(referee_actions, "move", fake_move) @@ -1106,16 +1106,16 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri node.update() assert len(captured) == 3 - for _, target in captured: + for _, target in captured.items(): assert target.x > 0.0, f"Expected positive-x (own half right), got {target}" def test_all_robots_placed_on_own_half_left(self, monkeypatch): from utama_core.strategy.referee import actions as referee_actions - captured = [] + captured = {} def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dribbling=False): - captured.append((robot_id, target_coords)) + captured[robot_id] = target_coords return ("move", robot_id) monkeypatch.setattr(referee_actions, "move", fake_move) @@ -1131,7 +1131,7 @@ def fake_move(game, motion_controller, robot_id, target_coords, target_oren, dri node.update() assert len(captured) == 3 - for _, target in captured: + for _, target in captured.items(): assert target.x < 0.0, f"Expected negative-x (own half left), got {target}" def test_positions_outside_centre_circle(self, monkeypatch): From 04288e58ded0e7ef33acbe4f9b10066d79c4fb45 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 15 Apr 2026 00:52:31 +0100 Subject: [PATCH 025/121] feat: make StrategyRunner the single source of truth for referee geometry Add CustomReferee.override_geometry() to replace geometry on both the referee and its internal state machine. StrategyRunner now calls this immediately after resolving field_bounds, so the custom referee always uses the actual full_field_dims + field_bounds rather than the standard- field values baked into the YAML profile. The YAML geometry block is preserved as a fallback for standalone CustomReferee use outside of StrategyRunner. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/custom_referee/custom_referee.py | 10 ++++++++++ utama_core/run/strategy_runner.py | 10 ++++++++++ 2 files changed, 20 insertions(+) diff --git a/utama_core/custom_referee/custom_referee.py b/utama_core/custom_referee/custom_referee.py index 79c666e3..42862342 100644 --- a/utama_core/custom_referee/custom_referee.py +++ b/utama_core/custom_referee/custom_referee.py @@ -161,6 +161,16 @@ def set_command(self, command: RefereeCommand, timestamp: float) -> None: # Properties (read-only access for callers that need to inspect state) # ------------------------------------------------------------------ + def override_geometry(self, geometry: RefereeGeometry) -> None: + """Replace the active field geometry on both the referee and the state machine. + + Called by StrategyRunner to ensure the referee's geometry always matches + the actual field dims/bounds in use, regardless of what the YAML profile + specifies. + """ + self._geometry = geometry + self._state._geometry = geometry + @property def geometry(self) -> RefereeGeometry: return self._geometry diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index ea44cdca..626de28f 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -173,6 +173,16 @@ def __init__( self.field_bounds = field_bounds if field_bounds else full_field_dims.full_field_bounds self.referee_system = self._resolve_referee_system(self.mode, referee_system, custom_referee) + # Ensure the custom referee's geometry matches the actual field in use. + # The YAML profile geometry is the fallback for standalone use; here + # full_field_dims + field_bounds is the single source of truth. + if self.referee_system == "custom" and self.custom_referee is not None: + from utama_core.custom_referee.geometry import RefereeGeometry + + self.custom_referee.override_geometry( + RefereeGeometry.from_field_dims(self.full_field_dims, self.field_bounds) + ) + self.vision_buffers, self.ref_buffer = self._setup_vision_and_referee() assert_valid_bounding_box( From fe1c490ad5360b4894b33a5fd0b743ada9bb0ec1 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 15 Apr 2026 00:53:56 +0100 Subject: [PATCH 026/121] refactor: remove RefereeGeometry.from_standard_div_b() from_field_dims(STANDARD_FIELD_DIMS) is the direct equivalent and makes the standard-field case no more special than any other. Update the test fixture accordingly. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/custom_referee/geometry.py | 18 +----------------- .../custom_referee/test_custom_referee.py | 3 ++- 2 files changed, 3 insertions(+), 18 deletions(-) diff --git a/utama_core/custom_referee/geometry.py b/utama_core/custom_referee/geometry.py index 572793ef..4fa7ecd6 100644 --- a/utama_core/custom_referee/geometry.py +++ b/utama_core/custom_referee/geometry.py @@ -2,11 +2,7 @@ from dataclasses import dataclass -from utama_core.config.field_params import ( - STANDARD_FIELD_DIMS, - FieldBounds, - FieldDimensions, -) +from utama_core.config.field_params import FieldBounds, FieldDimensions @dataclass(frozen=True) @@ -24,18 +20,6 @@ class RefereeGeometry: half_defense_width: float center_circle_radius: float - @classmethod - def from_standard_div_b(cls) -> "RefereeGeometry": - """Return geometry matching the standard SSL Division B field.""" - return cls( - half_length=STANDARD_FIELD_DIMS.full_field_half_length, # 4.5 - half_width=STANDARD_FIELD_DIMS.full_field_half_width, # 3.0 - half_goal_width=STANDARD_FIELD_DIMS.half_goal_width, # 0.5 - half_defense_length=STANDARD_FIELD_DIMS.half_defense_area_depth, # 0.5 - half_defense_width=STANDARD_FIELD_DIMS.half_defense_area_width, # 1.0 - center_circle_radius=0.5, - ) - @classmethod def from_field_dims(cls, field_dims: FieldDimensions, field_bounds: FieldBounds | None = None) -> "RefereeGeometry": """Build geometry from a FieldDimensions instance. diff --git a/utama_core/tests/custom_referee/test_custom_referee.py b/utama_core/tests/custom_referee/test_custom_referee.py index c7191c08..2daf7aad 100644 --- a/utama_core/tests/custom_referee/test_custom_referee.py +++ b/utama_core/tests/custom_referee/test_custom_referee.py @@ -7,6 +7,7 @@ import pytest +from utama_core.config.field_params import STANDARD_FIELD_DIMS from utama_core.custom_referee.custom_referee import CustomReferee from utama_core.custom_referee.geometry import RefereeGeometry from utama_core.custom_referee.profiles.profile_loader import load_profile @@ -27,7 +28,7 @@ # Helpers # --------------------------------------------------------------------------- -GEO = RefereeGeometry.from_standard_div_b() +GEO = RefereeGeometry.from_field_dims(STANDARD_FIELD_DIMS) def _ball(x: float, y: float, z: float = 0.0) -> Ball: From 82051b9f0576463269a2e1d6ed704f32c0417f77 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 15 Apr 2026 00:54:36 +0100 Subject: [PATCH 027/121] =?UTF-8?q?refactor:=20rename=20half=5Fdefense=5Fl?= =?UTF-8?q?ength=20=E2=86=92=20half=5Fdefense=5Fdepth=20in=20RefereeGeomet?= =?UTF-8?q?ry?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Aligns with FieldDimensions.half_defense_area_depth. Updated geometry.py, profile_loader.py, gui.py, and both YAML profiles. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/custom_referee/geometry.py | 8 ++++---- utama_core/custom_referee/gui.py | 6 +++--- utama_core/custom_referee/profiles/human.yaml | 2 +- utama_core/custom_referee/profiles/profile_loader.py | 2 +- utama_core/custom_referee/profiles/simulation.yaml | 2 +- 5 files changed, 10 insertions(+), 10 deletions(-) diff --git a/utama_core/custom_referee/geometry.py b/utama_core/custom_referee/geometry.py index 4fa7ecd6..7f66319e 100644 --- a/utama_core/custom_referee/geometry.py +++ b/utama_core/custom_referee/geometry.py @@ -16,7 +16,7 @@ class RefereeGeometry: half_length: float half_width: float half_goal_width: float - half_defense_length: float + half_defense_depth: float half_defense_width: float center_circle_radius: float @@ -36,7 +36,7 @@ def from_field_dims(cls, field_dims: FieldDimensions, field_bounds: FieldBounds half_length=half_length, half_width=half_width, half_goal_width=field_dims.half_goal_width, - half_defense_length=field_dims.half_defense_area_depth, + half_defense_depth=field_dims.half_defense_area_depth, half_defense_width=field_dims.half_defense_area_width, center_circle_radius=0.5, ) @@ -59,8 +59,8 @@ def is_in_right_goal(self, x: float, y: float) -> bool: def is_in_left_defense_area(self, x: float, y: float) -> bool: """True if (x, y) is inside the left defense area.""" - return x <= -self.half_length + 2 * self.half_defense_length and abs(y) <= self.half_defense_width + return x <= -self.half_length + 2 * self.half_defense_depth and abs(y) <= self.half_defense_width def is_in_right_defense_area(self, x: float, y: float) -> bool: """True if (x, y) is inside the right defense area.""" - return x >= self.half_length - 2 * self.half_defense_length and abs(y) <= self.half_defense_width + return x >= self.half_length - 2 * self.half_defense_depth and abs(y) <= self.half_defense_width diff --git a/utama_core/custom_referee/gui.py b/utama_core/custom_referee/gui.py index b61cc7b5..5db58db3 100644 --- a/utama_core/custom_referee/gui.py +++ b/utama_core/custom_referee/gui.py @@ -322,7 +322,7 @@ def _build_config_json(profile: "RefereeProfile") -> str: "half_length": g.half_length, "half_width": g.half_width, "half_goal_width": g.half_goal_width, - "half_defense_length": g.half_defense_length, + "half_defense_depth": g.half_defense_depth, "half_defense_width": g.half_defense_width, "center_circle_radius": g.center_circle_radius, }, @@ -772,7 +772,7 @@ def _build_config_json(profile: "RefereeProfile") -> str: ctx.fill(); // Defence areas - const dl = g.half_defense_length, dw = g.half_defense_width; + const dl = g.half_defense_depth, dw = g.half_defense_width; // Left (negative x) ctx.strokeRect(toX(-g.half_length), toY(dw), dl * scale, 2 * dw * scale); // Right (positive x) @@ -940,7 +940,7 @@ def _build_config_json(profile: "RefereeProfile") -> str: cfgRow('half length', g.half_length + ' m') + cfgRow('half width', g.half_width + ' m') + cfgRow('half goal width', g.half_goal_width + ' m') + - cfgRow('defense length (half)', g.half_defense_length + ' m') + + cfgRow('defense length (half)', g.half_defense_depth + ' m') + cfgRow('defense width (half)', g.half_defense_width + ' m') + cfgRow('centre circle r', g.center_circle_radius + ' m'); diff --git a/utama_core/custom_referee/profiles/human.yaml b/utama_core/custom_referee/profiles/human.yaml index a531fd26..1e3302fd 100644 --- a/utama_core/custom_referee/profiles/human.yaml +++ b/utama_core/custom_referee/profiles/human.yaml @@ -3,7 +3,7 @@ geometry: half_length: 4.5 half_width: 3.0 half_goal_width: 0.5 - half_defense_length: 0.5 + half_defense_depth: 0.5 half_defense_width: 1.0 center_circle_radius: 0.5 rules: diff --git a/utama_core/custom_referee/profiles/profile_loader.py b/utama_core/custom_referee/profiles/profile_loader.py index a9eec66b..d3f22582 100644 --- a/utama_core/custom_referee/profiles/profile_loader.py +++ b/utama_core/custom_referee/profiles/profile_loader.py @@ -159,7 +159,7 @@ def _parse_profile(data: dict) -> RefereeProfile: half_length=geo_d.get("half_length", 4.5), half_width=geo_d.get("half_width", 3.0), half_goal_width=geo_d.get("half_goal_width", 0.5), - half_defense_length=geo_d.get("half_defense_length", 0.5), + half_defense_depth=geo_d.get("half_defense_depth", 0.5), half_defense_width=geo_d.get("half_defense_width", 1.0), center_circle_radius=geo_d.get("center_circle_radius", 0.5), ) diff --git a/utama_core/custom_referee/profiles/simulation.yaml b/utama_core/custom_referee/profiles/simulation.yaml index 66809f8e..53183233 100644 --- a/utama_core/custom_referee/profiles/simulation.yaml +++ b/utama_core/custom_referee/profiles/simulation.yaml @@ -3,7 +3,7 @@ geometry: half_length: 4.5 half_width: 3.0 half_goal_width: 0.5 - half_defense_length: 0.5 + half_defense_depth: 0.5 half_defense_width: 1.0 center_circle_radius: 0.5 rules: From 4869ca95382c9bebcfa247b87f0b722435d632ee Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 15 Apr 2026 01:00:18 +0100 Subject: [PATCH 028/121] fix: remove dead CLEARANCE_FALLBACK_DIRECTION and fix _clear_to_legal_positions MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Three issues addressed: 1. Remove CLEARANCE_FALLBACK_DIRECTION from referee_constants — it was the default parameter of _project_outside_circle but no caller used the default; the fallback is now always passed explicitly. 2. _clear_to_legal_positions now accepts an optional intended_targets dict. When provided, clearance starts from the intended formation target rather than robot.p, so the clearing pass refines rather than discards the formation intent. PrepareKickoffTheirsStep now passes intended_targets instead of pre-issuing move commands and relying on overwrite. 3. Use own-half direction as the coincidence fallback for both ball and designated-position clearance — consistent with the invariant that friendly robots belong on their own half during all restart states. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/config/referee_constants.py | 1 - utama_core/strategy/referee/actions.py | 38 +++++++++++++++++--------- 2 files changed, 25 insertions(+), 14 deletions(-) diff --git a/utama_core/config/referee_constants.py b/utama_core/config/referee_constants.py index beafc5ae..3e5333aa 100644 --- a/utama_core/config/referee_constants.py +++ b/utama_core/config/referee_constants.py @@ -5,7 +5,6 @@ OPPONENT_DEFENSE_AREA_KEEP_DISTANCE = 0.25 PENALTY_BEHIND_MARK_DISTANCE = 0.4 PENALTY_MARK_HALF_FIELD_RATIO = 0.5 -CLEARANCE_FALLBACK_DIRECTION = (1.0, 0.0) PENALTY_LINE_Y_STEP_RATIO = 0.35 / STANDARD_FIELD_DIMS.full_field_half_width diff --git a/utama_core/strategy/referee/actions.py b/utama_core/strategy/referee/actions.py index cbac6e18..46482f3d 100644 --- a/utama_core/strategy/referee/actions.py +++ b/utama_core/strategy/referee/actions.py @@ -17,7 +17,6 @@ from utama_core.config.referee_constants import ( BALL_KEEP_OUT_DISTANCE, BALL_PLACEMENT_DONE_DISTANCE, - CLEARANCE_FALLBACK_DIRECTION, KICKOFF_DEFENCE_POSITION_RATIOS_OWN_HALF, KICKOFF_SUPPORT_POSITION_RATIOS_OWN_HALF, OPPONENT_DEFENSE_AREA_KEEP_DISTANCE, @@ -87,7 +86,7 @@ def _project_outside_circle( point: Vector2D, center: Vector2D, keep_dist: float, - fallback_direction: tuple[float, float] = CLEARANCE_FALLBACK_DIRECTION, + fallback_direction: tuple[float, float], ) -> Vector2D: """Project a point to the circle boundary if it lies inside the keep-out radius.""" offset = point - center @@ -140,8 +139,14 @@ def _clear_to_legal_positions( designated_keep_dist: float | None = None, clear_opp_defense_area: bool = False, exempt_robot_ids: set[int] | None = None, + intended_targets: dict[int, Vector2D] | None = None, ) -> py_trees.common.Status: - """Move encroaching robots to the nearest legal location and stop the rest.""" + """Move encroaching robots to the nearest legal location and stop the rest. + + If intended_targets is provided, each robot's clearance starts from its + intended formation target rather than its current position, so the clearing + pass refines rather than discards the formation intent. + """ game = blackboard.game motion_controller = blackboard.motion_controller exempt_robot_ids = exempt_robot_ids or set() @@ -155,25 +160,34 @@ def _clear_to_legal_positions( if designated_keep_dist is not None and ref is not None and ref.designated_position is not None: designated_center = Vector2D(ref.designated_position[0], ref.designated_position[1]) - # When a robot is exactly coincident with the obstruction, push it toward own half. + # When a robot is exactly coincident with an obstruction center (dist == 0), + # push it toward own half — robots should be on their side in all restart states. own_half_sign = 1.0 if game.my_team_is_right else -1.0 own_half_fallback = (own_half_sign, 0.0) + ball_fallback = own_half_fallback + designated_fallback = own_half_fallback for robot_id, robot in game.friendly_robots.items(): if robot_id in exempt_robot_ids: continue - target = Vector2D(robot.p.x, robot.p.y) + # Start from the intended formation target if provided, otherwise + # fall back to the robot's current position. + if intended_targets is not None and robot_id in intended_targets: + target = intended_targets[robot_id] + else: + target = Vector2D(robot.p.x, robot.p.y) + if ball_center is not None: - target = _project_outside_circle(target, ball_center, ball_keep_dist, own_half_fallback) + target = _project_outside_circle(target, ball_center, ball_keep_dist, ball_fallback) if designated_center is not None: - target = _project_outside_circle(target, designated_center, designated_keep_dist, own_half_fallback) + target = _project_outside_circle(target, designated_center, designated_keep_dist, designated_fallback) if clear_opp_defense_area: target = _project_outside_opp_defense_area(game, target, OPPONENT_DEFENSE_AREA_KEEP_DISTANCE) target = _clamp_to_field(target, game) - if target == robot.p: + if target == Vector2D(robot.p.x, robot.p.y): blackboard.cmd_map[robot_id] = empty_command(False) continue @@ -338,17 +352,15 @@ class PrepareKickoffTheirsStep(AbstractBehaviour): def update(self) -> py_trees.common.Status: game = self.blackboard.game - motion_controller = self.blackboard.motion_controller positions = _formation_positions(game, KICKOFF_DEFENCE_POSITION_RATIOS_OWN_HALF) - - for idx, robot_id in enumerate(sorted(game.friendly_robots.keys())): - pos = positions[idx % len(positions)] - self.blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, pos, 0.0) + robot_ids = sorted(game.friendly_robots.keys()) + intended = {robot_id: positions[idx % len(positions)] for idx, robot_id in enumerate(robot_ids)} return _clear_to_legal_positions( self.blackboard, ball_keep_dist=BALL_KEEP_OUT_DISTANCE, + intended_targets=intended, ) From d6f4f115e44a07de5486f37a470dc116c57863e5 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 15 Apr 2026 01:03:08 +0100 Subject: [PATCH 029/121] fix: exclude PREPARE_KICKOFF/PENALTY from keep-out rule to prevent sequence resets MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit During PREPARE_KICKOFF_* and PREPARE_PENALTY_*, robots are actively moving to their formation positions. The keep-out rule was firing after 30 frames of encroachment and resetting the sequence to STOP → DIRECT_FREE, causing a violation loop. These states are now excluded from _STOPPAGE_COMMANDS — the state machine already gates progression via _kicker_in_centre_circle and _penalty_kicker_ready, so keep-out violations here are spurious. The rule remains active for DIRECT_FREE_* where defending robots must genuinely stay clear while the free kick is set up. Co-Authored-By: Claude Sonnet 4.6 --- .../custom_referee/rules/keep_out_rule.py | 17 +++++++---------- 1 file changed, 7 insertions(+), 10 deletions(-) diff --git a/utama_core/custom_referee/rules/keep_out_rule.py b/utama_core/custom_referee/rules/keep_out_rule.py index 514d33d6..11a1685d 100644 --- a/utama_core/custom_referee/rules/keep_out_rule.py +++ b/utama_core/custom_referee/rules/keep_out_rule.py @@ -15,13 +15,14 @@ # ball and the state machine already handles this via StopStep. Firing a # keep-out violation during STOP would overwrite next_command (e.g. replacing # PREPARE_KICKOFF_BLUE with DIRECT_FREE_YELLOW), which is wrong. +# PREPARE_KICKOFF_* and PREPARE_PENALTY_* are excluded for the same reason: +# robots are actively moving to their formation positions during these states. +# The state machine gates progression via _kicker_in_centre_circle / +# _penalty_kicker_ready, so keep-out violations here only cause unnecessary +# sequence resets. _STOPPAGE_COMMANDS = { RefereeCommand.DIRECT_FREE_YELLOW, RefereeCommand.DIRECT_FREE_BLUE, - RefereeCommand.PREPARE_KICKOFF_YELLOW, - RefereeCommand.PREPARE_KICKOFF_BLUE, - RefereeCommand.PREPARE_PENALTY_YELLOW, - RefereeCommand.PREPARE_PENALTY_BLUE, } @@ -101,10 +102,6 @@ def _any_robot_encroaching(self, robots, bx: float, by: float) -> bool: def _kicking_team_is_yellow(command: RefereeCommand) -> bool: """Return True if the kicking team is yellow, False if blue. - Only called when command is in _STOPPAGE_COMMANDS, so STOP is never passed. + Only called when command is in _STOPPAGE_COMMANDS (DIRECT_FREE_* only). """ - return command in ( - RefereeCommand.DIRECT_FREE_YELLOW, - RefereeCommand.PREPARE_KICKOFF_YELLOW, - RefereeCommand.PREPARE_PENALTY_YELLOW, - ) + return command == RefereeCommand.DIRECT_FREE_YELLOW From b3a02bddb37dd4d2879fc05a4a480042e6706c76 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 15 Apr 2026 01:06:12 +0100 Subject: [PATCH 030/121] Revert "fix: exclude PREPARE_KICKOFF/PENALTY from keep-out rule to prevent sequence resets" This reverts commit d6f4f115e44a07de5486f37a470dc116c57863e5. --- .../custom_referee/rules/keep_out_rule.py | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/utama_core/custom_referee/rules/keep_out_rule.py b/utama_core/custom_referee/rules/keep_out_rule.py index 11a1685d..514d33d6 100644 --- a/utama_core/custom_referee/rules/keep_out_rule.py +++ b/utama_core/custom_referee/rules/keep_out_rule.py @@ -15,14 +15,13 @@ # ball and the state machine already handles this via StopStep. Firing a # keep-out violation during STOP would overwrite next_command (e.g. replacing # PREPARE_KICKOFF_BLUE with DIRECT_FREE_YELLOW), which is wrong. -# PREPARE_KICKOFF_* and PREPARE_PENALTY_* are excluded for the same reason: -# robots are actively moving to their formation positions during these states. -# The state machine gates progression via _kicker_in_centre_circle / -# _penalty_kicker_ready, so keep-out violations here only cause unnecessary -# sequence resets. _STOPPAGE_COMMANDS = { RefereeCommand.DIRECT_FREE_YELLOW, RefereeCommand.DIRECT_FREE_BLUE, + RefereeCommand.PREPARE_KICKOFF_YELLOW, + RefereeCommand.PREPARE_KICKOFF_BLUE, + RefereeCommand.PREPARE_PENALTY_YELLOW, + RefereeCommand.PREPARE_PENALTY_BLUE, } @@ -102,6 +101,10 @@ def _any_robot_encroaching(self, robots, bx: float, by: float) -> bool: def _kicking_team_is_yellow(command: RefereeCommand) -> bool: """Return True if the kicking team is yellow, False if blue. - Only called when command is in _STOPPAGE_COMMANDS (DIRECT_FREE_* only). + Only called when command is in _STOPPAGE_COMMANDS, so STOP is never passed. """ - return command == RefereeCommand.DIRECT_FREE_YELLOW + return command in ( + RefereeCommand.DIRECT_FREE_YELLOW, + RefereeCommand.PREPARE_KICKOFF_YELLOW, + RefereeCommand.PREPARE_PENALTY_YELLOW, + ) From 3bb31bc81bfe9ba32a5fd9e644f300d2e7005f56 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 15 Apr 2026 01:07:21 +0100 Subject: [PATCH 031/121] fix: clear encroaching robots from current position, not formation target If a robot is currently inside a keep-out zone, sending it toward a distant formation target makes it traverse the exclusion zone for multiple frames, triggering the keep-out violation counter. Instead, when a robot is encroaching, project it out from its current position immediately. Only use the intended formation target when the robot is already clear of all exclusion zones. This prevents keep-out rule violations during PREPARE_KICKOFF without modifying the referee state machine. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/strategy/referee/actions.py | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/utama_core/strategy/referee/actions.py b/utama_core/strategy/referee/actions.py index 46482f3d..24d63ad5 100644 --- a/utama_core/strategy/referee/actions.py +++ b/utama_core/strategy/referee/actions.py @@ -171,12 +171,19 @@ def _clear_to_legal_positions( if robot_id in exempt_robot_ids: continue - # Start from the intended formation target if provided, otherwise - # fall back to the robot's current position. - if intended_targets is not None and robot_id in intended_targets: + robot_pos = Vector2D(robot.p.x, robot.p.y) + + # If the robot is currently inside any keep-out zone, clear it from its + # current position immediately — don't head toward a distant formation + # target that requires traversing the exclusion zone first. + currently_encroaching = (ball_center is not None and (ball_center - robot_pos).mag() < ball_keep_dist) or ( + designated_center is not None and (designated_center - robot_pos).mag() < designated_keep_dist + ) + + if not currently_encroaching and intended_targets is not None and robot_id in intended_targets: target = intended_targets[robot_id] else: - target = Vector2D(robot.p.x, robot.p.y) + target = robot_pos if ball_center is not None: target = _project_outside_circle(target, ball_center, ball_keep_dist, ball_fallback) From ea330663990db44afca5534e1690d05afba90b2d Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 15 Apr 2026 01:10:22 +0100 Subject: [PATCH 032/121] fix: use BALL_KEEP_OUT_DISTANCE in _ensure_outside_center_circle The function previously used a hardcoded 0.5 m (centre-circle radius), meaning formation positions could be placed at exactly 0.5 m from the ball. _clear_to_legal_positions would then push them out to 0.8 m, but the robot still had to travel through the keep-out zone to reach its target, accumulating violation frames. Using BALL_KEEP_OUT_DISTANCE (0.8 m) ensures formation positions are always placed at or beyond our enforced clearance distance, so robots never need to traverse the keep-out zone to reach their assigned position. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/strategy/referee/actions.py | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/utama_core/strategy/referee/actions.py b/utama_core/strategy/referee/actions.py index 24d63ad5..bf7a43a0 100644 --- a/utama_core/strategy/referee/actions.py +++ b/utama_core/strategy/referee/actions.py @@ -64,12 +64,17 @@ def _scaled_position(game, x_ratio: float, y_ratio: float) -> Vector2D: def _ensure_outside_center_circle(target: Vector2D) -> Vector2D: - """Project kickoff support points to the centre-circle boundary when needed.""" + """Project kickoff support points outside the ball keep-out zone if needed. + + Uses BALL_KEEP_OUT_DISTANCE (not just the centre-circle radius) so that + formation positions are never closer than our enforced clearance distance, + avoiding any need for _clear_to_legal_positions to further adjust them and + preventing robots from being placed on a path that crosses the keep-out zone. + """ dist = math.hypot(target.x, target.y) - keep_radius = 0.5 # standard SSL centre-circle radius - if dist == 0.0 or dist >= keep_radius: + if dist == 0.0 or dist >= BALL_KEEP_OUT_DISTANCE: return target - scale = keep_radius / dist + scale = BALL_KEEP_OUT_DISTANCE / dist return Vector2D(target.x * scale, target.y * scale) From 386dd941000052016850829e25673653c9722d4d Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Thu, 16 Apr 2026 15:48:10 +0100 Subject: [PATCH 033/121] fix: address Copilot review issues in referee code and docs MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Update docs/custom_referee.md: replace stale from_standard_div_b() / from_field_bounds() references with the actual from_field_dims() API; fix half_defense_length → half_defense_depth in the dataclass snippet - Fix misleading __eq__ comment in RefereeData: clarify that time_sent and time_received are excluded, not all timestamps - Fix GameFrame.is_ball_in_goal: accept a Field parameter (self.field does not exist on GameFrame); add ball None guard; simplify with abs() - Fix demo_custom_referee.py: replace non-existent from_standard_div_b() with from_field_dims(STANDARD_FIELD_DIMS); fix half_defense_length → half_defense_depth crash Co-Authored-By: Claude Sonnet 4.6 --- demo_custom_referee.py | 7 ++++--- docs/custom_referee.md | 7 +++---- utama_core/entities/data/referee.py | 4 ++-- utama_core/entities/game/game_frame.py | 13 +++++-------- 4 files changed, 14 insertions(+), 17 deletions(-) diff --git a/demo_custom_referee.py b/demo_custom_referee.py index a1b5322d..653221e1 100644 --- a/demo_custom_referee.py +++ b/demo_custom_referee.py @@ -32,6 +32,7 @@ import pygame +from utama_core.config.field_params import STANDARD_FIELD_DIMS from utama_core.custom_referee import CustomReferee, RefereeGeometry from utama_core.entities.data.vector import Vector2D, Vector3D from utama_core.entities.game.ball import Ball @@ -328,8 +329,8 @@ def _build_overlays( ovs: list[OverlayObject] = [] # Defense area outlines (purple, always visible) - rdx = geo.half_length - 2 * geo.half_defense_length # 3.5 - ldx = -geo.half_length + 2 * geo.half_defense_length # -3.5 + rdx = geo.half_length - 2 * geo.half_defense_depth # 3.5 + ldx = -geo.half_length + 2 * geo.half_defense_depth # -3.5 for pts in [ # Right defense area (yellow's goal) @@ -559,7 +560,7 @@ def main() -> None: "tiny": pygame.font.SysFont("monospace", 12), } - geo = RefereeGeometry.from_standard_div_b() + geo = RefereeGeometry.from_field_dims(STANDARD_FIELD_DIMS) referee = _make_referee() scene_idx = 0 diff --git a/docs/custom_referee.md b/docs/custom_referee.md index 1d054c22..c675e1f4 100644 --- a/docs/custom_referee.md +++ b/docs/custom_referee.md @@ -180,15 +180,14 @@ class RefereeGeometry: half_length: float # metres from centre to goal line half_width: float # metres from centre to sideline half_goal_width: float # half the goal opening width - half_defense_length: float # depth of defence area + half_defense_depth: float # depth of defence area half_defense_width: float # half-width of defence area center_circle_radius: float # keep-out radius for kickoffs ``` -Two convenience constructors: +Convenience constructor: -- `RefereeGeometry.from_standard_div_b()` — mirrors `Field` constants exactly (9 m × 6 m field). -- `RefereeGeometry.from_field_bounds(field_bounds)` — derives `half_length`/`half_width` from a `FieldBounds`; uses `Field` constants for goal and defence dimensions. +- `RefereeGeometry.from_field_dims(field_dims, field_bounds=None)` — builds geometry from a `FieldDimensions` instance. If `field_bounds` is provided, `half_length`/`half_width` are derived from it (useful for sub-field play areas); otherwise the full field extents from `field_dims` are used. --- diff --git a/utama_core/entities/data/referee.py b/utama_core/entities/data/referee.py index bd2230a7..27181b1b 100644 --- a/utama_core/entities/data/referee.py +++ b/utama_core/entities/data/referee.py @@ -57,8 +57,8 @@ class RefereeData: def __eq__(self, other): if not isinstance(other, RefereeData): return NotImplemented - # game_events, match_type, status_message, source_identifier, and - # timestamps are intentionally excluded from equality so they do not + # game_events, match_type, status_message, source_identifier, time_sent, + # and time_received are intentionally excluded from equality so they do not # trigger spurious re-records in RefereeRefiner. # TeamInfo has no __eq__ so compare the mutable game-state fields only. return ( diff --git a/utama_core/entities/game/game_frame.py b/utama_core/entities/game/game_frame.py index 8c06ae37..0ee5b9cb 100644 --- a/utama_core/entities/game/game_frame.py +++ b/utama_core/entities/game/game_frame.py @@ -21,13 +21,10 @@ class GameFrame: ball: Optional[Ball] referee: Optional[RefereeData] = None - def is_ball_in_goal(self, right_goal: bool) -> bool: + def is_ball_in_goal(self, right_goal: bool, field: Field) -> bool: + if self.ball is None: + return False ball_pos = self.ball.p - return ( - ball_pos.x < -self.field.half_length - and (ball_pos.y < self.field.half_goal_width and ball_pos.y > -self.field.half_goal_width) - and not right_goal - or ball_pos.x > self.field.half_length - and (ball_pos.y < self.field.half_goal_width and ball_pos.y > -self.field.half_goal_width) - and right_goal + return (ball_pos.x < -field.half_length and abs(ball_pos.y) < field.half_goal_width and not right_goal) or ( + ball_pos.x > field.half_length and abs(ball_pos.y) < field.half_goal_width and right_goal ) From ea8514bd8f469fa97542187040d679c3ff9fb70d Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Thu, 16 Apr 2026 17:38:31 +0100 Subject: [PATCH 034/121] fix: address Copilot review issues in referee actions and tests MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Fix PreparePenaltyTheirsStep: behind_line_x used +sign which placed non-keeper robots toward our goal instead of toward the centre line; change to -sign so robots are correctly positioned behind the penalty mark facing midfield (mirrors the existing PreparePenaltyOursStep logic) - Rename misleading test: test_resolve_referee_system_defaults_to_none_even_when_custom_referee_is_provided → test_resolve_referee_system_rejects_custom_referee_without_explicit_system - Fix demo_referee_gui_rsim.py docstring: run command pointed to utama_core/tests/referee/ path instead of the actual root-level file Co-Authored-By: Claude Sonnet 4.6 --- demo_referee_gui_rsim.py | 2 +- utama_core/strategy/referee/actions.py | 2 +- utama_core/tests/strategy_runner/test_runner_misconfig.py | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/demo_referee_gui_rsim.py b/demo_referee_gui_rsim.py index a71d4407..b74e6b2b 100644 --- a/demo_referee_gui_rsim.py +++ b/demo_referee_gui_rsim.py @@ -1,7 +1,7 @@ """demo_referee_gui_rsim.py — CustomReferee + web GUI + StrategyRunner (RSim). Run: - pixi run python utama_core/tests/referee/demo_referee_gui_rsim.py + pixi run python demo_referee_gui_rsim.py # RSim window opens; open http://localhost:8080 in a browser What it does: diff --git a/utama_core/strategy/referee/actions.py b/utama_core/strategy/referee/actions.py index bf7a43a0..fdb84597 100644 --- a/utama_core/strategy/referee/actions.py +++ b/utama_core/strategy/referee/actions.py @@ -454,7 +454,7 @@ def update(self) -> py_trees.common.Status: # Opponent's penalty mark is in our half, between centre and our goal line. opp_penalty_mark_x = _penalty_mark_x(our_goal_x) - behind_line_x = opp_penalty_mark_x + sign * PENALTY_BEHIND_MARK_DISTANCE + behind_line_x = opp_penalty_mark_x - sign * PENALTY_BEHIND_MARK_DISTANCE robot_ids = sorted(game.friendly_robots.keys()) behind_idx = 0 diff --git a/utama_core/tests/strategy_runner/test_runner_misconfig.py b/utama_core/tests/strategy_runner/test_runner_misconfig.py index b4be0c64..e2166d63 100644 --- a/utama_core/tests/strategy_runner/test_runner_misconfig.py +++ b/utama_core/tests/strategy_runner/test_runner_misconfig.py @@ -41,7 +41,7 @@ def test_resolve_referee_system_defaults_to_none_in_grsim(): assert StrategyRunner._resolve_referee_system(Mode.GRSIM, None, None) == "none" -def test_resolve_referee_system_defaults_to_none_even_when_custom_referee_is_provided(): +def test_resolve_referee_system_rejects_custom_referee_without_explicit_system(): with pytest.raises(ValueError, match="custom_referee"): StrategyRunner._resolve_referee_system(Mode.RSIM, None, object()) From 530cd0b38991265e24053a1f739b3ac10e1ed428 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Thu, 16 Apr 2026 17:52:42 +0100 Subject: [PATCH 035/121] fix: keep RefereeRefiner properties current when deduplication skips a record Properties like last_command, blue_team, status_message, etc. were all reading from _referee_records[-1], which is not updated when the new RefereeData compares equal (e.g. only status_message or time_sent changes). This could leave live properties stale between meaningful state changes. Add _latest_referee_data, updated unconditionally on every refine() call (alongside the existing _latest_stage_time_left), and point all live properties at it. _referee_records still grows only on meaningful state changes, preserving its role as a deduplicated history. Co-Authored-By: Claude Sonnet 4.6 --- .../data_processing/refiners/referee.py | 37 ++++++++++--------- 1 file changed, 20 insertions(+), 17 deletions(-) diff --git a/utama_core/data_processing/refiners/referee.py b/utama_core/data_processing/refiners/referee.py index 27700f61..bee99d9a 100644 --- a/utama_core/data_processing/refiners/referee.py +++ b/utama_core/data_processing/refiners/referee.py @@ -11,6 +11,7 @@ class RefereeRefiner(BaseRefiner): def __init__(self): self._referee_records = [] + self._latest_referee_data: Optional[RefereeData] = None self._latest_stage_time_left: float = 0.0 def refine(self, game_frame, data: Optional[RefereeData]): @@ -26,7 +27,9 @@ def refine(self, game_frame, data: Optional[RefereeData]): if data is None: return game_frame - # Always track the latest countdown, even when deduplication skips the record + # Always track the latest data so live properties (status_message, etc.) + # stay current even when deduplication skips appending a new record. + self._latest_referee_data = data self._latest_stage_time_left = data.stage_time_left # Add to history @@ -40,27 +43,27 @@ def add_new_referee_data(self, referee_data: RefereeData) -> None: self._referee_records.append(referee_data) def source_identifier(self) -> Optional[str]: - return self._referee_records[-1].source_identifier if self._referee_records else None + return self._latest_referee_data.source_identifier if self._latest_referee_data else None @property def last_time_sent(self) -> float: - return self._referee_records[-1].time_sent if self._referee_records else 0.0 + return self._latest_referee_data.time_sent if self._latest_referee_data else 0.0 @property def last_time_received(self) -> float: - return self._referee_records[-1].time_received if self._referee_records else 0.0 + return self._latest_referee_data.time_received if self._latest_referee_data else 0.0 @property def last_command(self) -> RefereeCommand: - return self._referee_records[-1].referee_command if self._referee_records else RefereeCommand.HALT + return self._latest_referee_data.referee_command if self._latest_referee_data else RefereeCommand.HALT @property def last_command_timestamp(self) -> float: - return self._referee_records[-1].referee_command_timestamp if self._referee_records else 0.0 + return self._latest_referee_data.referee_command_timestamp if self._latest_referee_data else 0.0 @property def stage(self) -> Stage: - return self._referee_records[-1].stage if self._referee_records else Stage.NORMAL_FIRST_HALF_PRE + return self._latest_referee_data.stage if self._latest_referee_data else Stage.NORMAL_FIRST_HALF_PRE @property def stage_time_left(self) -> float: @@ -69,8 +72,8 @@ def stage_time_left(self) -> float: @property def blue_team(self) -> TeamInfo: return ( - self._referee_records[-1].blue_team - if self._referee_records + self._latest_referee_data.blue_team + if self._latest_referee_data else TeamInfo( name="", score=0, @@ -86,8 +89,8 @@ def blue_team(self) -> TeamInfo: @property def yellow_team(self) -> TeamInfo: return ( - self._referee_records[-1].yellow_team - if self._referee_records + self._latest_referee_data.yellow_team + if self._latest_referee_data else TeamInfo( name="", score=0, @@ -102,27 +105,27 @@ def yellow_team(self) -> TeamInfo: @property def designated_position(self) -> Optional[tuple[float]]: - return self._referee_records[-1].designated_position if self._referee_records else None + return self._latest_referee_data.designated_position if self._latest_referee_data else None @property def blue_team_on_positive_half(self) -> Optional[bool]: - return self._referee_records[-1].blue_team_on_positive_half if self._referee_records else None + return self._latest_referee_data.blue_team_on_positive_half if self._latest_referee_data else None @property def next_command(self) -> Optional[RefereeCommand]: - return self._referee_records[-1].next_command if self._referee_records else None + return self._latest_referee_data.next_command if self._latest_referee_data else None @property def current_action_time_remaining(self) -> Optional[int]: - return self._referee_records[-1].current_action_time_remaining if self._referee_records else None + return self._latest_referee_data.current_action_time_remaining if self._latest_referee_data else None @property def last_status_message(self) -> Optional[str]: - return self._referee_records[-1].status_message if self._referee_records else None + return self._latest_referee_data.status_message if self._latest_referee_data else None @property def last_next_command(self) -> Optional[RefereeCommand]: - return self._referee_records[-1].next_command if self._referee_records else None + return self._latest_referee_data.next_command if self._latest_referee_data else None @property def is_halt(self) -> bool: From 770797341bc4c634d1969a2490668dd2813e0b79 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Thu, 16 Apr 2026 18:15:22 +0100 Subject: [PATCH 036/121] =?UTF-8?q?docs:=20rename=20half=5Fdefense=5Flengt?= =?UTF-8?q?h=20=E2=86=92=20half=5Fdefense=5Fdepth=20in=20all=20docs?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit The field was renamed in code (RefereeGeometry, YAML profiles) but three doc files still used the old name in YAML examples and the field table. Updated docs/custom_referee.md, docs/referee_integration.md, and docs/custom_referee_gui.md to match the actual API. Co-Authored-By: Claude Sonnet 4.6 --- docs/custom_referee.md | 2 +- docs/custom_referee_gui.md | 6 +++--- docs/referee_integration.md | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/docs/custom_referee.md b/docs/custom_referee.md index c675e1f4..cf82767f 100644 --- a/docs/custom_referee.md +++ b/docs/custom_referee.md @@ -221,7 +221,7 @@ geometry: half_length: 4.5 half_width: 3.0 half_goal_width: 0.5 - half_defense_length: 0.5 + half_defense_depth: 0.5 half_defense_width: 1.0 center_circle_radius: 0.5 rules: diff --git a/docs/custom_referee_gui.md b/docs/custom_referee_gui.md index 29a444ec..16f847e2 100644 --- a/docs/custom_referee_gui.md +++ b/docs/custom_referee_gui.md @@ -174,7 +174,7 @@ canvas auto-scales to match. | `half_length` | Distance from centre to goal line | GoalRule, OutOfBoundsRule, DefenseAreaRule | | `half_width` | Distance from centre to touch line | OutOfBoundsRule | | `half_goal_width` | Half-width of each goal mouth | GoalRule | -| `half_defense_length` | Depth of defence area | DefenseAreaRule | +| `half_defense_depth` | Depth of defence area | DefenseAreaRule | | `half_defense_width` | Half-width of defence area | DefenseAreaRule | | `center_circle_radius` | Centre circle drawn on canvas; reserved for future keep-out rule | — | @@ -284,7 +284,7 @@ geometry: half_length: 4.5 # metres from centre to goal line (full length = 9.0 m) half_width: 3.0 # metres from centre to touch line (full width = 6.0 m) half_goal_width: 0.5 # metres from centre of goal mouth to post - half_defense_length: 0.5 # depth of defence area from goal line + half_defense_depth: 0.5 # depth of defence area from goal line half_defense_width: 1.0 # half-width of defence area center_circle_radius: 0.5 # used for canvas only (future: keep-out at kickoff) @@ -330,7 +330,7 @@ geometry: half_length: 2.0 half_width: 1.335 half_goal_width: 0.35 - half_defense_length: 0.4 + half_defense_depth: 0.4 half_defense_width: 0.7 center_circle_radius: 0.35 diff --git a/docs/referee_integration.md b/docs/referee_integration.md index a0dcaaf1..ae217711 100644 --- a/docs/referee_integration.md +++ b/docs/referee_integration.md @@ -354,7 +354,7 @@ geometry: half_length: 4.5 # metres from centre to goal line half_width: 3.0 # metres from centre to touch line half_goal_width: 0.5 # metres from centre of goal to post - half_defense_length: 0.5 # depth of defense area from goal line + half_defense_depth: 0.5 # depth of defense area from goal line half_defense_width: 1.0 # half-width of defense area center_circle_radius: 0.5 rules: From e5f381b9db160cff478713dfabdbb7f7d96ff97a Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Thu, 16 Apr 2026 18:19:02 +0100 Subject: [PATCH 037/121] docs: remove non-existent exhibition.yaml from file structure Only simulation.yaml and human.yaml exist under profiles/. exhibition.yaml was listed in the directory tree but was never created. Co-Authored-By: Claude Sonnet 4.6 --- docs/custom_referee.md | 1 - 1 file changed, 1 deletion(-) diff --git a/docs/custom_referee.md b/docs/custom_referee.md index cf82767f..be86f095 100644 --- a/docs/custom_referee.md +++ b/docs/custom_referee.md @@ -337,7 +337,6 @@ utama_core/custom_referee/ ├── __init__.py ├── profile_loader.py # load_profile(name|path) → RefereeProfile ├── simulation.yaml - ├── exhibition.yaml └── human.yaml utama_core/tests/custom_referee/ From 0c65a12d3cdd62bb491cd1237da3046762668a9b Mon Sep 17 00:00:00 2001 From: Joel Date: Sun, 10 May 2026 16:50:39 +0100 Subject: [PATCH 038/121] bug fix for pytest and add referee example in main --- main.py | 7 +++++++ .../motion_planning/oscillating_obstacle_strategy.py | 9 ++++++--- 2 files changed, 13 insertions(+), 3 deletions(-) diff --git a/main.py b/main.py index 3832df2a..ff1bac88 100644 --- a/main.py +++ b/main.py @@ -1,5 +1,7 @@ from utama_core.config.field_params import GREAT_EXHIBITION_FIELD_DIMS +from utama_core.custom_referee import CustomReferee from utama_core.entities.game.field import FieldBounds +from utama_core.entities.referee.referee_command import RefereeCommand from utama_core.replay import ReplayWriterConfig from utama_core.rsoccer_simulator.src.Utils.gaussian_noise import RsimGaussianNoise from utama_core.run import StrategyRunner @@ -12,6 +14,9 @@ TwoRobotPlacementStrategy, ) +referee = CustomReferee.from_profile_name("simulation", n_robots_yellow=3, n_robots_blue=3, enable_gui=True) +referee.set_command(RefereeCommand.NORMAL_START, timestamp=0.0) + def main(): # Setup for real testing @@ -30,6 +35,8 @@ def main(): full_field_dims=GREAT_EXHIBITION_FIELD_DIMS, show_live_status=True, profiler_name=None, + referee_system="custom", + custom_referee=referee, ) runner.my.strategy.render() runner.run() diff --git a/utama_core/strategy/examples/motion_planning/oscillating_obstacle_strategy.py b/utama_core/strategy/examples/motion_planning/oscillating_obstacle_strategy.py index df5d34aa..ee973d5a 100644 --- a/utama_core/strategy/examples/motion_planning/oscillating_obstacle_strategy.py +++ b/utama_core/strategy/examples/motion_planning/oscillating_obstacle_strategy.py @@ -3,7 +3,6 @@ from __future__ import annotations import math -import time from typing import TYPE_CHECKING, List, Optional import py_trees @@ -53,18 +52,22 @@ def __init__( def initialise(self): """Record start time when behaviour is initialized.""" - self.start_time = time.time() + # Wait to set start time until the first update to use game.ts + self.start_time = None def update(self) -> py_trees.common.Status: """Command robot to oscillate along specified axis.""" game = self.blackboard.game rsim_env = self.blackboard.rsim_env + if self.start_time is None: + self.start_time = game.ts + if not game.friendly_robots or self.obstacle_id not in game.friendly_robots: return py_trees.common.Status.RUNNING # Calculate oscillation based on elapsed time - elapsed_time = time.time() - self.start_time + elapsed_time = game.ts - self.start_time if self.direction_up_or_right: offset = self.amplitude * math.sin(self.speed * elapsed_time) else: From 82e80a216f523fb6e1b340e85af2cf8bdd51dc50 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Fri, 15 May 2026 10:14:02 +0100 Subject: [PATCH 039/121] fix: use game.ts as referee timebase instead of wall clock GameStateMachine.stage_start_time is now seeded lazily from the first current_time passed to step(), so the timebase matches the caller's clock. StrategyRunner now passes game_frame.ts instead of time.time(), making referee cooldowns and stage durations operate in sim-time for RSIM (which starts near 0) rather than wall-clock time. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/custom_referee/state_machine.py | 10 ++++++---- utama_core/run/strategy_runner.py | 2 +- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/utama_core/custom_referee/state_machine.py b/utama_core/custom_referee/state_machine.py index 451af006..479be681 100644 --- a/utama_core/custom_referee/state_machine.py +++ b/utama_core/custom_referee/state_machine.py @@ -5,7 +5,6 @@ import copy import logging import math -import time from typing import Optional from utama_core.custom_referee.geometry import RefereeGeometry @@ -50,9 +49,9 @@ def __init__( self.command_timestamp = 0.0 self.stage = initial_stage - self.stage_start_time = ( - time.time() if initial_time is None else initial_time - ) + # Seeded lazily on the first step() call so that the timebase matches + # whatever clock the caller uses (wall time or game.ts). + self.stage_start_time: Optional[float] = initial_time self.stage_duration = half_duration_seconds self.yellow_team = TeamInfo( @@ -163,6 +162,9 @@ def step( game_frame: Optional["GameFrame"] = None, ) -> RefereeData: """Process one tick. Apply violation if not in cooldown. Return RefereeData.""" + if self.stage_start_time is None: + self.stage_start_time = current_time + if violation is not None and self._can_transition(current_time): self._apply_violation(violation, current_time) diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index 626de28f..7047194e 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -865,7 +865,7 @@ def _run_step(self): self._draw_rsim_field_bounds_overlay() if self.referee_system == "custom": - ref_data = self.custom_referee.step(self.my.current_game_frame, time.time()) + ref_data = self.custom_referee.step(self.my.current_game_frame, self.my.current_game_frame.ts) self.ref_buffer.append(ref_data) _ball_placement_next = ref_data.next_command in ( RefereeCommand.BALL_PLACEMENT_YELLOW, From 69b96e0dded4f2b1d58e0cb7e03536b73824e4aa Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Fri, 15 May 2026 10:37:32 +0100 Subject: [PATCH 040/121] fix(#107): suppress Kalman ghost tracking during robot substitution GameStateMachine now sets bot_substitution_allowed=False by default and flips it to True only when the stage transitions to a halftime/break stage (where SSL rules permit substitution). PositionRefiner reads this flag from game_frame.referee and skips adding None vanishing entries for robots that disappear during an open substitution window, preventing the Kalman filter from ghost-predicting their positions. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/custom_referee/state_machine.py | 15 ++++++++-- .../data_processing/refiners/position.py | 28 +++++++++---------- 2 files changed, 27 insertions(+), 16 deletions(-) diff --git a/utama_core/custom_referee/state_machine.py b/utama_core/custom_referee/state_machine.py index 479be681..eff0d75e 100644 --- a/utama_core/custom_referee/state_machine.py +++ b/utama_core/custom_referee/state_machine.py @@ -68,7 +68,7 @@ def __init__( can_place_ball=True, max_allowed_bots=n_robots_yellow, bot_substitution_intent=False, - bot_substitution_allowed=True, + bot_substitution_allowed=False, bot_substitutions_left=5, ) self.blue_team = TeamInfo( @@ -85,7 +85,7 @@ def __init__( can_place_ball=True, max_allowed_bots=n_robots_blue, bot_substitution_intent=False, - bot_substitution_allowed=True, + bot_substitution_allowed=False, bot_substitutions_left=5, ) @@ -154,6 +154,14 @@ def __init__( RefereeCommand.BALL_PLACEMENT_BLUE, } ) + _SUBSTITUTION_ALLOWED_STAGES = frozenset( + { + Stage.NORMAL_HALF_TIME, + Stage.EXTRA_TIME_BREAK, + Stage.EXTRA_HALF_TIME, + Stage.PENALTY_SHOOTOUT_BREAK, + } + ) def step( self, @@ -528,6 +536,9 @@ def advance_stage(self, new_stage: Stage, timestamp: float) -> None: logger.info("Stage %s → %s", self.stage.name, new_stage.name) self.stage = new_stage self.stage_start_time = timestamp + allowed = new_stage in self._SUBSTITUTION_ALLOWED_STAGES + self.yellow_team.bot_substitution_allowed = allowed + self.blue_team.bot_substitution_allowed = allowed # ------------------------------------------------------------------ # Internal helpers diff --git a/utama_core/data_processing/refiners/position.py b/utama_core/data_processing/refiners/position.py index 9036efe4..4b0dfb33 100644 --- a/utama_core/data_processing/refiners/position.py +++ b/utama_core/data_processing/refiners/position.py @@ -220,17 +220,18 @@ def _include_vanished_robots( self, vision_data: VisionData, game_frame: GameFrame ) -> Tuple[dict[int, Optional[VisionRobotData]], dict[int, Optional[VisionRobotData]]]: """ - Augment the VisionData lists with None for vanished robots so that the Kalman filter - knows that data vanished. + Augment VisionData with None for vanished robots so the Kalman filter knows that data + vanished. Robots that disappear during an open substitution window are silently dropped + instead of imputed, preventing ghost predictions. Returns: Tuple of (yellow_vision_dict, blue_vision_dict) where vanished robots are represented as None. """ - - # TODO: major issue is that if we do a robot substitution, the - # Kalman filter will think the old robot vanished and a new robot appeared. - # needs to be adjusted when referee system is in place. - # see issue #107 on GitHub for more details. + yellow_sub_window = False + blue_sub_window = False + if game_frame.referee is not None: + yellow_sub_window = bool(game_frame.referee.yellow_team.bot_substitution_allowed) + blue_sub_window = bool(game_frame.referee.blue_team.bot_substitution_allowed) yellow_ids_last_frame, blue_ids_last_frame = map_friendly_enemy_to_colors( game_frame.my_team_is_yellow, @@ -238,19 +239,18 @@ def _include_vanished_robots( game_frame.enemy_robots.keys(), ) - # Current vision IDs yellow_present = {r.id for r in vision_data.yellow_robots} blue_present = {r.id for r in vision_data.blue_robots} - # Start with current measurements yellow_vision_dict: dict[int, Optional[VisionRobotData]] = {r.id: r for r in vision_data.yellow_robots} blue_vision_dict: dict[int, Optional[VisionRobotData]] = {r.id: r for r in vision_data.blue_robots} - # Add None for vanished robots - for robot_id in yellow_ids_last_frame - yellow_present: - yellow_vision_dict[robot_id] = None - for robot_id in blue_ids_last_frame - blue_present: - blue_vision_dict[robot_id] = None + if not yellow_sub_window: + for robot_id in yellow_ids_last_frame - yellow_present: + yellow_vision_dict[robot_id] = None + if not blue_sub_window: + for robot_id in blue_ids_last_frame - blue_present: + blue_vision_dict[robot_id] = None return yellow_vision_dict, blue_vision_dict From 3cc2ee895d831ddce8002f638fb2421ae47722f1 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Fri, 15 May 2026 10:45:35 +0100 Subject: [PATCH 041/121] Revert "fix(#107): suppress Kalman ghost tracking during robot substitution" This reverts commit 69b96e0dded4f2b1d58e0cb7e03536b73824e4aa. --- utama_core/custom_referee/state_machine.py | 15 ++-------- .../data_processing/refiners/position.py | 28 +++++++++---------- 2 files changed, 16 insertions(+), 27 deletions(-) diff --git a/utama_core/custom_referee/state_machine.py b/utama_core/custom_referee/state_machine.py index eff0d75e..479be681 100644 --- a/utama_core/custom_referee/state_machine.py +++ b/utama_core/custom_referee/state_machine.py @@ -68,7 +68,7 @@ def __init__( can_place_ball=True, max_allowed_bots=n_robots_yellow, bot_substitution_intent=False, - bot_substitution_allowed=False, + bot_substitution_allowed=True, bot_substitutions_left=5, ) self.blue_team = TeamInfo( @@ -85,7 +85,7 @@ def __init__( can_place_ball=True, max_allowed_bots=n_robots_blue, bot_substitution_intent=False, - bot_substitution_allowed=False, + bot_substitution_allowed=True, bot_substitutions_left=5, ) @@ -154,14 +154,6 @@ def __init__( RefereeCommand.BALL_PLACEMENT_BLUE, } ) - _SUBSTITUTION_ALLOWED_STAGES = frozenset( - { - Stage.NORMAL_HALF_TIME, - Stage.EXTRA_TIME_BREAK, - Stage.EXTRA_HALF_TIME, - Stage.PENALTY_SHOOTOUT_BREAK, - } - ) def step( self, @@ -536,9 +528,6 @@ def advance_stage(self, new_stage: Stage, timestamp: float) -> None: logger.info("Stage %s → %s", self.stage.name, new_stage.name) self.stage = new_stage self.stage_start_time = timestamp - allowed = new_stage in self._SUBSTITUTION_ALLOWED_STAGES - self.yellow_team.bot_substitution_allowed = allowed - self.blue_team.bot_substitution_allowed = allowed # ------------------------------------------------------------------ # Internal helpers diff --git a/utama_core/data_processing/refiners/position.py b/utama_core/data_processing/refiners/position.py index 4b0dfb33..9036efe4 100644 --- a/utama_core/data_processing/refiners/position.py +++ b/utama_core/data_processing/refiners/position.py @@ -220,18 +220,17 @@ def _include_vanished_robots( self, vision_data: VisionData, game_frame: GameFrame ) -> Tuple[dict[int, Optional[VisionRobotData]], dict[int, Optional[VisionRobotData]]]: """ - Augment VisionData with None for vanished robots so the Kalman filter knows that data - vanished. Robots that disappear during an open substitution window are silently dropped - instead of imputed, preventing ghost predictions. + Augment the VisionData lists with None for vanished robots so that the Kalman filter + knows that data vanished. Returns: Tuple of (yellow_vision_dict, blue_vision_dict) where vanished robots are represented as None. """ - yellow_sub_window = False - blue_sub_window = False - if game_frame.referee is not None: - yellow_sub_window = bool(game_frame.referee.yellow_team.bot_substitution_allowed) - blue_sub_window = bool(game_frame.referee.blue_team.bot_substitution_allowed) + + # TODO: major issue is that if we do a robot substitution, the + # Kalman filter will think the old robot vanished and a new robot appeared. + # needs to be adjusted when referee system is in place. + # see issue #107 on GitHub for more details. yellow_ids_last_frame, blue_ids_last_frame = map_friendly_enemy_to_colors( game_frame.my_team_is_yellow, @@ -239,18 +238,19 @@ def _include_vanished_robots( game_frame.enemy_robots.keys(), ) + # Current vision IDs yellow_present = {r.id for r in vision_data.yellow_robots} blue_present = {r.id for r in vision_data.blue_robots} + # Start with current measurements yellow_vision_dict: dict[int, Optional[VisionRobotData]] = {r.id: r for r in vision_data.yellow_robots} blue_vision_dict: dict[int, Optional[VisionRobotData]] = {r.id: r for r in vision_data.blue_robots} - if not yellow_sub_window: - for robot_id in yellow_ids_last_frame - yellow_present: - yellow_vision_dict[robot_id] = None - if not blue_sub_window: - for robot_id in blue_ids_last_frame - blue_present: - blue_vision_dict[robot_id] = None + # Add None for vanished robots + for robot_id in yellow_ids_last_frame - yellow_present: + yellow_vision_dict[robot_id] = None + for robot_id in blue_ids_last_frame - blue_present: + blue_vision_dict[robot_id] = None return yellow_vision_dict, blue_vision_dict From d89a3afe9423f47223c7e6883da4b9aff8816f10 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Fri, 15 May 2026 11:38:47 +0100 Subject: [PATCH 042/121] fix: address Copilot review issues in main.py and referee tree dispatchers - Move CustomReferee construction inside main() to eliminate import-time side effects - Store _is_opp_strat on AbstractBehaviour so setup_() can propagate it to inner nodes - Fix dispatcher setup_() calls in tree.py to forward is_opp_strat instead of hardcoding False Co-Authored-By: Claude Sonnet 4.6 --- main.py | 6 +++--- .../strategy/common/abstract_behaviour.py | 1 + utama_core/strategy/referee/tree.py | 17 ++++++++--------- 3 files changed, 12 insertions(+), 12 deletions(-) diff --git a/main.py b/main.py index ff1bac88..017cfc9f 100644 --- a/main.py +++ b/main.py @@ -14,11 +14,11 @@ TwoRobotPlacementStrategy, ) -referee = CustomReferee.from_profile_name("simulation", n_robots_yellow=3, n_robots_blue=3, enable_gui=True) -referee.set_command(RefereeCommand.NORMAL_START, timestamp=0.0) - def main(): + referee = CustomReferee.from_profile_name("simulation", n_robots_yellow=3, n_robots_blue=3, enable_gui=True) + referee.set_command(RefereeCommand.NORMAL_START, timestamp=0.0) + # Setup for real testing # Custom field size based setup in real custom_bounds = FieldBounds(top_left=(-2, 1.5), bottom_right=(1, -1.5)) diff --git a/utama_core/strategy/common/abstract_behaviour.py b/utama_core/strategy/common/abstract_behaviour.py index 3564fc2d..1f14b5ee 100644 --- a/utama_core/strategy/common/abstract_behaviour.py +++ b/utama_core/strategy/common/abstract_behaviour.py @@ -55,6 +55,7 @@ def setup(self, **kwargs: Any) -> None: We setup the common blackboard keys to all behaviours. """ is_opp_strategy = kwargs.get("is_opp_strat", False) + self._is_opp_strat: bool = is_opp_strategy self.blackboard: BaseBlackboard = self.attach_blackboard_client( name="GlobalBlackboard", namespace=BLACKBOARD_NAMESPACE_MAP[is_opp_strategy] ) diff --git a/utama_core/strategy/referee/tree.py b/utama_core/strategy/referee/tree.py index 01413d68..0dd1e1ec 100644 --- a/utama_core/strategy/referee/tree.py +++ b/utama_core/strategy/referee/tree.py @@ -191,9 +191,8 @@ def __init__(self, is_yellow_command: bool, name: str): self._theirs = BallPlacementTheirsStep(name="BallPlacementTheirs") def setup_(self): - # Propagate setup to the inner nodes so their blackboards are initialised - self._ours.setup(is_opp_strat=False) - self._theirs.setup(is_opp_strat=False) + self._ours.setup(is_opp_strat=self._is_opp_strat) + self._theirs.setup(is_opp_strat=self._is_opp_strat) def update(self) -> py_trees.common.Status: if self._is_yellow_command == self.blackboard.game.my_team_is_yellow: @@ -214,8 +213,8 @@ def __init__(self, is_yellow_command: bool, name: str): self._theirs = PrepareKickoffTheirsStep(name="KickoffTheirs") def setup_(self): - self._ours.setup(is_opp_strat=False) - self._theirs.setup(is_opp_strat=False) + self._ours.setup(is_opp_strat=self._is_opp_strat) + self._theirs.setup(is_opp_strat=self._is_opp_strat) def update(self) -> py_trees.common.Status: if self._is_yellow_command == self.blackboard.game.my_team_is_yellow: @@ -236,8 +235,8 @@ def __init__(self, is_yellow_command: bool, name: str): self._theirs = PreparePenaltyTheirsStep(name="PenaltyTheirs") def setup_(self): - self._ours.setup(is_opp_strat=False) - self._theirs.setup(is_opp_strat=False) + self._ours.setup(is_opp_strat=self._is_opp_strat) + self._theirs.setup(is_opp_strat=self._is_opp_strat) def update(self) -> py_trees.common.Status: if self._is_yellow_command == self.blackboard.game.my_team_is_yellow: @@ -258,8 +257,8 @@ def __init__(self, is_yellow_command: bool, name: str): self._theirs = DirectFreeTheirsStep(name="DirectFreeTheirs") def setup_(self): - self._ours.setup(is_opp_strat=False) - self._theirs.setup(is_opp_strat=False) + self._ours.setup(is_opp_strat=self._is_opp_strat) + self._theirs.setup(is_opp_strat=self._is_opp_strat) def update(self) -> py_trees.common.Status: if self._is_yellow_command == self.blackboard.game.my_team_is_yellow: From 2e653612a72853b4b4da85f5b6f71e299f6eeb76 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Fri, 15 May 2026 12:15:13 +0100 Subject: [PATCH 043/121] fix: make DefenseAreaRule color-aware for symmetric enforcement Previously the rule only checked the "friendly" team's defense area, missing violations in the opponent's box. Now derives yellow/blue sides from my_team_is_right XOR my_team_is_yellow and checks both areas in one pass. Also fix two stale doc issues: - Remove STOP from KeepOutRule active-commands table (it was always excluded) - Update design-decisions section 4 to reflect that reset() is already called on command transitions Co-Authored-By: Claude Sonnet 4.6 --- docs/custom_referee.md | 2 +- docs/custom_referee_design_decisions.md | 23 +----- .../custom_referee/rules/defense_area_rule.py | 78 ++++++++++++------- 3 files changed, 55 insertions(+), 48 deletions(-) diff --git a/docs/custom_referee.md b/docs/custom_referee.md index be86f095..bc6c1570 100644 --- a/docs/custom_referee.md +++ b/docs/custom_referee.md @@ -125,7 +125,7 @@ Each rule is a `BaseRule` subclass. Rules are evaluated in priority order; the * | 1 | `GoalRule` | `NORMAL_START`, `FORCE_START` | | 2 | `OutOfBoundsRule` | `NORMAL_START`, `FORCE_START` | | 3 | `DefenseAreaRule` | `NORMAL_START`, `FORCE_START` | -| 4 | `KeepOutRule` | `STOP`, `DIRECT_FREE_*`, `PREPARE_KICKOFF_*`, `PREPARE_PENALTY_*` | +| 4 | `KeepOutRule` | `DIRECT_FREE_*`, `PREPARE_KICKOFF_*`, `PREPARE_PENALTY_*` | ### GoalRule diff --git a/docs/custom_referee_design_decisions.md b/docs/custom_referee_design_decisions.md index c585336a..a255faff 100644 --- a/docs/custom_referee_design_decisions.md +++ b/docs/custom_referee_design_decisions.md @@ -46,27 +46,10 @@ and slightly more realistic if desired. --- -## 4. `KeepOutRule` violation count carries over between command changes +## 4. ✅ `KeepOutRule` violation count resets on command change — resolved -**File:** `utama_core/custom_referee/rules/keep_out_rule.py` - -**Current behaviour:** -`_violation_count` accumulates across command changes (e.g., transitions from -`DIRECT_FREE_YELLOW` to `PREPARE_KICKOFF_BLUE`). If a robot was encroaching for 20 frames -under one command and the command changes, it only needs 10 more frames under the new command -to trigger a violation. - -**Risk level:** Low — the transition cooldown (`_TRANSITION_COOLDOWN = 0.3 s`) means the -command change and any new violation are unlikely to overlap. Also, robot positions are -usually compliant after a command transition. - -**Options:** -- **A (current, keep):** Accept the minor inconsistency. The persistence threshold (30 frames) - is large enough to make false positives very unlikely. -- **B (reset on command change):** Track the previous command and reset `_violation_count` - whenever `current_command` changes. Clean, low cost. - -**Recommendation:** Option B is a one-liner fix with no downside. +**Resolution:** `CustomReferee.step()` calls `rule.reset()` on every command transition, +which clears `_violation_count`. No carry-over occurs. --- diff --git a/utama_core/custom_referee/rules/defense_area_rule.py b/utama_core/custom_referee/rules/defense_area_rule.py index a5820772..4c8e91b1 100644 --- a/utama_core/custom_referee/rules/defense_area_rule.py +++ b/utama_core/custom_referee/rules/defense_area_rule.py @@ -15,8 +15,21 @@ } +def _split_by_color(game_frame: GameFrame): + """Return (yellow_robots, blue_robots) as dict_values of Robot.""" + if game_frame.my_team_is_yellow: + return game_frame.friendly_robots.values(), game_frame.enemy_robots.values() + else: + return game_frame.enemy_robots.values(), game_frame.friendly_robots.values() + + class DefenseAreaRule(BaseRule): - """Detects attacker encroachment or too many defenders in the defense area.""" + """Detects attacker encroachment or too many defenders in either defense area. + + Checks both teams symmetrically regardless of which team is "friendly", + so enforcement is correct whether CustomReferee is stepped from yellow or + blue perspective. + """ def __init__(self, max_defenders: int = 1, attacker_infringement: bool = True) -> None: self._max_defenders = max_defenders @@ -31,42 +44,53 @@ def check( if current_command not in _ACTIVE_PLAY_COMMANDS: return None - my_team_is_right = game_frame.my_team_is_right - my_team_is_yellow = game_frame.my_team_is_yellow - - # Determine which geometry helper corresponds to "my" defense area. - if my_team_is_right: - in_my_defense = geometry.is_in_right_defense_area - # in_opp_defense = geometry.is_in_left_defense_area - else: - in_my_defense = geometry.is_in_left_defense_area - # in_opp_defense = geometry.is_in_right_defense_area - - # Check: too many friendly defenders in own area. - n_friendly_in_own = sum(1 for r in game_frame.friendly_robots.values() if in_my_defense(r.p.x, r.p.y)) - if n_friendly_in_own > self._max_defenders: - # Opponent gets a free kick. - free_kick_cmd = RefereeCommand.DIRECT_FREE_BLUE if my_team_is_yellow else RefereeCommand.DIRECT_FREE_YELLOW + # Derive which side each color defends from the caller's perspective. + # yellow_is_right is True when yellow defends the right goal. + yellow_is_right = game_frame.my_team_is_right == game_frame.my_team_is_yellow + + in_yellow_defense = geometry.is_in_right_defense_area if yellow_is_right else geometry.is_in_left_defense_area + in_blue_defense = geometry.is_in_left_defense_area if yellow_is_right else geometry.is_in_right_defense_area + + yellow_robots, blue_robots = (list(g) for g in _split_by_color(game_frame)) + + # --- Yellow defense area --- + n_yellow_defenders = sum(1 for r in yellow_robots if in_yellow_defense(r.p.x, r.p.y)) + if n_yellow_defenders > self._max_defenders: return RuleViolation( rule_name="defense_area", suggested_command=RefereeCommand.STOP, - next_command=free_kick_cmd, - status_message="Too many defenders in own area", + next_command=RefereeCommand.DIRECT_FREE_BLUE, + status_message="Too many yellow defenders in own area", ) - # Check: enemy attacker inside our defense area. if self._attacker_infringement: - for robot in game_frame.enemy_robots.values(): - if in_my_defense(robot.p.x, robot.p.y): - # Defending team (friendly) gets the free kick. - free_kick_cmd = ( - RefereeCommand.DIRECT_FREE_YELLOW if my_team_is_yellow else RefereeCommand.DIRECT_FREE_BLUE + for r in blue_robots: + if in_yellow_defense(r.p.x, r.p.y): + return RuleViolation( + rule_name="defense_area", + suggested_command=RefereeCommand.STOP, + next_command=RefereeCommand.DIRECT_FREE_YELLOW, + status_message="Blue attacker in yellow defense area", ) + + # --- Blue defense area --- + n_blue_defenders = sum(1 for r in blue_robots if in_blue_defense(r.p.x, r.p.y)) + if n_blue_defenders > self._max_defenders: + return RuleViolation( + rule_name="defense_area", + suggested_command=RefereeCommand.STOP, + next_command=RefereeCommand.DIRECT_FREE_YELLOW, + status_message="Too many blue defenders in own area", + ) + + if self._attacker_infringement: + for r in yellow_robots: + if in_blue_defense(r.p.x, r.p.y): return RuleViolation( rule_name="defense_area", suggested_command=RefereeCommand.STOP, - next_command=free_kick_cmd, - status_message="Attacker in defense area", + next_command=RefereeCommand.DIRECT_FREE_BLUE, + status_message="Yellow attacker in blue defense area", ) return None From 6db9d493007df0da7db5ca00751041ee90398967 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Fri, 15 May 2026 12:36:14 +0100 Subject: [PATCH 044/121] fix: cache last RefereeData so GameFrame.referee stays populated between packets When using referee_system='official', the GC sends packets at ~10 Hz while the main loop runs at 60 Hz. popleft() returned None on most ticks, causing GameFrame.referee to drop out intermittently and disabling the referee layer. Now the last successfully received RefereeData is cached and reused on ticks where the buffer is empty. The RSIM/custom path is unaffected (data is always produced on the same tick it is consumed). Co-Authored-By: Claude Sonnet 4.6 --- utama_core/run/strategy_runner.py | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index 7047194e..f24ac479 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -13,7 +13,7 @@ from utama_core.config.enums import Mode, mode_str_to_enum from utama_core.config.field_params import STANDARD_FIELD_DIMS, FieldDimensions -from utama_core.config.formations import get_formations +from utama_core.config.formations import FormationType, get_formations from utama_core.config.physical_constants import MAX_ROBOTS from utama_core.config.settings import ( FPS_PRINT_INTERVAL, @@ -61,6 +61,7 @@ if TYPE_CHECKING: from utama_core.custom_referee import CustomReferee + from utama_core.entities.data.referee import RefereeData logging.basicConfig( filename="Utama.log", @@ -157,17 +158,20 @@ def __init__( filtering: bool = False, referee_system: Optional[str] = None, custom_referee: Optional["CustomReferee"] = None, + formation_type: Optional[FormationType] = None, ): self.logger = logging.getLogger(__name__) self.custom_referee = custom_referee self._prev_custom_ref_command: Optional[RefereeCommand] = None + self._last_referee_data: Optional["RefereeData"] = None self.my_team_is_yellow = my_team_is_yellow self.my_team_is_right = my_team_is_right self.mode: Mode = self._load_mode(mode) self.exp_friendly = exp_friendly self.exp_enemy = exp_enemy self.exp_ball = exp_ball + self.formation_type = formation_type self.full_field_dims = full_field_dims # if field bounds not provided, default to full field dimensions self.field_bounds = field_bounds if field_bounds else full_field_dims.full_field_bounds @@ -423,11 +427,14 @@ def _load_sim( if self.mode == Mode.REAL: return None, None - right_start, left_start = get_formations( + get_formations_kwargs = dict( bounds=self.field_bounds, n_right=self.exp_friendly if self.my_team_is_right else self.exp_enemy, n_left=self.exp_enemy if self.my_team_is_right else self.exp_friendly, ) + if self.formation_type is not None: + get_formations_kwargs["formation_type"] = self.formation_type + right_start, left_start = get_formations(**get_formations_kwargs) yellow_start, blue_start = map_left_right_to_colors( self.my_team_is_yellow, self.my_team_is_right, right_start, left_start @@ -888,7 +895,9 @@ def _run_step(self): referee_data = self.ref_buffer.popleft() if self.ref_buffer else None else: vision_frames = [buffer.popleft() if buffer else None for buffer in self.vision_buffers] - referee_data = self.ref_buffer.popleft() if self.ref_buffer else None + if self.ref_buffer: + self._last_referee_data = self.ref_buffer.popleft() + referee_data = self._last_referee_data # alternate between opp and friendly playing if self.toggle_opp_first: From 0a1e9125a9608968f21aa0ad250dddce36ac821b Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Sat, 16 May 2026 20:50:17 +0100 Subject: [PATCH 045/121] fix: address Copilot review issues in referee tree dispatchers and penalty docstrings Remove redundant child.blackboard assignments in all dispatcher update() methods since each child already attaches to the same global blackboard namespace during setup(). Clarify penalty positioning docstrings to reflect current behaviour and flag them as the place for strategy team tuning. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/strategy/referee/actions.py | 12 ++++++++---- utama_core/strategy/referee/tree.py | 8 -------- 2 files changed, 8 insertions(+), 12 deletions(-) diff --git a/utama_core/strategy/referee/actions.py b/utama_core/strategy/referee/actions.py index fdb84597..a9f5c8aa 100644 --- a/utama_core/strategy/referee/actions.py +++ b/utama_core/strategy/referee/actions.py @@ -384,10 +384,11 @@ def update(self) -> py_trees.common.Status: class PreparePenaltyOursStep(AbstractBehaviour): """Positions robots for our penalty kick. - Kicker (lowest non-keeper ID): moves to our penalty mark, faces goal. - All others: stop on a line behind the penalty mark on our side. + Kicker (lowest non-keeper ID): moves to the penalty mark, faces goal. + All others: stop on a line behind the penalty mark spread along y. - Penalty mark is placed halfway between the centre line and the target goal line. + Exact placement of non-kicker/non-keeper robots is a strategy decision + and can be tuned here by the strategy team. """ def update(self) -> py_trees.common.Status: @@ -436,7 +437,10 @@ class PreparePenaltyTheirsStep(AbstractBehaviour): """Positions our robots for the opponent's penalty kick. Goalkeeper: moves to our goal line centre. - All others: move to a line behind the penalty mark on our half. + All others: stop on a line behind the penalty mark spread along y. + + Exact placement of non-keeper robots is a strategy decision + and can be tuned here by the strategy team. """ def update(self) -> py_trees.common.Status: diff --git a/utama_core/strategy/referee/tree.py b/utama_core/strategy/referee/tree.py index 0dd1e1ec..e77f3d6b 100644 --- a/utama_core/strategy/referee/tree.py +++ b/utama_core/strategy/referee/tree.py @@ -196,10 +196,8 @@ def setup_(self): def update(self) -> py_trees.common.Status: if self._is_yellow_command == self.blackboard.game.my_team_is_yellow: - self._ours.blackboard = self.blackboard return self._ours.update() else: - self._theirs.blackboard = self.blackboard return self._theirs.update() @@ -218,10 +216,8 @@ def setup_(self): def update(self) -> py_trees.common.Status: if self._is_yellow_command == self.blackboard.game.my_team_is_yellow: - self._ours.blackboard = self.blackboard return self._ours.update() else: - self._theirs.blackboard = self.blackboard return self._theirs.update() @@ -240,10 +236,8 @@ def setup_(self): def update(self) -> py_trees.common.Status: if self._is_yellow_command == self.blackboard.game.my_team_is_yellow: - self._ours.blackboard = self.blackboard return self._ours.update() else: - self._theirs.blackboard = self.blackboard return self._theirs.update() @@ -262,8 +256,6 @@ def setup_(self): def update(self) -> py_trees.common.Status: if self._is_yellow_command == self.blackboard.game.my_team_is_yellow: - self._ours.blackboard = self.blackboard return self._ours.update() else: - self._theirs.blackboard = self.blackboard return self._theirs.update() From 60b7c52597e999c79df1f7ef110d4f1a4f964aa7 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Sun, 17 May 2026 14:07:44 +0100 Subject: [PATCH 046/121] fix: prevent keep-out violations and defense-area infinite loop - PrepareKickoffOursStep: route support robots through _clear_to_legal_positions with intended_targets so their paths never cross the 0.5m keep-out circle, even when starting on the enemy half after a STOP clearance. Kicker approaches from own-half side offset (ROBOT_RADIUS + 0.03m) instead of exactly (0,0). - StopStep: add own-defense-area eviction so excess defenders are pushed outside the front edge during STOP. Prevents the infinite loop where two robots sit in their own area, STOP ends, the DefenseAreaRule fires immediately, STOP restarts, and no robot ever moves out. New helpers in actions.py: _is_in_own_defense_area(game, x, y) _own_defense_area_exit_x(game) New params on _clear_to_legal_positions: clear_own_defense_area: bool = False max_own_defenders: int = 1 - formations.py: add START_2V2 formation for 2v2 exhibition matches. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/config/formations.py | 7 +++ utama_core/strategy/referee/actions.py | 78 ++++++++++++++++++++++---- 2 files changed, 73 insertions(+), 12 deletions(-) diff --git a/utama_core/config/formations.py b/utama_core/config/formations.py index 4708dfc4..a53855b2 100644 --- a/utama_core/config/formations.py +++ b/utama_core/config/formations.py @@ -30,9 +30,16 @@ class FormationEntry(NamedTuple): class FormationType(Enum): START_ONE = "START_ONE" + START_2V2 = "START_2V2" FORMATIONS = { + FormationType.START_2V2: [ + # Robot 0: goalkeeper — just in front of defense area (normalised x = 0.775 → 1.55m on exhibition field) + FormationEntry(0.775, 0.0, np.pi), + # Robot 1: field player — centre of own half, clear of keep-out circle + FormationEntry(0.3, 0.0, np.pi), + ], FormationType.START_ONE: [ FormationEntry(0.9, 0.0, np.pi), FormationEntry(0.75, -0.2, np.pi), diff --git a/utama_core/strategy/referee/actions.py b/utama_core/strategy/referee/actions.py index a9f5c8aa..facc9093 100644 --- a/utama_core/strategy/referee/actions.py +++ b/utama_core/strategy/referee/actions.py @@ -14,6 +14,7 @@ import py_trees +from utama_core.config.physical_constants import ROBOT_RADIUS from utama_core.config.referee_constants import ( BALL_KEEP_OUT_DISTANCE, BALL_PLACEMENT_DONE_DISTANCE, @@ -116,6 +117,30 @@ def _clamp_to_field(point: Vector2D, game) -> Vector2D: ) +def _is_in_own_defense_area(game, x: float, y: float) -> bool: + """Return True if (x, y) is inside our own defense area.""" + own_goal_sign = 1.0 if game.my_team_is_right else -1.0 + field_half_length = _field_half_length(game) + depth = game.field.half_defense_area_depth + width = game.field.half_defense_area_width + # Own defense area inner edge (closest to center) + inner_x = own_goal_sign * (field_half_length - 2.0 * depth) + if own_goal_sign > 0: + return x >= inner_x and abs(y) <= width + else: + return x <= inner_x and abs(y) <= width + + +def _own_defense_area_exit_x(game) -> float: + """Return the x-coordinate just outside our own defense area front edge.""" + own_goal_sign = 1.0 if game.my_team_is_right else -1.0 + field_half_length = _field_half_length(game) + depth = game.field.half_defense_area_depth + inner_x = own_goal_sign * (field_half_length - 2.0 * depth) + # Step one robot-diameter outside the front edge + return inner_x - own_goal_sign * (2 * ROBOT_RADIUS + 0.05) + + def _project_outside_opp_defense_area(game, point: Vector2D, keep_dist: float) -> Vector2D: """Project a point out of the opponent defense area plus the required keep distance.""" field_half_length = _field_half_length(game) @@ -143,6 +168,8 @@ def _clear_to_legal_positions( ball_keep_dist: float | None = None, designated_keep_dist: float | None = None, clear_opp_defense_area: bool = False, + clear_own_defense_area: bool = False, + max_own_defenders: int = 1, exempt_robot_ids: set[int] | None = None, intended_targets: dict[int, Vector2D] | None = None, ) -> py_trees.common.Status: @@ -151,11 +178,27 @@ def _clear_to_legal_positions( If intended_targets is provided, each robot's clearance starts from its intended formation target rather than its current position, so the clearing pass refines rather than discards the formation intent. + + If clear_own_defense_area is True, robots in excess of max_own_defenders + inside our own defense area are pushed out to just outside the front edge. + The goalkeeper (lowest-ID robot inside the area) is kept as the allowed defender. """ game = blackboard.game motion_controller = blackboard.motion_controller exempt_robot_ids = exempt_robot_ids or set() + # Determine which friendly robots must exit own defense area. + own_defense_evict: set[int] = set() + if clear_own_defense_area: + in_own_area = [ + rid + for rid, robot in game.friendly_robots.items() + if rid not in exempt_robot_ids and _is_in_own_defense_area(game, robot.p.x, robot.p.y) + ] + # Keep the first max_own_defenders (sorted by id) — evict the rest. + for rid in sorted(in_own_area)[max_own_defenders:]: + own_defense_evict.add(rid) + ball_center = None if ball_keep_dist is not None and game.ball is not None: ball_center = Vector2D(game.ball.p.x, game.ball.p.y) @@ -190,6 +233,8 @@ def _clear_to_legal_positions( else: target = robot_pos + if robot_id in own_defense_evict: + target = Vector2D(_own_defense_area_exit_x(game), robot.p.y) if ball_center is not None: target = _project_outside_circle(target, ball_center, ball_keep_dist, ball_fallback) if designated_center is not None: @@ -238,6 +283,8 @@ def update(self) -> py_trees.common.Status: self.blackboard, ball_keep_dist=BALL_KEEP_OUT_DISTANCE, clear_opp_defense_area=True, + clear_own_defense_area=True, + max_own_defenders=1, ) @@ -335,23 +382,30 @@ def update(self) -> py_trees.common.Status: robot_ids = sorted(game.friendly_robots.keys()) kicker_id = robot_ids[0] - # Support positions depend on which side we defend - support_positions = _formation_positions(game, KICKOFF_SUPPORT_POSITION_RATIOS_OWN_HALF) + # Kicker: approach from own-half side so the robot doesn't push the ball. + own_half_sign = 1.0 if game.my_team_is_right else -1.0 + kicker_target = Vector2D(own_half_sign * (ROBOT_RADIUS + 0.03), 0.0) + goal_x = _field_half_length(game) if not game.my_team_is_right else -_field_half_length(game) + oren = math.atan2(0.0 - kicker_target.y, goal_x - kicker_target.x) + self.blackboard.cmd_map[kicker_id] = move(game, motion_controller, kicker_id, kicker_target, oren) + # Support robots: route through _clear_to_legal_positions so their paths + # never cut across the keep-out zone even if they start on the enemy half. + support_positions = _formation_positions(game, KICKOFF_SUPPORT_POSITION_RATIOS_OWN_HALF) support_idx = 0 + intended: dict[int, Vector2D] = {} for robot_id in robot_ids: if robot_id == kicker_id: - # Approach the ball at centre, face the opponent goal - target = Vector2D(0.0, 0.0) - goal_x = _field_half_length(game) if not game.my_team_is_right else -_field_half_length(game) - oren = math.atan2(0.0 - target.y, goal_x - target.x) - self.blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, target, oren) - else: - pos = support_positions[support_idx % len(support_positions)] - support_idx += 1 - self.blackboard.cmd_map[robot_id] = move(game, motion_controller, robot_id, pos, 0.0) + continue + intended[robot_id] = support_positions[support_idx % len(support_positions)] + support_idx += 1 - return py_trees.common.Status.RUNNING + return _clear_to_legal_positions( + self.blackboard, + ball_keep_dist=BALL_KEEP_OUT_DISTANCE, + exempt_robot_ids={kicker_id}, + intended_targets=intended, + ) # --------------------------------------------------------------------------- From b31781145a47e911002a4c198bc200d5e648e4c7 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Sun, 17 May 2026 15:18:10 +0100 Subject: [PATCH 047/121] fix: seed _prepare_entered_time in set_command() for direct PREPARE_* commands When set_command() is called with a PREPARE_KICKOFF_* or PREPARE_PENALTY_* command while already in STOP/HALT (bypassing the insert-STOP branch), _prepare_entered_time was never updated from -inf, causing the auto-advance prepare-duration check to fire immediately. Seed it (and _stop_entered_time for STOP/HALT) in the fallthrough path so the delay is always respected. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/custom_referee/state_machine.py | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/utama_core/custom_referee/state_machine.py b/utama_core/custom_referee/state_machine.py index 479be681..a3c7b248 100644 --- a/utama_core/custom_referee/state_machine.py +++ b/utama_core/custom_referee/state_machine.py @@ -509,6 +509,16 @@ def set_command(self, command: RefereeCommand, timestamp: float) -> None: self._advance3_ready_since = math.inf self._advance4_ready_since = math.inf + if command in (RefereeCommand.STOP, RefereeCommand.HALT): + self._stop_entered_time = timestamp + elif command in ( + RefereeCommand.PREPARE_KICKOFF_YELLOW, + RefereeCommand.PREPARE_KICKOFF_BLUE, + RefereeCommand.PREPARE_PENALTY_YELLOW, + RefereeCommand.PREPARE_PENALTY_BLUE, + ): + self._prepare_entered_time = timestamp + # Advance PRE stages to their active counterpart when play begins. _PRE_TO_ACTIVE = { Stage.NORMAL_FIRST_HALF_PRE: Stage.NORMAL_FIRST_HALF, From 56b20a9f67faa3cddfbd117e9cbcddb1d7e76411 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Mon, 18 May 2026 14:57:01 +0100 Subject: [PATCH 048/121] refactor: replace referee_system+custom_referee args with typed RefereeSource union MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Replaces the two coupled StrategyRunner arguments (`referee_system: str` and `custom_referee: CustomReferee`) with a single `referee: RefereeSource` parameter that accepts `None`, `OfficialReferee()`, or a `CustomReferee` instance — a proper discriminated union with no string magic. Also fixes referee clock initialisation: StrategyRunner now calls `CustomReferee.seed_clock()` after `_load_game()` so all internal timers are anchored to the first real `game_frame.ts` rather than a hardcoded 0.0. This makes the referee work correctly when reusing a long-running grsim instance (wall-clock ts) or rsim (sim-time ts). The initial command is automatically chosen by mode — FORCE_START for rsim/grsim, HALT for real — so developers no longer need to call `set_command()` at startup. Co-Authored-By: Claude Sonnet 4.6 --- demo_referee_gui_rsim.py | 6 +- main.py | 5 +- utama_core/custom_referee/custom_referee.py | 13 ++ utama_core/custom_referee/state_machine.py | 17 +++ utama_core/run/__init__.py | 1 + utama_core/run/referee_source.py | 17 +++ utama_core/run/strategy_runner.py | 139 ++++++++++++------ .../tests/referee/demo_referee_gui_rsim.py | 6 +- .../strategy_runner/test_error_handling.py | 2 + .../strategy_runner/test_referee_rsim.py | 3 +- .../strategy_runner/test_runner_misconfig.py | 49 +++--- 11 files changed, 164 insertions(+), 94 deletions(-) create mode 100644 utama_core/run/referee_source.py diff --git a/demo_referee_gui_rsim.py b/demo_referee_gui_rsim.py index b74e6b2b..561b9a1a 100644 --- a/demo_referee_gui_rsim.py +++ b/demo_referee_gui_rsim.py @@ -7,8 +7,7 @@ What it does: - Creates a CustomReferee (human profile) with enable_gui=True so the browser panel starts automatically. - - Passes the referee to StrategyRunner via custom_referee= with - referee_system="custom". StrategyRunner + - Passes the referee to StrategyRunner via referee=. StrategyRunner calls referee.step() on every tick and handles ball teleports on STOP automatically — no patching required. - WanderingStrategy is used as the base strategy so robots visibly move and @@ -65,8 +64,7 @@ def main() -> None: control_scheme="pid", exp_friendly=N_ROBOTS, exp_enemy=N_ROBOTS, - referee_system="custom", - custom_referee=referee, # StrategyRunner drives referee.step() each tick + referee=referee, # StrategyRunner drives referee.step() each tick show_live_status=True, opp_strategy=WanderingStrategy(), ) diff --git a/main.py b/main.py index 017cfc9f..75cd4870 100644 --- a/main.py +++ b/main.py @@ -1,7 +1,6 @@ from utama_core.config.field_params import GREAT_EXHIBITION_FIELD_DIMS from utama_core.custom_referee import CustomReferee from utama_core.entities.game.field import FieldBounds -from utama_core.entities.referee.referee_command import RefereeCommand from utama_core.replay import ReplayWriterConfig from utama_core.rsoccer_simulator.src.Utils.gaussian_noise import RsimGaussianNoise from utama_core.run import StrategyRunner @@ -17,7 +16,6 @@ def main(): referee = CustomReferee.from_profile_name("simulation", n_robots_yellow=3, n_robots_blue=3, enable_gui=True) - referee.set_command(RefereeCommand.NORMAL_START, timestamp=0.0) # Setup for real testing # Custom field size based setup in real @@ -35,8 +33,7 @@ def main(): full_field_dims=GREAT_EXHIBITION_FIELD_DIMS, show_live_status=True, profiler_name=None, - referee_system="custom", - custom_referee=referee, + referee=referee, ) runner.my.strategy.render() runner.run() diff --git a/utama_core/custom_referee/custom_referee.py b/utama_core/custom_referee/custom_referee.py index 42862342..2be3cd00 100644 --- a/utama_core/custom_referee/custom_referee.py +++ b/utama_core/custom_referee/custom_referee.py @@ -153,6 +153,19 @@ def step(self, game_frame: GameFrame, current_time: float) -> RefereeData: self._gui_server.notify(result, game_frame) return result + def seed_clock(self, timestamp: float, initial_command: RefereeCommand = RefereeCommand.HALT) -> None: + """Align all internal state-machine timers to *timestamp* and apply + *initial_command*. + + Called by StrategyRunner after the first valid game frame is available, + so the referee's timebase matches game_frame.ts from the very first tick. + This handles both rsim (sim-time starting near 0) and grsim/real reuse + (wall-clock timestamps that may be far from 0). + """ + self._state.seed_clock(timestamp) + if initial_command != RefereeCommand.HALT: + self._state.set_command(initial_command, timestamp) + def set_command(self, command: RefereeCommand, timestamp: float) -> None: """Manual override — for operator use or test scripting.""" self._state.set_command(command, timestamp) diff --git a/utama_core/custom_referee/state_machine.py b/utama_core/custom_referee/state_machine.py index a3c7b248..e97a10fb 100644 --- a/utama_core/custom_referee/state_machine.py +++ b/utama_core/custom_referee/state_machine.py @@ -456,6 +456,23 @@ def _ball_placement_done(self, game_frame: "GameFrame") -> bool: } ) + def seed_clock(self, timestamp: float) -> None: + """Align all internal timers to *timestamp*. + + Resets every timer that was initialised before the real vision clock + was known (construction time) so that durations are measured from the + correct timebase. Safe to call only once, immediately after the first + valid game frame is available. + """ + if self.stage_start_time is None: + self.stage_start_time = timestamp + self.command_timestamp = timestamp + # Push all "entered-at" sentinels to the new timebase so that + # cooldowns / durations are not immediately satisfied. + self._last_transition_time = timestamp - _TRANSITION_COOLDOWN # allow transitions immediately + self._stop_entered_time = timestamp - self._stop_duration_seconds # won't auto-advance yet + self._prepare_entered_time = timestamp - self._prepare_duration_seconds # same + def set_command(self, command: RefereeCommand, timestamp: float) -> None: """Manual override — for operator use or test scripting. diff --git a/utama_core/run/__init__.py b/utama_core/run/__init__.py index bbc3d365..b36a0cf8 100644 --- a/utama_core/run/__init__.py +++ b/utama_core/run/__init__.py @@ -1,2 +1,3 @@ from utama_core.run.game_gater import GameGater +from utama_core.run.referee_source import OfficialReferee, RefereeSource from utama_core.run.strategy_runner import StrategyRunner diff --git a/utama_core/run/referee_source.py b/utama_core/run/referee_source.py new file mode 100644 index 00000000..b2283696 --- /dev/null +++ b/utama_core/run/referee_source.py @@ -0,0 +1,17 @@ +"""Referee source discriminated union for StrategyRunner.""" + +from __future__ import annotations + +from dataclasses import dataclass +from typing import TYPE_CHECKING, Union + +if TYPE_CHECKING: + from utama_core.custom_referee import CustomReferee + + +@dataclass(frozen=True) +class OfficialReferee: + """Sentinel: consume referee commands from the official SSL game-controller over the network.""" + + +RefereeSource = Union[None, OfficialReferee, "CustomReferee"] diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index f24ac479..82dab5ec 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -6,6 +6,7 @@ import warnings from collections import deque from dataclasses import dataclass, field +from pathlib import Path from typing import TYPE_CHECKING, List, Optional, Tuple from rich.live import Live @@ -21,6 +22,7 @@ MAX_GAME_HISTORY, TIMESTEP, ) +from utama_core.custom_referee import CustomReferee from utama_core.data_processing.receivers import RefereeMessageReceiver, VisionReceiver from utama_core.data_processing.refiners import ( PositionRefiner, @@ -44,6 +46,8 @@ from utama_core.rsoccer_simulator.src.ssl.envs import SSLStandardEnv from utama_core.rsoccer_simulator.src.Utils.gaussian_noise import RsimGaussianNoise from utama_core.run import GameGater +from utama_core.run.game_tracer import GameTracer +from utama_core.run.referee_source import OfficialReferee, RefereeSource from utama_core.strategy.common.abstract_strategy import AbstractStrategy from utama_core.team_controller.src.controllers import ( AbstractSimController, @@ -60,7 +64,6 @@ ) if TYPE_CHECKING: - from utama_core.custom_referee import CustomReferee from utama_core.entities.data.referee import RefereeData logging.basicConfig( @@ -118,6 +121,10 @@ class StrategyRunner: show_live_status (bool, optional): Whether to show the live terminal status panel. This panel includes FPS, referee command, stage, score, time remaining, and optional status text. Defaults to False. + verbose_trace (bool, optional): Whether to emit a human- and LLM-readable trace of + meaningful game-state changes (referee commands, ball possession, role assignments, + robot actuations). Trace is written to ``game_trace_.log`` in the working + directory and also printed to stderr. Defaults to False. print_real_fps (bool, optional): Deprecated alias for `show_live_status`. profiler_name (Optional[str], optional): Enables and sets profiler name. Defaults to None which disables profiler. rsim_noise (RsimGaussianNoise, optional): When running in rsim, add Gaussian noise to balls and robots with the @@ -126,13 +133,10 @@ class StrategyRunner: rsim_vanishing (float, optional): When running in rsim, cause robots and ball to vanish with the given probability. Defaults to 0. filtering (bool, optional): Turn on Kalman filtering. Defaults to false. - referee_system (str, optional): Referee source selector. Valid values are - `"none"`, `"official"`, and `"custom"`. When omitted, it defaults to - `"none"` and no referee input is consumed unless an explicit referee - system is selected. - custom_referee (CustomReferee, optional): In-process referee source used instead of the - network referee receiver. Works across rsim, grsim, and real modes by pushing RefereeData - into ref_buffer each tick before the strategy step. + referee (RefereeSource, optional): Referee source. Pass a ``CustomReferee`` + instance to use the in-process referee, ``OfficialReferee()`` to consume + commands from the SSL game-controller over the network, or ``None`` + (default) to run without any referee input. """ def __init__( @@ -151,18 +155,17 @@ def __init__( opp_control_scheme: Optional[str] = None, replay_writer_config: Optional[ReplayWriterConfig] = None, show_live_status: bool = False, # Turn this on for simulator debugging + verbose_trace: bool = False, print_real_fps: Optional[bool] = None, profiler_name: Optional[str] = None, rsim_noise: RsimGaussianNoise = RsimGaussianNoise(), rsim_vanishing: float = 0, filtering: bool = False, - referee_system: Optional[str] = None, - custom_referee: Optional["CustomReferee"] = None, + referee: RefereeSource = None, formation_type: Optional[FormationType] = None, ): self.logger = logging.getLogger(__name__) - self.custom_referee = custom_referee self._prev_custom_ref_command: Optional[RefereeCommand] = None self._last_referee_data: Optional["RefereeData"] = None self.my_team_is_yellow = my_team_is_yellow @@ -175,17 +178,15 @@ def __init__( self.full_field_dims = full_field_dims # if field bounds not provided, default to full field dimensions self.field_bounds = field_bounds if field_bounds else full_field_dims.full_field_bounds - self.referee_system = self._resolve_referee_system(self.mode, referee_system, custom_referee) + self.referee: RefereeSource = self._validate_referee(self.mode, referee) # Ensure the custom referee's geometry matches the actual field in use. # The YAML profile geometry is the fallback for standalone use; here # full_field_dims + field_bounds is the single source of truth. - if self.referee_system == "custom" and self.custom_referee is not None: + if isinstance(self.referee, CustomReferee): from utama_core.custom_referee.geometry import RefereeGeometry - self.custom_referee.override_geometry( - RefereeGeometry.from_field_dims(self.full_field_dims, self.field_bounds) - ) + self.referee.override_geometry(RefereeGeometry.from_field_dims(self.full_field_dims, self.field_bounds)) self.vision_buffers, self.ref_buffer = self._setup_vision_and_referee() @@ -217,6 +218,15 @@ def __init__( # Load all game related data self._load_game() self._assert_exp_goals() + + # Seed the custom referee's internal clocks from the first real vision + # timestamp so all timers are on the same timebase regardless of mode + # (rsim sim-time or grsim/real wall-time). + # Sim modes start in FORCE_START so play begins immediately; real mode + # starts in HALT so the operator can set up before play begins. + if isinstance(self.referee, CustomReferee): + initial_command = RefereeCommand.HALT if self.mode == Mode.REAL else RefereeCommand.FORCE_START + self.referee.seed_clock(self.my.current_game_frame.ts, initial_command) self.my.strategy.setup_behaviour_tree(is_opp_strat=False) if self.opp: self.opp.strategy.setup_behaviour_tree(is_opp_strat=True) @@ -238,6 +248,29 @@ def __init__( else None ) + # Verbose game-state tracer (one per side, written to separate files) + my_color = "yellow" if my_team_is_yellow else "blue" + opp_color = "blue" if my_team_is_yellow else "yellow" + self.game_tracer = ( + GameTracer( + trace_path=Path(f"game_trace_{my_color}.log"), + to_stdout=True, + team_color=my_color, + ) + if verbose_trace + else None + ) + self.opp_game_tracer = ( + GameTracer( + trace_path=Path(f"game_trace_{opp_color}.log"), + to_stdout=True, + team_color=opp_color, + ) + if verbose_trace and self.opp is not None + else None + ) + self._trace_frame_count = 0 + # Live terminal status panel self.num_frames_elapsed = 0 self.elapsed_time = 0.0 @@ -279,36 +312,17 @@ def _load_mode(self, mode_str: str) -> Mode: return mode @staticmethod - def _resolve_referee_system( - mode: Mode, - referee_system: Optional[str], - custom_referee: Optional["CustomReferee"], - ) -> str: - """Resolve and validate referee source selection. - - Default behavior: - - omitted -> "none" - """ - if referee_system is None: - referee_system = "none" - - system = referee_system.lower() - if system not in {"none", "official", "custom"}: - raise ValueError(f"Unknown referee_system: {referee_system}. Choose from 'none', 'official', or 'custom'.") - - if system == "custom" and custom_referee is None: - raise ValueError("referee_system='custom' requires a custom_referee instance.") - - if system != "custom" and custom_referee is not None: - raise ValueError( - "custom_referee was provided, but referee_system is not 'custom'. " - "Use referee_system='custom' or remove custom_referee." + def _validate_referee(mode: Mode, referee: RefereeSource) -> RefereeSource: + """Validate the referee source against the current mode.""" + if referee is not None and not isinstance(referee, (OfficialReferee, CustomReferee)): + raise TypeError( + f"referee must be None, OfficialReferee(), or a CustomReferee instance; got {type(referee).__name__}." ) - if system == "official" and mode == Mode.RSIM: - raise ValueError("referee_system='official' is not supported in rsim. Use 'none' or 'custom'.") + if isinstance(referee, OfficialReferee) and mode == Mode.RSIM: + raise ValueError("OfficialReferee is not supported in rsim mode. Use None or a CustomReferee instance.") - return system + return referee def data_update_listener(self, receiver: VisionReceiver): """Listener function to pull vision data from a VisionReceiver. @@ -502,7 +516,7 @@ def _setup_vision_and_referee(self) -> Tuple[deque, deque]: ref_buffer = deque(maxlen=1) if self.mode != Mode.RSIM: vision_receiver = VisionReceiver(vision_buffers) - if self.referee_system == "official": + if isinstance(self.referee, OfficialReferee): referee_receiver = RefereeMessageReceiver(ref_buffer) self.start_threads(vision_receiver, referee_receiver) else: @@ -754,6 +768,10 @@ def close(self, stop_command_repeat: int = 20): self.rsim_env.close() if self._fps_live: self._fps_live.stop() + if self.game_tracer: + self.game_tracer.close() + if self.opp_game_tracer: + self.opp_game_tracer.close() def run_test( self, @@ -871,8 +889,8 @@ def _run_step(self): frame_start = time.perf_counter() self._draw_rsim_field_bounds_overlay() - if self.referee_system == "custom": - ref_data = self.custom_referee.step(self.my.current_game_frame, self.my.current_game_frame.ts) + if isinstance(self.referee, CustomReferee): + ref_data = self.referee.step(self.my.current_game_frame, self.my.current_game_frame.ts) self.ref_buffer.append(ref_data) _ball_placement_next = ref_data.next_command in ( RefereeCommand.BALL_PLACEMENT_YELLOW, @@ -947,11 +965,15 @@ def _run_step(self): display.append(" Yellow") display.append(f" | {stage_min}:{stage_sec:02d} left") display.append(" | Ref: ") - display.append(self.referee_system, style="bold magenta") - if self.referee_system == "custom" and self.custom_referee is not None: + if isinstance(self.referee, CustomReferee): + display.append("custom", style="bold magenta") display.append(" (") - display.append(self.custom_referee.profile_name, style="magenta") + display.append(self.referee.profile_name, style="magenta") display.append(")") + elif isinstance(self.referee, OfficialReferee): + display.append("official", style="bold magenta") + else: + display.append("none", style="bold magenta") if ref.last_status_message: display.append(f" | {ref.last_status_message}", style="dim") @@ -1015,3 +1037,22 @@ def _step_game( side.game.add_game_frame(new_game_frame) side.strategy.step() + + tracer = self.opp_game_tracer if running_opp else self.game_tracer + if tracer is not None: + if not running_opp: + self._trace_frame_count += 1 + bb = side.strategy.blackboard + try: + tactic = bb.tactic + except KeyError: + tactic = None + tracer.step( + game_frame=new_game_frame, + role_map=bb.role_map or {}, + cmd_map=bb.cmd_map or {}, + frame_number=self._trace_frame_count, + tactic=tactic, + behaviour_tree=side.strategy.behaviour_tree, + blackboard=bb, + ) diff --git a/utama_core/tests/referee/demo_referee_gui_rsim.py b/utama_core/tests/referee/demo_referee_gui_rsim.py index fc7f962c..8da0d9a1 100644 --- a/utama_core/tests/referee/demo_referee_gui_rsim.py +++ b/utama_core/tests/referee/demo_referee_gui_rsim.py @@ -7,8 +7,7 @@ What it does: - Creates a CustomReferee (human profile) with enable_gui=True so the browser panel starts automatically. - - Passes the referee to StrategyRunner via custom_referee= with - referee_system="custom". StrategyRunner + - Passes the referee to StrategyRunner via referee=. StrategyRunner calls referee.step() on every tick and handles ball teleports on STOP automatically — no patching required. - WanderingStrategy is used as the base strategy so robots visibly move and @@ -64,8 +63,7 @@ def main() -> None: mode="rsim", exp_friendly=N_ROBOTS, exp_enemy=N_ROBOTS, - referee_system="custom", - custom_referee=referee, # StrategyRunner drives referee.step() each tick + referee=referee, # StrategyRunner drives referee.step() each tick show_live_status=True, ) diff --git a/utama_core/tests/strategy_runner/test_error_handling.py b/utama_core/tests/strategy_runner/test_error_handling.py index 340c7fe0..5d5b3481 100644 --- a/utama_core/tests/strategy_runner/test_error_handling.py +++ b/utama_core/tests/strategy_runner/test_error_handling.py @@ -20,6 +20,8 @@ def mock_runner(): runner.replay_writer = None runner.rsim_env = None runner._fps_live = None + runner.game_tracer = None + runner.opp_game_tracer = None runner._stop_event = MagicMock() runner._stop_event.is_set.return_value = False diff --git a/utama_core/tests/strategy_runner/test_referee_rsim.py b/utama_core/tests/strategy_runner/test_referee_rsim.py index 3db63184..e68c4c81 100644 --- a/utama_core/tests/strategy_runner/test_referee_rsim.py +++ b/utama_core/tests/strategy_runner/test_referee_rsim.py @@ -101,8 +101,7 @@ def _make_runner(referee: CustomReferee, n_friendly: int = 3) -> StrategyRunner: exp_friendly=n_friendly, exp_enemy=0, exp_ball=True, - referee_system="custom", - custom_referee=referee, + referee=referee, ) diff --git a/utama_core/tests/strategy_runner/test_runner_misconfig.py b/utama_core/tests/strategy_runner/test_runner_misconfig.py index e2166d63..0e4d4a2c 100644 --- a/utama_core/tests/strategy_runner/test_runner_misconfig.py +++ b/utama_core/tests/strategy_runner/test_runner_misconfig.py @@ -5,7 +5,9 @@ from utama_core.config.enums import Mode from utama_core.config.field_params import GREAT_EXHIBITION_FIELD_DIMS +from utama_core.custom_referee import CustomReferee from utama_core.entities.game.field import FieldBounds +from utama_core.run.referee_source import OfficialReferee from utama_core.run.strategy_runner import StrategyRunner from utama_core.tests.strategy_runner.strat_runner_test_utils import DummyStrategy @@ -33,42 +35,27 @@ def test_load_mode_invalid(base_runner): base_runner._load_mode("invalid_mode") -def test_resolve_referee_system_defaults_to_none_in_rsim(): - assert StrategyRunner._resolve_referee_system(Mode.RSIM, None, None) == "none" +def test_validate_referee_defaults_to_none_in_rsim(): + assert StrategyRunner._validate_referee(Mode.RSIM, None) is None -def test_resolve_referee_system_defaults_to_none_in_grsim(): - assert StrategyRunner._resolve_referee_system(Mode.GRSIM, None, None) == "none" +def test_validate_referee_defaults_to_none_in_grsim(): + assert StrategyRunner._validate_referee(Mode.GRSIM, None) is None -def test_resolve_referee_system_rejects_custom_referee_without_explicit_system(): - with pytest.raises(ValueError, match="custom_referee"): - StrategyRunner._resolve_referee_system(Mode.RSIM, None, object()) +def test_validate_referee_rejects_unknown_type(): + with pytest.raises(TypeError, match="OfficialReferee"): + StrategyRunner._validate_referee(Mode.RSIM, object()) -def test_resolve_referee_system_rejects_invalid_name(): - with pytest.raises(ValueError, match="Unknown referee_system"): - StrategyRunner._resolve_referee_system(Mode.RSIM, "auto", None) +def test_validate_referee_rejects_official_in_rsim(): + with pytest.raises(ValueError, match="OfficialReferee"): + StrategyRunner._validate_referee(Mode.RSIM, OfficialReferee()) -def test_resolve_referee_system_rejects_official_in_rsim(): - with pytest.raises(ValueError, match="official"): - StrategyRunner._resolve_referee_system(Mode.RSIM, "official", None) - - -def test_resolve_referee_system_requires_custom_referee_for_custom_mode(): - with pytest.raises(ValueError, match="custom_referee"): - StrategyRunner._resolve_referee_system(Mode.RSIM, "custom", None) - - -def test_resolve_referee_system_rejects_custom_referee_with_none_mode(): - with pytest.raises(ValueError, match="custom_referee"): - StrategyRunner._resolve_referee_system(Mode.RSIM, "none", object()) - - -def test_resolve_referee_system_rejects_custom_referee_with_official_mode(): - with pytest.raises(ValueError, match="custom_referee"): - StrategyRunner._resolve_referee_system(Mode.GRSIM, "official", object()) +def test_validate_referee_accepts_official_in_grsim(): + result = StrategyRunner._validate_referee(Mode.GRSIM, OfficialReferee()) + assert isinstance(result, OfficialReferee) def test_setup_vision_and_referee_starts_vision_only_when_referee_none(monkeypatch): @@ -89,7 +76,7 @@ def __init__(self, buffer): fake_runner = SimpleNamespace( mode=Mode.GRSIM, - referee_system="none", + referee=None, start_threads=lambda vision_receiver, referee_receiver=None: started.append( (vision_receiver, referee_receiver) ), @@ -122,7 +109,7 @@ def __init__(self, buffer): fake_runner = SimpleNamespace( mode=Mode.REAL, - referee_system="custom", + referee=MagicMock(spec=CustomReferee), start_threads=lambda vision_receiver, referee_receiver=None: started.append( (vision_receiver, referee_receiver) ), @@ -153,7 +140,7 @@ def __init__(self, buffer): fake_runner = SimpleNamespace( mode=Mode.GRSIM, - referee_system="official", + referee=OfficialReferee(), start_threads=lambda vision_receiver, referee_receiver=None: started.append( (vision_receiver, referee_receiver) ), From 4104b9510aae3fc992bd1434c83b2146de05eeea Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Mon, 18 May 2026 15:02:09 +0100 Subject: [PATCH 049/121] feat: add center_circle_radius to FieldDimensions Moves the hardcoded 0.5 m center circle radius out of RefereeGeometry and into FieldDimensions, the single source of truth for all field measurements. RefereeGeometry.from_field_dims() now reads it from the field dims instead of hardcoding it. GREAT_EXHIBITION_FIELD_DIMS uses 0.3 m to reflect its smaller scale. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/config/field_params.py | 3 +++ utama_core/custom_referee/geometry.py | 2 +- utama_core/custom_referee/state_machine.py | 2 +- .../tests/config/test_field_dimensions.py | 23 ++++++++++++------- 4 files changed, 20 insertions(+), 10 deletions(-) diff --git a/utama_core/config/field_params.py b/utama_core/config/field_params.py index 3f230557..f6947bdf 100644 --- a/utama_core/config/field_params.py +++ b/utama_core/config/field_params.py @@ -26,6 +26,7 @@ class FieldDimensions: half_defense_area_depth: float half_defense_area_width: float half_goal_width: float + center_circle_radius: float # --- Bounds --- @@ -137,6 +138,7 @@ def __post_init__(self): half_defense_area_depth=0.5, half_defense_area_width=1, half_goal_width=0.5, + center_circle_radius=0.5, ) GREAT_EXHIBITION_FIELD_DIMS = FieldDimensions( @@ -145,4 +147,5 @@ def __post_init__(self): half_defense_area_depth=0.4, half_defense_area_width=0.8, half_goal_width=0.5, + center_circle_radius=0.3, ) diff --git a/utama_core/custom_referee/geometry.py b/utama_core/custom_referee/geometry.py index 7f66319e..9a40ba25 100644 --- a/utama_core/custom_referee/geometry.py +++ b/utama_core/custom_referee/geometry.py @@ -38,7 +38,7 @@ def from_field_dims(cls, field_dims: FieldDimensions, field_bounds: FieldBounds half_goal_width=field_dims.half_goal_width, half_defense_depth=field_dims.half_defense_area_depth, half_defense_width=field_dims.half_defense_area_width, - center_circle_radius=0.5, + center_circle_radius=field_dims.center_circle_radius, ) # ------------------------------------------------------------------ diff --git a/utama_core/custom_referee/state_machine.py b/utama_core/custom_referee/state_machine.py index e97a10fb..e8c3b857 100644 --- a/utama_core/custom_referee/state_machine.py +++ b/utama_core/custom_referee/state_machine.py @@ -372,7 +372,7 @@ def _all_robots_clear(self, game_frame: "GameFrame") -> bool: def _kicker_in_centre_circle(self, command: RefereeCommand, game_frame: "GameFrame") -> bool: """Return True if at least one robot of the attacking team is inside the centre circle.""" - r = self._geometry.center_circle_radius if self._geometry is not None else 0.5 + r = self._geometry.center_circle_radius if self._geometry is not None else 0.5 # fallback for standalone use kicking_is_yellow = command == RefereeCommand.PREPARE_KICKOFF_YELLOW attackers = ( game_frame.friendly_robots if kicking_is_yellow == game_frame.my_team_is_yellow else game_frame.enemy_robots diff --git a/utama_core/tests/config/test_field_dimensions.py b/utama_core/tests/config/test_field_dimensions.py index e677a8af..791c8034 100644 --- a/utama_core/tests/config/test_field_dimensions.py +++ b/utama_core/tests/config/test_field_dimensions.py @@ -22,6 +22,7 @@ half_defense_area_depth=0.5, half_defense_area_width=1.0, half_goal_width=0.5, + center_circle_radius=0.5, ), ], ) @@ -40,7 +41,7 @@ def test_full_field_bounds_follow_resized_dimensions(dims: FieldDimensions): [ STANDARD_FIELD_DIMS, GREAT_EXHIBITION_FIELD_DIMS, - FieldDimensions(5.2, 3.6, 0.7, 1.4, 0.6), + FieldDimensions(5.2, 3.6, 0.7, 1.4, 0.6, 0.5), ], ) def test_full_field_polygon_matches_dimensions(dims: FieldDimensions): @@ -51,8 +52,8 @@ def test_full_field_polygon_matches_dimensions(dims: FieldDimensions): def test_goal_lines_shift_when_full_field_is_resized(): - small = FieldDimensions(3.0, 2.0, 0.5, 1.0, 0.5) - large = FieldDimensions(6.0, 2.0, 0.5, 1.0, 0.5) + small = FieldDimensions(3.0, 2.0, 0.5, 1.0, 0.5, 0.5) + large = FieldDimensions(6.0, 2.0, 0.5, 1.0, 0.5, 0.5) assert_array_equal(small.right_goal_line, np.array([(3.0, 0.5), (3.0, -0.5)])) assert_array_equal(large.right_goal_line, np.array([(6.0, 0.5), (6.0, -0.5)])) @@ -61,7 +62,7 @@ def test_goal_lines_shift_when_full_field_is_resized(): def test_defense_areas_track_resized_full_length(): - dims = FieldDimensions(5.0, 3.0, 0.75, 1.25, 0.5) + dims = FieldDimensions(5.0, 3.0, 0.75, 1.25, 0.5, 0.5) expected_right = np.array([(5.0, 1.25), (3.5, 1.25), (3.5, -1.25), (5.0, -1.25)]) expected_left = np.array([(-5.0, 1.25), (-3.5, 1.25), (-3.5, -1.25), (-5.0, -1.25)]) @@ -72,7 +73,7 @@ def test_defense_areas_track_resized_full_length(): @pytest.mark.parametrize("team_is_right", [True, False]) def test_field_goal_lines_match_resized_dimensions(team_is_right: bool): - dims = FieldDimensions(6.0, 4.0, 0.5, 1.0, 0.5) + dims = FieldDimensions(6.0, 4.0, 0.5, 1.0, 0.5, 0.5) field = Field( my_team_is_right=team_is_right, field_dims=dims, @@ -89,7 +90,7 @@ def test_field_goal_lines_match_resized_dimensions(team_is_right: bool): @pytest.mark.parametrize("team_is_right", [True, False]) def test_field_reports_goal_lines_present_on_full_resized_bounds(team_is_right: bool): - dims = FieldDimensions(6.0, 4.0, 0.5, 1.0, 0.5) + dims = FieldDimensions(6.0, 4.0, 0.5, 1.0, 0.5, 0.5) field = Field( my_team_is_right=team_is_right, field_dims=dims, @@ -104,7 +105,7 @@ def test_field_reports_goal_lines_present_on_full_resized_bounds(team_is_right: def test_field_reports_goal_lines_absent_when_bounds_crop_goal_width( team_is_right: bool, ): - dims = FieldDimensions(6.0, 4.0, 0.5, 1.0, 0.5) + dims = FieldDimensions(6.0, 4.0, 0.5, 1.0, 0.5, 0.5) cropped_bounds = FieldBounds(top_left=(-6.0, 0.4), bottom_right=(6.0, -0.4)) field = Field( my_team_is_right=team_is_right, @@ -126,6 +127,7 @@ def test_field_reports_goal_lines_absent_when_bounds_crop_goal_width( "half_defense_area_depth": 0.5, "half_defense_area_width": 1.0, "half_goal_width": 0.5, + "center_circle_radius": 0.5, }, "Field length/width must be positive", ), @@ -136,6 +138,7 @@ def test_field_reports_goal_lines_absent_when_bounds_crop_goal_width( "half_defense_area_depth": 0.0, "half_defense_area_width": 1.0, "half_goal_width": 0.5, + "center_circle_radius": 0.5, }, "Goal/defense measurements must be positive", ), @@ -146,6 +149,7 @@ def test_field_reports_goal_lines_absent_when_bounds_crop_goal_width( "half_defense_area_depth": 0.6, "half_defense_area_width": 1.0, "half_goal_width": 0.5, + "center_circle_radius": 0.5, }, "exceeds field length", ), @@ -156,6 +160,7 @@ def test_field_reports_goal_lines_absent_when_bounds_crop_goal_width( "half_defense_area_depth": 0.5, "half_defense_area_width": 1.1, "half_goal_width": 0.5, + "center_circle_radius": 0.5, }, "Defense width .* exceeds field width", ), @@ -166,6 +171,7 @@ def test_field_reports_goal_lines_absent_when_bounds_crop_goal_width( "half_defense_area_depth": 0.5, "half_defense_area_width": 1.0, "half_goal_width": 1.1, + "center_circle_radius": 0.5, }, "Goal width .* exceeds field width", ), @@ -176,6 +182,7 @@ def test_field_reports_goal_lines_absent_when_bounds_crop_goal_width( "half_defense_area_depth": 0.5, "half_defense_area_width": 0.6, "half_goal_width": 0.8, + "center_circle_radius": 0.5, }, "should not exceed defense width", ), @@ -187,7 +194,7 @@ def test_invalid_field_dimensions_raise_value_errors(kwargs, error_pattern: str) def test_cached_geometry_properties_return_same_objects(): - dims = FieldDimensions(4.5, 3.0, 0.5, 1.0, 0.5) + dims = FieldDimensions(4.5, 3.0, 0.5, 1.0, 0.5, 0.5) assert dims.full_field is dims.full_field assert dims.full_field_bounds is dims.full_field_bounds From 58fd7e125ec29f826ddf2b494204aa249837ad09 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Mon, 18 May 2026 15:11:25 +0100 Subject: [PATCH 050/121] refactor: replace hardcoded geometry fallbacks with STANDARD_FIELD_DIMS references profile_loader.py: default geometry values in _parse_profile() now read from STANDARD_FIELD_DIMS instead of bare magic numbers, so they stay consistent if standard field constants ever change. state_machine.py: the 4.5 m half_length fallback in _penalty_kicker_ready() replaced with STANDARD_FIELD_DIMS.full_field_half_length for the same reason. Co-Authored-By: Claude Sonnet 4.6 --- .../custom_referee/profiles/profile_loader.py | 14 ++++++++------ utama_core/custom_referee/state_machine.py | 5 ++++- 2 files changed, 12 insertions(+), 7 deletions(-) diff --git a/utama_core/custom_referee/profiles/profile_loader.py b/utama_core/custom_referee/profiles/profile_loader.py index d3f22582..cc2b787b 100644 --- a/utama_core/custom_referee/profiles/profile_loader.py +++ b/utama_core/custom_referee/profiles/profile_loader.py @@ -10,6 +10,7 @@ import yaml +from utama_core.config.field_params import STANDARD_FIELD_DIMS from utama_core.custom_referee.geometry import RefereeGeometry _PROFILES_DIR = Path(__file__).parent @@ -155,13 +156,14 @@ def load_profile(name_or_path: str) -> RefereeProfile: def _parse_profile(data: dict) -> RefereeProfile: geo_d = data.get("geometry", {}) + _s = STANDARD_FIELD_DIMS geometry = RefereeGeometry( - half_length=geo_d.get("half_length", 4.5), - half_width=geo_d.get("half_width", 3.0), - half_goal_width=geo_d.get("half_goal_width", 0.5), - half_defense_depth=geo_d.get("half_defense_depth", 0.5), - half_defense_width=geo_d.get("half_defense_width", 1.0), - center_circle_radius=geo_d.get("center_circle_radius", 0.5), + half_length=geo_d.get("half_length", _s.full_field_half_length), + half_width=geo_d.get("half_width", _s.full_field_half_width), + half_goal_width=geo_d.get("half_goal_width", _s.half_goal_width), + half_defense_depth=geo_d.get("half_defense_depth", _s.half_defense_area_depth), + half_defense_width=geo_d.get("half_defense_width", _s.half_defense_area_width), + center_circle_radius=geo_d.get("center_circle_radius", _s.center_circle_radius), ) rules_d = data.get("rules", {}) diff --git a/utama_core/custom_referee/state_machine.py b/utama_core/custom_referee/state_machine.py index e8c3b857..afeb8944 100644 --- a/utama_core/custom_referee/state_machine.py +++ b/utama_core/custom_referee/state_machine.py @@ -7,6 +7,7 @@ import math from typing import Optional +from utama_core.config.field_params import STANDARD_FIELD_DIMS from utama_core.custom_referee.geometry import RefereeGeometry from utama_core.custom_referee.profiles.profile_loader import AutoAdvanceConfig from utama_core.custom_referee.rules.base_rule import RuleViolation @@ -388,7 +389,9 @@ def _penalty_kicker_ready(self, command: RefereeCommand, game_frame: "GameFrame" if not attackers: return False - half_length = self._geometry.half_length if self._geometry is not None else 4.5 + half_length = ( + self._geometry.half_length if self._geometry is not None else STANDARD_FIELD_DIMS.full_field_half_length + ) yellow_is_right = game_frame.my_team_is_right == game_frame.my_team_is_yellow if kicking_is_yellow: goal_sign = -1.0 if yellow_is_right else 1.0 From bdbe130d2f39f010cce120b33f1778c808b711a9 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Mon, 18 May 2026 15:18:15 +0100 Subject: [PATCH 051/121] refactor: remove dead initial_command and initial_time params from GameStateMachine Both were made obsolete by seed_clock(), which is now the single place where the initial command and clock are applied after the first real game frame is available. The constructor always starts in HALT with stage_start_time=None. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/custom_referee/state_machine.py | 9 +++------ utama_core/tests/custom_referee/test_custom_referee.py | 6 ++++-- 2 files changed, 7 insertions(+), 8 deletions(-) diff --git a/utama_core/custom_referee/state_machine.py b/utama_core/custom_referee/state_machine.py index afeb8944..f194bdcd 100644 --- a/utama_core/custom_referee/state_machine.py +++ b/utama_core/custom_referee/state_machine.py @@ -36,23 +36,20 @@ def __init__( n_robots_yellow: int, n_robots_blue: int, initial_stage: Stage = Stage.NORMAL_FIRST_HALF_PRE, - initial_command: RefereeCommand = RefereeCommand.HALT, force_start_after_goal: bool = False, stop_duration_seconds: float = 3.0, prepare_duration_seconds: float = 3.0, kickoff_timeout_seconds: float = 10.0, geometry: Optional[RefereeGeometry] = None, auto_advance: Optional[AutoAdvanceConfig] = None, - initial_time: Optional[float] = None, ) -> None: - self.command = initial_command + self.command = RefereeCommand.HALT self.command_counter = 0 self.command_timestamp = 0.0 self.stage = initial_stage - # Seeded lazily on the first step() call so that the timebase matches - # whatever clock the caller uses (wall time or game.ts). - self.stage_start_time: Optional[float] = initial_time + # Seeded by seed_clock() after the first valid game frame is available. + self.stage_start_time: Optional[float] = None self.stage_duration = half_duration_seconds self.yellow_team = TeamInfo( diff --git a/utama_core/tests/custom_referee/test_custom_referee.py b/utama_core/tests/custom_referee/test_custom_referee.py index 2daf7aad..1fb17557 100644 --- a/utama_core/tests/custom_referee/test_custom_referee.py +++ b/utama_core/tests/custom_referee/test_custom_referee.py @@ -67,13 +67,15 @@ def _frame( def _state_machine() -> GameStateMachine: - return GameStateMachine( + sm = GameStateMachine( half_duration_seconds=300.0, kickoff_team="yellow", n_robots_yellow=3, n_robots_blue=3, - initial_command=RefereeCommand.NORMAL_START, ) + sm.seed_clock(0.0) + sm.set_command(RefereeCommand.NORMAL_START, 0.0) + return sm # --------------------------------------------------------------------------- From 750247277547db1095a41cf0bf89a236266eeded Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Mon, 18 May 2026 15:36:32 +0100 Subject: [PATCH 052/121] refactor: remove GameTracer from referee_integration branch GameTracer belongs to agentic-harness; its import was causing CI collection errors on this branch. Co-Authored-By: Claude Sonnet 4.6 --- utama_core/run/strategy_runner.py | 53 ------------------- .../strategy_runner/test_error_handling.py | 2 - 2 files changed, 55 deletions(-) diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index 82dab5ec..e9fdd1d3 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -6,7 +6,6 @@ import warnings from collections import deque from dataclasses import dataclass, field -from pathlib import Path from typing import TYPE_CHECKING, List, Optional, Tuple from rich.live import Live @@ -46,7 +45,6 @@ from utama_core.rsoccer_simulator.src.ssl.envs import SSLStandardEnv from utama_core.rsoccer_simulator.src.Utils.gaussian_noise import RsimGaussianNoise from utama_core.run import GameGater -from utama_core.run.game_tracer import GameTracer from utama_core.run.referee_source import OfficialReferee, RefereeSource from utama_core.strategy.common.abstract_strategy import AbstractStrategy from utama_core.team_controller.src.controllers import ( @@ -121,10 +119,6 @@ class StrategyRunner: show_live_status (bool, optional): Whether to show the live terminal status panel. This panel includes FPS, referee command, stage, score, time remaining, and optional status text. Defaults to False. - verbose_trace (bool, optional): Whether to emit a human- and LLM-readable trace of - meaningful game-state changes (referee commands, ball possession, role assignments, - robot actuations). Trace is written to ``game_trace_.log`` in the working - directory and also printed to stderr. Defaults to False. print_real_fps (bool, optional): Deprecated alias for `show_live_status`. profiler_name (Optional[str], optional): Enables and sets profiler name. Defaults to None which disables profiler. rsim_noise (RsimGaussianNoise, optional): When running in rsim, add Gaussian noise to balls and robots with the @@ -155,7 +149,6 @@ def __init__( opp_control_scheme: Optional[str] = None, replay_writer_config: Optional[ReplayWriterConfig] = None, show_live_status: bool = False, # Turn this on for simulator debugging - verbose_trace: bool = False, print_real_fps: Optional[bool] = None, profiler_name: Optional[str] = None, rsim_noise: RsimGaussianNoise = RsimGaussianNoise(), @@ -248,29 +241,6 @@ def __init__( else None ) - # Verbose game-state tracer (one per side, written to separate files) - my_color = "yellow" if my_team_is_yellow else "blue" - opp_color = "blue" if my_team_is_yellow else "yellow" - self.game_tracer = ( - GameTracer( - trace_path=Path(f"game_trace_{my_color}.log"), - to_stdout=True, - team_color=my_color, - ) - if verbose_trace - else None - ) - self.opp_game_tracer = ( - GameTracer( - trace_path=Path(f"game_trace_{opp_color}.log"), - to_stdout=True, - team_color=opp_color, - ) - if verbose_trace and self.opp is not None - else None - ) - self._trace_frame_count = 0 - # Live terminal status panel self.num_frames_elapsed = 0 self.elapsed_time = 0.0 @@ -768,10 +738,6 @@ def close(self, stop_command_repeat: int = 20): self.rsim_env.close() if self._fps_live: self._fps_live.stop() - if self.game_tracer: - self.game_tracer.close() - if self.opp_game_tracer: - self.opp_game_tracer.close() def run_test( self, @@ -1037,22 +1003,3 @@ def _step_game( side.game.add_game_frame(new_game_frame) side.strategy.step() - - tracer = self.opp_game_tracer if running_opp else self.game_tracer - if tracer is not None: - if not running_opp: - self._trace_frame_count += 1 - bb = side.strategy.blackboard - try: - tactic = bb.tactic - except KeyError: - tactic = None - tracer.step( - game_frame=new_game_frame, - role_map=bb.role_map or {}, - cmd_map=bb.cmd_map or {}, - frame_number=self._trace_frame_count, - tactic=tactic, - behaviour_tree=side.strategy.behaviour_tree, - blackboard=bb, - ) diff --git a/utama_core/tests/strategy_runner/test_error_handling.py b/utama_core/tests/strategy_runner/test_error_handling.py index 5d5b3481..340c7fe0 100644 --- a/utama_core/tests/strategy_runner/test_error_handling.py +++ b/utama_core/tests/strategy_runner/test_error_handling.py @@ -20,8 +20,6 @@ def mock_runner(): runner.replay_writer = None runner.rsim_env = None runner._fps_live = None - runner.game_tracer = None - runner.opp_game_tracer = None runner._stop_event = MagicMock() runner._stop_event.is_set.return_value = False From 7b95ae838d091cc490d5a3e81526377dbd8d5e5b Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Mon, 18 May 2026 15:40:34 +0100 Subject: [PATCH 053/121] =?UTF-8?q?fix:=20address=20Copilot=20review=20iss?= =?UTF-8?q?ues=20=E2=80=94=20timebase=20mismatch=20and=20center=5Fcircle?= =?UTF-8?q?=5Fradius=20validation?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - test_referee_rsim: replace time.time() with game.ts in set_command() calls so timer comparisons use sim-time consistently - field_params: validate center_circle_radius > 0 and <= half_width in __post_init__ Co-Authored-By: Claude Sonnet 4.6 --- utama_core/config/field_params.py | 6 +++++ .../tests/config/test_field_dimensions.py | 22 +++++++++++++++++++ .../strategy_runner/test_referee_rsim.py | 9 ++++---- 3 files changed, 32 insertions(+), 5 deletions(-) diff --git a/utama_core/config/field_params.py b/utama_core/config/field_params.py index f6947bdf..462fa54a 100644 --- a/utama_core/config/field_params.py +++ b/utama_core/config/field_params.py @@ -113,11 +113,17 @@ def __post_init__(self): DW = self.half_defense_area_width G = self.half_goal_width + R = self.center_circle_radius + # --- Positivity --- if not (L > 0 and W > 0): raise ValueError("Field length/width must be positive") if not (D > 0 and DW > 0 and G > 0): raise ValueError("Goal/defense measurements must be positive") + if R <= 0: + raise ValueError("center_circle_radius must be positive") + if R > W: + raise ValueError(f"center_circle_radius {R} must not exceed field half-width {W}") # --- Fit constraints --- if 2 * D > L: diff --git a/utama_core/tests/config/test_field_dimensions.py b/utama_core/tests/config/test_field_dimensions.py index 791c8034..eeb3aa40 100644 --- a/utama_core/tests/config/test_field_dimensions.py +++ b/utama_core/tests/config/test_field_dimensions.py @@ -186,6 +186,28 @@ def test_field_reports_goal_lines_absent_when_bounds_crop_goal_width( }, "should not exceed defense width", ), + ( + { + "full_field_half_length": 4.5, + "full_field_half_width": 3.0, + "half_defense_area_depth": 0.5, + "half_defense_area_width": 1.0, + "half_goal_width": 0.5, + "center_circle_radius": 0.0, + }, + "center_circle_radius must be positive", + ), + ( + { + "full_field_half_length": 4.5, + "full_field_half_width": 3.0, + "half_defense_area_depth": 0.5, + "half_defense_area_width": 1.0, + "half_goal_width": 0.5, + "center_circle_radius": 3.1, + }, + "must not exceed field half-width", + ), ], ) def test_invalid_field_dimensions_raise_value_errors(kwargs, error_pattern: str): diff --git a/utama_core/tests/strategy_runner/test_referee_rsim.py b/utama_core/tests/strategy_runner/test_referee_rsim.py index e68c4c81..67f3877e 100644 --- a/utama_core/tests/strategy_runner/test_referee_rsim.py +++ b/utama_core/tests/strategy_runner/test_referee_rsim.py @@ -33,7 +33,6 @@ """ import math -import time from typing import Optional import py_trees @@ -135,7 +134,7 @@ def reset_field(self, sim_controller: AbstractSimController, game: Game): # Ball far from the placement target sim_controller.teleport_ball(-1.0, -1.0) # Issue BALL_PLACEMENT directly and set the designated target - self._referee.set_command(RefereeCommand.BALL_PLACEMENT_YELLOW, time.time()) + self._referee.set_command(RefereeCommand.BALL_PLACEMENT_YELLOW, game.ts) self._referee._state.ball_placement_target = self.TARGET def eval_status(self, game: Game) -> TestingStatus: @@ -201,7 +200,7 @@ def reset_field(self, sim_controller: AbstractSimController, game: Game): sim_controller.teleport_robot(game.my_team_is_yellow, 2, -2.0, -0.5) # Ball heading out the top sideline sim_controller.teleport_ball(0.0, 2.5, vx=0.0, vy=2.5) - self._referee.set_command(RefereeCommand.FORCE_START, time.time()) + self._referee.set_command(RefereeCommand.FORCE_START, game.ts) def eval_status(self, game: Game) -> TestingStatus: ref = game.referee @@ -273,7 +272,7 @@ def reset_field(self, sim_controller: AbstractSimController, game: Game): sim_controller.teleport_robot(game.my_team_is_yellow, 2, -0.1, 2.3) # Ball heading out the top sideline; robot 0 is close enough for last-touch sim_controller.teleport_ball(0.0, 2.5, vx=0.0, vy=2.5) - self._referee.set_command(RefereeCommand.FORCE_START, time.time()) + self._referee.set_command(RefereeCommand.FORCE_START, game.ts) def eval_status(self, game: Game) -> TestingStatus: ref = game.referee @@ -342,7 +341,7 @@ def reset_field(self, sim_controller: AbstractSimController, game: Game): sim_controller.teleport_robot(game.my_team_is_yellow, 1, -0.2, 0.5) sim_controller.teleport_robot(game.my_team_is_yellow, 2, -0.2, -0.5) sim_controller.teleport_ball(0.0, 0.0) - self._referee.set_command(RefereeCommand.PREPARE_KICKOFF_YELLOW, time.time()) + self._referee.set_command(RefereeCommand.PREPARE_KICKOFF_YELLOW, game.ts) def eval_status(self, game: Game) -> TestingStatus: ref = game.referee From d689b5d7f1faf6fab872aa7b2de93ffd51a39e7a Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Mon, 18 May 2026 16:50:46 +0100 Subject: [PATCH 054/121] fix: snapshot TeamInfo per packet to prevent retroactive history mutation MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit RefereeMessageReceiver was passing the same mutable blue_info/yellow_info instances into every RefereeData record, so a score or goalkeeper update would silently mutate all previously recorded referee states. Added TeamInfo.snapshot() and call it in the receiver so each RefereeData owns independent TeamInfo values — consistent with how GameStateMachine already used copy.copy() on its own team instances. Also fixes the Optional[tuple[float]] → Optional[tuple[float, float]] type annotation on RefereeRefiner.designated_position. Co-Authored-By: Claude Sonnet 4.6 --- .../receivers/referee_receiver.py | 4 ++-- .../data_processing/refiners/referee.py | 2 +- utama_core/entities/game/team_info.py | 22 +++++++++++++++++++ 3 files changed, 25 insertions(+), 3 deletions(-) diff --git a/utama_core/data_processing/receivers/referee_receiver.py b/utama_core/data_processing/receivers/referee_receiver.py index f16280f7..b8999979 100644 --- a/utama_core/data_processing/receivers/referee_receiver.py +++ b/utama_core/data_processing/receivers/referee_receiver.py @@ -167,8 +167,8 @@ def _update_data(self, referee_packet: Referee) -> None: referee_command_timestamp=self.command_timestamp, stage=self.stage, stage_time_left=self.stage_time_left, - blue_team=self.blue_info, - yellow_team=self.yellow_info, + blue_team=self.blue_info.snapshot(), + yellow_team=self.yellow_info.snapshot(), designated_position=designated_position, blue_team_on_positive_half=referee_packet.blue_team_on_positive_half, next_command=( diff --git a/utama_core/data_processing/refiners/referee.py b/utama_core/data_processing/refiners/referee.py index bee99d9a..97dc91a3 100644 --- a/utama_core/data_processing/refiners/referee.py +++ b/utama_core/data_processing/refiners/referee.py @@ -104,7 +104,7 @@ def yellow_team(self) -> TeamInfo: ) @property - def designated_position(self) -> Optional[tuple[float]]: + def designated_position(self) -> Optional[tuple[float, float]]: return self._latest_referee_data.designated_position if self._latest_referee_data else None @property diff --git a/utama_core/entities/game/team_info.py b/utama_core/entities/game/team_info.py index 82a5060d..72018f09 100644 --- a/utama_core/entities/game/team_info.py +++ b/utama_core/entities/game/team_info.py @@ -109,3 +109,25 @@ def decrement_timeouts(self): def add_timeout_time(self, time: int): self.timeout_time += time + + def snapshot(self) -> "TeamInfo": + """Return a new TeamInfo with a copy of the current state.""" + return TeamInfo( + name=self.name, + score=self.score, + red_cards=self.red_cards, + yellow_card_times=list(self.yellow_card_times), + yellow_cards=self.yellow_cards, + timeouts=self.timeouts, + timeout_time=self.timeout_time, + goalkeeper=self.goalkeeper, + foul_counter=self.foul_counter, + ball_placement_failures=self.ball_placement_failures, + can_place_ball=self.can_place_ball, + max_allowed_bots=self.max_allowed_bots, + bot_substitution_intent=self.bot_substitution_intent, + ball_placement_failures_reached=self.ball_placement_failures_reached, + bot_substitution_allowed=self.bot_substitution_allowed, + bot_substitutions_left=self.bot_substitutions_left, + bot_substitution_time_left=self.bot_substitution_time_left, + ) From 180d00a7224e3e4fc84e094b0b1105fe00a86b29 Mon Sep 17 00:00:00 2001 From: Joel Date: Tue, 19 May 2026 19:10:42 +0100 Subject: [PATCH 055/121] update center circle render for rsim --- utama_core/entities/game/field.py | 4 ++++ utama_core/rsoccer_simulator/src/ssl/envs/standard_ssl.py | 1 + 2 files changed, 5 insertions(+) diff --git a/utama_core/entities/game/field.py b/utama_core/entities/game/field.py index 0cef547c..33756550 100644 --- a/utama_core/entities/game/field.py +++ b/utama_core/entities/game/field.py @@ -110,6 +110,10 @@ def full_field_half_width(self) -> float: def half_goal_width(self) -> float: return self._field_dims.half_goal_width + @property + def center_circle_radius(self) -> float: + return self._field_dims.center_circle_radius + @property def left_goal_line(self) -> np.ndarray: return self._field_dims.left_goal_line diff --git a/utama_core/rsoccer_simulator/src/ssl/envs/standard_ssl.py b/utama_core/rsoccer_simulator/src/ssl/envs/standard_ssl.py index a83b8fa3..d0a13a51 100644 --- a/utama_core/rsoccer_simulator/src/ssl/envs/standard_ssl.py +++ b/utama_core/rsoccer_simulator/src/ssl/envs/standard_ssl.py @@ -97,6 +97,7 @@ def __init__( "penalty_length": 2 * full_field_dims.half_defense_area_depth, "penalty_width": 2 * full_field_dims.half_defense_area_width, "goal_width": 2 * full_field_dims.half_goal_width, + "center_circle_r": full_field_dims.center_circle_radius, } super().__init__( From d0fb4629de96189b2cd203657c83514bba73099f Mon Sep 17 00:00:00 2001 From: Joel Date: Tue, 19 May 2026 19:17:29 +0100 Subject: [PATCH 056/121] fix crash when rsim not included for rendering fpp --- .../motion_planning/src/fastpathplanning/planner.py | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/utama_core/motion_planning/src/fastpathplanning/planner.py b/utama_core/motion_planning/src/fastpathplanning/planner.py index 86379c21..ce7881f5 100644 --- a/utama_core/motion_planning/src/fastpathplanning/planner.py +++ b/utama_core/motion_planning/src/fastpathplanning/planner.py @@ -63,7 +63,8 @@ def _get_obstacles( obstacle_list.append(obstacle_segment) # DRAWING: Show the projected velocity line in Red - self._env.draw_line(obstacle_segment, color="Red") + if self._env is not None: + self._env.draw_line(obstacle_segment, color="Red") # Field bounds as obstacles (static, usually not drawn to keep screen clean) tl, br = np.array(field_bounds.top_left), np.array(field_bounds.bottom_right) @@ -272,10 +273,12 @@ def _path_to( # 5. Draw the resulting safe path segments for i in final_trajectory: - self._env.draw_line(i) + if self._env is not None: + self._env.draw_line(i) # 6. Smooth the path and draw the final "Carrot" target in Blue new_target = self.smooth_path(final_trajectory, safe_target, our_pos) - self._env.draw_line((our_pos, new_target), color="Blue") + if self._env is not None: + self._env.draw_line((our_pos, new_target), color="Blue") return new_target From 9193f38880e1d17f828b9e724866393e20c3096b Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Tue, 19 May 2026 23:52:58 +0100 Subject: [PATCH 057/121] refactor: make StrategyRunner.full_field_dims the single source of field geometry - Remove geometry block from RefereeProfile, profile_loader.py, and built-in YAML profiles (human, simulation); CustomReferee now initialises _geometry from STANDARD_FIELD_DIMS as a placeholder - StrategyRunner calls override_geometry() at startup so the referee always uses full_field_dims (or its field_bounds projection) - For gRSim/Real, VisionReceiver fires a one-shot on_geometry callback that validates the vision geometry packet against full_field_dims and raises RuntimeError on mismatch - GUI /config endpoint reads referee.geometry live so it reflects the overridden geometry, not stale profile values - Update docs to document the geometry authority chain Co-Authored-By: Claude Sonnet 4.6 --- docs/custom_referee.md | 33 ++++--- docs/custom_referee_gui.md | 12 ++- docs/referee_integration.md | 23 +++-- utama_core/custom_referee/custom_referee.py | 11 +-- utama_core/custom_referee/gui.py | 98 ++++++++++--------- utama_core/custom_referee/profiles/human.yaml | 7 -- .../custom_referee/profiles/profile_loader.py | 18 ---- .../custom_referee/profiles/simulation.yaml | 7 -- .../receivers/vision_receiver.py | 13 ++- utama_core/run/strategy_runner.py | 72 +++++++++++--- .../strategy_runner/test_grsim_sim_setup.py | 4 +- .../strategy_runner/test_runner_misconfig.py | 79 ++++++++++----- 12 files changed, 218 insertions(+), 159 deletions(-) diff --git a/docs/custom_referee.md b/docs/custom_referee.md index bc6c1570..bb2fc19d 100644 --- a/docs/custom_referee.md +++ b/docs/custom_referee.md @@ -215,15 +215,19 @@ referee = CustomReferee.from_profile_name("/path/to/my_profile.yaml") ### YAML schema +The `geometry` block is optional — all fields default to `STANDARD_FIELD_DIMS` (standard SSL 9×6 m field) if omitted. When running through `StrategyRunner`, geometry is always overridden from `full_field_dims` at startup, so the YAML geometry block only matters when constructing `CustomReferee` standalone (outside `StrategyRunner`). + ```yaml profile_name: "simulation" -geometry: - half_length: 4.5 - half_width: 3.0 - half_goal_width: 0.5 - half_defense_depth: 0.5 - half_defense_width: 1.0 - center_circle_radius: 0.5 +# geometry block omitted — defaults to STANDARD_FIELD_DIMS +# Add a geometry block only for standalone use with a non-standard field: +# geometry: +# half_length: 2.0 +# half_width: 1.5 +# half_goal_width: 0.5 +# half_defense_depth: 0.4 +# half_defense_width: 0.8 +# center_circle_radius: 0.3 rules: goal_detection: enabled: true @@ -256,18 +260,23 @@ game: ## Integration with StrategyRunner -`StrategyRunner` accepts an optional `custom_referee` parameter. When set: +`StrategyRunner` accepts an optional `referee` parameter. Pass a `CustomReferee` instance to use the in-process referee. When set: 1. `RefereeMessageReceiver` is **not** started (no UDP multicast thread). 2. Each tick, `CustomReferee.step()` is called with `self.my_current_game_frame` and the result is pushed into `ref_buffer` before `_step_game()` reads it. 3. On the **transition edge** into `STOP` (i.e. the first frame the command becomes `STOP`), if `RefereeData.designated_position` is not `None` and a `sim_controller` is present, the ball is teleported to `designated_position` in the simulator. After a goal this is always `(0.0, 0.0)` — the centre spot. +### Field geometry and `full_field_dims` + +`StrategyRunner` overrides the referee's geometry at startup using `full_field_dims` and `field_bounds` — the YAML profile geometry is irrelevant when running through `StrategyRunner`. This ensures the referee always enforces the same field the simulator is actually running. + +For **gRSim and Real** modes, `StrategyRunner` also validates the first vision geometry packet against `full_field_dims` and raises `RuntimeError` immediately if they don't match, preventing silent mismatches between configured and actual field size. + ```python from utama_core.custom_referee import CustomReferee -from utama_core.entities.referee.referee_command import RefereeCommand +from utama_core.config.field_params import GREAT_EXHIBITION_FIELD_DIMS referee = CustomReferee.from_profile_name("simulation", n_robots_yellow=3, n_robots_blue=3) -referee.set_command(RefereeCommand.NORMAL_START, timestamp=0.0) runner = StrategyRunner( strategy=MyStrategy(), @@ -276,8 +285,8 @@ runner = StrategyRunner( mode="rsim", exp_friendly=3, exp_enemy=3, - referee_system="custom", - custom_referee=referee, + full_field_dims=GREAT_EXHIBITION_FIELD_DIMS, # referee geometry set from this + referee=referee, ) runner.run() ``` diff --git a/docs/custom_referee_gui.md b/docs/custom_referee_gui.md index 16f847e2..b311b10e 100644 --- a/docs/custom_referee_gui.md +++ b/docs/custom_referee_gui.md @@ -163,11 +163,9 @@ safety and testing. Use `simulation` for simulator, strategy testing, and RL wor --- -## Changing field dimensions +## Field dimensions -All six `geometry` fields are in **metres** and are fully dynamic — every rule reads geometry -on each tick, so changing a value in the profile instantly changes rule behaviour. The field -canvas auto-scales to match. +All six geometry fields are in **metres**. The field canvas auto-scales to the active geometry. | Field | Controls | Rules affected | |---|---|---| @@ -178,6 +176,12 @@ canvas auto-scales to match. | `half_defense_width` | Half-width of defence area | DefenseAreaRule | | `center_circle_radius` | Centre circle drawn on canvas; reserved for future keep-out rule | — | +### Where geometry comes from + +**When running through `StrategyRunner`** (the normal path): geometry is set from `full_field_dims` at startup and is not read from the YAML profile. The GUI's `/config` endpoint reads `referee.geometry` live, so it always reflects the actual active geometry — including the correct values after `StrategyRunner` overrides them. + +**Standalone use** (constructing `CustomReferee` directly without `StrategyRunner`): geometry comes from the `geometry:` block in the YAML profile, defaulting to `STANDARD_FIELD_DIMS` if the block is omitted. + --- ## Configuring rules diff --git a/docs/referee_integration.md b/docs/referee_integration.md index ae217711..45775bb2 100644 --- a/docs/referee_integration.md +++ b/docs/referee_integration.md @@ -346,17 +346,22 @@ To customise, copy a YAML file, edit the values, and pass the path: pixi run python referee_gui.py --profile /path/to/my_profile.yaml ``` -The YAML structure mirrors the dataclasses in `profile_loader.py`: +The YAML structure mirrors the dataclasses in `profile_loader.py`. The `geometry` block is +optional — all fields default to `STANDARD_FIELD_DIMS` (standard SSL 9×6 m field) if omitted. +When running through `StrategyRunner`, geometry is always overridden from `full_field_dims` +at startup, so the YAML geometry block only matters for standalone use outside `StrategyRunner`. ```yaml profile_name: "my_profile" -geometry: - half_length: 4.5 # metres from centre to goal line - half_width: 3.0 # metres from centre to touch line - half_goal_width: 0.5 # metres from centre of goal to post - half_defense_depth: 0.5 # depth of defense area from goal line - half_defense_width: 1.0 # half-width of defense area - center_circle_radius: 0.5 +# geometry block omitted — defaults to STANDARD_FIELD_DIMS when running via StrategyRunner. +# Add only for standalone use with a non-standard field: +# geometry: +# half_length: 2.0 # metres from centre to goal line +# half_width: 1.5 # metres from centre to touch line +# half_goal_width: 0.5 # metres from centre of goal to post +# half_defense_depth: 0.4 # depth of defense area from goal line +# half_defense_width: 0.8 # half-width of defense area +# center_circle_radius: 0.3 rules: goal_detection: enabled: true @@ -451,7 +456,7 @@ The **Field** panel shows a top-down canvas updated in real time at ~30 Hz via S | Element | Colour | Notes | |---|---|---| -| Field background | Green | Scaled to profile geometry | +| Field background | Green | Scaled to active referee geometry (set by StrategyRunner at startup) | | Lines / circles | White | Boundary, centre line, centre circle, defence areas | | Left goal | Yellow (translucent) | Yellow team's goal (negative x side) | | Right goal | Blue (translucent) | Blue team's goal (positive x side) | diff --git a/utama_core/custom_referee/custom_referee.py b/utama_core/custom_referee/custom_referee.py index 2be3cd00..9aa0f8f9 100644 --- a/utama_core/custom_referee/custom_referee.py +++ b/utama_core/custom_referee/custom_referee.py @@ -4,6 +4,7 @@ from typing import List, Optional +from utama_core.config.field_params import STANDARD_FIELD_DIMS from utama_core.custom_referee.geometry import RefereeGeometry from utama_core.custom_referee.profiles.profile_loader import ( RefereeProfile, @@ -76,7 +77,7 @@ def __init__( gui_port: int = 8080, ) -> None: self._profile_name = profile.profile_name - self._geometry: RefereeGeometry = profile.geometry + self._geometry: RefereeGeometry = RefereeGeometry.from_field_dims(STANDARD_FIELD_DIMS) self._rules: List[BaseRule] = _build_active_rules(profile.rules) self._state = GameStateMachine( half_duration_seconds=profile.game.half_duration_seconds, @@ -87,18 +88,14 @@ def __init__( stop_duration_seconds=profile.game.stop_duration_seconds, prepare_duration_seconds=profile.game.prepare_duration_seconds, kickoff_timeout_seconds=profile.game.kickoff_timeout_seconds, - geometry=profile.geometry, + geometry=self._geometry, auto_advance=profile.game.auto_advance, ) self._gui_server = None if enable_gui: # Lazy import to keep this module free of HTTP/GUI dependencies # when the GUI is not needed. - from utama_core.custom_referee.gui import ( - _build_config_json, - _RefereeGUIServer, - attach_gui, - ) + from utama_core.custom_referee.gui import _RefereeGUIServer self._gui_server = _RefereeGUIServer(self, profile, gui_port, run_tick_loop=False) self._gui_server.start() diff --git a/utama_core/custom_referee/gui.py b/utama_core/custom_referee/gui.py index 5db58db3..231f7128 100644 --- a/utama_core/custom_referee/gui.py +++ b/utama_core/custom_referee/gui.py @@ -89,7 +89,7 @@ def __init__( self._referee = referee self._port = port self._run_tick_loop = run_tick_loop - self._config_json = _build_config_json(profile) + self._static_config = _build_static_config(profile) self._lock = threading.Lock() self._ref_data = None @@ -122,6 +122,19 @@ def _tick_loop(self) -> None: self._broadcast() time.sleep(1 / 30) + def _build_config_json(self) -> str: + g = self._referee.geometry + config = dict(self._static_config) + config["geometry"] = { + "half_length": g.half_length, + "half_width": g.half_width, + "half_goal_width": g.half_goal_width, + "half_defense_depth": g.half_defense_depth, + "half_defense_width": g.half_defense_width, + "center_circle_radius": g.center_circle_radius, + } + return json.dumps(config) + # ---- called by external loops to push a new state snapshot ---- def notify(self, ref_data, game_frame=None) -> None: @@ -178,7 +191,7 @@ def _serve_index(self): self.wfile.write(body) def _serve_config(self): - body = server_instance._config_json.encode() + body = server_instance._build_config_json().encode() self.send_response(200) self.send_header("Content-Type", "application/json") self.send_header("Content-Length", str(len(body))) @@ -311,57 +324,46 @@ def _serialise_state(ref_data, game_frame=None) -> str: ) -def _build_config_json(profile: "RefereeProfile") -> str: - g = profile.geometry +def _build_static_config(profile: "RefereeProfile") -> dict: r = profile.rules gm = profile.game - return json.dumps( - { - "profile_name": profile.profile_name, - "geometry": { - "half_length": g.half_length, - "half_width": g.half_width, - "half_goal_width": g.half_goal_width, - "half_defense_depth": g.half_defense_depth, - "half_defense_width": g.half_defense_width, - "center_circle_radius": g.center_circle_radius, + return { + "profile_name": profile.profile_name, + "rules": { + "goal_detection": { + "enabled": r.goal_detection.enabled, + "cooldown_seconds": r.goal_detection.cooldown_seconds, }, - "rules": { - "goal_detection": { - "enabled": r.goal_detection.enabled, - "cooldown_seconds": r.goal_detection.cooldown_seconds, - }, - "out_of_bounds": { - "enabled": r.out_of_bounds.enabled, - "free_kick_assigner": r.out_of_bounds.free_kick_assigner, - }, - "defense_area": { - "enabled": r.defense_area.enabled, - "max_defenders": r.defense_area.max_defenders, - "attacker_infringement": r.defense_area.attacker_infringement, - }, - "keep_out": { - "enabled": r.keep_out.enabled, - "radius_meters": r.keep_out.radius_meters, - "violation_persistence_frames": r.keep_out.violation_persistence_frames, - }, + "out_of_bounds": { + "enabled": r.out_of_bounds.enabled, + "free_kick_assigner": r.out_of_bounds.free_kick_assigner, }, - "game": { - "half_duration_seconds": gm.half_duration_seconds, - "kickoff_team": gm.kickoff_team, - "force_start_after_goal": gm.force_start_after_goal, - "stop_duration_seconds": gm.stop_duration_seconds, - "auto_advance": { - "stop_to_next_command": gm.auto_advance.stop_to_next_command, - "prepare_kickoff_to_normal": gm.auto_advance.prepare_kickoff_to_normal, - "prepare_penalty_to_normal": gm.auto_advance.prepare_penalty_to_normal, - "direct_free_to_normal": gm.auto_advance.direct_free_to_normal, - "ball_placement_to_next": gm.auto_advance.ball_placement_to_next, - "normal_start_to_force": gm.auto_advance.normal_start_to_force, - }, + "defense_area": { + "enabled": r.defense_area.enabled, + "max_defenders": r.defense_area.max_defenders, + "attacker_infringement": r.defense_area.attacker_infringement, }, - } - ) + "keep_out": { + "enabled": r.keep_out.enabled, + "radius_meters": r.keep_out.radius_meters, + "violation_persistence_frames": r.keep_out.violation_persistence_frames, + }, + }, + "game": { + "half_duration_seconds": gm.half_duration_seconds, + "kickoff_team": gm.kickoff_team, + "force_start_after_goal": gm.force_start_after_goal, + "stop_duration_seconds": gm.stop_duration_seconds, + "auto_advance": { + "stop_to_next_command": gm.auto_advance.stop_to_next_command, + "prepare_kickoff_to_normal": gm.auto_advance.prepare_kickoff_to_normal, + "prepare_penalty_to_normal": gm.auto_advance.prepare_penalty_to_normal, + "direct_free_to_normal": gm.auto_advance.direct_free_to_normal, + "ball_placement_to_next": gm.auto_advance.ball_placement_to_next, + "normal_start_to_force": gm.auto_advance.normal_start_to_force, + }, + }, + } # --------------------------------------------------------------------------- diff --git a/utama_core/custom_referee/profiles/human.yaml b/utama_core/custom_referee/profiles/human.yaml index 1e3302fd..b3c80728 100644 --- a/utama_core/custom_referee/profiles/human.yaml +++ b/utama_core/custom_referee/profiles/human.yaml @@ -1,11 +1,4 @@ profile_name: "human" -geometry: - half_length: 4.5 - half_width: 3.0 - half_goal_width: 0.5 - half_defense_depth: 0.5 - half_defense_width: 1.0 - center_circle_radius: 0.5 rules: goal_detection: enabled: true diff --git a/utama_core/custom_referee/profiles/profile_loader.py b/utama_core/custom_referee/profiles/profile_loader.py index cc2b787b..b3228143 100644 --- a/utama_core/custom_referee/profiles/profile_loader.py +++ b/utama_core/custom_referee/profiles/profile_loader.py @@ -2,17 +2,12 @@ from __future__ import annotations -import os import warnings from dataclasses import dataclass, field from pathlib import Path -from typing import Optional import yaml -from utama_core.config.field_params import STANDARD_FIELD_DIMS -from utama_core.custom_referee.geometry import RefereeGeometry - _PROFILES_DIR = Path(__file__).parent @@ -115,7 +110,6 @@ class GameConfig: @dataclass class RefereeProfile: profile_name: str - geometry: RefereeGeometry rules: RulesConfig game: GameConfig @@ -155,17 +149,6 @@ def load_profile(name_or_path: str) -> RefereeProfile: def _parse_profile(data: dict) -> RefereeProfile: - geo_d = data.get("geometry", {}) - _s = STANDARD_FIELD_DIMS - geometry = RefereeGeometry( - half_length=geo_d.get("half_length", _s.full_field_half_length), - half_width=geo_d.get("half_width", _s.full_field_half_width), - half_goal_width=geo_d.get("half_goal_width", _s.half_goal_width), - half_defense_depth=geo_d.get("half_defense_depth", _s.half_defense_area_depth), - half_defense_width=geo_d.get("half_defense_width", _s.half_defense_area_width), - center_circle_radius=geo_d.get("center_circle_radius", _s.center_circle_radius), - ) - rules_d = data.get("rules", {}) gd = rules_d.get("goal_detection", {}) @@ -224,7 +207,6 @@ def _parse_profile(data: dict) -> RefereeProfile: return RefereeProfile( profile_name=data.get("profile_name", "unknown"), - geometry=geometry, rules=rules, game=game, ) diff --git a/utama_core/custom_referee/profiles/simulation.yaml b/utama_core/custom_referee/profiles/simulation.yaml index 53183233..eca74468 100644 --- a/utama_core/custom_referee/profiles/simulation.yaml +++ b/utama_core/custom_referee/profiles/simulation.yaml @@ -1,11 +1,4 @@ profile_name: "simulation" -geometry: - half_length: 4.5 - half_width: 3.0 - half_goal_width: 0.5 - half_defense_depth: 0.5 - half_defense_width: 1.0 - center_circle_radius: 0.5 rules: goal_detection: enabled: true diff --git a/utama_core/data_processing/receivers/vision_receiver.py b/utama_core/data_processing/receivers/vision_receiver.py index 8121efe7..5d6fd75f 100644 --- a/utama_core/data_processing/receivers/vision_receiver.py +++ b/utama_core/data_processing/receivers/vision_receiver.py @@ -1,7 +1,7 @@ import logging import time from collections import deque -from typing import Deque, List +from typing import Callable, Deque, List, Optional from utama_core.config.settings import MULTICAST_GROUP, VISION_PORT from utama_core.entities.data.raw_vision import RawBallData, RawRobotData, RawVisionData @@ -18,9 +18,15 @@ class VisionReceiver: """Receives protobuf data from SSL Vision over the network, formats into RawData types and passes it over to the VisionProcessor.""" - def __init__(self, vision_buffers: List[Deque[RawVisionData]]): + def __init__( + self, + vision_buffers: List[Deque[RawVisionData]], + on_geometry: Optional[Callable] = None, + ): self.net = network_manager.NetworkManager(address=(MULTICAST_GROUP, VISION_PORT), bind_socket=True) self.vision_buffers = vision_buffers + self._on_geometry = on_geometry + self._geometry_fired = False self.packet_timestamps = deque() self.fps_print_interval = 1 # seconds self.last_fps_print_time = time.time() @@ -48,6 +54,9 @@ def pull_game_data(self, fps=False) -> None: if data is not None: vision_packet.Clear() vision_packet.ParseFromString(data) + if self._on_geometry and not self._geometry_fired and vision_packet.HasField("geometry"): + self._on_geometry(vision_packet.geometry.field) + self._geometry_fired = True # print(vision_packet.detection) self.prev_frame_num = vision_packet.detection.frame_number self._add_detection_to_buffer(vision_packet.detection) diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index e9fdd1d3..0cb49b61 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -64,6 +64,8 @@ if TYPE_CHECKING: from utama_core.entities.data.referee import RefereeData +_GEOMETRY_MATCH_TOLERANCE_M = 0.001 # mm-precision integers from vision → 1 mm tolerance + logging.basicConfig( filename="Utama.log", level=logging.CRITICAL, @@ -110,7 +112,9 @@ class StrategyRunner: exp_ball (bool): Whether the ball is expected to be present. Only raises error when strategy expects ball but runtime does not provide it. Defaults to True. - full_field_dims (FieldDimensions): The dimensions of the full field. Defaults to standard field dimensions. + full_field_dims (FieldDimensions): The dimensions of the full field. Defaults to standard + field dimensions. For gRSim/Real, this must match the actual field configured in + gRSim/SSL-Vision — a RuntimeError is raised on the first vision packet if they differ. field_bounds (FieldBounds): Bounds of the subset of the full field being used. Defaults to None (ie full field). opp_strategy (AbstractStrategy, optional): Opponent strategy for pvp. Defaults to None for single player. control_scheme (str, optional): Name of the motion control scheme to use. @@ -169,13 +173,9 @@ def __init__( self.exp_ball = exp_ball self.formation_type = formation_type self.full_field_dims = full_field_dims - # if field bounds not provided, default to full field dimensions self.field_bounds = field_bounds if field_bounds else full_field_dims.full_field_bounds self.referee: RefereeSource = self._validate_referee(self.mode, referee) - # Ensure the custom referee's geometry matches the actual field in use. - # The YAML profile geometry is the fallback for standalone use; here - # full_field_dims + field_bounds is the single source of truth. if isinstance(self.referee, CustomReferee): from utama_core.custom_referee.geometry import RefereeGeometry @@ -185,8 +185,8 @@ def __init__( assert_valid_bounding_box( self.field_bounds, - full_field_dims.full_field_half_length, - full_field_dims.full_field_half_width, + self.full_field_dims.full_field_half_length, + self.full_field_dims.full_field_half_width, ) self.referee_refiner = RefereeRefiner() @@ -477,23 +477,63 @@ def _load_sim( return None, sim_controller def _setup_vision_and_referee(self) -> Tuple[deque, deque]: - """Setup the vision and referee buffers. - - Returns: - tuple: Vision and referee buffers. - """ + """Setup vision and referee buffers, starting network receivers for gRSim/Real.""" vision_buffers = [deque(maxlen=1) for _ in range(MAX_CAMERAS)] ref_buffer = deque(maxlen=1) if self.mode != Mode.RSIM: - vision_receiver = VisionReceiver(vision_buffers) + on_geometry = self._make_geometry_validation_callback() + vision_receiver = VisionReceiver(vision_buffers, on_geometry=on_geometry) if isinstance(self.referee, OfficialReferee): - referee_receiver = RefereeMessageReceiver(ref_buffer) - self.start_threads(vision_receiver, referee_receiver) + self.start_threads(vision_receiver, RefereeMessageReceiver(ref_buffer)) else: self.start_threads(vision_receiver) - return vision_buffers, ref_buffer + def _make_geometry_validation_callback(self): + """Return a one-shot callback that validates vision geometry matches full_field_dims. + + Raises RuntimeError if the field size reported by gRSim/SSL-Vision differs from + full_field_dims by more than _GEOMETRY_MATCH_TOLERANCE_M metres. + """ + + def _on_geometry(field_size) -> None: + vision_half_length = field_size.field_length / 2000.0 + vision_half_width = field_size.field_width / 2000.0 + vision_half_goal_width = field_size.goal_width / 2000.0 + vision_half_defense_depth = field_size.penalty_area_depth / 2000.0 + vision_half_defense_width = field_size.penalty_area_width / 2000.0 + d = self.full_field_dims + t = _GEOMETRY_MATCH_TOLERANCE_M + mismatches = [] + if abs(vision_half_length - d.full_field_half_length) > t: + mismatches.append( + f"field_length: vision={vision_half_length * 2:.3f}m configured={d.full_field_half_length * 2:.3f}m" + ) + if abs(vision_half_width - d.full_field_half_width) > t: + mismatches.append( + f"field_width: vision={vision_half_width * 2:.3f}m configured={d.full_field_half_width * 2:.3f}m" + ) + if abs(vision_half_goal_width - d.half_goal_width) > t: + mismatches.append( + f"goal_width: vision={vision_half_goal_width * 2:.3f}m configured={d.half_goal_width * 2:.3f}m" + ) + if abs(vision_half_defense_depth - d.half_defense_area_depth) > t: + mismatches.append( + f"penalty_area_depth: vision={vision_half_defense_depth * 2:.3f}m configured={d.half_defense_area_depth * 2:.3f}m" + ) + if abs(vision_half_defense_width - d.half_defense_area_width) > t: + mismatches.append( + f"penalty_area_width: vision={vision_half_defense_width * 2:.3f}m configured={d.half_defense_area_width * 2:.3f}m" + ) + if mismatches: + raise RuntimeError( + "Field geometry mismatch between full_field_dims and vision packet:\n" + + "\n".join(f" {m}" for m in mismatches) + + "\nUpdate full_field_dims in StrategyRunner to match the actual field." + ) + + return _on_geometry + def _assert_exp_robots_and_ball( self, exp_friendly: int, diff --git a/utama_core/tests/strategy_runner/test_grsim_sim_setup.py b/utama_core/tests/strategy_runner/test_grsim_sim_setup.py index 509b6783..575aa1d7 100644 --- a/utama_core/tests/strategy_runner/test_grsim_sim_setup.py +++ b/utama_core/tests/strategy_runner/test_grsim_sim_setup.py @@ -57,7 +57,7 @@ def test_grsim_spawn_positions_and_ball_use_field_bounds_center(): patch.object( StrategyRunner, "start_threads", - lambda self, vision_receiver: None, + lambda self, *args: None, ), patch.object( StrategyRunner, @@ -135,7 +135,7 @@ def test_grsim_exp_ball_false_removes_ball_not_center_teleport(): patch.object( StrategyRunner, "start_threads", - lambda self, vision_receiver: None, + lambda self, *args: None, ), patch.object( StrategyRunner, diff --git a/utama_core/tests/strategy_runner/test_runner_misconfig.py b/utama_core/tests/strategy_runner/test_runner_misconfig.py index 0e4d4a2c..1a04f9e4 100644 --- a/utama_core/tests/strategy_runner/test_runner_misconfig.py +++ b/utama_core/tests/strategy_runner/test_runner_misconfig.py @@ -1,10 +1,14 @@ +from collections import deque from types import SimpleNamespace -from unittest.mock import MagicMock +from unittest.mock import MagicMock, patch import pytest from utama_core.config.enums import Mode -from utama_core.config.field_params import GREAT_EXHIBITION_FIELD_DIMS +from utama_core.config.field_params import ( + GREAT_EXHIBITION_FIELD_DIMS, + STANDARD_FIELD_DIMS, +) from utama_core.custom_referee import CustomReferee from utama_core.entities.game.field import FieldBounds from utama_core.run.referee_source import OfficialReferee @@ -58,18 +62,30 @@ def test_validate_referee_accepts_official_in_grsim(): assert isinstance(result, OfficialReferee) +def _make_fake_field_size(dims=STANDARD_FIELD_DIMS): + """Build a fake SSL_GeometryFieldSize-like object from a FieldDimensions.""" + return SimpleNamespace( + field_length=int(dims.full_field_half_length * 2000), + field_width=int(dims.full_field_half_width * 2000), + goal_width=int(dims.half_goal_width * 2000), + penalty_area_depth=int(dims.half_defense_area_depth * 2000), + penalty_area_width=int(dims.half_defense_area_width * 2000), + field_arcs=[SimpleNamespace(name="CenterCircle", radius=int(dims.center_circle_radius * 1000))], + ) + + def test_setup_vision_and_referee_starts_vision_only_when_referee_none(monkeypatch): from utama_core.run import strategy_runner as runner_mod started = [] class DummyVisionReceiver: - def __init__(self, buffers): - self.buffers = buffers + def __init__(self, buffers, on_geometry=None): + pass class DummyRefereeReceiver: def __init__(self, buffer): - self.buffer = buffer + pass monkeypatch.setattr(runner_mod, "VisionReceiver", DummyVisionReceiver) monkeypatch.setattr(runner_mod, "RefereeMessageReceiver", DummyRefereeReceiver) @@ -77,9 +93,9 @@ def __init__(self, buffer): fake_runner = SimpleNamespace( mode=Mode.GRSIM, referee=None, - start_threads=lambda vision_receiver, referee_receiver=None: started.append( - (vision_receiver, referee_receiver) - ), + full_field_dims=STANDARD_FIELD_DIMS, + start_threads=lambda *args: started.append(args), + _make_geometry_validation_callback=lambda: None, ) vision_buffers, ref_buffer = StrategyRunner._setup_vision_and_referee(fake_runner) @@ -88,7 +104,7 @@ def __init__(self, buffer): assert ref_buffer.maxlen == 1 assert len(started) == 1 assert isinstance(started[0][0], DummyVisionReceiver) - assert started[0][1] is None + assert len(started[0]) == 1 def test_setup_vision_and_referee_starts_vision_only_when_referee_custom(monkeypatch): @@ -97,29 +113,23 @@ def test_setup_vision_and_referee_starts_vision_only_when_referee_custom(monkeyp started = [] class DummyVisionReceiver: - def __init__(self, buffers): - self.buffers = buffers - - class DummyRefereeReceiver: - def __init__(self, buffer): - self.buffer = buffer + def __init__(self, buffers, on_geometry=None): + pass monkeypatch.setattr(runner_mod, "VisionReceiver", DummyVisionReceiver) - monkeypatch.setattr(runner_mod, "RefereeMessageReceiver", DummyRefereeReceiver) fake_runner = SimpleNamespace( mode=Mode.REAL, referee=MagicMock(spec=CustomReferee), - start_threads=lambda vision_receiver, referee_receiver=None: started.append( - (vision_receiver, referee_receiver) - ), + full_field_dims=STANDARD_FIELD_DIMS, + start_threads=lambda *args: started.append(args), + _make_geometry_validation_callback=lambda: None, ) StrategyRunner._setup_vision_and_referee(fake_runner) assert len(started) == 1 - assert isinstance(started[0][0], DummyVisionReceiver) - assert started[0][1] is None + assert len(started[0]) == 1 def test_setup_vision_and_referee_starts_both_receivers_when_referee_official(monkeypatch): @@ -128,12 +138,12 @@ def test_setup_vision_and_referee_starts_both_receivers_when_referee_official(mo started = [] class DummyVisionReceiver: - def __init__(self, buffers): - self.buffers = buffers + def __init__(self, buffers, on_geometry=None): + pass class DummyRefereeReceiver: def __init__(self, buffer): - self.buffer = buffer + pass monkeypatch.setattr(runner_mod, "VisionReceiver", DummyVisionReceiver) monkeypatch.setattr(runner_mod, "RefereeMessageReceiver", DummyRefereeReceiver) @@ -141,9 +151,9 @@ def __init__(self, buffer): fake_runner = SimpleNamespace( mode=Mode.GRSIM, referee=OfficialReferee(), - start_threads=lambda vision_receiver, referee_receiver=None: started.append( - (vision_receiver, referee_receiver) - ), + full_field_dims=STANDARD_FIELD_DIMS, + start_threads=lambda *args: started.append(args), + _make_geometry_validation_callback=lambda: None, ) StrategyRunner._setup_vision_and_referee(fake_runner) @@ -153,6 +163,21 @@ def __init__(self, buffer): assert isinstance(started[0][1], DummyRefereeReceiver) +def test_geometry_validation_passes_on_matching_field(monkeypatch): + fake_field_size = _make_fake_field_size(STANDARD_FIELD_DIMS) + fake_runner = SimpleNamespace(full_field_dims=STANDARD_FIELD_DIMS) + callback = StrategyRunner._make_geometry_validation_callback(fake_runner) + callback(fake_field_size) # should not raise + + +def test_geometry_validation_raises_on_mismatched_field(monkeypatch): + fake_field_size = _make_fake_field_size(GREAT_EXHIBITION_FIELD_DIMS) + fake_runner = SimpleNamespace(full_field_dims=STANDARD_FIELD_DIMS) + callback = StrategyRunner._make_geometry_validation_callback(fake_runner) + with pytest.raises(RuntimeError, match="Field geometry mismatch"): + callback(fake_field_size) + + def test_assert_exp_robots_valid(base_runner): base_runner._assert_exp_robots_and_ball(3, 3, True) # Should not raise From eac4eb87ff8ee5f1b82573a5f923ec08184e468c Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 20 May 2026 00:06:10 +0100 Subject: [PATCH 058/121] feat: add Exhibition Road festival demo (2v2, compact field, human-operator referee) --- demo_exhibition_road.py | 147 ++++++++++++++++++++++++++++++++++++++++ 1 file changed, 147 insertions(+) create mode 100644 demo_exhibition_road.py diff --git a/demo_exhibition_road.py b/demo_exhibition_road.py new file mode 100644 index 00000000..67a4aae9 --- /dev/null +++ b/demo_exhibition_road.py @@ -0,0 +1,147 @@ +"""demo_exhibition_road.py — Exhibition Road Festival demo. + +Run: + pixi run python demo_exhibition_road.py + # RSim window opens; open http://localhost:8080 in a browser + +What it does: + - Uses GREAT_EXHIBITION_FIELD_DIMS (4 m × 3 m) — the compact field sized + for the Exhibition Road festival venue. + - Builds a custom RefereeProfile inline (same style as Utama-Strategy/main.py) + with all rules enabled and human-operator auto-advance settings so a + festival steward can control the game from the browser GUI. + - 2v2 format: two yellow robots vs two blue robots, matching the small field. + - Strategy_2v2 from Utama-Strategy is used for both sides so the robots + play a proper pass-and-shoot game rather than just wandering. + - enable_gui=True starts the browser panel at http://localhost:8080 so the + crowd can watch the referee state in real time. + +Operator workflow: + 1. Open http://localhost:8080 in a browser. + 2. Robots begin under FORCE_START (rsim auto-seed). + 3. Click Halt / Stop / Kickoff Yellow… to intervene. + 4. Click Normal Start to resume. + 5. Goals are detected automatically; the referee waits for the operator to + advance play (human auto-advance profile). +""" + +import sys +from pathlib import Path + +# --------------------------------------------------------------------------- +# Make Utama-Strategy importable when running from Utama-Core root. +# Adjust or remove this block if your pixi/venv already has it on sys.path. +# --------------------------------------------------------------------------- +_STRATEGY_ROOT = Path(__file__).parent.parent / "Utama-Strategy" +if _STRATEGY_ROOT.exists() and str(_STRATEGY_ROOT) not in sys.path: + sys.path.insert(0, str(_STRATEGY_ROOT)) + +from utama_strategy.examples.strategy_2v2 import Strategy_2v2 + +from utama_core.config.field_params import GREAT_EXHIBITION_FIELD_DIMS +from utama_core.custom_referee import CustomReferee +from utama_core.custom_referee.profiles.profile_loader import ( + AutoAdvanceConfig, + DefenseAreaConfig, + GameConfig, + GoalDetectionConfig, + KeepOutConfig, + OutOfBoundsConfig, + RefereeProfile, + RulesConfig, +) +from utama_core.run import StrategyRunner + +# --------------------------------------------------------------------------- +# Configuration +# --------------------------------------------------------------------------- + +GUI_PORT = 8080 +N_ROBOTS = 2 # 2v2 fits the compact exhibition field +MY_TEAM_IS_YELLOW = True +MY_TEAM_IS_RIGHT = True + +# --------------------------------------------------------------------------- +# Exhibition Road referee profile +# +# Rules: all on, max 1 defender in area (2v2 — one is effectively GK), +# keep-out radius scaled down to 0.3 m to match the smaller field. +# Game: 5-minute halves, human operator advances play after goals/restarts +# so a steward can pause and commentate for the crowd. +# --------------------------------------------------------------------------- + +_EXHIBITION_PROFILE = RefereeProfile( + profile_name="exhibition_road", + rules=RulesConfig( + goal_detection=GoalDetectionConfig( + enabled=True, + cooldown_seconds=1.0, + ), + out_of_bounds=OutOfBoundsConfig( + enabled=True, + free_kick_assigner="last_touch", + ), + defense_area=DefenseAreaConfig( + enabled=True, + max_defenders=1, # one robot allowed in own penalty area + attacker_infringement=True, + ), + keep_out=KeepOutConfig( + enabled=True, + radius_meters=0.3, # scaled down from standard 0.5 m for small field + violation_persistence_frames=30, + ), + ), + game=GameConfig( + half_duration_seconds=300.0, # 5-minute halves + kickoff_team="yellow", + force_start_after_goal=False, # operator manually advances after goals + stop_duration_seconds=3.0, + prepare_duration_seconds=3.0, + kickoff_timeout_seconds=10.0, + auto_advance=AutoAdvanceConfig( + # Human operator controls all state transitions — prevents robots + # from suddenly moving while the crowd is close to the field. + stop_to_next_command=False, + prepare_kickoff_to_normal=False, + prepare_penalty_to_normal=False, + direct_free_to_normal=False, + ball_placement_to_next=False, + normal_start_to_force=True, # still auto-force if kickoff stalls + ), + ), +) + +# --------------------------------------------------------------------------- +# Entry point +# --------------------------------------------------------------------------- + + +def main() -> None: + referee = CustomReferee( + _EXHIBITION_PROFILE, + n_robots_yellow=N_ROBOTS, + n_robots_blue=N_ROBOTS, + enable_gui=True, + gui_port=GUI_PORT, + ) + + runner = StrategyRunner( + strategy=Strategy_2v2(my_team_is_right=MY_TEAM_IS_RIGHT), + opp_strategy=Strategy_2v2(my_team_is_right=not MY_TEAM_IS_RIGHT), + my_team_is_yellow=MY_TEAM_IS_YELLOW, + my_team_is_right=MY_TEAM_IS_RIGHT, + mode="rsim", + control_scheme="pid", + exp_friendly=N_ROBOTS, + exp_enemy=N_ROBOTS, + full_field_dims=GREAT_EXHIBITION_FIELD_DIMS, # 4 m × 3 m exhibition field + referee=referee, + show_live_status=True, + ) + + runner.run() + + +if __name__ == "__main__": + main() From 3799bae58e967498a53a8559ff931f62e9d941e7 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 20 May 2026 00:07:48 +0100 Subject: [PATCH 059/121] refactor: use WanderingStrategy instead of external Strategy_2v2 import --- demo_exhibition_road.py | 22 +++++----------------- 1 file changed, 5 insertions(+), 17 deletions(-) diff --git a/demo_exhibition_road.py b/demo_exhibition_road.py index 67a4aae9..3be79e18 100644 --- a/demo_exhibition_road.py +++ b/demo_exhibition_road.py @@ -11,8 +11,8 @@ with all rules enabled and human-operator auto-advance settings so a festival steward can control the game from the browser GUI. - 2v2 format: two yellow robots vs two blue robots, matching the small field. - - Strategy_2v2 from Utama-Strategy is used for both sides so the robots - play a proper pass-and-shoot game rather than just wandering. + - WanderingStrategy is used so robots visibly move and you can watch the + RefereeOverride tree interrupt them when you issue commands from the GUI. - enable_gui=True starts the browser panel at http://localhost:8080 so the crowd can watch the referee state in real time. @@ -25,19 +25,6 @@ advance play (human auto-advance profile). """ -import sys -from pathlib import Path - -# --------------------------------------------------------------------------- -# Make Utama-Strategy importable when running from Utama-Core root. -# Adjust or remove this block if your pixi/venv already has it on sys.path. -# --------------------------------------------------------------------------- -_STRATEGY_ROOT = Path(__file__).parent.parent / "Utama-Strategy" -if _STRATEGY_ROOT.exists() and str(_STRATEGY_ROOT) not in sys.path: - sys.path.insert(0, str(_STRATEGY_ROOT)) - -from utama_strategy.examples.strategy_2v2 import Strategy_2v2 - from utama_core.config.field_params import GREAT_EXHIBITION_FIELD_DIMS from utama_core.custom_referee import CustomReferee from utama_core.custom_referee.profiles.profile_loader import ( @@ -51,6 +38,7 @@ RulesConfig, ) from utama_core.run import StrategyRunner +from utama_core.tests.referee.wandering_strategy import WanderingStrategy # --------------------------------------------------------------------------- # Configuration @@ -127,8 +115,8 @@ def main() -> None: ) runner = StrategyRunner( - strategy=Strategy_2v2(my_team_is_right=MY_TEAM_IS_RIGHT), - opp_strategy=Strategy_2v2(my_team_is_right=not MY_TEAM_IS_RIGHT), + strategy=WanderingStrategy(), + opp_strategy=WanderingStrategy(), my_team_is_yellow=MY_TEAM_IS_YELLOW, my_team_is_right=MY_TEAM_IS_RIGHT, mode="rsim", From b8a259df7c790bfb956fb2716d320412584879d7 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 20 May 2026 00:11:31 +0100 Subject: [PATCH 060/121] feat: scale WanderingStrategy waypoints to field_dims; pass exhibition dims in demo --- demo_exhibition_road.py | 4 +- .../tests/referee/wandering_strategy.py | 69 ++++++++----------- 2 files changed, 32 insertions(+), 41 deletions(-) diff --git a/demo_exhibition_road.py b/demo_exhibition_road.py index 3be79e18..fd1fdc64 100644 --- a/demo_exhibition_road.py +++ b/demo_exhibition_road.py @@ -115,8 +115,8 @@ def main() -> None: ) runner = StrategyRunner( - strategy=WanderingStrategy(), - opp_strategy=WanderingStrategy(), + strategy=WanderingStrategy(field_dims=GREAT_EXHIBITION_FIELD_DIMS), + opp_strategy=WanderingStrategy(field_dims=GREAT_EXHIBITION_FIELD_DIMS), my_team_is_yellow=MY_TEAM_IS_YELLOW, my_team_is_right=MY_TEAM_IS_RIGHT, mode="rsim", diff --git a/utama_core/tests/referee/wandering_strategy.py b/utama_core/tests/referee/wandering_strategy.py index 225a7f43..a7402ecc 100644 --- a/utama_core/tests/referee/wandering_strategy.py +++ b/utama_core/tests/referee/wandering_strategy.py @@ -6,58 +6,41 @@ and repositioned by the referee. """ -import math - import py_trees +from utama_core.config.field_params import STANDARD_FIELD_DIMS, FieldDimensions from utama_core.entities.data.vector import Vector2D from utama_core.skills.src.utils.move_utils import move from utama_core.strategy.common import AbstractBehaviour, AbstractStrategy -# One waypoint list per robot (by index into sorted robot IDs). -# Robots on the right half defend the right goal, so positions are spread -# across both halves to make motion easy to see. -_WAYPOINT_SETS = [ +# Waypoints defined as fractions of the standard field half-dimensions +# (half_length=4.5, half_width=3.0) so they scale correctly to any field. +# Values are in the range (-1, 1) relative to each half-axis. +_WAYPOINT_SETS_NORMALISED = [ # Robot 0 — large figure-8 across the field - [ - Vector2D(-3.0, 1.5), - Vector2D(0.0, 0.0), - Vector2D(3.0, -1.5), - Vector2D(0.0, 0.0), - ], + [(-0.67, 0.50), (0.0, 0.0), (0.67, -0.50), (0.0, 0.0)], # Robot 1 — diagonal patrol - [ - Vector2D(-2.0, -2.0), - Vector2D(2.0, 2.0), - ], + [(-0.44, -0.67), (0.44, 0.67)], # Robot 2 — wide horizontal sweep - [ - Vector2D(-3.5, 0.5), - Vector2D(3.5, 0.5), - Vector2D(3.5, -0.5), - Vector2D(-3.5, -0.5), - ], + [(-0.78, 0.17), (0.78, 0.17), (0.78, -0.17), (-0.78, -0.17)], # Robot 3 — small loop near centre - [ - Vector2D(1.0, 1.0), - Vector2D(-1.0, 1.0), - Vector2D(-1.0, -1.0), - Vector2D(1.0, -1.0), - ], + [(0.22, 0.33), (-0.22, 0.33), (-0.22, -0.33), (0.22, -0.33)], # Robot 4 — left-half patrol - [ - Vector2D(-3.0, 0.0), - Vector2D(-1.0, 2.0), - Vector2D(-1.0, -2.0), - ], + [(-0.67, 0.0), (-0.22, 0.67), (-0.22, -0.67)], # Robot 5 — right-half patrol - [ - Vector2D(3.0, 0.0), - Vector2D(1.0, 2.0), - Vector2D(1.0, -2.0), - ], + [(0.67, 0.0), (0.22, 0.67), (0.22, -0.67)], ] + +def _scale_waypoints( + field_dims: FieldDimensions, +) -> list[list[Vector2D]]: + """Return waypoint lists scaled to *field_dims*.""" + L = field_dims.full_field_half_length + W = field_dims.full_field_half_width + return [[Vector2D(fx * L, fy * W) for fx, fy in pattern] for pattern in _WAYPOINT_SETS_NORMALISED] + + _ARRIVAL_THRESHOLD = 0.15 # metres — how close counts as "reached" @@ -75,7 +58,7 @@ def update(self) -> py_trees.common.Status: robot_ids = sorted(game.friendly_robots.keys()) for slot, robot_id in enumerate(robot_ids): - waypoints = _WAYPOINT_SETS[slot % len(_WAYPOINT_SETS)] + waypoints = self.blackboard.strategy._waypoints[slot % len(self.blackboard.strategy._waypoints)] if robot_id not in self._wp_index: self._wp_index[robot_id] = 0 @@ -100,10 +83,18 @@ def update(self) -> py_trees.common.Status: class WanderingStrategy(AbstractStrategy): """Strategy where every robot continuously patrols a set of waypoints. + Waypoints are scaled to *field_dims* so the strategy works correctly on + any field size. Defaults to STANDARD_FIELD_DIMS when omitted, which + preserves the original behaviour for existing callers. + Intended for use with the referee visualisation simulation so that referee commands visibly interrupt robot motion. """ + def __init__(self, field_dims: FieldDimensions | None = None) -> None: + super().__init__() + self._waypoints = _scale_waypoints(field_dims or STANDARD_FIELD_DIMS) + def assert_exp_robots(self, n_runtime_friendly: int, n_runtime_enemy: int) -> bool: return True From 7b19c9283e66a104d6e52a763c422f2a611e6fb7 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 20 May 2026 00:17:37 +0100 Subject: [PATCH 061/121] fix: propagate geometry mismatch error from vision thread to main thread --- .../data_processing/receivers/vision_receiver.py | 14 +++++++++++++- utama_core/run/strategy_runner.py | 12 ++++++++++++ 2 files changed, 25 insertions(+), 1 deletion(-) diff --git a/utama_core/data_processing/receivers/vision_receiver.py b/utama_core/data_processing/receivers/vision_receiver.py index 5d6fd75f..a2fdaab2 100644 --- a/utama_core/data_processing/receivers/vision_receiver.py +++ b/utama_core/data_processing/receivers/vision_receiver.py @@ -1,4 +1,5 @@ import logging +import threading import time from collections import deque from typing import Callable, Deque, List, Optional @@ -22,11 +23,16 @@ def __init__( self, vision_buffers: List[Deque[RawVisionData]], on_geometry: Optional[Callable] = None, + stop_event: Optional[threading.Event] = None, ): self.net = network_manager.NetworkManager(address=(MULTICAST_GROUP, VISION_PORT), bind_socket=True) self.vision_buffers = vision_buffers self._on_geometry = on_geometry self._geometry_fired = False + self._stop_event = stop_event + # Parked exception from the geometry callback — re-raised in the main + # thread by StrategyRunner._run_step() so the process exits cleanly. + self.thread_exception: Optional[BaseException] = None self.packet_timestamps = deque() self.fps_print_interval = 1 # seconds self.last_fps_print_time = time.time() @@ -55,7 +61,13 @@ def pull_game_data(self, fps=False) -> None: vision_packet.Clear() vision_packet.ParseFromString(data) if self._on_geometry and not self._geometry_fired and vision_packet.HasField("geometry"): - self._on_geometry(vision_packet.geometry.field) + try: + self._on_geometry(vision_packet.geometry.field) + except Exception as exc: + self.thread_exception = exc + if self._stop_event is not None: + self._stop_event.set() + return self._geometry_fired = True # print(vision_packet.detection) self.prev_frame_num = vision_packet.detection.frame_number diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index 0cb49b61..ffc18d37 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -256,6 +256,7 @@ def __init__( self.profiler_name = profiler_name self.profiler = cProfile.Profile() if profiler_name else None self._stop_event = threading.Event() + self._vision_receiver: Optional[VisionReceiver] = None def _handle_sigint(self, sig, frame): self._stop_event.set() @@ -319,6 +320,11 @@ def start_threads( vision_receiver: VisionReceiver to run in a background thread. referee_receiver: Optional RefereeMessageReceiver to run in a background thread. """ + # Give the receiver a handle to _stop_event so geometry errors can + # signal the main loop to stop and re-raise the exception cleanly. + vision_receiver._stop_event = self._stop_event + self._vision_receiver = vision_receiver + vision_thread = threading.Thread(target=vision_receiver.pull_game_data) vision_thread.daemon = True @@ -893,6 +899,12 @@ def _run_step(self): No return value; updates internal game state and controllers. """ frame_start = time.perf_counter() + + # Re-raise any exception parked by a background thread (e.g. geometry + # mismatch from VisionReceiver) so the main loop exits with a clean + # traceback instead of crashing somewhere unrelated later. + if self._vision_receiver is not None and self._vision_receiver.thread_exception is not None: + raise self._vision_receiver.thread_exception self._draw_rsim_field_bounds_overlay() if isinstance(self.referee, CustomReferee): From a4107af203da038a76a5bdd596d7d496c1d4c704 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 20 May 2026 00:20:55 +0100 Subject: [PATCH 062/121] fix: initialise _stop_event before _setup_vision_and_referee in __init__ --- utama_core/run/strategy_runner.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index ffc18d37..98d21851 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -176,6 +176,9 @@ def __init__( self.field_bounds = field_bounds if field_bounds else full_field_dims.full_field_bounds self.referee: RefereeSource = self._validate_referee(self.mode, referee) + self._stop_event = threading.Event() + self._vision_receiver: Optional[VisionReceiver] = None + if isinstance(self.referee, CustomReferee): from utama_core.custom_referee.geometry import RefereeGeometry @@ -255,8 +258,6 @@ def __init__( # Profiler setup self.profiler_name = profiler_name self.profiler = cProfile.Profile() if profiler_name else None - self._stop_event = threading.Event() - self._vision_receiver: Optional[VisionReceiver] = None def _handle_sigint(self, sig, frame): self._stop_event.set() From 2a9237b964556784364fc85f61f7b972319fe7f5 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 20 May 2026 00:21:55 +0100 Subject: [PATCH 063/121] fix: guard draw_line calls when env is None (grsim/real mode) --- utama_core/motion_planning/src/fastpathplanning/planner.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/utama_core/motion_planning/src/fastpathplanning/planner.py b/utama_core/motion_planning/src/fastpathplanning/planner.py index ce7881f5..84079c17 100644 --- a/utama_core/motion_planning/src/fastpathplanning/planner.py +++ b/utama_core/motion_planning/src/fastpathplanning/planner.py @@ -272,8 +272,8 @@ def _path_to( final_trajectory, _ = self.check_segment((our_pos, safe_target), obstacles, 0, safe_target, field_bounds) # 5. Draw the resulting safe path segments - for i in final_trajectory: - if self._env is not None: + if self._env is not None: + for i in final_trajectory: self._env.draw_line(i) # 6. Smooth the path and draw the final "Carrot" target in Blue From f5f30f0f3de732346a5e8e04aab3ea3dfdd486d0 Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 20 May 2026 00:23:13 +0100 Subject: [PATCH 064/121] fix: re-raise parked thread exception after stop_event exits the run loop --- utama_core/run/strategy_runner.py | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/utama_core/run/strategy_runner.py b/utama_core/run/strategy_runner.py index 98d21851..c8be0312 100644 --- a/utama_core/run/strategy_runner.py +++ b/utama_core/run/strategy_runner.py @@ -881,8 +881,14 @@ def run(self): try: while not self._stop_event.is_set(): self._run_step() + # Loop exited via stop_event — check whether a background thread + # parked an exception (e.g. geometry mismatch from VisionReceiver). + if self._vision_receiver is not None and self._vision_receiver.thread_exception is not None: + raise self._vision_receiver.thread_exception except Exception: - if self._stop_event.is_set(): + if self._stop_event.is_set() and ( + self._vision_receiver is None or self._vision_receiver.thread_exception is None + ): self.logger.info("Stopping run loop due to interrupt.") else: self.logger.exception("Exception occurred during run loop:") From a0f2bc68d745dcae4fb844597757b58a4532158e Mon Sep 17 00:00:00 2001 From: isaac0804 Date: Wed, 20 May 2026 00:26:48 +0100 Subject: [PATCH 065/121] feat: redesign GUI to 2x2 quadrant layout with field filling top-left --- utama_core/custom_referee/gui.py | 385 ++++++++++++++++++------------- 1 file changed, 225 insertions(+), 160 deletions(-) diff --git a/utama_core/custom_referee/gui.py b/utama_core/custom_referee/gui.py index 231f7128..e0e8206a 100644 --- a/utama_core/custom_referee/gui.py +++ b/utama_core/custom_referee/gui.py @@ -132,6 +132,7 @@ def _build_config_json(self) -> str: "half_defense_depth": g.half_defense_depth, "half_defense_width": g.half_defense_width, "center_circle_radius": g.center_circle_radius, + "goal_depth": g.goal_depth, } return json.dumps(config) @@ -393,67 +394,91 @@ def _build_static_config(profile: "RefereeProfile") -> dict: --radius: 6px; } + html, body { + height: 100%; + } + body { background: var(--bg); color: var(--text); font-family: ui-monospace, "Cascadia Code", "Fira Code", monospace; - min-height: 100vh; - display: flex; - flex-direction: column; - align-items: center; - padding: 24px 16px; - gap: 20px; - } - - h1 { - font-size: 1.4rem; - letter-spacing: .12em; - text-transform: uppercase; - color: var(--text); - opacity: .9; + height: 100vh; + display: grid; + grid-template-columns: 1fr 1fr; + grid-template-rows: 1fr 1fr; + grid-template-areas: + "field controls" + "log config"; + gap: 0; + overflow: hidden; } - .panel { + /* ── Quadrant base ── */ + .quad { background: var(--surface); border: 1px solid var(--border); - border-radius: var(--radius); - width: 100%; - max-width: 640px; overflow: hidden; + display: flex; + flex-direction: column; } - - .panel-title { - padding: 10px 20px; - font-size: .7rem; + .quad-title { + padding: 8px 16px; + font-size: .65rem; letter-spacing: .12em; text-transform: uppercase; color: var(--muted); border-bottom: 1px solid var(--border); + flex-shrink: 0; } + /* ── Top-left: field ── */ + #quad-field { + grid-area: field; + } + #field-canvas { + display: block; + width: 100%; + height: 100%; + object-fit: contain; + } + .field-wrap { + flex: 1; + min-height: 0; + position: relative; + } + .field-wrap canvas { + position: absolute; + inset: 0; + width: 100%; + height: 100%; + } + + /* ── Top-right: controls ── */ + #quad-controls { + grid-area: controls; + overflow-y: auto; + } .scoreboard { display: grid; grid-template-columns: 1fr 1fr; border-bottom: 1px solid var(--border); + flex-shrink: 0; } - .score-cell { - padding: 18px 24px; + padding: 12px 16px; text-align: center; } .score-cell:first-child { border-right: 1px solid var(--border); } - .team-name { - font-size: .75rem; + font-size: .7rem; letter-spacing: .1em; text-transform: uppercase; - margin-bottom: 6px; + margin-bottom: 4px; } .team-name.yellow { color: var(--yellow); } .team-name.blue { color: var(--blue); } - .score-value { - font-size: 3rem; + font-size: 2.4rem; font-weight: 700; line-height: 1; } @@ -461,23 +486,23 @@ def _build_static_config(profile: "RefereeProfile") -> dict: .score-value.blue { color: var(--blue); } .info-block { - padding: 16px 24px; + padding: 12px 16px; display: flex; flex-direction: column; - gap: 10px; + gap: 8px; + border-bottom: 1px solid var(--border); + flex-shrink: 0; } - .info-row { display: flex; align-items: center; gap: 10px; - font-size: .9rem; + font-size: .85rem; } - .label { color: var(--muted); - min-width: 90px; - font-size: .75rem; + min-width: 84px; + font-size: .7rem; text-transform: uppercase; letter-spacing: .05em; flex-shrink: 0; @@ -485,9 +510,9 @@ def _build_static_config(profile: "RefereeProfile") -> dict: .badge { display: inline-block; - padding: 4px 12px; + padding: 3px 10px; border-radius: 4px; - font-size: .85rem; + font-size: .8rem; font-weight: 600; letter-spacing: .05em; text-transform: uppercase; @@ -511,68 +536,20 @@ def _build_static_config(profile: "RefereeProfile") -> dict: .badge.TIMEOUT_BLUE { background: var(--blue); color: #111; } .badge.unknown { background: #444; color: #ccc; } - .config-grid { - display: grid; - grid-template-columns: 1fr 1fr; - } - - .config-section { - padding: 14px 20px; - border-bottom: 1px solid var(--border); - } - .config-section:nth-child(odd) { border-right: 1px solid var(--border); } - .config-section:nth-last-child(-n+2) { border-bottom: none; } - - .config-section-title { - font-size: .68rem; - letter-spacing: .1em; - text-transform: uppercase; - color: var(--muted); - margin-bottom: 8px; - } - - .cfg-row { - display: flex; - justify-content: space-between; - align-items: center; - font-size: .8rem; - padding: 2px 0; - gap: 8px; - } - - .cfg-key { color: var(--muted); flex-shrink: 0; } - .cfg-val { text-align: right; word-break: break-word; } - - .pill { - display: inline-block; - padding: 1px 7px; - border-radius: 3px; - font-size: .75rem; - font-weight: 600; - } - .pill.on { background: #1a3a1a; color: var(--green); border: 1px solid #2a5a2a; } - .pill.off { background: #3a1a1a; color: #c0605a; border: 1px solid #5a2a2a; } - .buttons { - background: var(--surface); - border: 1px solid var(--border); - border-radius: var(--radius); - width: 100%; - max-width: 640px; - padding: 16px 20px; + padding: 12px 16px; display: flex; flex-direction: column; - gap: 10px; + gap: 8px; + flex-shrink: 0; } - - .btn-row { display: flex; flex-wrap: wrap; gap: 8px; } - + .btn-row { display: flex; flex-wrap: wrap; gap: 6px; } button { - padding: 8px 16px; + padding: 7px 13px; border: 1px solid transparent; border-radius: var(--radius); font-family: inherit; - font-size: .8rem; + font-size: .75rem; font-weight: 600; letter-spacing: .05em; text-transform: uppercase; @@ -581,7 +558,6 @@ def _build_static_config(profile: "RefereeProfile") -> dict: } button:active { transform: scale(.96); } button:hover { filter: brightness(1.15); } - .btn-halt { background: var(--red); color: #fff; } .btn-stop { background: var(--orange); color: #fff; } .btn-normal-start, @@ -590,38 +566,106 @@ def _build_static_config(profile: "RefereeProfile") -> dict: .btn-blue { background: var(--blue); color: #111; } .conn { + padding: 8px 16px; display: flex; align-items: center; gap: 6px; - font-size: .75rem; + font-size: .7rem; color: var(--muted); + border-top: 1px solid var(--border); + flex-shrink: 0; + margin-top: auto; } .dot { - width: 8px; height: 8px; + width: 7px; height: 7px; border-radius: 50%; background: #555; transition: background .3s; } .dot.live { background: var(--green); } - /* Phase 2 additions */ - .viz-row { display:flex; gap:16px; width:100%; max-width:640px; align-items:flex-start; } - .field-panel { flex:1 1 0; min-width:0; overflow:hidden; } - #field-canvas { display:block; width:100%; height:auto; } - .log-panel { flex:1 1 0; min-width:0; display:flex; flex-direction:column; max-height:260px; } - .log-entries { overflow-y:auto; flex:1; padding:8px 12px; display:flex; flex-direction:column; gap:4px; } - .log-entry { font-size:.72rem; line-height:1.4; border-bottom:1px solid var(--border); padding-bottom:3px; } - .log-time { color:var(--muted); margin-right:6px; } - .log-cmd { color:var(--green); } - .log-score{ color:var(--yellow); } - .log-msg { color:var(--text); opacity:.8; } + /* ── Bottom-left: event log ── */ + #quad-log { + grid-area: log; + } + .log-entries { + overflow-y: auto; + flex: 1; + min-height: 0; + padding: 8px 12px; + display: flex; + flex-direction: column; + gap: 3px; + } + .log-entry { + font-size: .7rem; + line-height: 1.4; + border-bottom: 1px solid var(--border); + padding-bottom: 3px; + } + .log-time { color: var(--muted); margin-right: 6px; } + .log-cmd { color: var(--green); } + .log-score { color: var(--yellow); } + .log-msg { color: var(--text); opacity: .8; } + + /* ── Bottom-right: config ── */ + #quad-config { + grid-area: config; + overflow-y: auto; + } + .config-grid { + display: grid; + grid-template-columns: 1fr 1fr; + flex: 1; + min-height: 0; + } + .config-section { + padding: 10px 16px; + border-bottom: 1px solid var(--border); + } + .config-section:nth-child(odd) { border-right: 1px solid var(--border); } + .config-section:nth-last-child(-n+2) { border-bottom: none; } + .config-section-title { + font-size: .63rem; + letter-spacing: .1em; + text-transform: uppercase; + color: var(--muted); + margin-bottom: 6px; + } + .cfg-row { + display: flex; + justify-content: space-between; + align-items: center; + font-size: .75rem; + padding: 2px 0; + gap: 8px; + } + .cfg-key { color: var(--muted); flex-shrink: 0; } + .cfg-val { text-align: right; word-break: break-word; } + .pill { + display: inline-block; + padding: 1px 6px; + border-radius: 3px; + font-size: .7rem; + font-weight: 600; + } + .pill.on { background: #1a3a1a; color: var(--green); border: 1px solid #2a5a2a; } + .pill.off { background: #3a1a1a; color: #c0605a; border: 1px solid #5a2a2a; } -

Custom Referee

+ +
+
Field
+
+ +
+
-
+ +
+
Controls
Yellow
@@ -632,7 +676,6 @@ def _build_static_config(profile: "RefereeProfile") -> dict:
-
Command @@ -653,57 +696,51 @@ def _build_static_config(profile: "RefereeProfile") -> dict:
-
- -
-
- - - - -
-
- - +
+
+ + + + +
+
+ + +
+
+ + +
-
- - +
+
+ connecting…
-
-
-
Field
- -
-
-
Event Log
-
-
+ +
+
Event Log
+
-
-
Profile — loading…
+ +
+
Profile — loading…
-
-
- connecting… -
-