Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ def __init__(self, node, blackboard=None):
self.free_kick_kickoff_team: bool | None = None
self.game_controller_stop: bool = False
self.last_timestep_whistle_detected: Time | None = None
self.team_com_limit_has_reached: bool = False
# publish stopped msg for hcm
self.stop_pub = node.create_publisher(Bool, "game_controller/stop_msg", 1)

Expand Down Expand Up @@ -84,12 +85,21 @@ def get_seconds_since_unpenalized(self) -> float:

def get_is_penalized(self) -> bool:
return self.gamestate.penalized

def get_penalized_team_mates(self) -> int:
return self.gamestate.team_mates_with_penalty

def get_penalized_rivals(self) -> int:
return self.gamestate.rivals_with_penalty

def received_gamestate(self) -> bool:
return self.last_update != 0.0

def get_team_id(self) -> int:
return self.team_id

def get_team_com_limit_has_reached(self) -> bool:
return self.team_com_limit_has_reached

def gamestate_callback(self, gamestate_msg: GameState) -> None:
if self.gamestate.penalized and not gamestate_msg.penalized:
Expand All @@ -106,6 +116,8 @@ def gamestate_callback(self, gamestate_msg: GameState) -> None:

self.stop_pub.publish(Bool(data=self.game_controller_stop))

self.team_com_limit_has_reached = gamestate_msg.message_budget < 40

"""Anstoß im Falle von Overtime jetzt erstmal nicht genauer geregelt
if (
gamestate_msg.main_state == GameState.STATE_SET
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,16 @@ def __init__(self, node, blackboard):
self.data_timeout: float = float(self._node.get_parameter("team_data_timeout").value)
self.ball_max_covariance: float = float(self._node.get_parameter("ball_max_covariance").value)

# --- Save informations for handling decisions after team com has switched off ---
# The last rank to ball result before team_com limit was reached
self.last_rank_to_ball_with_team_com: int = -1
# Was goalie active before team_com limit was reached
self.was_goalie_active: bool = True
# Was goalie handling the ball before team_com limit was reached
self.was_goalie_handling_ball_with_team_com: bool = False
# The last number of active field players before team_com limit was reached
self.last_number_of_active_players: int = -1

@cached_capsule_function
def time(self) -> Time:
"""Returns the current time of the node, this is its own function so it can be cached during the decision loop."""
Expand All @@ -93,7 +103,9 @@ def is_goalie_handling_ball(self) -> bool:
and data.strategy.role == Strategy.ROLE_GOALIE
and data.strategy.action in [Strategy.ACTION_GOING_TO_BALL, Strategy.ACTION_KICKING]
):
self.was_goalie_handling_ball_with_team_com = True
return True
self.was_goalie_handling_ball_with_team_com = False
return False

@cached_capsule_function
Expand Down Expand Up @@ -138,7 +150,9 @@ def team_rank_to_ball(
)
for rank, distance in enumerate(sorted(distances)):
if own_ball_distance < distance:
self.last_rank_to_ball_with_team_com = rank + 1
return rank + 1
self.last_rank_to_ball_with_team_com = len(distances) + 1
return len(distances) + 1

def set_action(self, action: int) -> None:
Expand All @@ -151,6 +165,18 @@ def set_action(self, action: int) -> None:

def get_action(self) -> tuple[int, float]:
return self.strategy.action, self.action_update

def get_was_goalie_handling_ball(self) -> bool:
return self.was_goalie_handling_ball_with_team_com

def get_was_goalie_active(self) -> bool:
return self.was_goalie_active

def get_last_rank_with_team_com(self) -> int:
return self.last_rank_to_ball_with_team_com

def get_last_number_active_player(self) -> int:
return self.last_number_of_active_players

def set_role(self, role: Literal["goalie", "offense", "defense"]) -> None:
"""Set the role of this robot in the team
Expand Down Expand Up @@ -195,6 +221,7 @@ def is_not_goalie(team_data: TeamData) -> bool:
team_data_infos = filter(is_not_goalie, team_data_infos) # type: ignore[assignment]

# Count valid team data infos (aka robots with valid team data)
self.last_number_of_active_players = sum(map(self.is_valid, team_data_infos))
return sum(map(self.is_valid, team_data_infos))

@cached_capsule_function
Expand All @@ -209,6 +236,7 @@ def is_a_goalie(team_data: TeamData) -> bool:
team_data_infos = filter(is_a_goalie, team_data_infos) # type: ignore[assignment]

