Skip to content

Commit

Permalink
Change to GameStateManger
Browse files Browse the repository at this point in the history
  • Loading branch information
JornJorn committed Dec 6, 2023
1 parent 8db75b3 commit 07c4148
Show file tree
Hide file tree
Showing 7 changed files with 88 additions and 163 deletions.
10 changes: 8 additions & 2 deletions roboteam_ai/include/roboteam_ai/utilities/GameStateManager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,13 @@ class GameStateManager {
* @return The referee data
*/
static proto::SSL_Referee getRefereeData();
/**
* @brief Converts the referee command to a RefCommand
* @param command The command received from the referee
* @param isYellow Whether our team is the yellow team
* @return RefCommand The corresponding RefCommand for the received referee command
*/
static RefCommand getCommandFromRefMsg(proto::SSL_Referee_Command command, bool isYellow);
/**
* @brief Getter for the current game state
* @return The current game state
Expand All @@ -31,9 +38,8 @@ class GameStateManager {
/**
* @brief Force a new game state. This overrules the referee
* @param cmd The game state we want
* @param ball The current ball data
*/
static void forceNewGameState(RefCommand cmd, std::optional<rtt::world::view::BallView> ball);
static void forceNewGameState(RefCommand cmd);
/**
* @brief Getter for a designated position from the referee. For example: ball placement position
* @return Designated position from the referee
Expand Down
3 changes: 1 addition & 2 deletions roboteam_ai/include/roboteam_ai/utilities/StrategyManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,8 @@ class StrategyManager {
/**
* @brief Forces the AI into a given game state
* @param command The game state that should be considered
* @param ballOpt Data about the ball
*/
void forceCurrentRefGameState(RefCommand command, std::optional<rtt::world::view::BallView> ballOpt);
void forceCurrentRefGameState(RefCommand command);

/**
* @brief Gets the game state that belongs to the given command
Expand Down
2 changes: 1 addition & 1 deletion roboteam_ai/src/STPManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ const STPManager::PlaysVec STPManager::plays = ([] {
/// Start running behaviour trees. While doing so, publish settings and log the FPS of the system
void STPManager::start(std::atomic_flag &exitApplication) {
// make sure we start in halt state for safety
ai::GameStateManager::forceNewGameState(RefCommand::HALT, std::nullopt);
ai::GameStateManager::forceNewGameState(RefCommand::HALT);
RTT_INFO("Start looping")
RTT_INFO("Waiting for field_data and robots...")

Expand Down
2 changes: 1 addition & 1 deletion roboteam_ai/src/gui/networking/InterfaceSubscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ void InterfaceSubscriber::onMessage(const proto::MsgFromInterface&& message) {
GameStateManager::updateInterfaceGameState(data.play_name().c_str());

interface::Output::setKeeperId(data.keeper_id());
interface::Output::setRuleSetName(data.ruleset_name());
// interface::Output::setRuleSetName(data.ruleset_name());
stp::PlayDecider::lockPlay(data.play_name());
} break;

Expand Down
220 changes: 69 additions & 151 deletions roboteam_ai/src/utilities/GameStateManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,124 +19,51 @@ proto::SSL_Referee GameStateManager::getRefereeData() {
return GameStateManager::refMsg;
}

RefCommand GameStateManager::getCommandFromRefMsg(proto::SSL_Referee_Command command, bool isYellow) {
switch (command) {
case proto::SSL_Referee_Command_HALT:
return RefCommand::HALT;
case proto::SSL_Referee_Command_STOP:
return RefCommand::STOP;
case proto::SSL_Referee_Command_NORMAL_START:
return RefCommand::NORMAL_START;
case proto::SSL_Referee_Command_FORCE_START:
return RefCommand::FORCED_START;
case proto::SSL_Referee_Command_PREPARE_KICKOFF_YELLOW:
return isYellow ? RefCommand::PREPARE_KICKOFF_US : RefCommand::PREPARE_KICKOFF_THEM;
case proto::SSL_Referee_Command_PREPARE_KICKOFF_BLUE:
return isYellow ? RefCommand::PREPARE_KICKOFF_THEM : RefCommand::PREPARE_KICKOFF_US;
case proto::SSL_Referee_Command_PREPARE_PENALTY_YELLOW:
return isYellow ? RefCommand::PREPARE_PENALTY_US : RefCommand::PREPARE_PENALTY_THEM;
case proto::SSL_Referee_Command_PREPARE_PENALTY_BLUE:
return isYellow ? RefCommand::PREPARE_PENALTY_THEM : RefCommand::PREPARE_PENALTY_US;
case proto::SSL_Referee_Command_DIRECT_FREE_YELLOW:
return isYellow ? RefCommand::DIRECT_FREE_US : RefCommand::DIRECT_FREE_THEM;
case proto::SSL_Referee_Command_DIRECT_FREE_BLUE:
return isYellow ? RefCommand::DIRECT_FREE_THEM : RefCommand::DIRECT_FREE_US;
case proto::SSL_Referee_Command_INDIRECT_FREE_YELLOW:
return isYellow ? RefCommand::INDIRECT_FREE_US : RefCommand::INDIRECT_FREE_THEM;
case proto::SSL_Referee_Command_INDIRECT_FREE_BLUE:
return isYellow ? RefCommand::INDIRECT_FREE_THEM : RefCommand::INDIRECT_FREE_US;
case proto::SSL_Referee_Command_TIMEOUT_YELLOW:
return isYellow ? RefCommand::TIMEOUT_US : RefCommand::TIMEOUT_THEM;
case proto::SSL_Referee_Command_TIMEOUT_BLUE:
return isYellow ? RefCommand::TIMEOUT_THEM : RefCommand::TIMEOUT_US;
case proto::SSL_Referee_Command_BALL_PLACEMENT_YELLOW:
return isYellow ? RefCommand::BALL_PLACEMENT_US : RefCommand::BALL_PLACEMENT_THEM;
case proto::SSL_Referee_Command_BALL_PLACEMENT_BLUE:
return isYellow ? RefCommand::BALL_PLACEMENT_THEM : RefCommand::BALL_PLACEMENT_US;
default:
RTT_ERROR("Unknown refstate, halting all robots for safety!")
return RefCommand::HALT;
}
}

void GameStateManager::setRefereeData(proto::SSL_Referee refMsg, const rtt::world::World* data) {
std::lock_guard<std::mutex> lock(refMsgLock);
GameStateManager::refMsg = refMsg;
RefCommand cmd;
// COLOR DEPENDENT STATES
if (GameSettings::isYellow()) {
switch (refMsg.command()) {
case proto::SSL_Referee_Command_HALT:
cmd = RefCommand::HALT;
break;
case proto::SSL_Referee_Command_STOP:
cmd = RefCommand::STOP;
break;
case proto::SSL_Referee_Command_NORMAL_START:
cmd = RefCommand::NORMAL_START;
break;
case proto::SSL_Referee_Command_FORCE_START:
cmd = RefCommand::FORCED_START;
break;
case proto::SSL_Referee_Command_PREPARE_KICKOFF_YELLOW:
cmd = RefCommand::PREPARE_KICKOFF_US;
break;
case proto::SSL_Referee_Command_PREPARE_KICKOFF_BLUE:
cmd = RefCommand::PREPARE_KICKOFF_THEM;
break;
case proto::SSL_Referee_Command_PREPARE_PENALTY_YELLOW:
cmd = RefCommand::PREPARE_PENALTY_US;
break;
case proto::SSL_Referee_Command_PREPARE_PENALTY_BLUE:
cmd = RefCommand::PREPARE_PENALTY_THEM;
break;
case proto::SSL_Referee_Command_DIRECT_FREE_YELLOW:
cmd = RefCommand::DIRECT_FREE_US;
break;
case proto::SSL_Referee_Command_DIRECT_FREE_BLUE:
cmd = RefCommand::DIRECT_FREE_THEM;
break;
case proto::SSL_Referee_Command_INDIRECT_FREE_YELLOW:
cmd = RefCommand::INDIRECT_FREE_US;
break;
case proto::SSL_Referee_Command_INDIRECT_FREE_BLUE:
cmd = RefCommand::INDIRECT_FREE_THEM;
break;
case proto::SSL_Referee_Command_TIMEOUT_YELLOW:
cmd = RefCommand::TIMEOUT_US;
break;
case proto::SSL_Referee_Command_TIMEOUT_BLUE:
cmd = RefCommand::TIMEOUT_THEM;
break;
case proto::SSL_Referee_Command_BALL_PLACEMENT_YELLOW:
cmd = RefCommand::BALL_PLACEMENT_US;
break;
case proto::SSL_Referee_Command_BALL_PLACEMENT_BLUE:
cmd = RefCommand::BALL_PLACEMENT_THEM;
break;
default: {
RTT_ERROR("Unknown refstate, halting all robots for safety!")
cmd = RefCommand::HALT;
break;
}
}
} else {
switch (refMsg.command()) {
case proto::SSL_Referee_Command_HALT:
cmd = RefCommand::HALT;
break;
case proto::SSL_Referee_Command_STOP:
cmd = RefCommand::STOP;
break;
case proto::SSL_Referee_Command_NORMAL_START:
cmd = RefCommand::NORMAL_START;
break;
case proto::SSL_Referee_Command_FORCE_START:
cmd = RefCommand::FORCED_START;
break;
case proto::SSL_Referee_Command_PREPARE_KICKOFF_YELLOW:
cmd = RefCommand::PREPARE_KICKOFF_THEM;
break;
case proto::SSL_Referee_Command_PREPARE_KICKOFF_BLUE:
cmd = RefCommand::PREPARE_KICKOFF_US;
break;
case proto::SSL_Referee_Command_PREPARE_PENALTY_YELLOW:
cmd = RefCommand::PREPARE_PENALTY_THEM;
break;
case proto::SSL_Referee_Command_PREPARE_PENALTY_BLUE:
cmd = RefCommand::PREPARE_PENALTY_US;
break;
case proto::SSL_Referee_Command_DIRECT_FREE_YELLOW:
cmd = RefCommand::DIRECT_FREE_THEM;
break;
case proto::SSL_Referee_Command_DIRECT_FREE_BLUE:
cmd = RefCommand::DIRECT_FREE_US;
break;
case proto::SSL_Referee_Command_INDIRECT_FREE_YELLOW:
cmd = RefCommand::INDIRECT_FREE_THEM;
break;
case proto::SSL_Referee_Command_INDIRECT_FREE_BLUE:
cmd = RefCommand::INDIRECT_FREE_US;
break;
case proto::SSL_Referee_Command_TIMEOUT_YELLOW:
cmd = RefCommand::TIMEOUT_THEM;
break;
case proto::SSL_Referee_Command_TIMEOUT_BLUE:
cmd = RefCommand::TIMEOUT_US;
break;
case proto::SSL_Referee_Command_BALL_PLACEMENT_YELLOW:
cmd = RefCommand::BALL_PLACEMENT_THEM;
break;
case proto::SSL_Referee_Command_BALL_PLACEMENT_BLUE:
cmd = RefCommand::BALL_PLACEMENT_US;
break;
default: {
RTT_ERROR("Unknown refstate, halting all robots for safety!")
cmd = RefCommand::HALT;
break;
}
}
}
bool isYellow = GameSettings::isYellow();
RefCommand cmd = getCommandFromRefMsg(refMsg.command(), isYellow);

auto stage = refMsg.stage();
auto world = data->getWorld();
Expand Down Expand Up @@ -170,12 +97,12 @@ GameState GameStateManager::getCurrentGameState() {
return newGameState;
}

void GameStateManager::forceNewGameState(RefCommand cmd, std::optional<rtt::world::view::BallView> ball) {
void GameStateManager::forceNewGameState(RefCommand cmd) {
RTT_INFO("Forcing new refstate!")

// overwrite both the interface and the strategy manager.
interface::Output::setInterfaceGameState(strategymanager.getRefGameStateForRefCommand(cmd));
strategymanager.forceCurrentRefGameState(cmd, ball);
strategymanager.forceCurrentRefGameState(cmd);
}

Vector2 GameStateManager::getRefereeDesignatedPosition() {
Expand All @@ -184,40 +111,31 @@ Vector2 GameStateManager::getRefereeDesignatedPosition() {
}

void GameStateManager::updateInterfaceGameState(const char* name) {
if (strcmp(name, "Ball Placement Us") == 0) {
interface::Output::setInterfaceGameState(GameState("ball_placement_us", Constants::RULESET_BALLPLACEMENT_US()));
} else if (strcmp(name, "Halt") == 0) {
interface::Output::setInterfaceGameState(GameState("halt", Constants::RULESET_HALT()));
} else if (strcmp(name, "Free Kick Them") == 0) {
interface::Output::setInterfaceGameState(GameState("free_kick_them", Constants::RULESET_STOP()));
} else if (strcmp(name, "Free Kick Us At Goal") == 0) {
interface::Output::setInterfaceGameState(GameState("free_kick_us", Constants::RULESET_DEFAULT()));
} else if (strcmp(name, "Free Kick Us Pass") == 0) {
interface::Output::setInterfaceGameState(GameState("free_kick_us", Constants::RULESET_DEFAULT()));
} else if (strcmp(name, "Ball Placement Them") == 0) {
interface::Output::setInterfaceGameState(GameState("ball_placement_them", Constants::RULESET_BALLPLACEMENT_THEM()));
} else if (strcmp(name, "Kick Off Them Prepare") == 0) {
interface::Output::setInterfaceGameState(GameState("kickoff_them_prepare", Constants::RULESET_KICKOFF()));
} else if (strcmp(name, "Kick Off Us Prepare") == 0) {
interface::Output::setInterfaceGameState(GameState("kickoff_us_prepare", Constants::RULESET_KICKOFF()));
} else if (strcmp(name, "Kick Off Them") == 0) {
interface::Output::setInterfaceGameState(GameState("kickoff_them", Constants::RULESET_DEFAULT()));
} else if (strcmp(name, "Kick Off Us") == 0) {
interface::Output::setInterfaceGameState(GameState("kickoff_us", Constants::RULESET_DEFAULT()));
} else if (strcmp(name, "Penalty Them Prepare") == 0) {
interface::Output::setInterfaceGameState(GameState("penalty_them_prepare", Constants::RULESET_DEFAULT()));
} else if (strcmp(name, "Penalty Us Prepare") == 0) {
interface::Output::setInterfaceGameState(GameState("penalty_us_prepare", Constants::RULESET_DEFAULT()));
} else if (strcmp(name, "Penalty Them") == 0) {
interface::Output::setInterfaceGameState(GameState("penalty_them", Constants::RULESET_DEFAULT()));
} else if (strcmp(name, "Penalty Us") == 0) {
interface::Output::setInterfaceGameState(GameState("penalty_us", Constants::RULESET_DEFAULT()));
} else if (strcmp(name, "Time Out") == 0) {
interface::Output::setInterfaceGameState(GameState("time_out", Constants::RULESET_DEFAULT()));
} else if (strcmp(name, "Defensive Stop Formation") == 0) {
interface::Output::setInterfaceGameState(GameState("stop", Constants::RULESET_STOP()));
} else if (strcmp(name, "Aggressive Stop Formation") == 0) {
interface::Output::setInterfaceGameState(GameState("stop", Constants::RULESET_STOP()));
static const std::map<std::string, std::pair<std::string, rtt::ai::RuleSet>> nameToGameState = {
{"Aggressive Stop Formation", {"stop", Constants::RULESET_STOP()}},
{"Defensive Stop Formation", {"stop", Constants::RULESET_STOP()}},
{"Ball Placement Us", {"ball_placement_us", Constants::RULESET_BALLPLACEMENT_US()}},
{"Ball Placement Them", {"ball_placement_them", Constants::RULESET_BALLPLACEMENT_THEM()}},
{"Halt", {"halt", Constants::RULESET_HALT()}},
{"Free Kick Them", {"free_kick_them", Constants::RULESET_STOP()}},
{"Free Kick Us At Goal", {"free_kick_us", Constants::RULESET_DEFAULT()}},
{"Free Kick Us Pass", {"free_kick_us", Constants::RULESET_DEFAULT()}},
{"Kick Off Us Prepare", {"kickoff_us_prepare", Constants::RULESET_KICKOFF()}},
{"Kick Off Them Prepare", {"kickoff_them_prepare", Constants::RULESET_KICKOFF()}},
{"Kick Off Us", {"kickoff_us", Constants::RULESET_DEFAULT()}},
{"Kick Off Them", {"kickoff_them", Constants::RULESET_DEFAULT()}},
{"Penalty Us Prepare", {"penalty_us_prepare", Constants::RULESET_DEFAULT()}},
{"Penalty Them Prepare", {"penalty_them_prepare", Constants::RULESET_DEFAULT()}},
{"Penalty Us", {"penalty_us", Constants::RULESET_DEFAULT()}},
{"Penalty Them", {"penalty_them", Constants::RULESET_DEFAULT()}},
{"Time Out", {"time_out", Constants::RULESET_DEFAULT()}},
{"Defensive Stop Formation", {"stop", Constants::RULESET_STOP()}},
{"Aggressive Stop Formation", {"stop", Constants::RULESET_STOP()}},
};

auto it = nameToGameState.find(name);
if (it != nameToGameState.end()) {
interface::Output::setInterfaceGameState(GameState(it->second.first, it->second.second));
} else {
RTT_WARNING("Play has been selected for which no ruleset is found!");
interface::Output::setInterfaceGameState(GameState("normal_play", Constants::RULESET_DEFAULT()));
Expand Down
12 changes: 7 additions & 5 deletions roboteam_ai/src/utilities/StrategyManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,16 +65,18 @@ void StrategyManager::setCurrentRefGameState(RefCommand command, proto::SSL_Refe
RefGameState StrategyManager::getCurrentRefGameState() { return currentRefGameState; }

const RefGameState StrategyManager::getRefGameStateForRefCommand(RefCommand command) {
for (auto gameState : this->gameStates) {
if (gameState.commandId == command) {
return gameState;
}
auto it = std::find_if(gameStates.begin(), gameStates.end(), [&command](const RefGameState &gameState) {
return gameState.commandId == command;
});

if (it != gameStates.end()) {
return *it;
}
std::cerr << "Returning an undefined refstate! This should never happen!" << std::endl;
return gameStates[0];
}

void StrategyManager::forceCurrentRefGameState(RefCommand command, std::optional<world::view::BallView> ballOpt) {
void StrategyManager::forceCurrentRefGameState(RefCommand command) {
// we need to change refgamestate here
RefGameState newState = getRefGameStateForRefCommand(command);

Expand Down
2 changes: 1 addition & 1 deletion roboteam_ai/test/TestFixtures/TestFixture.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ class RTT_AI_Tests : public ::testing::Test {

// Set other variables to their default values
rtt::ai::interface::Output::setKeeperId(-1);
rtt::ai::GameStateManager::forceNewGameState(rtt::RefCommand::NORMAL_START, std::nullopt);
rtt::ai::GameStateManager::forceNewGameState(rtt::RefCommand::NORMAL_START);
rtt::ai::interface::Output::setUseRefereeCommands(false);

// Make sure all plays exist as new
Expand Down

0 comments on commit 07c4148

Please sign in to comment.