From e4f75da1c7113633ac74d8ba19d3ef4979aad2b6 Mon Sep 17 00:00:00 2001 From: Jorn Date: Mon, 29 Jan 2024 11:01:52 +0100 Subject: [PATCH] Update protobuf and remove deprecated values --- .../utilities/GameStateManager.hpp | 8 +- .../roboteam_ai/utilities/RefCommand.h | 70 ++- .../roboteam_ai/utilities/StrategyManager.h | 4 +- .../include/roboteam_ai/utilities/normalize.h | 2 +- .../src/utilities/GameStateManager.cpp | 40 +- roboteam_ai/src/utilities/RefCommand.cpp | 72 ++- roboteam_ai/src/utilities/StrategyManager.cpp | 11 +- roboteam_ai/src/utilities/normalize.cpp | 2 +- roboteam_ai/test/UtilTests/RefereeTest.cpp | 18 +- roboteam_interface/src/generated/proto.d.ts | 2 - roboteam_networking/proto/State.proto | 4 +- .../messages_robocup_ssl_detection.proto | 2 +- ...s_robocup_ssl_game_controller_common.proto | 1 + ...robocup_ssl_game_controller_geometry.proto | 1 + .../messages_robocup_ssl_game_event.proto | 150 ++++--- .../proto/messages_robocup_ssl_geometry.proto | 170 +++++--- .../proto/messages_robocup_ssl_referee.proto | 409 +++++++++--------- roboteam_networking/proto/ssl_gc_common.proto | 2 +- .../proto/ssl_vision_detection.proto | 2 +- .../proto/ssl_vision_geometry.proto | 8 +- .../include/roboteam_observer/Handler.h | 4 +- .../observer/include/observer/Observer.h | 6 +- .../observer/filters/referee/RefereeFilter.h | 6 +- .../parameters/RobotParameterDatabase.h | 2 +- roboteam_world/observer/src/Observer.cpp | 12 +- .../src/filters/referee/RefereeFilter.cpp | 6 +- .../src/parameters/RobotParameterDatabase.cpp | 2 +- roboteam_world/src/Handler.cpp | 8 +- 28 files changed, 547 insertions(+), 477 deletions(-) diff --git a/roboteam_ai/include/roboteam_ai/utilities/GameStateManager.hpp b/roboteam_ai/include/roboteam_ai/utilities/GameStateManager.hpp index cb9bedadf..f086cbf03 100644 --- a/roboteam_ai/include/roboteam_ai/utilities/GameStateManager.hpp +++ b/roboteam_ai/include/roboteam_ai/utilities/GameStateManager.hpp @@ -17,19 +17,19 @@ class GameStateManager { * @param refMsg The data we get from the referee * @param data The current world */ - static void setRefereeData(proto::SSL_Referee refMsg, const rtt::world::World* data); + static void setRefereeData(proto::Referee refMsg, const rtt::world::World* data); /** * @brief Getter for the referee data * @return The referee data */ - static proto::SSL_Referee getRefereeData(); + static proto::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); + static RefCommand getCommandFromRefMsg(proto::Referee_Command command, bool isYellow); /** * @brief Getter for the current game state * @return The current game state @@ -52,7 +52,7 @@ class GameStateManager { static void updateInterfaceGameState(const char* name); private: - static proto::SSL_Referee refMsg; /**< Data from the referee */ + static proto::Referee refMsg; /**< Data from the referee */ static StrategyManager strategymanager; /**< Manager that updates the play according to the game state */ static std::mutex refMsgLock; /**< Synchronizer for referee data */ }; diff --git a/roboteam_ai/include/roboteam_ai/utilities/RefCommand.h b/roboteam_ai/include/roboteam_ai/utilities/RefCommand.h index 69ad692fd..f80d1b242 100644 --- a/roboteam_ai/include/roboteam_ai/utilities/RefCommand.h +++ b/roboteam_ai/include/roboteam_ai/utilities/RefCommand.h @@ -26,8 +26,6 @@ enum class RefCommand { PREPARE_PENALTY_THEM = 7, DIRECT_FREE_US = 8, DIRECT_FREE_THEM = 9, - INDIRECT_FREE_US = 10, - INDIRECT_FREE_THEM = 11, TIMEOUT_US = 12, TIMEOUT_THEM = 13, GOAL_US = 14, @@ -49,44 +47,40 @@ enum class RefCommand { UNDEFINED = -1 }; -inline RefCommand sslRefCmdToRefCmd(proto::SSL_Referee_Command sslRefCmd, bool isYellow) { - using RefCommandMap = std::unordered_map; +inline RefCommand sslRefCmdToRefCmd(proto::Referee_Command sslRefCmd, bool isYellow) { + using RefCommandMap = std::unordered_map; // static const == they are initialized only once, se we don't allocate on heap every time - static const RefCommandMap yellowMap = {{proto::SSL_Referee_Command_HALT, RefCommand::HALT}, - {proto::SSL_Referee_Command_STOP, RefCommand::STOP}, - {proto::SSL_Referee_Command_NORMAL_START, RefCommand::NORMAL_START}, - {proto::SSL_Referee_Command_FORCE_START, RefCommand::FORCED_START}, - {proto::SSL_Referee_Command_PREPARE_KICKOFF_YELLOW, RefCommand::PREPARE_KICKOFF_US}, - {proto::SSL_Referee_Command_PREPARE_KICKOFF_BLUE, RefCommand::PREPARE_KICKOFF_THEM}, - {proto::SSL_Referee_Command_PREPARE_PENALTY_YELLOW, RefCommand::PREPARE_PENALTY_US}, - {proto::SSL_Referee_Command_PREPARE_PENALTY_BLUE, RefCommand::PREPARE_PENALTY_THEM}, - {proto::SSL_Referee_Command_DIRECT_FREE_YELLOW, RefCommand::DIRECT_FREE_US}, - {proto::SSL_Referee_Command_DIRECT_FREE_BLUE, RefCommand::DIRECT_FREE_THEM}, - {proto::SSL_Referee_Command_INDIRECT_FREE_YELLOW, RefCommand::INDIRECT_FREE_US}, - {proto::SSL_Referee_Command_INDIRECT_FREE_BLUE, RefCommand::INDIRECT_FREE_THEM}, - {proto::SSL_Referee_Command_TIMEOUT_YELLOW, RefCommand::TIMEOUT_US}, - {proto::SSL_Referee_Command_TIMEOUT_BLUE, RefCommand::TIMEOUT_THEM}, - {proto::SSL_Referee_Command_BALL_PLACEMENT_YELLOW, RefCommand::BALL_PLACEMENT_US}, - {proto::SSL_Referee_Command_BALL_PLACEMENT_BLUE, RefCommand::BALL_PLACEMENT_THEM}}; + static const RefCommandMap yellowMap = {{proto::Referee_Command_HALT, RefCommand::HALT}, + {proto::Referee_Command_STOP, RefCommand::STOP}, + {proto::Referee_Command_NORMAL_START, RefCommand::NORMAL_START}, + {proto::Referee_Command_FORCE_START, RefCommand::FORCED_START}, + {proto::Referee_Command_PREPARE_KICKOFF_YELLOW, RefCommand::PREPARE_KICKOFF_US}, + {proto::Referee_Command_PREPARE_KICKOFF_BLUE, RefCommand::PREPARE_KICKOFF_THEM}, + {proto::Referee_Command_PREPARE_PENALTY_YELLOW, RefCommand::PREPARE_PENALTY_US}, + {proto::Referee_Command_PREPARE_PENALTY_BLUE, RefCommand::PREPARE_PENALTY_THEM}, + {proto::Referee_Command_DIRECT_FREE_YELLOW, RefCommand::DIRECT_FREE_US}, + {proto::Referee_Command_DIRECT_FREE_BLUE, RefCommand::DIRECT_FREE_THEM}, + {proto::Referee_Command_TIMEOUT_YELLOW, RefCommand::TIMEOUT_US}, + {proto::Referee_Command_TIMEOUT_BLUE, RefCommand::TIMEOUT_THEM}, + {proto::Referee_Command_BALL_PLACEMENT_YELLOW, RefCommand::BALL_PLACEMENT_US}, + {proto::Referee_Command_BALL_PLACEMENT_BLUE, RefCommand::BALL_PLACEMENT_THEM}}; // static const == they are initialized only once, se we don't allocate on heap every time - static const RefCommandMap blueMap = {{proto::SSL_Referee_Command_HALT, RefCommand::HALT}, - {proto::SSL_Referee_Command_STOP, RefCommand::STOP}, - {proto::SSL_Referee_Command_NORMAL_START, RefCommand::NORMAL_START}, - {proto::SSL_Referee_Command_FORCE_START, RefCommand::FORCED_START}, - {proto::SSL_Referee_Command_PREPARE_KICKOFF_YELLOW, RefCommand::PREPARE_KICKOFF_THEM}, - {proto::SSL_Referee_Command_PREPARE_KICKOFF_BLUE, RefCommand::PREPARE_KICKOFF_US}, - {proto::SSL_Referee_Command_PREPARE_PENALTY_YELLOW, RefCommand::PREPARE_PENALTY_THEM}, - {proto::SSL_Referee_Command_PREPARE_PENALTY_BLUE, RefCommand::PREPARE_PENALTY_US}, - {proto::SSL_Referee_Command_DIRECT_FREE_YELLOW, RefCommand::DIRECT_FREE_THEM}, - {proto::SSL_Referee_Command_DIRECT_FREE_BLUE, RefCommand::DIRECT_FREE_US}, - {proto::SSL_Referee_Command_INDIRECT_FREE_YELLOW, RefCommand::INDIRECT_FREE_THEM}, - {proto::SSL_Referee_Command_INDIRECT_FREE_BLUE, RefCommand::INDIRECT_FREE_US}, - {proto::SSL_Referee_Command_TIMEOUT_YELLOW, RefCommand::TIMEOUT_THEM}, - {proto::SSL_Referee_Command_TIMEOUT_BLUE, RefCommand::TIMEOUT_US}, - {proto::SSL_Referee_Command_BALL_PLACEMENT_YELLOW, RefCommand::BALL_PLACEMENT_THEM}, - {proto::SSL_Referee_Command_BALL_PLACEMENT_BLUE, RefCommand::BALL_PLACEMENT_US}}; + static const RefCommandMap blueMap = {{proto::Referee_Command_HALT, RefCommand::HALT}, + {proto::Referee_Command_STOP, RefCommand::STOP}, + {proto::Referee_Command_NORMAL_START, RefCommand::NORMAL_START}, + {proto::Referee_Command_FORCE_START, RefCommand::FORCED_START}, + {proto::Referee_Command_PREPARE_KICKOFF_YELLOW, RefCommand::PREPARE_KICKOFF_THEM}, + {proto::Referee_Command_PREPARE_KICKOFF_BLUE, RefCommand::PREPARE_KICKOFF_US}, + {proto::Referee_Command_PREPARE_PENALTY_YELLOW, RefCommand::PREPARE_PENALTY_THEM}, + {proto::Referee_Command_PREPARE_PENALTY_BLUE, RefCommand::PREPARE_PENALTY_US}, + {proto::Referee_Command_DIRECT_FREE_YELLOW, RefCommand::DIRECT_FREE_THEM}, + {proto::Referee_Command_DIRECT_FREE_BLUE, RefCommand::DIRECT_FREE_US}, + {proto::Referee_Command_TIMEOUT_YELLOW, RefCommand::TIMEOUT_THEM}, + {proto::Referee_Command_TIMEOUT_BLUE, RefCommand::TIMEOUT_US}, + {proto::Referee_Command_BALL_PLACEMENT_YELLOW, RefCommand::BALL_PLACEMENT_THEM}, + {proto::Referee_Command_BALL_PLACEMENT_BLUE, RefCommand::BALL_PLACEMENT_US}}; // .find() != .end() could be replaced by contains in C++20 if (isYellow && yellowMap.find(sslRefCmd) != yellowMap.end()) { @@ -100,8 +94,8 @@ inline RefCommand sslRefCmdToRefCmd(proto::SSL_Referee_Command sslRefCmd, bool i } std::string refCommandToString(RefCommand command); -std::string protoRefCommandToString(proto::SSL_Referee_Command command); -std::string protoRefStageToString(proto::SSL_Referee_Stage stage); +std::string protoRefCommandToString(proto::Referee_Command command); +std::string protoRefStageToString(proto::Referee_Stage stage); } // namespace rtt diff --git a/roboteam_ai/include/roboteam_ai/utilities/StrategyManager.h b/roboteam_ai/include/roboteam_ai/utilities/StrategyManager.h index 7f8b837ea..c291b74a8 100644 --- a/roboteam_ai/include/roboteam_ai/utilities/StrategyManager.h +++ b/roboteam_ai/include/roboteam_ai/utilities/StrategyManager.h @@ -38,7 +38,7 @@ class StrategyManager { * @param stage Stage of the game * @param ballOpt Data about the ball */ - void setCurrentRefGameState(RefCommand command, proto::SSL_Referee_Stage stage, std::optional ballOpt); + void setCurrentRefGameState(RefCommand command, proto::Referee_Stage stage, std::optional ballOpt); /** * @brief Forces the AI into a given game state @@ -77,11 +77,9 @@ class StrategyManager { RefGameState(RefCommand::PREPARE_SHOOTOUT_THEM, "penalty_them_prepare", Constants::RULESET_STOP(), false, RefCommand::DEFEND_SHOOTOUT), RefGameState(RefCommand::DIRECT_FREE_THEM, "free_kick_them", Constants::RULESET_DEFAULT()), - RefGameState(RefCommand::INDIRECT_FREE_THEM, "free_kick_them", Constants::RULESET_DEFAULT()), RefGameState(RefCommand::NORMAL_START, "normal_play", Constants::RULESET_DEFAULT()), RefGameState(RefCommand::FORCED_START, "normal_play", Constants::RULESET_DEFAULT()), RefGameState(RefCommand::DIRECT_FREE_US, "free_kick_us", Constants::RULESET_DEFAULT()), - RefGameState(RefCommand::INDIRECT_FREE_US, "free_kick_us", Constants::RULESET_DEFAULT()), RefGameState(RefCommand::DO_KICKOFF, "kickoff_us", Constants::RULESET_DEFAULT(), true), RefGameState(RefCommand::DEFEND_KICKOFF, "kickoff_them", Constants::RULESET_DEFAULT(), true), RefGameState(RefCommand::DO_PENALTY, "penalty_us", Constants::RULESET_DEFAULT(), true), diff --git a/roboteam_ai/include/roboteam_ai/utilities/normalize.h b/roboteam_ai/include/roboteam_ai/utilities/normalize.h index c249035af..fd0489d97 100644 --- a/roboteam_ai/include/roboteam_ai/utilities/normalize.h +++ b/roboteam_ai/include/roboteam_ai/utilities/normalize.h @@ -38,7 +38,7 @@ void rotate(proto::World *world); * Pointer is asserted in debug mode * @param refereeData Referee to rotate */ -void rotate(proto::SSL_Referee *refereeData); +void rotate(proto::Referee *refereeData); /** * @brief Rotates all members of a Circular arc diff --git a/roboteam_ai/src/utilities/GameStateManager.cpp b/roboteam_ai/src/utilities/GameStateManager.cpp index ffe110c8d..e4a578a3f 100644 --- a/roboteam_ai/src/utilities/GameStateManager.cpp +++ b/roboteam_ai/src/utilities/GameStateManager.cpp @@ -11,48 +11,44 @@ namespace rtt::ai { int GameState::cardId = -1; -proto::SSL_Referee GameStateManager::refMsg; +proto::Referee GameStateManager::refMsg; StrategyManager GameStateManager::strategymanager; std::mutex GameStateManager::refMsgLock; -proto::SSL_Referee GameStateManager::getRefereeData() { +proto::Referee GameStateManager::getRefereeData() { std::lock_guard lock(refMsgLock); return GameStateManager::refMsg; } -RefCommand GameStateManager::getCommandFromRefMsg(proto::SSL_Referee_Command command, bool isYellow) { +RefCommand GameStateManager::getCommandFromRefMsg(proto::Referee_Command command, bool isYellow) { switch (command) { - case proto::SSL_Referee_Command_HALT: + case proto::Referee_Command_HALT: return RefCommand::HALT; - case proto::SSL_Referee_Command_STOP: + case proto::Referee_Command_STOP: return RefCommand::STOP; - case proto::SSL_Referee_Command_NORMAL_START: + case proto::Referee_Command_NORMAL_START: return RefCommand::NORMAL_START; - case proto::SSL_Referee_Command_FORCE_START: + case proto::Referee_Command_FORCE_START: return RefCommand::FORCED_START; - case proto::SSL_Referee_Command_PREPARE_KICKOFF_YELLOW: + case proto::Referee_Command_PREPARE_KICKOFF_YELLOW: return isYellow ? RefCommand::PREPARE_KICKOFF_US : RefCommand::PREPARE_KICKOFF_THEM; - case proto::SSL_Referee_Command_PREPARE_KICKOFF_BLUE: + case proto::Referee_Command_PREPARE_KICKOFF_BLUE: return isYellow ? RefCommand::PREPARE_KICKOFF_THEM : RefCommand::PREPARE_KICKOFF_US; - case proto::SSL_Referee_Command_PREPARE_PENALTY_YELLOW: + case proto::Referee_Command_PREPARE_PENALTY_YELLOW: return isYellow ? RefCommand::PREPARE_PENALTY_US : RefCommand::PREPARE_PENALTY_THEM; - case proto::SSL_Referee_Command_PREPARE_PENALTY_BLUE: + case proto::Referee_Command_PREPARE_PENALTY_BLUE: return isYellow ? RefCommand::PREPARE_PENALTY_THEM : RefCommand::PREPARE_PENALTY_US; - case proto::SSL_Referee_Command_DIRECT_FREE_YELLOW: + case proto::Referee_Command_DIRECT_FREE_YELLOW: return isYellow ? RefCommand::DIRECT_FREE_US : RefCommand::DIRECT_FREE_THEM; - case proto::SSL_Referee_Command_DIRECT_FREE_BLUE: + case proto::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: + case proto::Referee_Command_TIMEOUT_YELLOW: return isYellow ? RefCommand::TIMEOUT_US : RefCommand::TIMEOUT_THEM; - case proto::SSL_Referee_Command_TIMEOUT_BLUE: + case proto::Referee_Command_TIMEOUT_BLUE: return isYellow ? RefCommand::TIMEOUT_THEM : RefCommand::TIMEOUT_US; - case proto::SSL_Referee_Command_BALL_PLACEMENT_YELLOW: + case proto::Referee_Command_BALL_PLACEMENT_YELLOW: return isYellow ? RefCommand::BALL_PLACEMENT_US : RefCommand::BALL_PLACEMENT_THEM; - case proto::SSL_Referee_Command_BALL_PLACEMENT_BLUE: + case proto::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!") @@ -60,7 +56,7 @@ RefCommand GameStateManager::getCommandFromRefMsg(proto::SSL_Referee_Command com } } -void GameStateManager::setRefereeData(proto::SSL_Referee refMsg, const rtt::world::World* data) { +void GameStateManager::setRefereeData(proto::Referee refMsg, const rtt::world::World* data) { std::lock_guard lock(refMsgLock); GameStateManager::refMsg = refMsg; bool isYellow = GameSettings::isYellow(); diff --git a/roboteam_ai/src/utilities/RefCommand.cpp b/roboteam_ai/src/utilities/RefCommand.cpp index 51d993db4..6c33f65be 100644 --- a/roboteam_ai/src/utilities/RefCommand.cpp +++ b/roboteam_ai/src/utilities/RefCommand.cpp @@ -28,10 +28,6 @@ std::string refCommandToString(RefCommand command) { return "DIRECT_FREE_US"; case RefCommand::DIRECT_FREE_THEM: return "DIRECT_FREE_THEM"; - case RefCommand::INDIRECT_FREE_US: - return "INDIRECT_FREE_US"; - case RefCommand::INDIRECT_FREE_THEM: - return "INDIRECT_FREE_THEM"; case RefCommand::TIMEOUT_US: return "TIMEOUT_US"; case RefCommand::TIMEOUT_THEM: @@ -69,77 +65,73 @@ std::string refCommandToString(RefCommand command) { } } -std::string protoRefCommandToString(proto::SSL_Referee_Command command) { +std::string protoRefCommandToString(proto::Referee_Command command) { switch (command) { - case proto::SSL_Referee_Command_HALT: + case proto::Referee_Command_HALT: return "HALT"; - case proto::SSL_Referee_Command_STOP: + case proto::Referee_Command_STOP: return "STOP"; - case proto::SSL_Referee_Command_NORMAL_START: + case proto::Referee_Command_NORMAL_START: return "NORMAL_START"; - case proto::SSL_Referee_Command_FORCE_START: + case proto::Referee_Command_FORCE_START: return "FORCE_START"; - case proto::SSL_Referee_Command_PREPARE_KICKOFF_YELLOW: + case proto::Referee_Command_PREPARE_KICKOFF_YELLOW: return "PREPARE_KICKOFF_YELLOW"; - case proto::SSL_Referee_Command_PREPARE_KICKOFF_BLUE: + case proto::Referee_Command_PREPARE_KICKOFF_BLUE: return "PREPARE_KICKOFF_BLUE"; - case proto::SSL_Referee_Command_PREPARE_PENALTY_YELLOW: + case proto::Referee_Command_PREPARE_PENALTY_YELLOW: return "PREPARE_PENALTY_YELLOW"; - case proto::SSL_Referee_Command_PREPARE_PENALTY_BLUE: + case proto::Referee_Command_PREPARE_PENALTY_BLUE: return "PREPARE_PENALTY_BLUE"; - case proto::SSL_Referee_Command_DIRECT_FREE_YELLOW: + case proto::Referee_Command_DIRECT_FREE_YELLOW: return "DIRECT_FREE_YELLOW"; - case proto::SSL_Referee_Command_DIRECT_FREE_BLUE: + case proto::Referee_Command_DIRECT_FREE_BLUE: return "DIRECT_FREE_BLUE"; - case proto::SSL_Referee_Command_INDIRECT_FREE_YELLOW: - return "INDIRECT_FREE_YELLOW"; - case proto::SSL_Referee_Command_INDIRECT_FREE_BLUE: - return "INDIRECT_FREE_BLUE"; - case proto::SSL_Referee_Command_TIMEOUT_YELLOW: + case proto::Referee_Command_TIMEOUT_YELLOW: return "TIMEOUT_YELLOW"; - case proto::SSL_Referee_Command_TIMEOUT_BLUE: + case proto::Referee_Command_TIMEOUT_BLUE: return "TIMEOUT_BLUE"; - case proto::SSL_Referee_Command_BALL_PLACEMENT_YELLOW: + case proto::Referee_Command_BALL_PLACEMENT_YELLOW: return "BALL_PLACEMENT_YELLOW"; - case proto::SSL_Referee_Command_BALL_PLACEMENT_BLUE: + case proto::Referee_Command_BALL_PLACEMENT_BLUE: return "BALL_PLACEMENT_BLUE"; default: - return "Warning: unknown SSL_Referee_Command"; + return "Warning: unknown Referee_Command"; } } -std::string protoRefStageToString(proto::SSL_Referee_Stage stage) { +std::string protoRefStageToString(proto::Referee_Stage stage) { switch (stage) { - case proto::SSL_Referee_Stage_NORMAL_FIRST_HALF_PRE: + case proto::Referee_Stage_NORMAL_FIRST_HALF_PRE: return "NORMAL_FIRST_HALF_PRE"; - case proto::SSL_Referee_Stage_NORMAL_FIRST_HALF: + case proto::Referee_Stage_NORMAL_FIRST_HALF: return "NORMAL_FIRST_HALF"; - case proto::SSL_Referee_Stage_NORMAL_HALF_TIME: + case proto::Referee_Stage_NORMAL_HALF_TIME: return "NORMAL_HALF_TIME"; - case proto::SSL_Referee_Stage_NORMAL_SECOND_HALF_PRE: + case proto::Referee_Stage_NORMAL_SECOND_HALF_PRE: return "NORMAL_SECOND_HALF_PRE"; - case proto::SSL_Referee_Stage_NORMAL_SECOND_HALF: + case proto::Referee_Stage_NORMAL_SECOND_HALF: return "NORMAL_SECOND_HALF"; - case proto::SSL_Referee_Stage_EXTRA_TIME_BREAK: + case proto::Referee_Stage_EXTRA_TIME_BREAK: return "EXTRA_TIME_BREAK"; - case proto::SSL_Referee_Stage_EXTRA_FIRST_HALF_PRE: + case proto::Referee_Stage_EXTRA_FIRST_HALF_PRE: return "EXTRA_FIRST_HALF_PRE"; - case proto::SSL_Referee_Stage_EXTRA_FIRST_HALF: + case proto::Referee_Stage_EXTRA_FIRST_HALF: return "EXTRA_FIRST_HALF"; - case proto::SSL_Referee_Stage_EXTRA_HALF_TIME: + case proto::Referee_Stage_EXTRA_HALF_TIME: return "EXTRA_HALF_TIME"; - case proto::SSL_Referee_Stage_EXTRA_SECOND_HALF_PRE: + case proto::Referee_Stage_EXTRA_SECOND_HALF_PRE: return "EXTRA_SECOND_HALF_PRE"; - case proto::SSL_Referee_Stage_EXTRA_SECOND_HALF: + case proto::Referee_Stage_EXTRA_SECOND_HALF: return "EXTRA_SECOND_HALF"; - case proto::SSL_Referee_Stage_PENALTY_SHOOTOUT_BREAK: + case proto::Referee_Stage_PENALTY_SHOOTOUT_BREAK: return "PENALTY_SHOOTOUT_BREAK"; - case proto::SSL_Referee_Stage_PENALTY_SHOOTOUT: + case proto::Referee_Stage_PENALTY_SHOOTOUT: return "PENALTY_SHOOTOUT"; - case proto::SSL_Referee_Stage_POST_GAME: + case proto::Referee_Stage_POST_GAME: return "POST_GAME"; default: - return "Warning: unknown SSL_Referee_Stage"; + return "Warning: unknown Referee_Stage"; } } diff --git a/roboteam_ai/src/utilities/StrategyManager.cpp b/roboteam_ai/src/utilities/StrategyManager.cpp index 6e953bccd..a37ab19a9 100644 --- a/roboteam_ai/src/utilities/StrategyManager.cpp +++ b/roboteam_ai/src/utilities/StrategyManager.cpp @@ -8,9 +8,9 @@ namespace rtt::ai { // process ref commands -void StrategyManager::setCurrentRefGameState(RefCommand command, proto::SSL_Referee_Stage stage, std::optional ballOpt) { +void StrategyManager::setCurrentRefGameState(RefCommand command, proto::Referee_Stage stage, std::optional ballOpt) { // if the stage is shootout, we interpret penalty commands as shootOut penalty commands - if (stage == proto::SSL_Referee_Stage_PENALTY_SHOOTOUT) { + if (stage == proto::Referee_Stage_PENALTY_SHOOTOUT) { if (command == RefCommand::PREPARE_PENALTY_US) { command = RefCommand::PREPARE_SHOOTOUT_US; } else if (command == RefCommand::PREPARE_PENALTY_THEM) { @@ -19,15 +19,14 @@ void StrategyManager::setCurrentRefGameState(RefCommand command, proto::SSL_Refe } // If game is in pre start stage and the game is in stop state - if (command == RefCommand::STOP && (stage == proto::SSL_Referee_Stage_NORMAL_FIRST_HALF_PRE || stage == proto::SSL_Referee_Stage_NORMAL_SECOND_HALF_PRE || - stage == proto::SSL_Referee_Stage_EXTRA_FIRST_HALF_PRE || stage == proto::SSL_Referee_Stage_EXTRA_SECOND_HALF_PRE)) { + if (command == RefCommand::STOP && (stage == proto::Referee_Stage_NORMAL_FIRST_HALF_PRE || stage == proto::Referee_Stage_NORMAL_SECOND_HALF_PRE || + stage == proto::Referee_Stage_EXTRA_FIRST_HALF_PRE || stage == proto::Referee_Stage_EXTRA_SECOND_HALF_PRE)) { command = RefCommand::PRE_HALF; } // If the ball has been kicked during kickoff or a free kick, continue with NORMAL_START if ((currentRefGameState.commandId == RefCommand::DIRECT_FREE_THEM || currentRefGameState.commandId == RefCommand::DIRECT_FREE_US || - currentRefGameState.commandId == RefCommand::DO_KICKOFF || currentRefGameState.commandId == RefCommand::DEFEND_KICKOFF || - currentRefGameState.commandId == RefCommand::INDIRECT_FREE_US || currentRefGameState.commandId == RefCommand::INDIRECT_FREE_THEM) && + currentRefGameState.commandId == RefCommand::DO_KICKOFF || currentRefGameState.commandId == RefCommand::DEFEND_KICKOFF) && ballOpt.has_value() && (ballOpt.value()->velocity.length() > stp::control_constants::BALL_IS_MOVING_SLOW_LIMIT)) { RefGameState newState = getRefGameStateForRefCommand(RefCommand::NORMAL_START); currentRefGameState = newState; diff --git a/roboteam_ai/src/utilities/normalize.cpp b/roboteam_ai/src/utilities/normalize.cpp index 6723b18a8..28759de9d 100644 --- a/roboteam_ai/src/utilities/normalize.cpp +++ b/roboteam_ai/src/utilities/normalize.cpp @@ -39,7 +39,7 @@ void rotate(proto::World *world) { // rotate the designated position given by the referee // this position is used for example for ball placement. -void rotate(proto::SSL_Referee *refereeData) { +void rotate(proto::Referee *refereeData) { assert(refereeData && "Invalid pointer for referee"); refereeData->mutable_designated_position()->set_x(refereeData->designated_position().x() * -1); refereeData->mutable_designated_position()->set_y(refereeData->designated_position().y() * -1); diff --git a/roboteam_ai/test/UtilTests/RefereeTest.cpp b/roboteam_ai/test/UtilTests/RefereeTest.cpp index bada2b47e..b2bd2bf41 100644 --- a/roboteam_ai/test/UtilTests/RefereeTest.cpp +++ b/roboteam_ai/test/UtilTests/RefereeTest.cpp @@ -23,28 +23,28 @@ TEST(RefereeTest, it_gets_and_sets_the_ref) { auto const& [_, worldPtr] = rtt::world::World::instance(); worldPtr->updateWorld(world); - proto::SSL_Referee refereeData; - refereeData.set_command(proto::SSL_Referee_Command_PREPARE_KICKOFF_BLUE); + proto::Referee refereeData; + refereeData.set_command(proto::Referee_Command_PREPARE_KICKOFF_BLUE); rtt::ai::GameStateManager::setRefereeData(refereeData, worldPtr); - EXPECT_EQ(rtt::ai::GameStateManager::getRefereeData().command(), proto::SSL_Referee_Command_PREPARE_KICKOFF_BLUE); + EXPECT_EQ(rtt::ai::GameStateManager::getRefereeData().command(), proto::Referee_Command_PREPARE_KICKOFF_BLUE); - refereeData.set_command(proto::SSL_Referee_Command_PREPARE_KICKOFF_YELLOW); + refereeData.set_command(proto::Referee_Command_PREPARE_KICKOFF_YELLOW); rtt::ai::GameStateManager::setRefereeData(refereeData, worldPtr); - EXPECT_EQ(rtt::ai::GameStateManager::getRefereeData().command(), proto::SSL_Referee_Command_PREPARE_KICKOFF_YELLOW); + EXPECT_EQ(rtt::ai::GameStateManager::getRefereeData().command(), proto::Referee_Command_PREPARE_KICKOFF_YELLOW); // this is necessary for this following test to work properly since it listens to the interface rtt::ai::interface::Output::setUseRefereeCommands(true); - refereeData.set_stage(proto::SSL_Referee_Stage_PENALTY_SHOOTOUT); - refereeData.set_command(proto::SSL_Referee_Command_PREPARE_PENALTY_YELLOW); + refereeData.set_stage(proto::Referee_Stage_PENALTY_SHOOTOUT); + refereeData.set_command(proto::Referee_Command_PREPARE_PENALTY_YELLOW); rtt::ai::GameStateManager::setRefereeData(refereeData, worldPtr); EXPECT_EQ(rtt::ai::GameStateManager::getCurrentGameState().getStrategyName(), "penalty_us_prepare"); - refereeData.set_stage(proto::SSL_Referee_Stage_PENALTY_SHOOTOUT); - refereeData.set_command(proto::SSL_Referee_Command_PREPARE_PENALTY_BLUE); + refereeData.set_stage(proto::Referee_Stage_PENALTY_SHOOTOUT); + refereeData.set_command(proto::Referee_Command_PREPARE_PENALTY_BLUE); rtt::ai::GameStateManager::setRefereeData(refereeData, worldPtr); EXPECT_EQ(rtt::ai::GameStateManager::getCurrentGameState().getStrategyName(), "penalty_them_prepare"); diff --git a/roboteam_interface/src/generated/proto.d.ts b/roboteam_interface/src/generated/proto.d.ts index 8d4f623d1..93a3e978a 100644 --- a/roboteam_interface/src/generated/proto.d.ts +++ b/roboteam_interface/src/generated/proto.d.ts @@ -4768,8 +4768,6 @@ export namespace proto { PREPARE_PENALTY_BLUE = 7, DIRECT_FREE_YELLOW = 8, DIRECT_FREE_BLUE = 9, - INDIRECT_FREE_YELLOW = 10, - INDIRECT_FREE_BLUE = 11, TIMEOUT_YELLOW = 12, TIMEOUT_BLUE = 13, BALL_PLACEMENT_YELLOW = 16, diff --git a/roboteam_networking/proto/State.proto b/roboteam_networking/proto/State.proto index 8ca911bb9..33e285ba8 100644 --- a/roboteam_networking/proto/State.proto +++ b/roboteam_networking/proto/State.proto @@ -18,8 +18,8 @@ message State { TeamParameters blue_robot_parameters = 4; TeamParameters yellow_robot_parameters = 5; SSL_GeometryData field = 6; //TODO: later change to a custom field type - SSL_Referee referee = 7; //TODO: later change to a custom referee type + Referee referee = 7; //TODO: later change to a custom referee type repeated SSL_WrapperPacket processed_vision_packets = 10; - repeated SSL_Referee processed_referee_packets = 11; + repeated Referee processed_referee_packets = 11; repeated RobotsFeedback processed_feedback_packets = 12; } \ No newline at end of file diff --git a/roboteam_networking/proto/messages_robocup_ssl_detection.proto b/roboteam_networking/proto/messages_robocup_ssl_detection.proto index b3d2b41a6..4441920ad 100644 --- a/roboteam_networking/proto/messages_robocup_ssl_detection.proto +++ b/roboteam_networking/proto/messages_robocup_ssl_detection.proto @@ -31,4 +31,4 @@ message SSL_DetectionFrame { repeated SSL_DetectionBall balls = 5; repeated SSL_DetectionRobot robots_yellow = 6; repeated SSL_DetectionRobot robots_blue = 7; -} +} \ No newline at end of file diff --git a/roboteam_networking/proto/messages_robocup_ssl_game_controller_common.proto b/roboteam_networking/proto/messages_robocup_ssl_game_controller_common.proto index ea567ffe5..902ae2ffa 100644 --- a/roboteam_networking/proto/messages_robocup_ssl_game_controller_common.proto +++ b/roboteam_networking/proto/messages_robocup_ssl_game_controller_common.proto @@ -1,4 +1,5 @@ syntax = "proto2"; + package proto; // Team is either blue or yellow diff --git a/roboteam_networking/proto/messages_robocup_ssl_game_controller_geometry.proto b/roboteam_networking/proto/messages_robocup_ssl_game_controller_geometry.proto index be80a2d5e..066f62939 100644 --- a/roboteam_networking/proto/messages_robocup_ssl_game_controller_geometry.proto +++ b/roboteam_networking/proto/messages_robocup_ssl_game_controller_geometry.proto @@ -1,4 +1,5 @@ syntax = "proto2"; + package proto; // A vector with two dimensions diff --git a/roboteam_networking/proto/messages_robocup_ssl_game_event.proto b/roboteam_networking/proto/messages_robocup_ssl_game_event.proto index 5dd806619..b64de237f 100644 --- a/roboteam_networking/proto/messages_robocup_ssl_game_event.proto +++ b/roboteam_networking/proto/messages_robocup_ssl_game_event.proto @@ -12,6 +12,10 @@ import "messages_robocup_ssl_game_controller_geometry.proto"; // An autoRef should ideally set all fields, except if there are good reasons to not do so. message GameEvent { + // A globally unique id of the game event. + optional string id = 50; + + // The type of the game event. optional Type type = 40; // The origins of this game event. @@ -20,6 +24,9 @@ message GameEvent { // Ignored if sent by autoRef to game controller. repeated string origin = 41; + // Unix timestamp in microseconds when the event was created. + optional uint64 created_timestamp = 49; + // the event that occurred oneof event { @@ -40,6 +47,7 @@ message GameEvent { BotPushedBot bot_pushed_bot = 24; BotHeldBallDeliberately bot_held_ball_deliberately = 26; BotTippedOver bot_tipped_over = 27; + BotDroppedParts bot_dropped_parts = 51; // Non-Stopping Fouls @@ -73,34 +81,34 @@ message GameEvent { BotSubstitution bot_substitution = 37; TooManyRobots too_many_robots = 38; ChallengeFlag challenge_flag = 46; + ChallengeFlagHandled challenge_flag_handled = 48; EmergencyStop emergency_stop = 47; UnsportingBehaviorMinor unsporting_behavior_minor = 35; UnsportingBehaviorMajor unsporting_behavior_major = 36; // Deprecated events - /* + // replaced by ready_to_continue flag - Prepared prepared = 1 [deprecated = true]; - // obsolete - IndirectGoal indirect_goal = 9 [deprecated = true]; - // replaced by the meta-information in the possible_goal event - ChippedGoal chipped_goal = 10 [deprecated = true]; - // obsolete - KickTimeout kick_timeout = 12 [deprecated = true]; - // rule removed - AttackerTouchedOpponentInDefenseArea attacker_touched_opponent_in_defense_area = 16 [deprecated = true]; - // obsolete - AttackerTouchedOpponentInDefenseArea attacker_touched_opponent_in_defense_area_skipped = 42 [deprecated = true]; - // obsolete - BotCrashUnique bot_crash_unique_skipped = 23 [deprecated = true]; - // can not be used as long as autoRefs do not judge pushing - BotPushedBot bot_pushed_bot_skipped = 25 [deprecated = true]; - // rule removed - DefenderInDefenseAreaPartially defender_in_defense_area_partially = 30 [deprecated = true]; - // the referee msg already indicates this - MultiplePlacementFailures multiple_placement_failures = 33 [deprecated = true]; - */ + // Prepared prepared = 1 [deprecated = true]; + // // obsolete + // IndirectGoal indirect_goal = 9 [deprecated = true]; + // // replaced by the meta-information in the possible_goal event + // ChippedGoal chipped_goal = 10 [deprecated = true]; + // // obsolete + // KickTimeout kick_timeout = 12 [deprecated = true]; + // // rule removed + // AttackerTouchedOpponentInDefenseArea attacker_touched_opponent_in_defense_area = 16 [deprecated = true]; + // // obsolete + // AttackerTouchedOpponentInDefenseArea attacker_touched_opponent_in_defense_area_skipped = 42 [deprecated = true]; + // // obsolete + // BotCrashUnique bot_crash_unique_skipped = 23 [deprecated = true]; + // // can not be used as long as autoRefs do not judge pushing + // BotPushedBot bot_pushed_bot_skipped = 25 [deprecated = true]; + // // rule removed + // DefenderInDefenseAreaPartially defender_in_defense_area_partially = 30 [deprecated = true]; + // // the referee msg already indicates this + // MultiplePlacementFailures multiple_placement_failures = 33 [deprecated = true]; } // the ball left the field normally @@ -109,7 +117,7 @@ message GameEvent { required Team by_team = 1; // the bot that last touched the ball optional uint32 by_bot = 2; - // the location where the ball left the field + // the location where the ball left the field [m] optional Vector2 location = 3; } // the ball left the field via goal line and a team committed an aimless kick @@ -118,9 +126,9 @@ message GameEvent { required Team by_team = 1; // the bot that last touched the ball optional uint32 by_bot = 2; - // the location where the ball left the field + // the location where the ball left the field [m] optional Vector2 location = 3; - // the location where the ball was last touched + // the location where the ball was last touched [m] optional Vector2 kick_location = 4; } // a team shot a goal @@ -131,11 +139,11 @@ message GameEvent { optional Team kicking_team = 6; // the bot that shot the goal optional uint32 kicking_bot = 2; - // the location where the ball entered the goal + // the location where the ball entered the goal [m] optional Vector2 location = 3; - // the location where the ball was kicked (for deciding if this was a valid goal) + // the location where the ball was kicked (for deciding if this was a valid goal) [m] optional Vector2 kick_location = 4; - // the maximum height the ball reached during the goal kick (for deciding if this was a valid goal) + // the maximum height the ball reached during the goal kick (for deciding if this was a valid goal) [m] optional float max_ball_height = 5; // number of robots of scoring team when the ball entered the goal (for deciding if this was a valid goal) optional uint32 num_robots_by_team = 7; @@ -150,9 +158,9 @@ message GameEvent { required Team by_team = 1; // the bot that kicked the ball - at least the team must be set optional uint32 by_bot = 2; - // the location where the ball entered the goal + // the location where the ball entered the goal [m] optional Vector2 location = 3; - // the location where the ball was kicked + // the location where the ball was kicked [m] optional Vector2 kick_location = 4; } // the ball entered the goal, but was initially chipped @@ -161,11 +169,11 @@ message GameEvent { required Team by_team = 1; // the bot that kicked the ball optional uint32 by_bot = 2; - // the location where the ball entered the goal + // the location where the ball entered the goal [m] optional Vector2 location = 3; - // the location where the ball was kicked + // the location where the ball was kicked [m] optional Vector2 kick_location = 4; - // the maximum height [m] of the ball, before it entered the goal and since the last kick + // the maximum height [m] of the ball, before it entered the goal and since the last kick [m] optional float max_ball_height = 5; } // a bot moved too fast while the game was stopped @@ -174,7 +182,7 @@ message GameEvent { required Team by_team = 1; // the bot that was too fast optional uint32 by_bot = 2; - // the location of the bot + // the location of the bot [m] optional Vector2 location = 3; // the bot speed [m/s] optional float speed = 4; @@ -185,7 +193,7 @@ message GameEvent { required Team by_team = 1; // the bot that violates the distance to the kick point optional uint32 by_bot = 2; - // the location of the bot + // the location of the bot [m] optional Vector2 location = 3; // the distance [m] from bot to the kick point (including the minimum radius) optional float distance = 4; @@ -196,7 +204,7 @@ message GameEvent { optional uint32 bot_yellow = 1; // the bot of the blue team optional uint32 bot_blue = 2; - // the location of the crash (center between both bots) + // the location of the crash (center between both bots) [m] optional Vector2 location = 3; // the calculated crash speed [m/s] of the two bots optional float crash_speed = 4; @@ -215,7 +223,7 @@ message GameEvent { optional uint32 violator = 2; // the bot of the opposite team that was involved in the crash optional uint32 victim = 3; - // the location of the crash (center between both bots) + // the location of the crash (center between both bots) [m] optional Vector2 location = 4; // the calculated crash speed vector [m/s] of the two bots optional float crash_speed = 5; @@ -234,7 +242,7 @@ message GameEvent { optional uint32 violator = 2; // the bot of the opposite team that was pushed optional uint32 victim = 3; - // the location of the push (center between both bots) + // the location of the push (center between both bots) [m] optional Vector2 location = 4; // the pushed distance [m] optional float pushed_distance = 5; @@ -245,9 +253,20 @@ message GameEvent { required Team by_team = 1; // the bot that tipped over optional uint32 by_bot = 2; - // the location of the bot + // the location of the bot [m] optional Vector2 location = 3; - // the location of the ball at the moment when this foul occurred + // the location of the ball at the moment when this foul occurred [m] + optional Vector2 ball_location = 4; + } + // a bot dropped parts + message BotDroppedParts { + // the team that found guilty + required Team by_team = 1; + // the bot that dropped the parts + optional uint32 by_bot = 2; + // the location where the parts were dropped [m] + optional Vector2 location = 3; + // the location of the ball at the moment when this foul occurred [m] optional Vector2 ball_location = 4; } // a defender other than the keeper was fully located inside its own defense and touched the ball @@ -256,7 +275,7 @@ message GameEvent { required Team by_team = 1; // the bot that is inside the penalty area optional uint32 by_bot = 2; - // the location of the bot + // the location of the bot [m] optional Vector2 location = 3; // the distance [m] from bot case to the nearest point outside the defense area optional float distance = 4; @@ -271,7 +290,7 @@ message GameEvent { optional Vector2 location = 3; // the distance [m] that the bot is inside the penalty area optional float distance = 4; - // the location of the ball at the moment when this foul occurred + // the location of the ball at the moment when this foul occurred [m] optional Vector2 ball_location = 5; } // an attacker touched the ball inside the opponent defense area @@ -280,7 +299,7 @@ message GameEvent { required Team by_team = 1; // the bot that is inside the penalty area optional uint32 by_bot = 2; - // the location of the bot + // the location of the bot [m] optional Vector2 location = 3; // the distance [m] that the bot is inside the penalty area optional float distance = 4; @@ -291,7 +310,7 @@ message GameEvent { required Team by_team = 1; // the bot that kicked too fast optional uint32 by_bot = 2; - // the location of the ball at the time of the highest speed + // the location of the ball at the time of the highest speed [m] optional Vector2 location = 3; // the absolute initial ball speed (kick speed) [m/s] optional float initial_ball_speed = 4; @@ -304,9 +323,9 @@ message GameEvent { required Team by_team = 1; // the bot that dribbled too far optional uint32 by_bot = 2; - // the location where the dribbling started + // the location where the dribbling started [m] optional Vector2 start = 3; - // the location where the maximum dribbling distance was reached + // the location where the maximum dribbling distance was reached [m] optional Vector2 end = 4; } // an attacker touched the opponent robot inside defense area @@ -317,7 +336,7 @@ message GameEvent { optional uint32 by_bot = 2; // the bot of the opposite team that was touched optional uint32 victim = 4; - // the location of the contact point between both bots + // the location of the contact point between both bots [m] optional Vector2 location = 3; } // an attacker touched the ball multiple times when it was not allowed to @@ -326,7 +345,7 @@ message GameEvent { required Team by_team = 1; // the bot that touched the ball twice optional uint32 by_bot = 2; - // the location of the ball when it was first touched + // the location of the ball when it was first touched [m] optional Vector2 location = 3; } // an attacker was located too near to the opponent defense area during stop or free kick @@ -335,11 +354,11 @@ message GameEvent { required Team by_team = 1; // the bot that is too close to the defense area optional uint32 by_bot = 2; - // the location of the bot + // the location of the bot [m] optional Vector2 location = 3; // the distance [m] of the bot to the penalty area optional float distance = 4; - // the location of the ball at the moment when this foul occurred + // the location of the ball at the moment when this foul occurred [m] optional Vector2 ball_location = 5; } // a bot held the ball for too long @@ -348,7 +367,7 @@ message GameEvent { required Team by_team = 1; // the bot that holds the ball optional uint32 by_bot = 2; - // the location of the ball + // the location of the ball [m] optional Vector2 location = 3; // the duration [s] that the bot hold the ball optional float duration = 4; @@ -359,10 +378,10 @@ message GameEvent { required Team by_team = 1; // the bot that interfered the placement optional uint32 by_bot = 2; - // the location of the bot + // the location of the bot [m] optional Vector2 location = 3; } - // a team collected multiple cards (yellow and red), which results in a penalty kick + // a team collected multiple yellow cards message MultipleCards { // the team that received multiple yellow cards required Team by_team = 1; @@ -371,6 +390,8 @@ message GameEvent { message MultipleFouls { // the team that collected multiple fouls required Team by_team = 1; + // the list of game events that caused the multiple fouls + repeated GameEvent caused_game_events = 2; } // a team failed to place the ball multiple times in a row message MultiplePlacementFailures { @@ -381,7 +402,7 @@ message GameEvent { message KickTimeout { // the team that that should have kicked required Team by_team = 1; - // the location of the ball + // the location of the ball [m] optional Vector2 location = 2; // the time [s] that was waited optional float time = 3; @@ -418,7 +439,7 @@ message GameEvent { message KeeperHeldBall { // the team that found guilty required Team by_team = 1; - // the location of the ball + // the location of the ball [m] optional Vector2 location = 2; // the duration [s] that the keeper hold the ball optional float duration = 3; @@ -446,9 +467,16 @@ message GameEvent { } // A challenge flag, requested by a team previously, is flagged message ChallengeFlag { - // the team that substitutes robots + // the team that requested the challenge flag required Team by_team = 1; } + // A challenge, flagged recently, has been handled by the referee + message ChallengeFlagHandled { + // the team that requested the challenge flag + required Team by_team = 1; + // the challenge was accepted by the referee + required bool accepted = 2; + } // An emergency stop, requested by team previously, occurred message EmergencyStop { // the team that substitutes robots @@ -462,22 +490,24 @@ message GameEvent { optional int32 num_robots_allowed = 2; // number of robots currently on the field optional int32 num_robots_on_field = 3; - // the location of the ball at the moment when this foul occurred + // the location of the ball at the moment when this foul occurred [m] optional Vector2 ball_location = 4; } // a robot chipped the ball over the field boundary out of the playing surface message BoundaryCrossing { // the team that has too many robots required Team by_team = 1; - // the location of the ball + // the location of the ball [m] optional Vector2 location = 2; } // the penalty kick failed (by time or by keeper) message PenaltyKickFailed { // the team that last touched the ball required Team by_team = 1; - // the location of the ball at the moment of this event + // the location of the ball at the moment of this event [m] optional Vector2 location = 2; + // an explanation of the failure + optional string reason = 3; } enum Type { @@ -500,6 +530,7 @@ message GameEvent { BOT_PUSHED_BOT = 24; // triggered by human ref BOT_HELD_BALL_DELIBERATELY = 26; // triggered by human ref BOT_TIPPED_OVER = 27; // triggered by human ref + BOT_DROPPED_PARTS = 47; // triggered by human ref // Non-Stopping Fouls @@ -533,6 +564,7 @@ message GameEvent { BOT_SUBSTITUTION = 37; // triggered by GC TOO_MANY_ROBOTS = 38; // triggered by GC CHALLENGE_FLAG = 44; // triggered by GC + CHALLENGE_FLAG_HANDLED = 46; // triggered by GC EMERGENCY_STOP = 45; // triggered by GC UNSPORTING_BEHAVIOR_MINOR = 35; // triggered by human ref @@ -552,4 +584,4 @@ message GameEvent { MULTIPLE_PLACEMENT_FAILURES = 33 [deprecated = true]; */ } -} +} \ No newline at end of file diff --git a/roboteam_networking/proto/messages_robocup_ssl_geometry.proto b/roboteam_networking/proto/messages_robocup_ssl_geometry.proto index 0dce4028d..c0db80643 100644 --- a/roboteam_networking/proto/messages_robocup_ssl_geometry.proto +++ b/roboteam_networking/proto/messages_robocup_ssl_geometry.proto @@ -8,87 +8,125 @@ package proto; // the center of the line, so the thickness of the line extends by thickness / 2 // on either side of the line. message SSL_FieldLineSegment { - // Name of this field marking. - required string name = 1; - // Start point of the line segment. - required Vector2f p1 = 2; - // End point of the line segment. - required Vector2f p2 = 3; - // Thickness of the line segment. - required float thickness = 4; - // The type of this shape - optional SSL_FieldShapeType type = 5; + // Name of this field marking. + required string name = 1; + // Start point of the line segment. + required Vector2f p1 = 2; + // End point of the line segment. + required Vector2f p2 = 3; + // Thickness of the line segment. + required float thickness = 4; + // The type of this shape + optional SSL_FieldShapeType type = 5; } // Represents a field marking as a circular arc segment represented by center point, a // start angle, an end angle, and an arc thickness. message SSL_FieldCircularArc { - // Name of this field marking. - required string name = 1; - // Center point of the circular arc. - required Vector2f center = 2; - // Radius of the arc. - required float radius = 3; - // Start angle in counter-clockwise order. - required float a1 = 4; - // End angle in counter-clockwise order. - required float a2 = 5; - // Thickness of the arc. - required float thickness = 6; - // The type of this shape - optional SSL_FieldShapeType type = 7; + // Name of this field marking. + required string name = 1; + // Center point of the circular arc. + required Vector2f center = 2; + // Radius of the arc. + required float radius = 3; + // Start angle in counter-clockwise order. + required float a1 = 4; + // End angle in counter-clockwise order. + required float a2 = 5; + // Thickness of the arc. + required float thickness = 6; + // The type of this shape + optional SSL_FieldShapeType type = 7; } message SSL_GeometryFieldSize { - required int32 field_length = 1; - required int32 field_width = 2; - required int32 goal_width = 3; - required int32 goal_depth = 4; - required int32 boundary_width = 5; - repeated SSL_FieldLineSegment field_lines = 6; - repeated SSL_FieldCircularArc field_arcs = 7; - optional int32 penalty_area_depth = 8; - optional int32 penalty_area_width = 9; + required int32 field_length = 1; + required int32 field_width = 2; + required int32 goal_width = 3; + required int32 goal_depth = 4; + required int32 boundary_width = 5; + repeated SSL_FieldLineSegment field_lines = 6; + repeated SSL_FieldCircularArc field_arcs = 7; + optional int32 penalty_area_depth = 8; + optional int32 penalty_area_width = 9; + optional int32 center_circle_radius = 10; + optional int32 line_thickness = 11; + optional int32 goal_center_to_penalty_mark = 12; + optional int32 goal_height = 13; + optional float ball_radius = 14; + optional float max_robot_radius = 15; } message SSL_GeometryCameraCalibration { - required uint32 camera_id = 1; - required float focal_length = 2; - required float principal_point_x = 3; - required float principal_point_y = 4; - required float distortion = 5; - required float q0 = 6; - required float q1 = 7; - required float q2 = 8; - required float q3 = 9; - required float tx = 10; - required float ty = 11; - required float tz = 12; - optional float derived_camera_world_tx = 13; - optional float derived_camera_world_ty = 14; - optional float derived_camera_world_tz = 15; - optional uint32 pixel_image_width = 16; - optional uint32 pixel_image_height = 17; + required uint32 camera_id = 1; + required float focal_length = 2; + required float principal_point_x = 3; + required float principal_point_y = 4; + required float distortion = 5; + required float q0 = 6; + required float q1 = 7; + required float q2 = 8; + required float q3 = 9; + required float tx = 10; + required float ty = 11; + required float tz = 12; + optional float derived_camera_world_tx = 13; + optional float derived_camera_world_ty = 14; + optional float derived_camera_world_tz = 15; + optional uint32 pixel_image_width = 16; + optional uint32 pixel_image_height = 17; +} + +// Two-Phase model for straight-kicked balls. +// There are two phases with different accelerations during the ball kicks: +// 1. Sliding +// 2. Rolling +// The full model is described in the TDP of ER-Force from 2016, which can be found here: +// https://ssl.robocup.org/wp-content/uploads/2019/01/2016_ETDP_ER-Force.pdf +message SSL_BallModelStraightTwoPhase { + // Ball sliding acceleration [m/s^2] (should be negative) + required double acc_slide = 1; + // Ball rolling acceleration [m/s^2] (should be negative) + required double acc_roll = 2; + // Fraction of the initial velocity where the ball starts to roll + required double k_switch = 3; +} + +// Fixed-Loss model for chipped balls. +// Uses fixed damping factors for xy and z direction per hop. +message SSL_BallModelChipFixedLoss { + // Chip kick velocity damping factor in XY direction for the first hop + required double damping_xy_first_hop = 1; + // Chip kick velocity damping factor in XY direction for all following hops + required double damping_xy_other_hops = 2; + // Chip kick velocity damping factor in Z direction for all hops + required double damping_z = 3; +} + +message SSL_GeometryModels { + optional SSL_BallModelStraightTwoPhase straight_two_phase = 1; + optional SSL_BallModelChipFixedLoss chip_fixed_loss = 2; } message SSL_GeometryData { - required SSL_GeometryFieldSize field = 1; - repeated SSL_GeometryCameraCalibration calib = 2; + required SSL_GeometryFieldSize field = 1; + repeated SSL_GeometryCameraCalibration calib = 2; + optional SSL_GeometryModels models = 3; } enum SSL_FieldShapeType { - Undefined = 0; - CenterCircle = 1; - TopTouchLine = 2; - BottomTouchLine = 3; - LeftGoalLine = 4; - RightGoalLine = 5; - HalfwayLine = 6; - CenterLine = 7; - LeftPenaltyStretch = 8; - RightPenaltyStretch = 9; - LeftFieldLeftPenaltyStretch = 10; - LeftFieldRightPenaltyStretch = 11; - RightFieldLeftPenaltyStretch = 12; - RightFieldRightPenaltyStretch = 13; + Undefined = 0; + CenterCircle = 1; + TopTouchLine = 2; + BottomTouchLine = 3; + LeftGoalLine = 4; + RightGoalLine = 5; + HalfwayLine = 6; + CenterLine = 7; + LeftPenaltyStretch = 8; + RightPenaltyStretch = 9; + LeftFieldLeftPenaltyStretch = 10; + LeftFieldRightPenaltyStretch = 11; + RightFieldLeftPenaltyStretch = 12; + RightFieldRightPenaltyStretch = 13; } \ No newline at end of file diff --git a/roboteam_networking/proto/messages_robocup_ssl_referee.proto b/roboteam_networking/proto/messages_robocup_ssl_referee.proto index 1f9ad3457..e4553673c 100644 --- a/roboteam_networking/proto/messages_robocup_ssl_referee.proto +++ b/roboteam_networking/proto/messages_robocup_ssl_referee.proto @@ -4,205 +4,220 @@ package proto; import "messages_robocup_ssl_game_event.proto"; // Each UDP packet contains one of these messages. -message SSL_Referee { - // The UNIX timestamp when the packet was sent, in microseconds. - // Divide by 1,000,000 to get a time_t. - required uint64 packet_timestamp = 1; - - // These are the "coarse" stages of the game. - enum Stage { - // The first half is about to start. - // A kickoff is called within this stage. - // This stage ends with the NORMAL_START. - NORMAL_FIRST_HALF_PRE = 0; - // The first half of the normal game, before half time. - NORMAL_FIRST_HALF = 1; - // Half time between first and second halves. - NORMAL_HALF_TIME = 2; - // The second half is about to start. - // A kickoff is called within this stage. - // This stage ends with the NORMAL_START. - NORMAL_SECOND_HALF_PRE = 3; - // The second half of the normal game, after half time. - NORMAL_SECOND_HALF = 4; - // The break before extra time. - EXTRA_TIME_BREAK = 5; - // The first half of extra time is about to start. - // A kickoff is called within this stage. - // This stage ends with the NORMAL_START. - EXTRA_FIRST_HALF_PRE = 6; - // The first half of extra time. - EXTRA_FIRST_HALF = 7; - // Half time between first and second extra halves. - EXTRA_HALF_TIME = 8; - // The second half of extra time is about to start. - // A kickoff is called within this stage. - // This stage ends with the NORMAL_START. - EXTRA_SECOND_HALF_PRE = 9; - // The second half of extra time. - EXTRA_SECOND_HALF = 10; - // The break before penalty shootout. - PENALTY_SHOOTOUT_BREAK = 11; - // The penalty shootout. - PENALTY_SHOOTOUT = 12; - // The game is over. - POST_GAME = 13; - } - required Stage stage = 2; - - // The number of microseconds left in the stage. - // The following stages have this value; the rest do not: - // NORMAL_FIRST_HALF - // NORMAL_HALF_TIME - // NORMAL_SECOND_HALF - // EXTRA_TIME_BREAK - // EXTRA_FIRST_HALF - // EXTRA_HALF_TIME - // EXTRA_SECOND_HALF - // PENALTY_SHOOTOUT_BREAK - // - // If the stage runs over its specified time, this value - // becomes negative. - optional sint32 stage_time_left = 3; - - // These are the "fine" states of play on the field. - enum Command { - // All robots should completely stop moving. - HALT = 0; - // Robots must keep 50 cm from the ball. - STOP = 1; - // A prepared kickoff or penalty may now be taken. - NORMAL_START = 2; - // The ball is dropped and free for either team. - FORCE_START = 3; - // The yellow team may move into kickoff position. - PREPARE_KICKOFF_YELLOW = 4; - // The blue team may move into kickoff position. - PREPARE_KICKOFF_BLUE = 5; - // The yellow team may move into penalty position. - PREPARE_PENALTY_YELLOW = 6; - // The blue team may move into penalty position. - PREPARE_PENALTY_BLUE = 7; - // The yellow team may take a direct free kick. - DIRECT_FREE_YELLOW = 8; - // The blue team may take a direct free kick. - DIRECT_FREE_BLUE = 9; - // The yellow team may take an indirect free kick. - INDIRECT_FREE_YELLOW = 10; - // The blue team may take an indirect free kick. - INDIRECT_FREE_BLUE = 11; - // The yellow team is currently in a timeout. - TIMEOUT_YELLOW = 12; - // The blue team is currently in a timeout. - TIMEOUT_BLUE = 13; - // The yellow team just scored a goal. - // For information only. - // For rules compliance, teams must treat as STOP. - // Deprecated: Use the score field from the team infos instead. That way, you can also detect revoked goals. - //GOAL_YELLOW = 14 [deprecated = true]; - // The blue team just scored a goal. See also GOAL_YELLOW. - //GOAL_BLUE = 15 [deprecated = true]; - // Equivalent to STOP, but the yellow team must pick up the ball and - // drop it in the Designated Position. - BALL_PLACEMENT_YELLOW = 16; - // Equivalent to STOP, but the blue team must pick up the ball and drop - // it in the Designated Position. - BALL_PLACEMENT_BLUE = 17; - } - required Command command = 4; - - // The number of commands issued since startup (mod 2^32). - required uint32 command_counter = 5; - - // The UNIX timestamp when the command was issued, in microseconds. - // This value changes only when a new command is issued, not on each packet. - required uint64 command_timestamp = 6; - - // Information about a single team. - message TeamInfo { - // The team's name (empty string if operator has not typed anything). - required string name = 1; - // The number of goals scored by the team during normal play and overtime. - required uint32 score = 2; - // The number of red cards issued to the team since the beginning of the game. - required uint32 red_cards = 3; - // The amount of time (in microseconds) left on each yellow card issued to the team. - // If no yellow cards are issued, this array has no elements. - // Otherwise, times are ordered from smallest to largest. - repeated uint32 yellow_card_times = 4 [packed = true]; - // The total number of yellow cards ever issued to the team. - required uint32 yellow_cards = 5; - // The number of timeouts this team can still call. - // If in a timeout right now, that timeout is excluded. - required uint32 timeouts = 6; - // The number of microseconds of timeout this team can use. - required uint32 timeout_time = 7; - // The pattern number of this team's goalkeeper. - required uint32 goalkeeper = 8; - // The total number of countable fouls that act towards yellow cards - optional uint32 foul_counter = 9; - // The number of consecutive ball placement failures of this team - optional uint32 ball_placement_failures = 10; - // Indicate if the team is able and allowed to place the ball - optional bool can_place_ball = 12; - // The maximum number of bots allowed on the field based on division and cards - optional uint32 max_allowed_bots = 13; - // The team has submitted an intent to substitute one or more robots at the next chance - optional bool bot_substitution_intent = 14; - // Indicate if the team reached the maximum allowed ball placement failures and is thus not allowed to place the ball anymore - optional bool ball_placement_failures_reached = 15; - } - - // Information about the two teams. - required TeamInfo yellow = 7; - required TeamInfo blue = 8; - - // The coordinates of the Designated Position. These are measured in - // millimetres and correspond to SSL-Vision coordinates. These fields are - // always either both present (in the case of a ball placement command) or - // both absent (in the case of any other command). - message Point { - required float x = 1; - required float y = 2; - } - optional Point designated_position = 9; - - // 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. - // Obviously, the yellow team will play on the opposite half. - optional bool blue_team_on_positive_half = 10; - - // The game event that caused the referee command. - // deprecated in favor of game_events. - // optional Game_Event game_event = 11 [deprecated = true]; - reserved 11; - - // The command that will be issued after the current stoppage and ball placement to continue the game. - optional Command next_command = 12; - - // All game events that were detected since the last RUNNING state. - // Will be cleared as soon as the game is continued. - reserved 13; - repeated GameEvent game_events = 16; - - // All non-finished proposed game events that may be processed next. - reserved 14; - repeated GameEventProposalGroup game_event_proposals = 17; - - // The time in microseconds that is remaining until the current action times out - // The time will not be reset. It can get negative. - // An autoRef would raise an appropriate event, if the time gets negative. - // Possible actions where this time is relevant: - // * free kicks - // * kickoff, penalty kick, force start - // * ball placement - optional int32 current_action_time_remaining = 15; +message Referee { + // A random UUID of the source that is kept constant at the source while running + // If multiple sources are broadcasting to the same network, this id can be used to identify individual sources + optional string source_identifier = 18; + + // The match type is a meta information about the current match that helps to process the logs after a competition + optional MatchType match_type = 19 [default = UNKNOWN_MATCH]; + + // The UNIX timestamp when the packet was sent, in microseconds. + // Divide by 1,000,000 to get a time_t. + required uint64 packet_timestamp = 1; + + // These are the "coarse" stages of the game. + enum Stage { + // The first half is about to start. + // A kickoff is called within this stage. + // This stage ends with the NORMAL_START. + NORMAL_FIRST_HALF_PRE = 0; + // The first half of the normal game, before half time. + NORMAL_FIRST_HALF = 1; + // Half time between first and second halves. + NORMAL_HALF_TIME = 2; + // The second half is about to start. + // A kickoff is called within this stage. + // This stage ends with the NORMAL_START. + NORMAL_SECOND_HALF_PRE = 3; + // The second half of the normal game, after half time. + NORMAL_SECOND_HALF = 4; + // The break before extra time. + EXTRA_TIME_BREAK = 5; + // The first half of extra time is about to start. + // A kickoff is called within this stage. + // This stage ends with the NORMAL_START. + EXTRA_FIRST_HALF_PRE = 6; + // The first half of extra time. + EXTRA_FIRST_HALF = 7; + // Half time between first and second extra halves. + EXTRA_HALF_TIME = 8; + // The second half of extra time is about to start. + // A kickoff is called within this stage. + // This stage ends with the NORMAL_START. + EXTRA_SECOND_HALF_PRE = 9; + // The second half of extra time. + EXTRA_SECOND_HALF = 10; + // The break before penalty shootout. + PENALTY_SHOOTOUT_BREAK = 11; + // The penalty shootout. + PENALTY_SHOOTOUT = 12; + // The game is over. + POST_GAME = 13; + } + required Stage stage = 2; + + // The number of microseconds left in the stage. + // The following stages have this value; the rest do not: + // NORMAL_FIRST_HALF + // NORMAL_HALF_TIME + // NORMAL_SECOND_HALF + // EXTRA_TIME_BREAK + // EXTRA_FIRST_HALF + // EXTRA_HALF_TIME + // EXTRA_SECOND_HALF + // PENALTY_SHOOTOUT_BREAK + // + // If the stage runs over its specified time, this value + // becomes negative. + optional sint64 stage_time_left = 3; + + // These are the "fine" states of play on the field. + enum Command { + // All robots should completely stop moving. + HALT = 0; + // Robots must keep 50 cm from the ball. + STOP = 1; + // A prepared kickoff or penalty may now be taken. + NORMAL_START = 2; + // The ball is dropped and free for either team. + FORCE_START = 3; + // The yellow team may move into kickoff position. + PREPARE_KICKOFF_YELLOW = 4; + // The blue team may move into kickoff position. + PREPARE_KICKOFF_BLUE = 5; + // The yellow team may move into penalty position. + PREPARE_PENALTY_YELLOW = 6; + // The blue team may move into penalty position. + PREPARE_PENALTY_BLUE = 7; + // The yellow team may take a direct free kick. + DIRECT_FREE_YELLOW = 8; + // The blue team may take a direct free kick. + DIRECT_FREE_BLUE = 9; + // The yellow team is currently in a timeout. + TIMEOUT_YELLOW = 12; + // The blue team is currently in a timeout. + TIMEOUT_BLUE = 13; + // Equivalent to STOP, but the yellow team must pick up the ball and + // drop it in the Designated Position. + BALL_PLACEMENT_YELLOW = 16; + // Equivalent to STOP, but the blue team must pick up the ball and drop + // it in the Designated Position. + BALL_PLACEMENT_BLUE = 17; + } + required Command command = 4; + + // The number of commands issued since startup (mod 2^32). + required uint32 command_counter = 5; + + // The UNIX timestamp when the command was issued, in microseconds. + // This value changes only when a new command is issued, not on each packet. + required uint64 command_timestamp = 6; + + // Information about a single team. + message TeamInfo { + // The team's name (empty string if operator has not typed anything). + required string name = 1; + // The number of goals scored by the team during normal play and overtime. + required uint32 score = 2; + // The number of red cards issued to the team since the beginning of the game. + required uint32 red_cards = 3; + // The amount of time (in microseconds) left on each yellow card issued to the team. + // If no yellow cards are issued, this array has no elements. + // Otherwise, times are ordered from smallest to largest. + repeated uint32 yellow_card_times = 4 [packed = true]; + // The total number of yellow cards ever issued to the team. + required uint32 yellow_cards = 5; + // The number of timeouts this team can still call. + // If in a timeout right now, that timeout is excluded. + required uint32 timeouts = 6; + // The number of microseconds of timeout this team can use. + required uint32 timeout_time = 7; + // The pattern number of this team's goalkeeper. + required uint32 goalkeeper = 8; + // The total number of countable fouls that act towards yellow cards + optional uint32 foul_counter = 9; + // The number of consecutive ball placement failures of this team + optional uint32 ball_placement_failures = 10; + // Indicate if the team is able and allowed to place the ball + optional bool can_place_ball = 12; + // The maximum number of bots allowed on the field based on division and cards + optional uint32 max_allowed_bots = 13; + // The team has submitted an intent to substitute one or more robots at the next chance + optional bool bot_substitution_intent = 14; + // Indicate if the team reached the maximum allowed ball placement failures and is thus not allowed to place the ball anymore + optional bool ball_placement_failures_reached = 15; + // The team is allowed to substitute one or more robots currently + optional bool bot_substitution_allowed = 16; + } + + // Information about the two teams. + required TeamInfo yellow = 7; + required TeamInfo blue = 8; + + // The coordinates of the Designated Position. These are measured in + // millimetres and correspond to SSL-Vision coordinates. These fields are + // always either both present (in the case of a ball placement command) or + // both absent (in the case of any other command). + message Point { + required float x = 1; + required float y = 2; + } + optional Point designated_position = 9; + + // 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. + // Obviously, the yellow team will play on the opposite half. + optional bool blue_team_on_positive_half = 10; + + // The game event that caused the referee command. + // deprecated in favor of game_events. + // optional Game_Event game_event = 11 [deprecated = true]; + reserved 11; + + // The command that will be issued after the current stoppage and ball placement to continue the game. + optional Command next_command = 12; + + // All game events that were detected since the last RUNNING state. + // Will be cleared as soon as the game is continued. + reserved 13; + repeated GameEvent game_events = 16; + + // All proposed game events that were detected since the last RUNNING state. + reserved 14; + repeated GameEventProposalGroup game_event_proposals = 17; + + // The time in microseconds that is remaining until the current action times out + // The time will not be reset. It can get negative. + // An autoRef would raise an appropriate event, if the time gets negative. + // Possible actions where this time is relevant: + // * free kicks + // * kickoff, penalty kick, force start + // * ball placement + optional int64 current_action_time_remaining = 15; + + // A message that can be displayed to the spectators, like a reason for a stoppage. + optional string status_message = 20; } // List of matching proposals message GameEventProposalGroup { - // The proposed game event. - repeated GameEvent game_event = 1; - // Whether the proposal group was accepted - optional bool accepted = 2; + // Unique ID of this group + optional string id = 3; + // The proposed game events + repeated GameEvent game_events = 1; + // Whether the proposal group was accepted + optional bool accepted = 2; +} + +// MatchType is a meta information about the current match for easier log processing +enum MatchType { + // not set + UNKNOWN_MATCH = 0; + // match is part of the group phase + GROUP_PHASE = 1; + // match is part of the elimination phase + ELIMINATION_PHASE = 2; + // a friendly match, not part of a tournament + FRIENDLY = 3; } \ No newline at end of file diff --git a/roboteam_networking/proto/ssl_gc_common.proto b/roboteam_networking/proto/ssl_gc_common.proto index c8fc863bb..c75ab25c9 100644 --- a/roboteam_networking/proto/ssl_gc_common.proto +++ b/roboteam_networking/proto/ssl_gc_common.proto @@ -24,4 +24,4 @@ enum Division { DIV_UNKNOWN = 0; DIV_A = 1; DIV_B = 2; -} +} \ No newline at end of file diff --git a/roboteam_networking/proto/ssl_vision_detection.proto b/roboteam_networking/proto/ssl_vision_detection.proto index 0586974f1..ab3109cde 100644 --- a/roboteam_networking/proto/ssl_vision_detection.proto +++ b/roboteam_networking/proto/ssl_vision_detection.proto @@ -30,4 +30,4 @@ message SSL_DetectionFrame { repeated SSL_DetectionBall balls = 5; repeated SSL_DetectionRobot robots_yellow = 6; repeated SSL_DetectionRobot robots_blue = 7; -} +} \ No newline at end of file diff --git a/roboteam_networking/proto/ssl_vision_geometry.proto b/roboteam_networking/proto/ssl_vision_geometry.proto index 440fd1e10..5a643c2b8 100644 --- a/roboteam_networking/proto/ssl_vision_geometry.proto +++ b/roboteam_networking/proto/ssl_vision_geometry.proto @@ -53,10 +53,16 @@ message SSL_GeometryFieldSize { repeated SSL_FieldCircularArc field_arcs = 7; optional int32 penalty_area_depth = 8; optional int32 penalty_area_width = 9; + optional int32 center_circle_radius = 10; + optional int32 line_thickness = 11; + optional int32 goal_center_to_penalty_mark = 12; + optional int32 goal_height = 13; + optional float ball_radius = 14; + optional float max_robot_radius = 15; } message SSL_GeometryCameraCalibration { - required uint32 camera_id = 1; + required uint32 camera_id = 1; required float focal_length = 2; required float principal_point_x = 3; required float principal_point_y = 4; diff --git a/roboteam_world/include/roboteam_observer/Handler.h b/roboteam_world/include/roboteam_observer/Handler.h index 3cfc98edf..6ca7c3526 100644 --- a/roboteam_world/include/roboteam_observer/Handler.h +++ b/roboteam_world/include/roboteam_observer/Handler.h @@ -21,7 +21,7 @@ class Handler { std::unique_ptr worldPublisher; std::unique_ptr> vision_client; - std::unique_ptr> referee_client; + std::unique_ptr> referee_client; Observer observer; std::vector receivedRobotData; @@ -41,7 +41,7 @@ class Handler { void startReplay(rtt::LogFileReader& reader); void start(std::string visionip, std::string refereeip, int visionport, int refereeport, bool shouldLog = false); std::vector receiveVisionPackets(); - std::vector receiveRefereePackets(); + std::vector receiveRefereePackets(); void onRobotFeedback(const rtt::RobotsFeedback& feedback); }; diff --git a/roboteam_world/observer/include/observer/Observer.h b/roboteam_world/observer/include/observer/Observer.h index 1cd37a90b..f34fd447d 100644 --- a/roboteam_world/observer/include/observer/Observer.h +++ b/roboteam_world/observer/include/observer/Observer.h @@ -32,7 +32,7 @@ class Observer { * @param refereePackets All of the packets which were received from the referee. *@return The entire known/predicted state of the game at this point in time. */ - proto::State process(const std::vector& visionPackets, const std::vector& refereePackets, + proto::State process(const std::vector& visionPackets, const std::vector& refereePackets, const std::vector& robotData); private: @@ -40,9 +40,9 @@ class Observer { VisionFilter visionFilter; RefereeFilter refereeFilter; - void updateRobotParams(std::vector refereePackets); + void updateRobotParams(std::vector refereePackets); - void updateReferee(const std::vector& refereePackets); + void updateReferee(const std::vector& refereePackets); }; #endif // RTT_OBSERVER_H diff --git a/roboteam_world/observer/include/observer/filters/referee/RefereeFilter.h b/roboteam_world/observer/include/observer/filters/referee/RefereeFilter.h index a65460c4b..51fdd3911 100644 --- a/roboteam_world/observer/include/observer/filters/referee/RefereeFilter.h +++ b/roboteam_world/observer/include/observer/filters/referee/RefereeFilter.h @@ -19,15 +19,15 @@ class RefereeFilter { /** * @param refereePackets packets to update the filter with */ - void process(const std::vector &refereePackets); + void process(const std::vector &refereePackets); /** * Returns the latest referee message if it exists. */ - std::optional getLastRefereeMessage() const; + std::optional getLastRefereeMessage() const; private: bool firstMessageReceived = false; - proto::SSL_Referee latestMessage; + proto::Referee latestMessage; }; #endif // RTT_REFEREEFILTER_H diff --git a/roboteam_world/observer/include/observer/parameters/RobotParameterDatabase.h b/roboteam_world/observer/include/observer/parameters/RobotParameterDatabase.h index f31e1fa13..fc12f2906 100644 --- a/roboteam_world/observer/include/observer/parameters/RobotParameterDatabase.h +++ b/roboteam_world/observer/include/observer/parameters/RobotParameterDatabase.h @@ -17,7 +17,7 @@ struct TwoTeamRobotParameters { }; class RobotParameterDatabase { public: - TwoTeamRobotParameters update(const proto::SSL_Referee& refMessage); + TwoTeamRobotParameters update(const proto::Referee& refMessage); [[nodiscard]] TwoTeamRobotParameters getParams() const; static RobotParameters getTeamParameters(const std::string& teamName); diff --git a/roboteam_world/observer/src/Observer.cpp b/roboteam_world/observer/src/Observer.cpp index 4b579b5a1..d051684b6 100644 --- a/roboteam_world/observer/src/Observer.cpp +++ b/roboteam_world/observer/src/Observer.cpp @@ -6,7 +6,7 @@ #include -proto::State Observer::process(const std::vector& visionPackets, const std::vector& refereePackets, +proto::State Observer::process(const std::vector& visionPackets, const std::vector& refereePackets, const std::vector& robotData) { updateRobotParams(refereePackets); proto::State state; @@ -29,7 +29,7 @@ proto::State Observer::process(const std::vector& visi state.mutable_field()->CopyFrom(geometry.value()); } - std::optional refMsg = refereeFilter.getLastRefereeMessage(); + std::optional refMsg = refereeFilter.getLastRefereeMessage(); if (refMsg) { state.mutable_referee()->CopyFrom(refMsg.value()); } @@ -39,7 +39,7 @@ proto::State Observer::process(const std::vector& visi packet->CopyFrom(visionPacket); } for (const auto& refpacket : refereePackets) { - proto::SSL_Referee* packet = state.add_processed_referee_packets(); + proto::Referee* packet = state.add_processed_referee_packets(); packet->CopyFrom(refpacket); } for (const auto& data : robotData) { @@ -48,13 +48,13 @@ proto::State Observer::process(const std::vector& visi return state; } -void Observer::updateRobotParams(std::vector refereePackets) { +void Observer::updateRobotParams(std::vector refereePackets) { // sort the referee packets; we only use the last one as there is no additional information in between packets - std::sort(refereePackets.begin(), refereePackets.end(), [](const proto::SSL_Referee& a, const proto::SSL_Referee& b) { return a.packet_timestamp() < b.packet_timestamp(); }); + std::sort(refereePackets.begin(), refereePackets.end(), [](const proto::Referee& a, const proto::Referee& b) { return a.packet_timestamp() < b.packet_timestamp(); }); TwoTeamRobotParameters parameters = !refereePackets.empty() ? parameterDatabase.update(refereePackets.back()) : parameterDatabase.getParams(); if (parameters.blueChanged || parameters.yellowChanged) { visionFilter.updateRobotParameters(parameters); } } -void Observer::updateReferee(const std::vector& refereePackets) { refereeFilter.process(refereePackets); } +void Observer::updateReferee(const std::vector& refereePackets) { refereeFilter.process(refereePackets); } diff --git a/roboteam_world/observer/src/filters/referee/RefereeFilter.cpp b/roboteam_world/observer/src/filters/referee/RefereeFilter.cpp index 7d140047e..1ac3a6b8e 100644 --- a/roboteam_world/observer/src/filters/referee/RefereeFilter.cpp +++ b/roboteam_world/observer/src/filters/referee/RefereeFilter.cpp @@ -4,17 +4,17 @@ #include "filters/referee/RefereeFilter.h" -void RefereeFilter::process(const std::vector &refereePackets) { +void RefereeFilter::process(const std::vector &refereePackets) { if (refereePackets.empty()) { return; } firstMessageReceived = true; auto packets = refereePackets; - std::sort(packets.begin(), packets.end(), [](const proto::SSL_Referee &a, const proto::SSL_Referee &b) { return a.packet_timestamp() < b.packet_timestamp(); }); + std::sort(packets.begin(), packets.end(), [](const proto::Referee &a, const proto::Referee &b) { return a.packet_timestamp() < b.packet_timestamp(); }); latestMessage = packets.back(); } -std::optional RefereeFilter::getLastRefereeMessage() const { +std::optional RefereeFilter::getLastRefereeMessage() const { if (firstMessageReceived) { return latestMessage; } else { diff --git a/roboteam_world/observer/src/parameters/RobotParameterDatabase.cpp b/roboteam_world/observer/src/parameters/RobotParameterDatabase.cpp index 353f188fb..36676d949 100644 --- a/roboteam_world/observer/src/parameters/RobotParameterDatabase.cpp +++ b/roboteam_world/observer/src/parameters/RobotParameterDatabase.cpp @@ -4,7 +4,7 @@ #include "parameters/RobotParameterDatabase.h" -TwoTeamRobotParameters RobotParameterDatabase::update(const proto::SSL_Referee &refMessage) { +TwoTeamRobotParameters RobotParameterDatabase::update(const proto::Referee &refMessage) { TwoTeamRobotParameters twoTeamParameters; if (refMessage.blue().name() != blueName) { twoTeamParameters.blueChanged = true; diff --git a/roboteam_world/src/Handler.cpp b/roboteam_world/src/Handler.cpp index 43e49c40a..18b5d18bd 100644 --- a/roboteam_world/src/Handler.cpp +++ b/roboteam_world/src/Handler.cpp @@ -142,7 +142,7 @@ bool Handler::setupSSLClients(std::string visionip, std::string refereeip, int v if (refereeAddress.isNull()) std::cout << "Error! Invalid referee ip-address: " << refereeip << std::endl; this->vision_client = std::make_unique>(visionAddress, visionport); - this->referee_client = std::make_unique>(refereeAddress, refereeport); + this->referee_client = std::make_unique>(refereeAddress, refereeport); success &= vision_client != nullptr && referee_client != nullptr; @@ -161,8 +161,8 @@ std::vector Handler::receiveVisionPackets() { } return receivedPackets; } -std::vector Handler::receiveRefereePackets() { - std::vector receivedPackets; +std::vector Handler::receiveRefereePackets() { + std::vector receivedPackets; bool ok = referee_client->receive(receivedPackets); if (!ok) { std::cout << "error receiving referee messages" << std::endl; @@ -188,7 +188,7 @@ void Handler::startReplay(rtt::LogFileReader& reader) { } std::vector visionPackets(state.processed_vision_packets().begin(), state.processed_vision_packets().end()); - std::vector refereePackets(state.processed_referee_packets().begin(), state.processed_referee_packets().end()); + std::vector refereePackets(state.processed_referee_packets().begin(), state.processed_referee_packets().end()); std::vector feedbackPackets; for (const auto& feedback : state.processed_feedback_packets()) { feedbackPackets.push_back(rtt::net::protoFeedbackToRobotsFeedback(feedback));