# Count valid team data infos (aka robots with valid team data)
self.was_goalie_active = sum(map(self.is_valid, team_data_infos)) == 1
return sum(map(self.is_valid, team_data_infos)) == 1

def get_own_time_to_ball(self) -> float:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,12 @@ def __init__(self, blackboard, dsd, parameters):
super().__init__(blackboard, dsd, parameters)

def perform(self, reevaluate=False):
my_time_to_ball = self.blackboard.team_data.get_own_time_to_ball()
rank = self.blackboard.team_data.team_rank_to_ball(my_time_to_ball, count_goalies=True, use_time_to_ball=True)
self.publish_debug_data("time to ball", my_time_to_ball)
if self.blackboard.gamstate.get_team_com_limit_has_reached():
rank = self.blackboard.team_data.get_last_rank_with_team_com()
else:
my_time_to_ball = self.blackboard.team_data.get_own_time_to_ball()
rank = self.blackboard.team_data.team_rank_to_ball(my_time_to_ball, count_goalies=True, use_time_to_ball=True)
self.publish_debug_data("time to ball", my_time_to_ball)
self.publish_debug_data("Rank to ball", rank)
if rank == 1:
return "YES"
Expand All @@ -47,9 +50,12 @@ def __init__(self, blackboard, dsd, parameters):
super().__init__(blackboard, dsd, parameters)

def perform(self, reevaluate=False):
my_time_to_ball = self.blackboard.team_data.get_own_time_to_ball()
rank = self.blackboard.team_data.team_rank_to_ball(my_time_to_ball, count_goalies=False, use_time_to_ball=True)
self.publish_debug_data("time to ball", my_time_to_ball)
if self.blackboard.gamstate.get_team_com_limit_has_reached():
rank = self.blackboard.team_data.get_last_rank_with_team_com()
else:
my_time_to_ball = self.blackboard.team_data.get_own_time_to_ball()
rank = self.blackboard.team_data.team_rank_to_ball(my_time_to_ball, count_goalies=False, use_time_to_ball=True)
self.publish_debug_data("time to ball", my_time_to_ball)
self.publish_debug_data("Rank to ball", rank)
if rank == 1:
return "FIRST"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,10 @@ def __init__(self, blackboard, dsd, parameters):
super().__init__(blackboard, dsd, parameters)

def perform(self, reevaluate=False):
number_of_active_teammates = self.blackboard.team_data.get_number_of_active_field_players(False)
if self.blackboard.gamstate.get_team_com_limit_has_reached():
number_of_active_teammates = self.blackboard.team_data.get_last_number_active_player()
else:
number_of_active_teammates = self.blackboard.team_data.get_number_of_active_field_players(False)
self.publish_debug_data("Number of active Teammates", number_of_active_teammates)
if number_of_active_teammates == 0:
return "ZERO"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,10 +13,16 @@ def __init__(self, blackboard, dsd, parameters):
super().__init__(blackboard, dsd, parameters)

def perform(self, reevaluate=False):
if self.blackboard.team_data.get_is_goalie_active():
return "YES"
if self.blackboard.gamstate.get_team_com_limit_has_reached():
if self.blackboard.team_data.get_was_goalie_active():
return "YES"
else:
return "NO"
else:
return "NO"
if self.blackboard.team_data.get_is_goalie_active():
return "YES"
else:
return "NO"

def get_reevaluate(self):
return True
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,16 @@ def perform(self, reevaluate=False):
"""
It is determined if the goalie is currently going towards the ball
"""
if self.blackboard.team_data.is_goalie_handling_ball():
return "YES"
if self.blackboard.gamstate.get_team_com_limit_has_reached():
if self.blackboard.team_data.get_was_goalie_handling_ball():
return "YES"
else:
return "NO"
else:
return "NO"
if self.blackboard.team_data.is_goalie_handling_ball():
return "YES"
else:
return "NO"

def get_reevaluate(self):
return True
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
from bitbots_blackboard.body_blackboard import BodyBlackboard
from dynamic_stack_decider.abstract_decision_element import AbstractDecisionElement
from game_controller_hsl_interfaces.msg import GameState


class NumberPenalizedTeamMates(AbstractDecisionElement):
blackboard: BodyBlackboard

def __init__(self, blackboard, dsd, parameters):
super().__init__(blackboard, dsd, parameters)

def perform(self, reevaluate=False):
"""
Return number of penalized team mates
:param reevaluate:
:return:
"""
game_state_penalized_team_mates = self.blackboard.gamestate.get_penalized_team_mates()

if game_state_penalized_team_mates == 4:
return "FOUR"
elif game_state_penalized_team_mates == 3:
return "THREE"
elif game_state_penalized_team_mates == 2:
return "TWO"
elif game_state_penalized_team_mates == 1:
return "ONE"
else:
return "ZERO"

def get_reevaluate(self):
"""
Game state can change during the game
"""
return True

class NumberPenalizedRivals(AbstractDecisionElement):
blackboard: BodyBlackboard

def __init__(self, blackboard, dsd, parameters):
super().__init__(blackboard, dsd, parameters)

def perform(self, reevaluate=False):
"""
Return number of penalized rivals
:param reevaluate:
:return:
"""
game_state_penalized_rivals = self.blackboard.gamestate.get_penalized_rivals()

if game_state_penalized_rivals == 4:
return "FOUR"
elif game_state_penalized_rivals == 3:
return "THREE"
elif game_state_penalized_rivals == 2:
return "TWO"
elif game_state_penalized_rivals == 1:
return "ONE"
else:
return "ZERO"
Comment on lines +20 to +60
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

There would be the possibility of having more than four in an advanced game with substitutes, I think.


def get_reevaluate(self):
"""
Game state can change during the game
"""
return True
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
from bitbots_blackboard.body_blackboard import BodyBlackboard
from dynamic_stack_decider.abstract_decision_element import AbstractDecisionElement


class TeamComLimitReached(AbstractDecisionElement):
blackboard: BodyBlackboard

def __init__(self, blackboard, dsd, parameters):
super().__init__(blackboard, dsd, parameters)

def perform(self, reevaluate=False):
if self.blackboard.gamstate.get_team_com_limit_has_reached():
return "YES"
else:
return "NO"

def get_reevaluate(self):
return True
Original file line number Diff line number Diff line change
Expand Up @@ -76,11 +76,13 @@ $GoalieActive
NO --> @LookAtFieldFeatures, @ChangeAction + action:positioning, @GoToBlockPosition

#SupporterRole
$PassStarted
YES --> $BallSeen
YES --> @TrackBall, @ChangeAction + action:positioning, @AvoidBallActive, @GoToPassAcceptPosition
NO --> @LookAtFieldFeatures, @ChangeAction + action:positioning, @AvoidBallActive, @GoToPassAcceptPosition
NO --> @LookAtFieldFeatures, @ChangeAction + action:positioning, @AvoidBallActive, @GoToPassPreparePosition
$TeamComLimitReached
YES --> @LookAtFieldFeatures, @ChangeAction + action:positioning, @AvoidBallActive, @GoToPassPreparePosition
NO --> $PassStarted
YES --> $BallSeen
YES --> @TrackBall, @ChangeAction + action:positioning, @AvoidBallActive, @GoToPassAcceptPosition
NO --> @LookAtFieldFeatures, @ChangeAction + action:positioning, @AvoidBallActive, @GoToPassAcceptPosition
NO --> @LookAtFieldFeatures, @ChangeAction + action:positioning, @AvoidBallActive, @GoToPassPreparePosition

#PenaltyShootoutBehavior
$SecondaryStateTeamDecider
Expand Down Expand Up @@ -119,6 +121,34 @@ $BallSeen
YES --> $KickOffTimeUp
NO_NORMAL --> #StandAndLook
NO_FREEKICK --> #Placing
YES --> $ConfigRole
GOALIE --> #GoalieBehavior
ELSE --> $TeamComLimitReached //this decision is only for better visualization
NO -- > $CountActiveRobotsWithoutGoalie
ONE --> $RankToBallNoGoalie
FIRST --> #StrikerRole
SECOND --> #DefensePositioning
ELSE --> $RankToBallNoGoalie
FIRST --> #StrikerRole
SECOND --> #SupporterRole
THIRD --> #DefensePositioning
YES --> $CountActiveRobotsWithoutGoalie
ONE --> $RankToBallNoGoalie
FIRST --> #StrikerRole
SECOND --> #DefensePositioning
ELSE --> $RankToBallNoGoalie
FIRST --> #StrikerRole
SECOND --> #SupporterRole
THIRD --> #DefensePositioning

#NormalBehaviorWithoutTeamCom
$BallSeen
NO --> $ConfigRole
GOALIE --> #RolePositionWithPause
ELSE --> #SearchBall
YES --> $KickOffTimeUp
NO_NORMAL --> #StandAndLook
NO_FREEKICK --> #PlacingWithoutTeamCom
YES --> $ConfigRole
GOALIE --> #GoalieBehavior
ELSE --> $CountActiveRobotsWithoutGoalie
Expand Down
Loading
Loading