From 3893533cf84778b049ee1b807b8f612af2c68d4b Mon Sep 17 00:00:00 2001 From: rolf Date: Mon, 15 Feb 2021 23:41:40 +0100 Subject: [PATCH 01/40] Refactor Playdecider to be less static --- CMakeLists.txt | 2 ++ include/roboteam_ai/AI.h | 12 ++++++++++++ include/roboteam_ai/stp/PlayDecider.hpp | 6 +++--- src/AI.cpp | 5 +++++ src/ApplicationManager.cpp | 4 ++-- src/interface/widgets/MainControlsWidget.cpp | 2 +- src/stp/PlayDecider.cpp | 4 ++-- src/utilities/Settings.cpp | 2 +- 8 files changed, 28 insertions(+), 9 deletions(-) create mode 100644 include/roboteam_ai/AI.h create mode 100644 src/AI.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index e3661fbd2d..3518d3648f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -249,6 +249,8 @@ set(WORLD_SOURCES # Putting it all together so we can use it in both the main executable and the test executable set(AI_SOURCES ${PROJECT_SOURCE_DIR}/src/ApplicationManager.cpp + src/AI.cpp + src/UIListener.cpp ${UTILS_SOURCES} ${SKILLS_SOURCES} ${TACTICS_SOURCES} diff --git a/include/roboteam_ai/AI.h b/include/roboteam_ai/AI.h new file mode 100644 index 0000000000..832f28d1da --- /dev/null +++ b/include/roboteam_ai/AI.h @@ -0,0 +1,12 @@ +// +// Created by rolf on 15-02-21. +// + +#ifndef RTT_ROBOTEAM_AI_SRC_AI_H_ +#define RTT_ROBOTEAM_AI_SRC_AI_H_ + +class AI { + +}; + +#endif //RTT_ROBOTEAM_AI_SRC_AI_H_ diff --git a/include/roboteam_ai/stp/PlayDecider.hpp b/include/roboteam_ai/stp/PlayDecider.hpp index 4c12e61b3a..cab51ed08a 100644 --- a/include/roboteam_ai/stp/PlayDecider.hpp +++ b/include/roboteam_ai/stp/PlayDecider.hpp @@ -17,16 +17,16 @@ class PlayDecider { /** * play that's set from the interface in case it's overridden */ - static inline Play *interfacePlay; + Play *interfacePlay; public: /** * Sets the locked play, read variable above * @param play Play to lock to */ - static void lockInterfacePlay(Play *play); + void lockInterfacePlay(Play *play); - static bool interfacePlayChanged; + bool interfacePlayChanged = false; /** * This function checks if there is a locked play. If there is, pick that play. diff --git a/src/AI.cpp b/src/AI.cpp new file mode 100644 index 0000000000..f82a219375 --- /dev/null +++ b/src/AI.cpp @@ -0,0 +1,5 @@ +// +// Created by rolf on 15-02-21. +// + +#include "AI.h" diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index d5be1fbc2c..03f0bf105e 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -155,12 +155,12 @@ void ApplicationManager::decidePlay(world::World *_world) { playChecker.update(_world); // Here for manual change with the interface - if(rtt::ai::stp::PlayDecider::interfacePlayChanged) { + if(playDecider.interfacePlayChanged) { auto validPlays = playChecker.getValidPlays(); currentPlay = playDecider.decideBestPlay(_world, validPlays); currentPlay->updateWorld(_world); currentPlay->initialize(); - rtt::ai::stp::PlayDecider::interfacePlayChanged = false; + playDecider.interfacePlayChanged = false; } // A new play will be chosen if the current play is not valid to keep diff --git a/src/interface/widgets/MainControlsWidget.cpp b/src/interface/widgets/MainControlsWidget.cpp index db581c5d8b..a14bba0e67 100644 --- a/src/interface/widgets/MainControlsWidget.cpp +++ b/src/interface/widgets/MainControlsWidget.cpp @@ -101,7 +101,7 @@ MainControlsWidget::MainControlsWidget(QWidget *parent, ApplicationManager *appM return; } // simply manager->plays[index] because they're inserted in-order - stp::PlayDecider::lockInterfacePlay(manager->plays[index].get()); + stp::PlayDecider::lockInterfacePlay(manager->plays[index].get()); //TODO: make button in new interface }); QObject::connect(select_goalie, static_cast(&QComboBox::activated), [=](const QString &goalieId) { diff --git a/src/stp/PlayDecider.cpp b/src/stp/PlayDecider.cpp index b05384afe9..2fb0c258e3 100644 --- a/src/stp/PlayDecider.cpp +++ b/src/stp/PlayDecider.cpp @@ -6,7 +6,7 @@ namespace rtt::ai::stp { - bool PlayDecider::interfacePlayChanged = false; + Play *PlayDecider::decideBestPlay(world::World *pWorld, std::vector plays) noexcept { if (interfacePlay) { @@ -17,7 +17,7 @@ namespace rtt::ai::stp { // This is only used by the interface to force new plays void PlayDecider::lockInterfacePlay(Play *play) { - PlayDecider::interfacePlayChanged = true; + interfacePlayChanged = true; interfacePlay = play; } } // namespace rtt::ai::stp \ No newline at end of file diff --git a/src/utilities/Settings.cpp b/src/utilities/Settings.cpp index cacbe71443..5e10c9661a 100644 --- a/src/utilities/Settings.cpp +++ b/src/utilities/Settings.cpp @@ -1,4 +1,4 @@ -// +/// // Created by mrlukasbos on 1-9-19. // From 199478484935dec38f9bcbc3bf3cc38c3f76e355 Mon Sep 17 00:00:00 2001 From: rolf Date: Mon, 22 Feb 2021 20:44:42 +0100 Subject: [PATCH 02/40] remove IOManager global --- CMakeLists.txt | 1 - include/roboteam_ai/AI.h | 34 ++++- include/roboteam_ai/ApplicationManager.h | 32 +---- include/roboteam_ai/control/ControlModule.h | 3 +- include/roboteam_ai/utilities/IOManager.h | 2 - src/AI.cpp | 92 +++++++++++++ src/ApplicationManager.cpp | 132 ++++++------------- src/control/ControlModule.cpp | 4 +- src/interface/widgets/MainControlsWidget.cpp | 8 +- src/interface/widgets/PlaysWidget.cpp | 14 +- src/roboteam_ai.cpp | 38 +----- src/utilities/Pause.cpp | 2 +- 12 files changed, 189 insertions(+), 173 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 3518d3648f..11557d0283 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -250,7 +250,6 @@ set(WORLD_SOURCES set(AI_SOURCES ${PROJECT_SOURCE_DIR}/src/ApplicationManager.cpp src/AI.cpp - src/UIListener.cpp ${UTILS_SOURCES} ${SKILLS_SOURCES} ${TACTICS_SOURCES} diff --git a/include/roboteam_ai/AI.h b/include/roboteam_ai/AI.h index 832f28d1da..86d1450bd7 100644 --- a/include/roboteam_ai/AI.h +++ b/include/roboteam_ai/AI.h @@ -5,8 +5,40 @@ #ifndef RTT_ROBOTEAM_AI_SRC_AI_H_ #define RTT_ROBOTEAM_AI_SRC_AI_H_ +#include "stp/PlayChecker.hpp" +#include "stp/PlayDecider.hpp" + +namespace rtt { class AI { + public: + AI(); -}; + void decidePlay(world::World *_world); + + private: + /** + * Current best play as picked by checker + decider + */ + rtt::ai::stp::Play *currentPlay{nullptr}; + /** + * Checks which plays are valid out of all the plays + */ + rtt::ai::stp::PlayChecker playChecker; + /** + * Checks, out of the valid plays, which play is the best to choose + */ + rtt::ai::stp::PlayDecider playDecider; + /** + * Function that decides whether to change plays given a world and field. + * @param _world the current world state + * @param field the current field state + */ + + /** + * The vector that contains all plays + */ + std::vector> plays; +}; +} #endif //RTT_ROBOTEAM_AI_SRC_AI_H_ diff --git a/include/roboteam_ai/ApplicationManager.h b/include/roboteam_ai/ApplicationManager.h index 6c2fff5a81..a35b30a1c4 100644 --- a/include/roboteam_ai/ApplicationManager.h +++ b/include/roboteam_ai/ApplicationManager.h @@ -8,8 +8,8 @@ #include #include "interface/widgets/mainWindow.h" -#include "stp/PlayChecker.hpp" -#include "stp/PlayDecider.hpp" +#include "AI.h" +#include "utilities/IOManager.h" namespace rtt { @@ -24,34 +24,12 @@ class ApplicationManager { bool fieldInitialized = false; bool robotsInitialized = false; ai::interface::MainWindow* mainWindow; + std::unique_ptr ai; + std::unique_ptr io; - /** - * Current best play as picked by checker + decider - */ - ai::stp::Play* currentPlay{nullptr}; - - /** - * Checks which plays are valid out of all the plays - */ - rtt::ai::stp::PlayChecker playChecker; - /** - * Checks, out of the valid plays, which play is the best to choose - */ - rtt::ai::stp::PlayDecider playDecider; - /** - * Function that decides whether to change plays given a world and field. - * @param _world the current world state - * @param field the current field state - */ - void decidePlay(world::World* _world); public: - void start(); - - /** - * The vector that contains all plays - */ - static inline std::vector> plays; + void start(int ai_id); ApplicationManager(ApplicationManager const&) = delete; ApplicationManager& operator=(ApplicationManager const&) = delete; diff --git a/include/roboteam_ai/control/ControlModule.h b/include/roboteam_ai/control/ControlModule.h index 3b904f5517..4b4b385a43 100644 --- a/include/roboteam_ai/control/ControlModule.h +++ b/include/roboteam_ai/control/ControlModule.h @@ -9,6 +9,7 @@ #include "stp/StpInfo.h" #include "world/views/RobotView.hpp" +#include "utilities/IOManager.h" namespace rtt::ai::control { @@ -54,7 +55,7 @@ namespace rtt::ai::control { /** * */ - static void sendAllCommands(); + static void sendAllCommands(std::unique_ptr& io); }; } // namespace rtt::ai::control diff --git a/include/roboteam_ai/utilities/IOManager.h b/include/roboteam_ai/utilities/IOManager.h index cd2c6fba60..0eaa2ae534 100644 --- a/include/roboteam_ai/utilities/IOManager.h +++ b/include/roboteam_ai/utilities/IOManager.h @@ -50,8 +50,6 @@ class IOManager { std::mutex stateMutex; }; - extern IOManager io; - } // namespace io } // namespace rtt::ai diff --git a/src/AI.cpp b/src/AI.cpp index f82a219375..3bc7dbceec 100644 --- a/src/AI.cpp +++ b/src/AI.cpp @@ -3,3 +3,95 @@ // #include "AI.h" + +/** + * Plays are included here + */ +#include "stp/plays/AggressiveStopFormation.h" +#include "stp/plays/Attack.h" +#include "stp/plays/AttackingPass.h" +#include "stp/plays/BallPlacementThem.h" +#include "stp/plays/BallPlacementUs.h" +#include "stp/plays/DefendPass.h" +#include "stp/plays/DefendShot.h" +#include "stp/plays/DefensiveStopFormation.h" +#include "stp/plays/FreeKickThem.h" +#include "stp/plays/GenericPass.h" +#include "stp/plays/GetBallPossession.h" +#include "stp/plays/GetBallRisky.h" +#include "stp/plays/Halt.h" +#include "stp/plays/KickOffThem.h" +#include "stp/plays/KickOffThemPrepare.h" +#include "stp/plays/KickOffUs.h" +#include "stp/plays/KickOffUsPrepare.h" +#include "stp/plays/PenaltyThem.h" +#include "stp/plays/PenaltyThemPrepare.h" +#include "stp/plays/PenaltyUs.h" +#include "stp/plays/PenaltyUsPrepare.h" +#include "stp/plays/ReflectKick.h" +#include "stp/plays/TestPlay.h" +#include "stp/plays/TimeOut.h" + +rtt::AI::AI() { + plays = std::vector>{}; + + /// This play is only used for testing purposes, when needed uncomment this play! + // plays.emplace_back(std::make_unique()); + + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + plays.emplace_back(std::make_unique()); + playChecker.setPlays(plays); + +} +void rtt::AI::decidePlay(rtt::world::World *_world) { + playChecker.update(_world); + + // Here for manual change with the interface + if(playDecider.interfacePlayChanged) { + auto validPlays = playChecker.getValidPlays(); + currentPlay = playDecider.decideBestPlay(_world, validPlays); + currentPlay->updateWorld(_world); + currentPlay->initialize(); + playDecider.interfacePlayChanged = false; + } + + // A new play will be chosen if the current play is not valid to keep + if (!currentPlay || !currentPlay->isValidPlayToKeep(_world)) { + auto validPlays = playChecker.getValidPlays(); + if (validPlays.empty()) { + RTT_ERROR("No valid plays") + currentPlay = playChecker.getPlayForName("Defend Shot"); //TODO Try out different default plays so both teams dont get stuck in Defend Shot when playing against yourself + if (!currentPlay) { + return; + } + } else { + currentPlay = playDecider.decideBestPlay(_world, validPlays); + } + currentPlay->updateWorld(_world); + currentPlay->initialize(); + } + + currentPlay->update(); + //mainWindow->updatePlay(currentPlay); TODO: send to interface +} diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index 03f0bf105e..1906abf4ca 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -7,33 +7,6 @@ #include "utilities/IOManager.h" #include "control/ControlModule.h" -/** - * Plays are included here - */ -#include "stp/plays/AggressiveStopFormation.h" -#include "stp/plays/Attack.h" -#include "stp/plays/AttackingPass.h" -#include "stp/plays/BallPlacementThem.h" -#include "stp/plays/BallPlacementUs.h" -#include "stp/plays/DefendPass.h" -#include "stp/plays/DefendShot.h" -#include "stp/plays/DefensiveStopFormation.h" -#include "stp/plays/FreeKickThem.h" -#include "stp/plays/GenericPass.h" -#include "stp/plays/GetBallPossession.h" -#include "stp/plays/GetBallRisky.h" -#include "stp/plays/Halt.h" -#include "stp/plays/KickOffThem.h" -#include "stp/plays/KickOffThemPrepare.h" -#include "stp/plays/KickOffUs.h" -#include "stp/plays/KickOffUsPrepare.h" -#include "stp/plays/PenaltyThem.h" -#include "stp/plays/PenaltyThemPrepare.h" -#include "stp/plays/PenaltyUs.h" -#include "stp/plays/PenaltyUsPrepare.h" -#include "stp/plays/ReflectKick.h" -#include "stp/plays/TestPlay.h" -#include "stp/plays/TimeOut.h" namespace io = rtt::ai::io; namespace ai = rtt::ai; @@ -41,41 +14,41 @@ namespace ai = rtt::ai; namespace rtt { /// Start running behaviour trees. While doing so, publish settings and log the FPS of the system -void ApplicationManager::start() { - // make sure we start in halt state for safety +void ApplicationManager::start(int id) { + io = std::make_unique(); + rtt::ai::Constants::init(); + RTT_INFO("This AI is initialized with id ", id) + // some default settings for different team ids (saves time while testing) + if (id == 1) { + // standard blue team on right + rtt::SETTINGS.init(id); + rtt::SETTINGS.setYellow(false); + rtt::SETTINGS.setLeft(false); + RTT_INFO("Initially playing as the BLUE team") + RTT_INFO("We are playing on the RIGHT side of the field") + } else { + // standard yellow team on left + rtt::SETTINGS.init(id); + rtt::SETTINGS.setYellow(true); + rtt::SETTINGS.setLeft(true); + RTT_INFO("Initially playing as the YELLOW team") + RTT_INFO("We are playing on the LEFT side of the field") + } + + rtt::SETTINGS.setSerialMode(false); + rtt::SETTINGS.setVisionIp("127.0.0.1"); + rtt::SETTINGS.setVisionPort(10006); + rtt::SETTINGS.setRefereeIp("224.5.23.1"); + rtt::SETTINGS.setRefereePort(10003); + rtt::SETTINGS.setRobothubSendIp("127.0.0.1"); + rtt::SETTINGS.setRobothubSendPort(20011); + io->init(rtt::SETTINGS.getId()); + + // make sure we start in halt state for safety ai::GameStateManager::forceNewGameState(RefCommand::HALT, std::nullopt); RTT_INFO("Start looping") RTT_INFO("Waiting for field_data and robots...") - - plays = std::vector>{}; - - /// This play is only used for testing purposes, when needed uncomment this play! - // plays.emplace_back(std::make_unique()); - - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - plays.emplace_back(std::make_unique()); - playChecker.setPlays(plays); + ai = std::make_unique(); int amountOfCycles = 0; roboteam_utils::Timer t; @@ -99,14 +72,14 @@ void ApplicationManager::start() { fpsUpdateRate); // publish settings, but limit this function call to only run 1 times/s at most - t.limit([&]() { io::io.publishSettings(SETTINGS.toMessage()); }, 1); + t.limit([&]() { io->publishSettings(SETTINGS.toMessage()); }, 1); }, ai::Constants::TICK_RATE()); } /// Run everything with regard to behaviour trees void ApplicationManager::runOneLoopCycle() { - auto state = io::io.getState(); + auto state = io->getState(); if (state.has_field()) { if (!fieldInitialized) RTT_SUCCESS("Received first field message!") fieldInitialized = true; @@ -131,7 +104,7 @@ void ApplicationManager::runOneLoopCycle() { world->updatePositionControl(); //world->updateFeedback(feedbackMap); - decidePlay(world); + ai->decidePlay(world); } else { if (robotsInitialized) { @@ -147,41 +120,12 @@ void ApplicationManager::runOneLoopCycle() { } std::this_thread::sleep_for(std::chrono::milliseconds(100)); } - rtt::ai::control::ControlModule::sendAllCommands(); - io::io.handleCentralServerConnection(); + //TODO: move to AI + rtt::ai::control::ControlModule::sendAllCommands(io); + io->handleCentralServerConnection(); } -void ApplicationManager::decidePlay(world::World *_world) { - playChecker.update(_world); - - // Here for manual change with the interface - if(playDecider.interfacePlayChanged) { - auto validPlays = playChecker.getValidPlays(); - currentPlay = playDecider.decideBestPlay(_world, validPlays); - currentPlay->updateWorld(_world); - currentPlay->initialize(); - playDecider.interfacePlayChanged = false; - } - // A new play will be chosen if the current play is not valid to keep - if (!currentPlay || !currentPlay->isValidPlayToKeep(_world)) { - auto validPlays = playChecker.getValidPlays(); - if (validPlays.empty()) { - RTT_ERROR("No valid plays") - currentPlay = playChecker.getPlayForName("Defend Shot"); //TODO Try out different default plays so both teams dont get stuck in Defend Shot when playing against yourself - if (!currentPlay) { - return; - } - } else { - currentPlay = playDecider.decideBestPlay(_world, validPlays); - } - currentPlay->updateWorld(_world); - currentPlay->initialize(); - } - - currentPlay->update(); - mainWindow->updatePlay(currentPlay); -} ApplicationManager::ApplicationManager(ai::interface::MainWindow *mainWindow) { this->mainWindow = mainWindow; } } // namespace rtt diff --git a/src/control/ControlModule.cpp b/src/control/ControlModule.cpp index 1a0bc6033b..01b0979b5c 100644 --- a/src/control/ControlModule.cpp +++ b/src/control/ControlModule.cpp @@ -77,9 +77,9 @@ namespace rtt::ai::control { } } - void ControlModule::sendAllCommands() { + void ControlModule::sendAllCommands(std::unique_ptr&io) { //TODO: check for double commands - io::io.publishAllRobotCommands(robotCommands); // When vector has all commands, send in one go + io->publishAllRobotCommands(robotCommands); // When vector has all commands, send in one go robotCommands.clear(); } } // namespace rtt::ai::stp \ No newline at end of file diff --git a/src/interface/widgets/MainControlsWidget.cpp b/src/interface/widgets/MainControlsWidget.cpp index a14bba0e67..dc618ea06e 100644 --- a/src/interface/widgets/MainControlsWidget.cpp +++ b/src/interface/widgets/MainControlsWidget.cpp @@ -101,7 +101,8 @@ MainControlsWidget::MainControlsWidget(QWidget *parent, ApplicationManager *appM return; } // simply manager->plays[index] because they're inserted in-order - stp::PlayDecider::lockInterfacePlay(manager->plays[index].get()); //TODO: make button in new interface + + //stp::PlayDecider::lockInterfacePlay(manager->plays[index].get()); //TODO: make button in new interface }); QObject::connect(select_goalie, static_cast(&QComboBox::activated), [=](const QString &goalieId) { @@ -210,10 +211,7 @@ void MainControlsWidget::updateContents() { } void MainControlsWidget::updatePlays() { - select_play->clear(); - for (auto const &each : manager->plays) { - select_play->addItem(each->getName()); - } + } void MainControlsWidget::setIgnoreInvariants(bool ignore) { diff --git a/src/interface/widgets/PlaysWidget.cpp b/src/interface/widgets/PlaysWidget.cpp index 7edc9aef2e..b6a97d2992 100644 --- a/src/interface/widgets/PlaysWidget.cpp +++ b/src/interface/widgets/PlaysWidget.cpp @@ -65,12 +65,12 @@ namespace rtt::ai::interface { * start: */ void PlaysWidget::updatePlays() { - QString ss = {}; - for (auto& each : ApplicationManager::plays) { - ss += formatPlay(each.get()); - } - auto sliderPos = verticalScrollBar()->sliderPosition(); - setHtml(ss); - verticalScrollBar()->setSliderPosition(sliderPos); +// QString ss = {}; +// for (auto& each : ApplicationManager::plays) { +// ss += formatPlay(each.get()); +// } +// auto sliderPos = verticalScrollBar()->sliderPosition(); +// setHtml(ss); +// verticalScrollBar()->setSliderPosition(sliderPos); } } diff --git a/src/roboteam_ai.cpp b/src/roboteam_ai.cpp index 8f18c777d3..5548812683 100644 --- a/src/roboteam_ai.cpp +++ b/src/roboteam_ai.cpp @@ -7,9 +7,9 @@ namespace ui = rtt::ai::interface; ui::MainWindow* window; -void runStp() { +void run_application(int ai_id) { rtt::ApplicationManager app{ window }; - app.start(); + app.start(ai_id); } void setDarkTheme() { @@ -45,52 +45,26 @@ int main(int argc, char* argv[]) { RTT_DEBUG("Debug prints enabled") - rtt::ai::Constants::init(); + // get the id of the ai from the init int id = 0; if (argc == 2) { id = *argv[1] - '0'; } - RTT_INFO("This AI is initialized with id ", id) - // some default settings for different team ids (saves time while testing) - if (id == 1) { - // standard blue team on right - rtt::SETTINGS.init(id); - rtt::SETTINGS.setYellow(false); - rtt::SETTINGS.setLeft(false); - RTT_INFO("Initially playing as the BLUE team") - RTT_INFO("We are playing on the RIGHT side of the field") - } else { - // standard yellow team on left - rtt::SETTINGS.init(id); - rtt::SETTINGS.setYellow(true); - rtt::SETTINGS.setLeft(true); - RTT_INFO("Initially playing as the YELLOW team") - RTT_INFO("We are playing on the LEFT side of the field") - } - - rtt::SETTINGS.setSerialMode(false); - rtt::SETTINGS.setVisionIp("127.0.0.1"); - rtt::SETTINGS.setVisionPort(10006); - rtt::SETTINGS.setRefereeIp("224.5.23.1"); - rtt::SETTINGS.setRefereePort(10003); - rtt::SETTINGS.setRobothubSendIp("127.0.0.1"); - rtt::SETTINGS.setRobothubSendPort(20011); - - rtt::ai::io::io.init(rtt::SETTINGS.getId()); // initialize the interface QApplication a(argc, argv); QCoreApplication::setAttribute(Qt::AA_EnableHighDpiScaling); setDarkTheme(); + std::thread app_thread = std::thread(&run_application,id); // Todo make this a not-global-static thingy window = new ui::MainWindow{ }; window->setWindowState(Qt::WindowMaximized); - std::thread stpThread = std::thread(&runStp); window->show(); - return a.exec(); + bool result = a.exec(); + return result; } diff --git a/src/utilities/Pause.cpp b/src/utilities/Pause.cpp index 9dfcebda57..0903ef5cbb 100644 --- a/src/utilities/Pause.cpp +++ b/src/utilities/Pause.cpp @@ -27,7 +27,7 @@ void Pause::haltRobots(rtt::world::World const* data) { cmd.set_w(static_cast(robot->getAngle())); commands.push_back(std::move(cmd)); } - io::io.publishAllRobotCommands(commands); + //io::io.publishAllRobotCommands(commands);TODO: replace } void Pause::setPause(bool set) { std::lock_guard lock(pauseLock); From 3a565bd96555cc77643ea8510a0939c73a17eac0 Mon Sep 17 00:00:00 2001 From: rolf Date: Mon, 22 Feb 2021 21:06:49 +0100 Subject: [PATCH 03/40] Remove interface input visualizations --- CMakeLists.txt | 2 - include/roboteam_ai/interface/api/Input.h | 64 ----------------- .../interface/widgets/GraphWidget.h | 29 -------- .../interface/widgets/mainWindow.h | 2 - include/roboteam_ai/world/FieldComputations.h | 1 - src/ApplicationManager.cpp | 1 - .../positionControl/PositionControl.cpp | 7 +- src/interface/api/Input.cpp | 63 ----------------- src/interface/widgets/GraphWidget.cpp | 69 ------------------- src/interface/widgets/STPVisualizerWidget.cpp | 1 + src/interface/widgets/mainWindow.cpp | 6 +- src/interface/widgets/widget.cpp | 67 ------------------ src/roboteam_ai.cpp | 3 +- src/utilities/IOManager.cpp | 1 - src/world/Ball.cpp | 7 +- src/world/FieldComputations.cpp | 6 +- 16 files changed, 15 insertions(+), 314 deletions(-) delete mode 100644 include/roboteam_ai/interface/api/Input.h delete mode 100644 include/roboteam_ai/interface/widgets/GraphWidget.h delete mode 100644 src/interface/api/Input.cpp delete mode 100644 src/interface/widgets/GraphWidget.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 11557d0283..ea888b00e9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -204,7 +204,6 @@ set(TEST_SOURCES set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/src/interface/widgets/mainWindow.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/widget.cpp - ${PROJECT_SOURCE_DIR}/src/interface/api/Input.cpp ${PROJECT_SOURCE_DIR}/src/interface/api/Output.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/STPVisualizerWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/RobotsWidget.cpp @@ -214,7 +213,6 @@ set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/src/interface/widgets/VisualizationSettingsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/api/Toggles.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/RuleSetWidget.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/GraphWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/SettingsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/ManualControlWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/PlaysWidget.cpp diff --git a/include/roboteam_ai/interface/api/Input.h b/include/roboteam_ai/interface/api/Input.h deleted file mode 100644 index c593c0cb35..0000000000 --- a/include/roboteam_ai/interface/api/Input.h +++ /dev/null @@ -1,64 +0,0 @@ -// -// Created by mrlukasbos on 4-12-18. -// - -#ifndef ROBOTEAM_AI_INPUT_H -#define ROBOTEAM_AI_INPUT_H - -#include -#include -#include -#include -#include -#include "Toggles.h" - -namespace rtt::ai::interface { - -/* - * For drawing to the interface we keep 'drawings' to draw data to the screen. - * a drawing represents a vector of points and some specifications on how to display those. - * e.g: form, color, size, and depth. - */ -struct Drawing { - enum DrawingMethod { LINES_CONNECTED, DOTS, CROSSES, CIRCLES, PLUSSES, ARROWS, REAL_LIFE_DOTS, REAL_LIFE_CIRCLES }; - - Drawing(Visual visual, std::vector points, QColor color, int robotId = -1, DrawingMethod method = DOTS, double width = 0.0, double height = 0.0, - double strokeWidth = 0.0) - : visual(visual), points(std::move(points)), color(std::move(color)), robotId(robotId), method(method), width(width), height(height), strokeWidth(strokeWidth){}; - - Visual visual; - std::vector points; - QColor color; - int robotId; - DrawingMethod method; - - // these values are used for dots, crosses and circles - double width = 4.0; - double height = 4.0; - double strokeWidth = 2.0; -}; - -class Input { - public: - explicit Input(); - virtual ~Input(); - - static void clearDrawings(); - static const std::vector getDrawings(); - static void drawData(Visual visual, std::vector points, QColor color, int robotId = -1, Drawing::DrawingMethod method = Drawing::DOTS, double width = 4.0, - double height = 4.0, double strokeWidth = 2.0); - static void drawDebugData(std::vector points, QColor color = Qt::yellow, int robotId = -1, Drawing::DrawingMethod method = Drawing::DOTS, double width = 4.0, - double height = 4.0, double strokeWidth = 4.0); - static int getFps(); - static void setFps(int fps); - - private: - static std::vector drawings; - static std::mutex drawingMutex; - static std::mutex fpsMutex; - static int FPS; -}; - -} // namespace rtt::ai::interface - -#endif // ROBOTEAM_AI_INPUT_H diff --git a/include/roboteam_ai/interface/widgets/GraphWidget.h b/include/roboteam_ai/interface/widgets/GraphWidget.h deleted file mode 100644 index 8abdf33782..0000000000 --- a/include/roboteam_ai/interface/widgets/GraphWidget.h +++ /dev/null @@ -1,29 +0,0 @@ -// -// Created by mrlukasbos on 22-9-19. -// -#include - -#ifndef RTT_GRAPHWIDGET_H -#define RTT_GRAPHWIDGET_H - -namespace rtt::ai::interface { - -class GraphWidget : public QWidget { - Q_OBJECT - private: - float seriesIndex = 0; - float fpsGraphYMax = 0; - float fpsGraphXMin = 0; - float fpsGraphXMax = 0; - QChartView *fpsView; - QLineSeries *fpsSeries; - - public: - explicit GraphWidget(QWidget *parent = nullptr); - public slots: - void updateContents(); -}; - -} // namespace rtt::ai::interface - -#endif // RTT_GRAPHWIDGET_H diff --git a/include/roboteam_ai/interface/widgets/mainWindow.h b/include/roboteam_ai/interface/widgets/mainWindow.h index 914c3b0b51..655019a95c 100644 --- a/include/roboteam_ai/interface/widgets/mainWindow.h +++ b/include/roboteam_ai/interface/widgets/mainWindow.h @@ -18,7 +18,6 @@ #include #include -#include "GraphWidget.h" #include "ManualControlWidget.h" #include "PidBox.h" #include "QColor" @@ -73,7 +72,6 @@ class MainWindow : public QMainWindow { STPVisualizerWidget *stpWidget; STPVisualizerWidget *keeperStpWidget; Visualizer *visualizer; - GraphWidget *graphWidget; PlaysWidget* playsWidget; // InvariantsWidget *invariantsWidget; }; diff --git a/include/roboteam_ai/world/FieldComputations.h b/include/roboteam_ai/world/FieldComputations.h index 64789f2ea3..eacd16414e 100644 --- a/include/roboteam_ai/world/FieldComputations.h +++ b/include/roboteam_ai/world/FieldComputations.h @@ -5,7 +5,6 @@ #include #include #include "control/ControlUtils.h" -#include "interface/api/Input.h" #include #include "world/Field.h" diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index 1906abf4ca..d9c91b5a18 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -66,7 +66,6 @@ void ApplicationManager::start(int id) { int fpsUpdateRate = 5; t.limit( [&]() { - ai::interface::Input::setFps(amountOfCycles * fpsUpdateRate); amountOfCycles = 0; }, fpsUpdateRate); diff --git a/src/control/positionControl/PositionControl.cpp b/src/control/positionControl/PositionControl.cpp index c5902b5857..9d8821f5a2 100644 --- a/src/control/positionControl/PositionControl.cpp +++ b/src/control/positionControl/PositionControl.cpp @@ -27,9 +27,10 @@ RobotCommand PositionControl::computeAndTrackPath(const rtt::world::Field &field computedPaths[robotId] = pathPlanningAlgorithm.computePath(currentPosition, targetPosition); } - interface::Input::drawData(interface::Visual::PATHFINDING, computedPaths[robotId], Qt::green, robotId, interface::Drawing::LINES_CONNECTED); - interface::Input::drawData(interface::Visual::PATHFINDING, {computedPaths[robotId].front(), currentPosition}, Qt::green, robotId, interface::Drawing::LINES_CONNECTED); - interface::Input::drawData(interface::Visual::PATHFINDING, computedPaths[robotId], Qt::blue, robotId, interface::Drawing::DOTS); + //TODO: replace with new interface +// interface::Input::drawData(interface::Visual::PATHFINDING, computedPaths[robotId], Qt::green, robotId, interface::Drawing::LINES_CONNECTED); +// interface::Input::drawData(interface::Visual::PATHFINDING, {computedPaths[robotId].front(), currentPosition}, Qt::green, robotId, interface::Drawing::LINES_CONNECTED); +// interface::Input::drawData(interface::Visual::PATHFINDING, computedPaths[robotId], Qt::blue, robotId, interface::Drawing::DOTS); RobotCommand command = RobotCommand(); command.pos = computedPaths[robotId].front(); diff --git a/src/interface/api/Input.cpp b/src/interface/api/Input.cpp deleted file mode 100644 index 671870a72d..0000000000 --- a/src/interface/api/Input.cpp +++ /dev/null @@ -1,63 +0,0 @@ -// -// Created by mrlukasbos on 4-12-18. -// - -#include "interface/api/Input.h" - -namespace rtt::ai::interface { - -// declare static variables -std::vector Input::drawings; -std::mutex Input::drawingMutex; -std::mutex Input::fpsMutex; - -int Input::FPS; - -/* - * Draw data to the screen - */ -void Input::drawData(Visual visual, std::vector points, QColor color, int robotId, Drawing::DrawingMethod method, double width, double height, double strokeWidth) { - if (method == Drawing::DrawingMethod::ARROWS) { - if (points.size() % 2 == 1) { - points.erase(points.end()); - } - } - std::lock_guard lock(drawingMutex); - drawings.emplace_back(visual, std::move(points), std::move(color), robotId, method, width, height, strokeWidth); -} - -/* - * Useful for debugging: quickly draw a vector of points. - */ -void Input::drawDebugData(std::vector points, QColor color, int robotId, Drawing::DrawingMethod method, double width, double height, double strokeWidth) { - std::lock_guard lock(drawingMutex); - drawings.emplace_back(Visual::DEBUG, std::move(points), std::move(color), robotId, method, width, height, strokeWidth); -} - -const std::vector Input::getDrawings() { - std::lock_guard lock(drawingMutex); - return drawings; -} - -void Input::clearDrawings() { - std::lock_guard drawingLock(drawingMutex); - drawings.clear(); -} - -Input::~Input() { clearDrawings(); } - -int Input::getFps() { - std::lock_guard lock(fpsMutex); - return FPS; -} - -void Input::setFps(int fps) { - std::lock_guard lock(fpsMutex); - FPS = fps; -} - -Input::Input() { - drawings.reserve(10000); -} - -} // namespace rtt::ai::interface \ No newline at end of file diff --git a/src/interface/widgets/GraphWidget.cpp b/src/interface/widgets/GraphWidget.cpp deleted file mode 100644 index e6c7e48d5e..0000000000 --- a/src/interface/widgets/GraphWidget.cpp +++ /dev/null @@ -1,69 +0,0 @@ -// -// Created by mrlukasbos on 22-9-19. -// - -#include "interface/widgets/GraphWidget.h" - -#include "interface/api/Input.h" - -namespace rtt::ai::interface { - -/* axisY() and axisX() are deprecated - * A non-deprecated method can be found here https://stackoverflow.com/questions/53812267/qtcharts-axisx-depreciated - * However, for some reason it gave segfaults the last time I tried this (jan 16 2020) - */ - -GraphWidget::GraphWidget(QWidget *parent) { - auto verticalLayout = new QVBoxLayout(this); - - fpsView = new QChartView(); - - fpsSeries = new QSplineSeries(); - fpsSeries->setUseOpenGL(); - fpsSeries->setColor(Qt::blue); - fpsSeries->setName("FPS"); - - fpsView->chart()->addSeries(fpsSeries); - fpsView->chart()->createDefaultAxes(); - fpsView->chart()->setMinimumHeight(300); - fpsView->chart()->setTheme(QChart::ChartThemeDark); - fpsView->chart()->setBackgroundBrush(QColor(53, 53, 53)); - fpsView->chart()->axisX()->setMinorGridLineColor(Qt::gray); - fpsView->chart()->axisY()->setGridLineVisible(true); - - connect(dynamic_cast(fpsSeries), &QSplineSeries::pointAdded, [=](int index) { - qreal y = fpsSeries->at(index).y(); - qreal x = fpsSeries->at(index).x(); - - if (y > fpsGraphYMax) { - if (y > fpsGraphYMax) fpsGraphYMax = y; - fpsView->chart()->axisX()->setRange(0, fpsGraphYMax + 20); - } - - if (x < fpsGraphXMin || x > fpsGraphXMax) { - if (x < fpsGraphXMin) - fpsGraphXMin = x; - if (x > fpsGraphXMax) - fpsGraphXMax = x; - - if (fpsGraphXMax - fpsGraphXMin > 30) { - fpsGraphXMin = fpsGraphXMax - 30; - } - fpsView->chart()->axisY()->setRange(fpsGraphXMin, fpsGraphXMax); - } - }); - - verticalLayout->addWidget(fpsView); - this->setLayout(verticalLayout); -} - -void GraphWidget::updateContents() { - fpsSeries->append(seriesIndex, Input::getFps()); - seriesIndex += 0.2; - fpsView->chart()->createDefaultAxes(); -} - -} // namespace rtt::ai::interface - -// QT performance improvement -#include "include/roboteam_ai/interface/widgets/moc_GraphWidget.cpp" diff --git a/src/interface/widgets/STPVisualizerWidget.cpp b/src/interface/widgets/STPVisualizerWidget.cpp index e865257ac0..764718084f 100644 --- a/src/interface/widgets/STPVisualizerWidget.cpp +++ b/src/interface/widgets/STPVisualizerWidget.cpp @@ -14,6 +14,7 @@ #include "interface/widgets/mainWindow.h" #include "stp/Play.hpp" +#include namespace rtt::ai::interface { constexpr static const char *tab = "    "; diff --git a/src/interface/widgets/mainWindow.cpp b/src/interface/widgets/mainWindow.cpp index e61feaae84..ba4b3980d9 100644 --- a/src/interface/widgets/mainWindow.cpp +++ b/src/interface/widgets/mainWindow.cpp @@ -5,7 +5,8 @@ #include "interface/widgets/MainControlsWidget.h" #include "interface/widgets/PidsWidget.h" #include "interface/widgets/VisualizationSettingsWidget.h" - +#include +#include namespace rtt::ai::interface { MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWindow(parent) { @@ -61,7 +62,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind // add the tab widget auto tabWidget = new QTabWidget; - graphWidget = new GraphWidget(this); playsWidget = new PlaysWidget(this); @@ -69,7 +69,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind DataTabWidget->addTab(behaviourTreeWidget, tr("STP states")); DataTabWidget->addTab(keeperStpWidget, tr("Keeper")); DataTabWidget->addTab(playsWidget, "Plays"); - DataTabWidget->addTab(graphWidget, tr("Charts")); DataTabWidget->addTab(robotsWidget, tr("Robots")); DataTabWidget->addTab(refWidget, tr("GameStateManager")); tabWidget->addTab(DataTabWidget, tr("Data")); @@ -115,7 +114,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind robotsTimer->start(500); // 2fps auto *graphTimer = new QTimer(this); - connect(graphTimer, SIGNAL(timeout()), graphWidget, SLOT(updateContents())); graphTimer->start(500); // 2fps connect(this, &MainWindow::updateStpWidgets, stpWidget, &STPVisualizerWidget::outputStpData); diff --git a/src/interface/widgets/widget.cpp b/src/interface/widgets/widget.cpp index f748eac2c4..dfd447720c 100644 --- a/src/interface/widgets/widget.cpp +++ b/src/interface/widgets/widget.cpp @@ -42,73 +42,6 @@ namespace rtt::ai::interface { drawRobots(painter, world.value()); if (world->getBall().has_value()) drawBall(painter, world->getBall().value()); - // draw the drawings from the input - auto drawings = Input::getDrawings(); - for (auto const &drawing : drawings) { - if (!drawing.points.empty()) { - bool shouldShow = false; - for (auto const &toggle : Toggles::toggles) { - if (drawing.visual == toggle.visual) { - shouldShow = shouldVisualize(toggle, drawing.robotId); - } - } - if (shouldShow) { - switch (drawing.method) { - case Drawing::DOTS: { - painter.setPen(Qt::NoPen); - painter.setBrush(drawing.color); - drawPoints(painter, drawing.points, drawing.width, drawing.height); - } - break; - case Drawing::CIRCLES: { - painter.setPen(drawing.color); - painter.setBrush(Qt::transparent); - drawPoints(painter, drawing.points, drawing.width, drawing.height); - } - break; - case Drawing::LINES_CONNECTED: { - painter.setPen(drawing.color); - painter.setBrush(Qt::transparent); - drawLines(painter, drawing.points); - } - break; - case Drawing::CROSSES: { - painter.setPen(drawing.color); - painter.setBrush(Qt::transparent); - drawCrosses(painter, drawing.points, drawing.width, drawing.height); - } - break; - case Drawing::PLUSSES: { - painter.setPen(drawing.color); - painter.setBrush(Qt::transparent); - drawPlusses(painter, drawing.points, drawing.width, drawing.height); - } - break; - case Drawing::ARROWS: { - painter.setPen(drawing.color); - painter.setBrush(Qt::transparent); - drawArrows(painter, drawing.points, drawing.width, drawing.height, - drawing.strokeWidth == 1); - } - break; - case Drawing::REAL_LIFE_CIRCLES: { - painter.setPen(drawing.color); - painter.setBrush(Qt::transparent); - drawRealLifeSizedPoints(painter, drawing.points, drawing.width, drawing.height); - } - break; - case Drawing::REAL_LIFE_DOTS: { - painter.setPen(Qt::NoPen); - painter.setBrush(drawing.color); - drawRealLifeSizedPoints(painter, drawing.points, drawing.width, drawing.height); - } - } - } - } - } - - Input::clearDrawings(); - if (showBallPlacementMarker) drawBallPlacementTarget(painter); } diff --git a/src/roboteam_ai.cpp b/src/roboteam_ai.cpp index 5548812683..73e97d0050 100644 --- a/src/roboteam_ai.cpp +++ b/src/roboteam_ai.cpp @@ -2,7 +2,8 @@ #include #include #include "ApplicationManager.h" - +#include +#include namespace ui = rtt::ai::interface; ui::MainWindow* window; diff --git a/src/utilities/IOManager.cpp b/src/utilities/IOManager.cpp index 3e3ceeb798..1f590847e4 100644 --- a/src/utilities/IOManager.cpp +++ b/src/utilities/IOManager.cpp @@ -3,7 +3,6 @@ #include -#include "interface/api/Input.h" #include "roboteam_utils/normalize.h" #include "utilities/Pause.h" #include "include/roboteam_ai/world/World.hpp" diff --git a/src/world/Ball.cpp b/src/world/Ball.cpp index 16952bf27c..2a875594d4 100644 --- a/src/world/Ball.cpp +++ b/src/world/Ball.cpp @@ -4,7 +4,6 @@ #include "include/roboteam_ai/world/Ball.hpp" -#include #include #include "include/roboteam_ai/world/World.hpp" @@ -106,9 +105,9 @@ void Ball::updateExpectedBallEndPosition(const world::World* data) noexcept { expectedEndPosition = ball->getPos() + ball->filteredVelocity.stretchToLength(ballVelSquared / frictionCoefficient); // Visualize the Expected Ball End Position - ai::interface::Input::drawData(ai::interface::Visual::BALL_DATA, {getExpectedEndPosition()}, ai::Constants::BALL_COLOR(), -1, ai::interface::Drawing::CIRCLES, 8, 8, 6); - ai::interface::Input::drawData(ai::interface::Visual::BALL_DATA, {position, getExpectedEndPosition()}, ai::Constants::BALL_COLOR(), -1, - ai::interface::Drawing::LINES_CONNECTED); +// ai::interface::Input::drawData(ai::interface::Visual::BALL_DATA, {getExpectedEndPosition()}, ai::Constants::BALL_COLOR(), -1, ai::interface::Drawing::CIRCLES, 8, 8, 6); +// ai::interface::Input::drawData(ai::interface::Visual::BALL_DATA, {position, getExpectedEndPosition()}, ai::Constants::BALL_COLOR(), -1, +// ai::interface::Drawing::LINES_CONNECTED); } void Ball::updateBallAtRobotPosition(const world::World* data) noexcept { diff --git a/src/world/FieldComputations.cpp b/src/world/FieldComputations.cpp index 19220deacf..dc35a3e9fc 100644 --- a/src/world/FieldComputations.cpp +++ b/src/world/FieldComputations.cpp @@ -115,7 +115,7 @@ Polygon FieldComputations::getDefenseArea(const rtt_world::Field &field, bool ou Vector2 topPenalty = ourDefenseArea ? field.getLeftPenaltyLineTop() + Vector2(margin, margin) : field.getRightPenaltyLineTop() + Vector2(-margin, margin); std::vector defenseArea = {bottomPenalty, topPenalty, aboveGoal, belowGoal}; - interface::Input::drawDebugData(defenseArea); +// interface::Input::drawDebugData(defenseArea); return Polygon(defenseArea); } @@ -127,14 +127,14 @@ Polygon FieldComputations::getGoalArea(const rtt_world::Field &field, bool ourGo Vector2 outerTopGoal = ourGoal ? field.getOurTopGoalSide() + Vector2(margin, margin) : field.getTheirTopGoalSide() + Vector2(-margin, margin); std::vector goalArea = {outerBottomGoal, innerBottomGoal, innerTopGoal, outerTopGoal}; - interface::Input::drawDebugData(goalArea, ourGoal ? Qt::green : Qt::red, interface::Drawing::LINES_CONNECTED); +// interface::Input::drawDebugData(goalArea, ourGoal ? Qt::green : Qt::red, interface::Drawing::LINES_CONNECTED); return Polygon(goalArea); } Polygon FieldComputations::getFieldEdge(const rtt_world::Field &field, double margin) { std::vector fieldEdge = {field.getBottomLeftCorner() + Vector2(-margin, -margin), field.getTopLeftCorner() + Vector2(-margin, margin), field.getTopRightCorner() + Vector2(margin, margin), field.getBottomRightCorner() + Vector2(margin, -margin)}; - interface::Input::drawDebugData(fieldEdge, Qt::red, interface::Drawing::LINES_CONNECTED); +// interface::Input::drawDebugData(fieldEdge, Qt::red, interface::Drawing::LINES_CONNECTED); return Polygon(fieldEdge); } From ab85b4e0ee750e3dee9739f1517b3f899df5694c Mon Sep 17 00:00:00 2001 From: rolf Date: Mon, 22 Feb 2021 21:46:23 +0100 Subject: [PATCH 04/40] Remove ruleset widget --- CMakeLists.txt | 2 - .../interface/widgets/RuleSetWidget.h | 30 ----------- .../interface/widgets/mainWindow.h | 2 - src/ApplicationManager.cpp | 11 ---- src/interface/widgets/RuleSetWidget.cpp | 50 ------------------- src/interface/widgets/mainWindow.cpp | 3 -- src/roboteam_ai.cpp | 1 - src/utilities/IOManager.cpp | 8 +-- 8 files changed, 4 insertions(+), 103 deletions(-) delete mode 100644 include/roboteam_ai/interface/widgets/RuleSetWidget.h delete mode 100644 src/interface/widgets/RuleSetWidget.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index ea888b00e9..9292f22c4d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -212,7 +212,6 @@ set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/src/interface/widgets/MainControlsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/VisualizationSettingsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/api/Toggles.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/RuleSetWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/SettingsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/ManualControlWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/PlaysWidget.cpp @@ -223,7 +222,6 @@ set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/MainControlsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/mainWindow.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/RobotsWidget.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/RuleSetWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/STPVisualizerWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/VisualizationSettingsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/widget.h diff --git a/include/roboteam_ai/interface/widgets/RuleSetWidget.h b/include/roboteam_ai/interface/widgets/RuleSetWidget.h deleted file mode 100644 index c7c4f610e2..0000000000 --- a/include/roboteam_ai/interface/widgets/RuleSetWidget.h +++ /dev/null @@ -1,30 +0,0 @@ -// -// Created by mrlukasbos on 15-5-19. -// - -#ifndef ROBOTEAM_AI_RULESETWIDGET_H -#define ROBOTEAM_AI_RULESETWIDGET_H - -#include -#include - -namespace rtt::ai::interface { - -class RuleSetWidget : public QWidget { - Q_OBJECT - - private: - QVBoxLayout *vLayout; - void updateLabels(); - QWidget *contentsWidget; - - public: - explicit RuleSetWidget(QWidget *parent = nullptr); - - public slots: - void updateContents(); -}; - -} // namespace rtt::ai::interface - -#endif // ROBOTEAM_AI_RULESETWIDGET_H diff --git a/include/roboteam_ai/interface/widgets/mainWindow.h b/include/roboteam_ai/interface/widgets/mainWindow.h index 655019a95c..ce92b789de 100644 --- a/include/roboteam_ai/interface/widgets/mainWindow.h +++ b/include/roboteam_ai/interface/widgets/mainWindow.h @@ -25,7 +25,6 @@ #include "QPushButton" #include "QTreeWidgetItemIterator" #include "RobotsWidget.h" -#include "RuleSetWidget.h" #include "STPVisualizerWidget.h" #include "widget.h" #include "PlaysWidget.hpp" @@ -67,7 +66,6 @@ class MainWindow : public QMainWindow { QVBoxLayout *mainLayout; QVBoxLayout *vLayout; RobotsWidget *robotsWidget; - RuleSetWidget *refWidget; ManualControlWidget *manualControlWidget; STPVisualizerWidget *stpWidget; STPVisualizerWidget *keeperStpWidget; diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index d9c91b5a18..6763127319 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -50,7 +50,6 @@ void ApplicationManager::start(int id) { RTT_INFO("Waiting for field_data and robots...") ai = std::make_unique(); - int amountOfCycles = 0; roboteam_utils::Timer t; t.loop( [&]() { @@ -60,16 +59,6 @@ void ApplicationManager::start(int id) { RTT_WARNING("Time: ", (std::clock() - start) / (double)(CLOCKS_PER_SEC / 1000), " ms") RTT_WARNING("Time allowed: 16 ms") - amountOfCycles++; - - // update the measured FPS, but limit this function call to only run 5 times/s at most - int fpsUpdateRate = 5; - t.limit( - [&]() { - amountOfCycles = 0; - }, - fpsUpdateRate); - // publish settings, but limit this function call to only run 1 times/s at most t.limit([&]() { io->publishSettings(SETTINGS.toMessage()); }, 1); }, diff --git a/src/interface/widgets/RuleSetWidget.cpp b/src/interface/widgets/RuleSetWidget.cpp deleted file mode 100644 index b25ffdfcb7..0000000000 --- a/src/interface/widgets/RuleSetWidget.cpp +++ /dev/null @@ -1,50 +0,0 @@ -// -// Created by mrlukasbos on 15-5-19. -// - -#include "interface/widgets/RuleSetWidget.h" - -#include -#include - -#include "interface/widgets/mainWindow.h" - -namespace rtt::ai::interface { - -RuleSetWidget::RuleSetWidget(QWidget *parent) { - vLayout = new QVBoxLayout(); - this->setLayout(vLayout); -} - -void RuleSetWidget::updateContents() { - MainWindow::clearLayout(vLayout); - updateLabels(); -} - -void RuleSetWidget::updateLabels() { - auto spacer = new QSpacerItem(100, 100, QSizePolicy::Expanding, QSizePolicy::Expanding); - - RuleSet ruleset = GameStateManager::getCurrentGameState().getRuleSet(); - - auto velLabel = new QLabel("Max robot velocity: " + QString::number(ruleset.maxRobotVel, 'G', 3) + " m/s"); - vLayout->addWidget(velLabel); - - auto maxBallVelLabel = new QLabel("Max ball velocity: " + QString::number(ruleset.maxBallVel, 'G', 3) + " m/s"); - vLayout->addWidget(maxBallVelLabel); - - auto distDefenceArea = new QLabel("Min distance to defense area " + QString::number(ruleset.minDistanceToDefenseArea, 'G', 3) + " m"); - vLayout->addWidget(distDefenceArea); - - auto enterDefenseLabel = new QLabel("Robots can enter defense area: " + (ruleset.robotsCanEnterDefenseArea() ? QString("true") : QString("false"))); - vLayout->addWidget(enterDefenseLabel); - - auto outOfFieldLabel = new QLabel("Robots can go out of field : " + (ruleset.robotsCanGoOutOfField ? QString("true") : QString("false"))); - vLayout->addWidget(outOfFieldLabel); - - auto touchBallLabel = new QLabel("Min distance to ball " + QString::number(ruleset.minDistanceToBall, 'G', 3) + " m"); - vLayout->addWidget(touchBallLabel); - - vLayout->addSpacerItem(spacer); -} - -} // namespace rtt::ai::interface diff --git a/src/interface/widgets/mainWindow.cpp b/src/interface/widgets/mainWindow.cpp index ba4b3980d9..e54d0084d9 100644 --- a/src/interface/widgets/mainWindow.cpp +++ b/src/interface/widgets/mainWindow.cpp @@ -56,7 +56,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind auto pidWidget = new PidsWidget(); robotsWidget = new RobotsWidget(this); - refWidget = new RuleSetWidget(this); manualControlWidget = new ManualControlWidget(this); // add the tab widget @@ -70,7 +69,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind DataTabWidget->addTab(keeperStpWidget, tr("Keeper")); DataTabWidget->addTab(playsWidget, "Plays"); DataTabWidget->addTab(robotsWidget, tr("Robots")); - DataTabWidget->addTab(refWidget, tr("GameStateManager")); tabWidget->addTab(DataTabWidget, tr("Data")); auto SettingsTabWidget = new QTabWidget; @@ -106,7 +104,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind // start the UI update cycles // these are slower than the tick rate auto *robotsTimer = new QTimer(this); - connect(robotsTimer, SIGNAL(timeout()), refWidget, SLOT(updateContents())); connect(robotsTimer, SIGNAL(timeout()), this, SLOT(updateRobotsWidget())); // we need to pass the visualizer so thats why a seperate function is used connect(robotsTimer, SIGNAL(timeout()), mainControlsWidget, SLOT(updatePause())); diff --git a/src/roboteam_ai.cpp b/src/roboteam_ai.cpp index 73e97d0050..3213ce78bc 100644 --- a/src/roboteam_ai.cpp +++ b/src/roboteam_ai.cpp @@ -1,6 +1,5 @@ #include #include -#include #include "ApplicationManager.h" #include #include diff --git a/src/utilities/IOManager.cpp b/src/utilities/IOManager.cpp index 1f590847e4..c3220e98b9 100644 --- a/src/utilities/IOManager.cpp +++ b/src/utilities/IOManager.cpp @@ -13,10 +13,10 @@ namespace rtt::ai::io { IOManager io; IOManager::~IOManager() { - delete worldSubscriber; - delete robotCommandPublisher; - delete settingsPublisher; - delete central_server_connection; + delete central_server_connection; + delete settingsPublisher; + delete robotCommandPublisher; + delete worldSubscriber; } void IOManager::init(int teamId) { From c7046c52fa88f6d01ba06a099e987f7c71c7c2a5 Mon Sep 17 00:00:00 2001 From: rolf Date: Mon, 22 Feb 2021 21:50:04 +0100 Subject: [PATCH 05/40] Remove playswidget --- CMakeLists.txt | 2 - .../interface/widgets/PlaysWidget.hpp | 32 -------- .../interface/widgets/mainWindow.h | 2 - src/interface/widgets/PlaysWidget.cpp | 76 ------------------- src/interface/widgets/mainWindow.cpp | 3 - 5 files changed, 115 deletions(-) delete mode 100644 include/roboteam_ai/interface/widgets/PlaysWidget.hpp delete mode 100644 src/interface/widgets/PlaysWidget.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 9292f22c4d..b992d352c4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -214,7 +214,6 @@ set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/src/interface/api/Toggles.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/SettingsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/ManualControlWidget.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/PlaysWidget.cpp #QT wants to know about these headers ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/PidBox.h @@ -227,7 +226,6 @@ set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/widget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/SettingsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/ManualControlWidget.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/PlaysWidget.hpp ) set(WORLD_SOURCES diff --git a/include/roboteam_ai/interface/widgets/PlaysWidget.hpp b/include/roboteam_ai/interface/widgets/PlaysWidget.hpp deleted file mode 100644 index 6ff44dadbb..0000000000 --- a/include/roboteam_ai/interface/widgets/PlaysWidget.hpp +++ /dev/null @@ -1,32 +0,0 @@ -// -// Created by john on 4/30/20. -// - -#ifndef RTT_PLAYSWIDGET_HPP -#define RTT_PLAYSWIDGET_HPP - -#include -#include - -namespace rtt::ai::interface { - - class PlaysWidget : public QTextEdit { - Q_OBJECT - public: - /** - * Constructor that sets readonly(true) - * @param parent parent of the widget - */ - explicit PlaysWidget(QWidget* parent = nullptr); - ~PlaysWidget() override = default; - - public slots: - /** - * Slot that updates plays, gets them from ApplicationManager. - * The behavior is undefined if this is called using a non-signal-slot style. - */ - void updatePlays(); - }; -} - -#endif //RTT_PLAYSWIDGET_HPP diff --git a/include/roboteam_ai/interface/widgets/mainWindow.h b/include/roboteam_ai/interface/widgets/mainWindow.h index ce92b789de..714e6b379a 100644 --- a/include/roboteam_ai/interface/widgets/mainWindow.h +++ b/include/roboteam_ai/interface/widgets/mainWindow.h @@ -27,7 +27,6 @@ #include "RobotsWidget.h" #include "STPVisualizerWidget.h" #include "widget.h" -#include "PlaysWidget.hpp" namespace rtt { class ApplicationManager; @@ -70,7 +69,6 @@ class MainWindow : public QMainWindow { STPVisualizerWidget *stpWidget; STPVisualizerWidget *keeperStpWidget; Visualizer *visualizer; - PlaysWidget* playsWidget; // InvariantsWidget *invariantsWidget; }; diff --git a/src/interface/widgets/PlaysWidget.cpp b/src/interface/widgets/PlaysWidget.cpp deleted file mode 100644 index b6a97d2992..0000000000 --- a/src/interface/widgets/PlaysWidget.cpp +++ /dev/null @@ -1,76 +0,0 @@ -// -// Created by john on 4/30/20. -// - -#include -#include "include/roboteam_ai/interface/widgets/PlaysWidget.hpp" - -namespace rtt::ai::interface { - inline QString formatPlay(stp::Play* play) - { - std::optional world; - std::optional field; - - { - auto const&[_, worldOwner] = rtt::world::World::instance(); - field = worldOwner->getField(); - world = worldOwner->getWorld(); - } - - if (!world.has_value()) { - return "Unable to read world..."; - } - if (!field.has_value()) { - return "Unable to read field..."; - } - if (!world.value()) { - return "World is null"; - } - - rtt::world::WorldData data = *world.value(); - - QString ss = ""; - ss += play->getName(); - ss += ":
  keep:
"; - for (auto& each : play->keepPlayInvariants) - { - ss += "    "; - ss += each->getName(); - ss += ": "; - ss += (each->checkInvariant(rtt::world::view::WorldDataView{ &data }, &*field) ? "true" : "false"); - ss += "
"; - } - - ss += "  start:
"; - for (auto& each : play->startPlayInvariants) - { - ss += "    "; - ss += each->getName(); - ss += ": "; - ss += (each->checkInvariant(world.value(), &*field) ? "true" : "false"); - ss += "
"; - } - ss += "
"; - return ss; - } - - PlaysWidget::PlaysWidget(QWidget* parent) : QTextEdit(parent) { - setReadOnly(true); - } - - /** - * NAME: - * keep: - * Invariant -> true / false - * start: - */ - void PlaysWidget::updatePlays() { -// QString ss = {}; -// for (auto& each : ApplicationManager::plays) { -// ss += formatPlay(each.get()); -// } -// auto sliderPos = verticalScrollBar()->sliderPosition(); -// setHtml(ss); -// verticalScrollBar()->setSliderPosition(sliderPos); - } -} diff --git a/src/interface/widgets/mainWindow.cpp b/src/interface/widgets/mainWindow.cpp index e54d0084d9..c67adfd2e9 100644 --- a/src/interface/widgets/mainWindow.cpp +++ b/src/interface/widgets/mainWindow.cpp @@ -62,12 +62,10 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind auto tabWidget = new QTabWidget; - playsWidget = new PlaysWidget(this); auto DataTabWidget = new QTabWidget; DataTabWidget->addTab(behaviourTreeWidget, tr("STP states")); DataTabWidget->addTab(keeperStpWidget, tr("Keeper")); - DataTabWidget->addTab(playsWidget, "Plays"); DataTabWidget->addTab(robotsWidget, tr("Robots")); tabWidget->addTab(DataTabWidget, tr("Data")); @@ -115,7 +113,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind connect(this, &MainWindow::updateStpWidgets, stpWidget, &STPVisualizerWidget::outputStpData); connect(this, &MainWindow::updateStpWidgets, keeperStpWidget, &STPVisualizerWidget::outputStpData); - connect(this, &MainWindow::updateStpWidgets, playsWidget, &PlaysWidget::updatePlays); } /// Set up a checkbox and add it to the layout From 0103d9343948a7059d93d30113738d15aba9750e Mon Sep 17 00:00:00 2001 From: rolf Date: Mon, 22 Feb 2021 21:56:05 +0100 Subject: [PATCH 06/40] Remove stp visualization widget --- CMakeLists.txt | 2 - .../interface/widgets/STPVisualizerWidget.h | 125 --------------- .../interface/widgets/mainWindow.h | 8 +- src/interface/widgets/STPVisualizerWidget.cpp | 148 ------------------ src/interface/widgets/mainWindow.cpp | 22 +-- 5 files changed, 2 insertions(+), 303 deletions(-) delete mode 100644 include/roboteam_ai/interface/widgets/STPVisualizerWidget.h delete mode 100644 src/interface/widgets/STPVisualizerWidget.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index b992d352c4..66e61679df 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -205,7 +205,6 @@ set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/src/interface/widgets/mainWindow.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/widget.cpp ${PROJECT_SOURCE_DIR}/src/interface/api/Output.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/STPVisualizerWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/RobotsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/PidBox.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/PidsWidget.cpp @@ -221,7 +220,6 @@ set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/MainControlsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/mainWindow.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/RobotsWidget.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/STPVisualizerWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/VisualizationSettingsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/widget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/SettingsWidget.h diff --git a/include/roboteam_ai/interface/widgets/STPVisualizerWidget.h b/include/roboteam_ai/interface/widgets/STPVisualizerWidget.h deleted file mode 100644 index 236b322edf..0000000000 --- a/include/roboteam_ai/interface/widgets/STPVisualizerWidget.h +++ /dev/null @@ -1,125 +0,0 @@ -// -// Created by mrlukasbos on 1-2-19. -// - -#ifndef ROBOTEAM_AI_TREEVISUALIZER_H -#define ROBOTEAM_AI_TREEVISUALIZER_H - -#include - -#include -#include - -namespace rtt::ai::stp { - class Play; - class Role; - class Tactic; - class Skill; -} - -namespace rtt::ai::interface { - - class MainWindow; - - /** - * Class that visualizes the new STP system. - */ - class STPVisualizerWidget : public QTextEdit { - Q_OBJECT - - FRIEND_TEST(TreeVisualizerTest, it_properly_displays_trees); - - FRIEND_TEST(TreeVisualizerTest, it_sets_proper_color_for_status); - - private: - /** - * Gets the color for a status code - * @param status Status value - * @return a view to a (static constexpr) char* - * - * See impl. - */ - std::string_view getColorForStatus(stp::Status status); - - /** - * Mutex that's locked whenever content is edited or read - */ - std::mutex contentLock; - - /** - * Content that's used for updating the html edit - */ - std::stringstream updateContent; - - /** - * Main window pointer, used for signaling the other (keeper tree) widget - */ - MainWindow *parent = nullptr; - - /** - * Displays play, calls displayRole, tactic and skill to display - * them respectively - * @param play Play to display, null is checked - */ - void displayPlay(stp::Play* play); - - /** - * Displays role - * @param role Role to display - * @param state State of this Role - * @param last true if it's the last role, for future, might want to append more data - * @param updatingForKeeper true if you're updating for keeper, - * to prevent recursive calls - */ - void displayRole(stp::Role* role, stp::Status state, bool last, bool updatingForKeeper = false); - - /** - * Displays tactic - * @param tactic tactic to display - * @param last same as for displayRole - */ - void displayTactic(stp::Tactic* tactic, bool last); - - /** - * Displays a skill - * @param skill Skill to display - * @param last same as displayRole - */ - void displaySkill(stp::Skill* skill, bool last); - - /** - * Outputs a status in the correct format. - * @param status status to output - * - * stream << getColor(status) << status << white; - */ - void outputStatus(stp::Status status); - - public slots: - /** - * Calls this->setHtml(updateContent); - */ - void outputStpData(); - - public: - /** - * Constructor, sets `this->parent` and makes it readonly - * @param parent Parent to set this->parent to - */ - explicit STPVisualizerWidget(MainWindow *parent); - - /** - * Clears stream, displayPlay() and outputStpData(); - * @param currentPlay - */ - void updateContents(stp::Play* currentPlay); - - /** - * Updates `this` to reflect the keeper content - * @param pRole Role pointer that the keerp has - * @param state State of this Role. - */ - void updateKeeperContents(stp::Role *pRole, stp::Status state); - }; -} // namespace rtt::ai::interface -#endif // ROBOTEAM_AI_TREEVISUALIZER_H diff --git a/include/roboteam_ai/interface/widgets/mainWindow.h b/include/roboteam_ai/interface/widgets/mainWindow.h index 714e6b379a..d98a3957dc 100644 --- a/include/roboteam_ai/interface/widgets/mainWindow.h +++ b/include/roboteam_ai/interface/widgets/mainWindow.h @@ -25,7 +25,6 @@ #include "QPushButton" #include "QTreeWidgetItemIterator" #include "RobotsWidget.h" -#include "STPVisualizerWidget.h" #include "widget.h" namespace rtt { @@ -49,16 +48,12 @@ class MainWindow : public QMainWindow { static void configureCheckableMenuItem(QString title, const QString &hint, QMenu *menu, const QObject *receiver, const char *method, bool defaultState); static void clearLayout(QLayout *layout); - void updatePlay(stp::Play *play); - signals: - void updateStpWidgets(); public slots: void updateRobotsWidget(); void setPlayForRobot(std::string const &str, uint8_t id); void setTacticForRobot(std::string const &str, uint8_t id); - void setKeeperRole(stp::Role *role, stp::Status state); private: QHBoxLayout *horizontalLayout; @@ -66,8 +61,7 @@ class MainWindow : public QMainWindow { QVBoxLayout *vLayout; RobotsWidget *robotsWidget; ManualControlWidget *manualControlWidget; - STPVisualizerWidget *stpWidget; - STPVisualizerWidget *keeperStpWidget; + Visualizer *visualizer; // InvariantsWidget *invariantsWidget; }; diff --git a/src/interface/widgets/STPVisualizerWidget.cpp b/src/interface/widgets/STPVisualizerWidget.cpp deleted file mode 100644 index 764718084f..0000000000 --- a/src/interface/widgets/STPVisualizerWidget.cpp +++ /dev/null @@ -1,148 +0,0 @@ -/* - * - * This widget visualizes a behaviour (strategy) tree. - * - * Update contents updates the statuses, ticktimes and amount of ticks for each node. - * The nodes in the tree are not refreshed until the whole tree is invalidated. - * - */ - -#include "interface/widgets/STPVisualizerWidget.h" - -#include -#include - -#include "interface/widgets/mainWindow.h" -#include "stp/Play.hpp" -#include - -namespace rtt::ai::interface { - constexpr static const char *tab = "    "; - - STPVisualizerWidget::STPVisualizerWidget(MainWindow *parent) : QTextEdit(parent) { - this->parent = parent; - this->setReadOnly(true); - } - - std::string_view STPVisualizerWidget::getColorForStatus(stp::Status status) { - switch (status) { - case stp::Status::Failure: - return ""; - case stp::Status::Running: - return ""; // dark green - case stp::Status::Success: - return ""; // bright green - case stp::Status::Waiting: - return ""; - default: - return ""; - } - } - - void STPVisualizerWidget::updateContents(stp::Play *currentPlay) { - std::lock_guard lck{ contentLock }; - updateContent.str(""); - displayPlay(currentPlay); - } - - void STPVisualizerWidget::displayPlay(stp::Play *currentPlay) { - updateContent << " Play: "; - if (!currentPlay) { - updateContent << "None
"; - return; - } - updateContent << currentPlay->getName() << "
" << tab; - std::vector> states = { currentPlay->getRoleStatuses().begin(), currentPlay->getRoleStatuses().end() }; - // lhs and rhs are std::pair>, this function returns true if lhs < rhs (the robot id) - std::sort(states.begin(), states.end(), [](auto const& lhs, auto const& rhs) { - auto firstRobot = lhs.first->getCurrentRobot(); - auto secondRobot = rhs.first->getCurrentRobot(); - - if (!firstRobot || !firstRobot.value()) { - return true; - } - if (!secondRobot || !firstRobot.value()) { - return false; - } - - return firstRobot.value()->getId() < secondRobot.value()->getId(); - }); - - for (auto &elem : states) { - auto&[role, state] = elem; - displayRole(role, state, &elem == &*states.end()); - } - } - - void STPVisualizerWidget::displayTactic(stp::Tactic *tactic, bool last) { - updateContent << "Tactic: "; - if (!tactic) { - updateContent << "None
" << tab << tab; - return; - } - - updateContent << tactic->getName() << " => "; - outputStatus(tactic->getStatus()); - updateContent << ":
" << tab << tab << tab; - displaySkill(tactic->getCurrentSkill(), last); - } - - void STPVisualizerWidget::displayRole(stp::Role *role, stp::Status state, bool last, bool updatingForKeeper) { - updateContent << "Role: "; - updateContent << role->getName() << " "; - auto &curBot = role->getCurrentRobot(); - if (!curBot) { - updateContent << "None
" << tab; - return; - } - - auto &botView = curBot.value(); - if (!botView) { - updateContent << "None
" << tab; - return; - } - - parent->setPlayForRobot(role->getName(), botView->getId()); - - if (!updatingForKeeper && GameStateManager::getCurrentGameState().keeperId == botView->getId()) { - parent->setKeeperRole(role, state); - return; - } - updateContent << "Robot ID: " << botView->getId() << " => "; - outputStatus(state); - updateContent << ":
" << tab << tab; - displayTactic(role->getCurrentTactic(), last); - } - - void STPVisualizerWidget::displaySkill(stp::Skill *skill, bool last) { - updateContent << "Skill: "; - if (!skill) { - updateContent << "None
"; - return; - } - - updateContent << skill->getName() << " => "; - outputStatus(skill->getStatus()); - updateContent << "

"; - if (!last) { - updateContent << tab; - } - } - - void STPVisualizerWidget::outputStpData() { - auto sliderPos = this->verticalScrollBar()->sliderPosition(); - setHtml(QString::fromStdString(updateContent.str())); - this->verticalScrollBar()->setSliderPosition(sliderPos); - } - - void STPVisualizerWidget::outputStatus(stp::Status status) { - updateContent << getColorForStatus(status) << status << "
"; - } - - void STPVisualizerWidget::updateKeeperContents(stp::Role *pRole, stp::Status state) { - std::lock_guard lck{ contentLock }; - updateContent.str(""); - updateContent << "Keeper Role:
" << tab; - displayRole(pRole, state, false, true); - } -} // namespace rtt::ai::interface \ No newline at end of file diff --git a/src/interface/widgets/mainWindow.cpp b/src/interface/widgets/mainWindow.cpp index c67adfd2e9..cc6d83cf67 100644 --- a/src/interface/widgets/mainWindow.cpp +++ b/src/interface/widgets/mainWindow.cpp @@ -42,15 +42,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind auto mainControlsWidget = new MainControlsWidget(this, manager); vLayout->addWidget(mainControlsWidget); - auto behaviourTreeWidget = new QWidget(this); - auto behaviourTreeWidgetLayout = new QVBoxLayout(); - // create widgets hidden under tabs - stpWidget = new STPVisualizerWidget(this); - - behaviourTreeWidgetLayout->addWidget(stpWidget); - behaviourTreeWidget->setLayout(behaviourTreeWidgetLayout); - - keeperStpWidget = new STPVisualizerWidget(this); auto visualizationSettingsWidget = new VisualizationSettingsWidget(visualizer, this); auto settingsWidget = new SettingsWidget(this); @@ -64,8 +55,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind auto DataTabWidget = new QTabWidget; - DataTabWidget->addTab(behaviourTreeWidget, tr("STP states")); - DataTabWidget->addTab(keeperStpWidget, tr("Keeper")); DataTabWidget->addTab(robotsWidget, tr("Robots")); tabWidget->addTab(DataTabWidget, tr("Data")); @@ -111,8 +100,7 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind auto *graphTimer = new QTimer(this); graphTimer->start(500); // 2fps - connect(this, &MainWindow::updateStpWidgets, stpWidget, &STPVisualizerWidget::outputStpData); - connect(this, &MainWindow::updateStpWidgets, keeperStpWidget, &STPVisualizerWidget::outputStpData); + } /// Set up a checkbox and add it to the layout @@ -163,15 +151,7 @@ void MainWindow::updateRobotsWidget() { } } -void MainWindow::updatePlay(stp::Play *play) { - stpWidget->updateContents(play); - updateStpWidgets(); -} - void MainWindow::setPlayForRobot(std::string const &str, uint8_t id) { visualizer->setPlayForRobot(str, id); } - -void MainWindow::setKeeperRole(stp::Role *keeperRole, stp::Status state) { keeperStpWidget->updateKeeperContents(keeperRole, state); } - void MainWindow::setTacticForRobot(std::string const &str, uint8_t id) { visualizer->setTacticForRobot(str, id); } } // namespace rtt::ai::interface From ef01485a860526a462a13a161abd55a3d26b6b6e Mon Sep 17 00:00:00 2001 From: rolf Date: Mon, 22 Feb 2021 22:01:50 +0100 Subject: [PATCH 07/40] Remove robotswidget --- CMakeLists.txt | 2 - .../interface/widgets/RobotsWidget.h | 29 ------ .../interface/widgets/mainWindow.h | 3 - src/interface/widgets/RobotsWidget.cpp | 97 ------------------- src/interface/widgets/mainWindow.cpp | 21 ---- 5 files changed, 152 deletions(-) delete mode 100644 include/roboteam_ai/interface/widgets/RobotsWidget.h delete mode 100644 src/interface/widgets/RobotsWidget.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 66e61679df..c8ccf8ea03 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -205,7 +205,6 @@ set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/src/interface/widgets/mainWindow.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/widget.cpp ${PROJECT_SOURCE_DIR}/src/interface/api/Output.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/RobotsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/PidBox.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/PidsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/MainControlsWidget.cpp @@ -219,7 +218,6 @@ set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/PidsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/MainControlsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/mainWindow.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/RobotsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/VisualizationSettingsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/widget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/SettingsWidget.h diff --git a/include/roboteam_ai/interface/widgets/RobotsWidget.h b/include/roboteam_ai/interface/widgets/RobotsWidget.h deleted file mode 100644 index 5028431448..0000000000 --- a/include/roboteam_ai/interface/widgets/RobotsWidget.h +++ /dev/null @@ -1,29 +0,0 @@ -// -// Created by mrlukasbos on 1-2-19. -// - -#ifndef ROBOTEAM_AI_ROBOTSWIDGET_H -#define ROBOTEAM_AI_ROBOTSWIDGET_H - -#include "QLayout" -#include "widget.h" -#include "world/Field.h" - -namespace rtt::ai::interface { - -class RobotsWidget : public QWidget { - Q_OBJECT - private: - QVBoxLayout *createRobotGroupItem(const rtt::world::Field &field, rtt::world::view::RobotView robot); - int amountOfSelectedRobots = 0; - QVBoxLayout *VLayout; - - public: - explicit RobotsWidget(QWidget *parent); - public slots: - void updateContents(Visualizer *visualizer, rtt::world::view::WorldDataView world); -}; - -} // namespace rtt::ai::interface - -#endif // ROBOTEAM_AI_ROBOTSWIDGET_H diff --git a/include/roboteam_ai/interface/widgets/mainWindow.h b/include/roboteam_ai/interface/widgets/mainWindow.h index d98a3957dc..13d5ec56b0 100644 --- a/include/roboteam_ai/interface/widgets/mainWindow.h +++ b/include/roboteam_ai/interface/widgets/mainWindow.h @@ -24,7 +24,6 @@ #include "QHBoxLayout" #include "QPushButton" #include "QTreeWidgetItemIterator" -#include "RobotsWidget.h" #include "widget.h" namespace rtt { @@ -51,7 +50,6 @@ class MainWindow : public QMainWindow { public slots: - void updateRobotsWidget(); void setPlayForRobot(std::string const &str, uint8_t id); void setTacticForRobot(std::string const &str, uint8_t id); @@ -59,7 +57,6 @@ class MainWindow : public QMainWindow { QHBoxLayout *horizontalLayout; QVBoxLayout *mainLayout; QVBoxLayout *vLayout; - RobotsWidget *robotsWidget; ManualControlWidget *manualControlWidget; Visualizer *visualizer; diff --git a/src/interface/widgets/RobotsWidget.cpp b/src/interface/widgets/RobotsWidget.cpp deleted file mode 100644 index ffd5cb5814..0000000000 --- a/src/interface/widgets/RobotsWidget.cpp +++ /dev/null @@ -1,97 +0,0 @@ -// -// Created by mrlukasbos on 1-2-19. -// - -#include "interface/widgets/RobotsWidget.h" -#include -#include -#include -#include "interface/widgets/mainWindow.h" - -namespace rtt::ai::interface { - -RobotsWidget::RobotsWidget(QWidget *parent) : QWidget(parent) { - // make sure it is scrollable - auto container = new QVBoxLayout(); - VLayout = new QVBoxLayout(); - auto scroll = new QScrollArea(); - scroll->setWidgetResizable(true); - auto inner = new QFrame(scroll); - inner->setLayout(VLayout); - scroll->setWidget(inner); - container->addWidget(scroll); - this->setLayout(container); -} - -void RobotsWidget::updateContents(Visualizer *visualizer, rtt::world::view::WorldDataView world) { - std::optional field; - { - auto const& [_, world] = rtt::world::World::instance(); - field = world->getField(); - } - - if (!field){ - RTT_ERROR("Could not get field!") - return; - } - auto us =world->getUs(); - - // reload the widgets completely if a robot is added or removed - // or if the amount of selected robots is not accurate - if (VLayout->count() != static_cast(world.getUs().size()) || amountOfSelectedRobots != static_cast(visualizer->getSelectedRobots().size())) { - amountOfSelectedRobots = visualizer->getSelectedRobots().size(); - MainWindow::clearLayout(VLayout); - - for (auto &robot : world.getUs()) { - QGroupBox *groupBox = new QGroupBox("Robot " + QString::number(robot->getId())); - groupBox->setCheckable(true); - groupBox->setChecked(visualizer->robotIsSelected(robot->getId())); - QObject::connect(groupBox, &QGroupBox::clicked, [=]() { visualizer->toggleSelectedRobot(robot); }); - groupBox->setLayout(createRobotGroupItem(*field, robot)); - VLayout->addWidget(groupBox); - } - } else { - for (int i = 0; i < static_cast(world->getUs().size()); i++) { - if (VLayout->itemAt(i) && VLayout->itemAt(i)->widget()) { - auto robotwidget = VLayout->itemAt(i)->widget(); - MainWindow::clearLayout(robotwidget->layout()); - delete robotwidget->layout(); - if (!robotwidget->layout()) { - robotwidget->setLayout(createRobotGroupItem(*field, world.getUs().at(i))); - } - } - } - } - auto robotSpacer = new QSpacerItem(100, 100, QSizePolicy::Expanding, QSizePolicy::Expanding); - VLayout->addSpacerItem(robotSpacer); -} - -/// create a single layout with robot information for a specific robot -QVBoxLayout *RobotsWidget::createRobotGroupItem(const rtt::world::Field &field, rtt::world::view::RobotView robot) { - auto vbox = new QVBoxLayout(); - - auto absVel = robot->getVel().length(); - - auto velLabel = new QLabel("vel: {x = " + QString::number(robot->getVel().x, 'G', 3) + ", y = " + QString::number(robot->getVel().y, 'g', 3) + - "} m/s,\n" - " absolute: " + - QString::number(absVel, 'G', 3) + " m/s"); - velLabel->setFixedWidth(250); - vbox->addWidget(velLabel); - - auto angleLabel = new QLabel("angle: " + QString::number(robot->getAngle(), 'g', 3) + " radians"); - angleLabel->setFixedWidth(250); - vbox->addWidget(angleLabel); - - auto posLabel = new QLabel("pos: (x = " + QString::number(robot->getPos().x, 'g', 3) + ", y = " + QString::number(robot->getPos().y, 'g', 3) + ")"); - posLabel->setFixedWidth(250); - vbox->addWidget(posLabel); - - auto wLabel = new QLabel("w: " + QString::number(robot->getAngularVelocity(), 'g', 3) + "rad/s"); - wLabel->setFixedWidth(250); - vbox->addWidget(wLabel); - - return vbox; -} - -} // namespace rtt::ai::interface diff --git a/src/interface/widgets/mainWindow.cpp b/src/interface/widgets/mainWindow.cpp index cc6d83cf67..da5dfc1731 100644 --- a/src/interface/widgets/mainWindow.cpp +++ b/src/interface/widgets/mainWindow.cpp @@ -46,7 +46,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind auto settingsWidget = new SettingsWidget(this); auto pidWidget = new PidsWidget(); - robotsWidget = new RobotsWidget(this); manualControlWidget = new ManualControlWidget(this); // add the tab widget @@ -54,9 +53,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind - auto DataTabWidget = new QTabWidget; - DataTabWidget->addTab(robotsWidget, tr("Robots")); - tabWidget->addTab(DataTabWidget, tr("Data")); auto SettingsTabWidget = new QTabWidget; SettingsTabWidget->addTab(settingsWidget, tr("General settings")); @@ -91,8 +87,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind // start the UI update cycles // these are slower than the tick rate auto *robotsTimer = new QTimer(this); - connect(robotsTimer, SIGNAL(timeout()), this, - SLOT(updateRobotsWidget())); // we need to pass the visualizer so thats why a seperate function is used connect(robotsTimer, SIGNAL(timeout()), mainControlsWidget, SLOT(updatePause())); connect(robotsTimer, SIGNAL(timeout()), mainControlsWidget, SLOT(updateContents())); robotsTimer->start(500); // 2fps @@ -135,21 +129,6 @@ void MainWindow::clearLayout(QLayout *layout) { } } -// when updating the robotswidget it needs the current visualizer state -void MainWindow::updateRobotsWidget() { - std::optional currentWorld; - { - auto const &[_, world] = rtt::world::World::instance(); - if (!world) { - std::cerr << "World is nullptr" << std::endl; - return; - } - currentWorld = world->getWorld(); - } - if (currentWorld) { - robotsWidget->updateContents(visualizer, *currentWorld); - } -} void MainWindow::setPlayForRobot(std::string const &str, uint8_t id) { visualizer->setPlayForRobot(str, id); } void MainWindow::setTacticForRobot(std::string const &str, uint8_t id) { visualizer->setTacticForRobot(str, id); } From 9ded68d5d19db7f7fdd5bb8b22ab050f5ffec127 Mon Sep 17 00:00:00 2001 From: rolf Date: Mon, 22 Feb 2021 22:14:12 +0100 Subject: [PATCH 08/40] Remove toggles and visualization settings --- CMakeLists.txt | 3 - include/roboteam_ai/interface/api/Toggles.h | 42 ------------- .../interface/widgets/ManualControlWidget.h | 2 - .../widgets/VisualizationSettingsWidget.h | 21 ------- .../roboteam_ai/interface/widgets/widget.h | 2 - src/interface/api/Toggles.cpp | 20 ------ .../widgets/VisualizationSettingsWidget.cpp | 62 ------------------- src/interface/widgets/mainWindow.cpp | 3 - src/interface/widgets/widget.cpp | 29 --------- 9 files changed, 184 deletions(-) delete mode 100644 include/roboteam_ai/interface/api/Toggles.h delete mode 100644 include/roboteam_ai/interface/widgets/VisualizationSettingsWidget.h delete mode 100644 src/interface/api/Toggles.cpp delete mode 100644 src/interface/widgets/VisualizationSettingsWidget.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index c8ccf8ea03..a9d75a031b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -208,8 +208,6 @@ set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/src/interface/widgets/PidBox.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/PidsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/MainControlsWidget.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/VisualizationSettingsWidget.cpp - ${PROJECT_SOURCE_DIR}/src/interface/api/Toggles.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/SettingsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/ManualControlWidget.cpp @@ -218,7 +216,6 @@ set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/PidsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/MainControlsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/mainWindow.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/VisualizationSettingsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/widget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/SettingsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/ManualControlWidget.h diff --git a/include/roboteam_ai/interface/api/Toggles.h b/include/roboteam_ai/interface/api/Toggles.h deleted file mode 100644 index 853bad1e35..0000000000 --- a/include/roboteam_ai/interface/api/Toggles.h +++ /dev/null @@ -1,42 +0,0 @@ -// -// Created by mrlukasbos on 7-5-19. -// - -#ifndef ROBOTEAM_AI_TOGGLES_H -#define ROBOTEAM_AI_TOGGLES_H - -#include -#include -#include - -namespace rtt::ai::interface { - -enum Visual { DEBUG, BALL_DATA, BALL_HANDLING, PATHFINDING, PATHFINDING_DEBUG, KEEPER, INTERCEPT, DEFENSE, OFFENSE, SHOTLINES, BALLPLACEMENT, AVOIDANCE }; - -enum ShowType { GENERAL, ROBOT }; - -enum RobotShowType { NO_ROBOTS = 0, SELECTED_ROBOTS = 1, ALL_ROBOTS = 2 }; - -enum GeneralShowType { OFF = 0, ON = 1 }; - -class Toggle { - public: - Visual visual; - ShowType showType; - RobotShowType robotShowType; - GeneralShowType generalShowType; - QString title; - - Toggle() = default; - explicit Toggle(Visual vis, RobotShowType rst, QString t) : visual(vis), robotShowType(rst), title(t) { showType = ROBOT; }; - explicit Toggle(Visual vis, GeneralShowType gst, QString t) : visual(vis), generalShowType(gst), title(t) { showType = GENERAL; }; -}; - -class Toggles { - public: - static std::vector toggles; -}; - -} // namespace rtt::ai::interface - -#endif // ROBOTEAM_AI_TOGGLES_H diff --git a/include/roboteam_ai/interface/widgets/ManualControlWidget.h b/include/roboteam_ai/interface/widgets/ManualControlWidget.h index 1ccbee2ec3..841dc121fb 100644 --- a/include/roboteam_ai/interface/widgets/ManualControlWidget.h +++ b/include/roboteam_ai/interface/widgets/ManualControlWidget.h @@ -5,7 +5,6 @@ #ifndef RTT_MANUALCONTROLWIDGET_H #define RTT_MANUALCONTROLWIDGET_H -#include #include #include #include @@ -18,7 +17,6 @@ class ManualControlWidget : public QWidget { private: std::thread joyThread; rtt::input::JoystickManager manager; - Toggle RobotSelector; }; } // namespace rtt #endif // RTT_MANUALCONTROLWIDGET_H diff --git a/include/roboteam_ai/interface/widgets/VisualizationSettingsWidget.h b/include/roboteam_ai/interface/widgets/VisualizationSettingsWidget.h deleted file mode 100644 index 8c2e535c0d..0000000000 --- a/include/roboteam_ai/interface/widgets/VisualizationSettingsWidget.h +++ /dev/null @@ -1,21 +0,0 @@ -// -// Created by mrlukasbos on 7-5-19. -// - -#ifndef ROBOTEAM_AI_VISUALIZATIONSETTINGSWIDGET_H -#define ROBOTEAM_AI_VISUALIZATIONSETTINGSWIDGET_H - -#include "QLayout" -#include "widget.h" - -namespace rtt::ai::interface { - -class VisualizationSettingsWidget : public QWidget { - Q_OBJECT - public: - explicit VisualizationSettingsWidget(Visualizer *visualizer, QWidget *parent = nullptr); -}; - -} // namespace rtt::ai::interface - -#endif // ROBOTEAM_AI_VISUALIZATIONSETTINGSWIDGET_H diff --git a/include/roboteam_ai/interface/widgets/widget.h b/include/roboteam_ai/interface/widgets/widget.h index 0946f6b4a1..e1b3afb10f 100644 --- a/include/roboteam_ai/interface/widgets/widget.h +++ b/include/roboteam_ai/interface/widgets/widget.h @@ -11,7 +11,6 @@ #include #include -#include #include #include #include @@ -66,7 +65,6 @@ class Visualizer : public QWidget { void drawLines(QPainter &painter, std::vector points); void drawArrows(QPainter &painter, std::vector points, double factor, double maxSize, bool closedArrow); - bool shouldVisualize(Toggle toggle, int robotId); // utitlity functions std::string getTacticNameForRobot(rtt::world::view::RobotView robot); diff --git a/src/interface/api/Toggles.cpp b/src/interface/api/Toggles.cpp deleted file mode 100644 index c2242b6908..0000000000 --- a/src/interface/api/Toggles.cpp +++ /dev/null @@ -1,20 +0,0 @@ -#include "interface/api/Toggles.h" - -namespace rtt::ai::interface { - -std::vector Toggles::toggles = {Toggle(Visual::DEBUG, GeneralShowType::ON, "Show debug values"), - Toggle(Visual::BALL_DATA, GeneralShowType::ON, "Show ball data"), - Toggle(Visual::BALL_HANDLING, RobotShowType::ALL_ROBOTS, "Show ball handling"), - Toggle(Visual::PATHFINDING, RobotShowType::ALL_ROBOTS, "Show final paths"), - Toggle(Visual::PATHFINDING_DEBUG, RobotShowType::NO_ROBOTS, "Show pathfinding tried paths"), - Toggle(Visual::KEEPER, RobotShowType::NO_ROBOTS, "Show keeper points"), - Toggle(Visual::INTERCEPT, RobotShowType::ALL_ROBOTS, "Show Interceptions"), - Toggle(Visual::DEFENSE, RobotShowType::ALL_ROBOTS, "Show defensive location"), - Toggle(Visual::SHOTLINES, RobotShowType::ALL_ROBOTS, "Show desired shotlines"), - Toggle(Visual::OFFENSE, RobotShowType::SELECTED_ROBOTS, "Show offensive default locations"), - Toggle(Visual::BALLPLACEMENT, RobotShowType::ALL_ROBOTS, "Show ballplacement hints"), - Toggle(Visual::AVOIDANCE, RobotShowType::ALL_ROBOTS, "Show offensive default locations") - -}; - -} // namespace rtt::ai::interface diff --git a/src/interface/widgets/VisualizationSettingsWidget.cpp b/src/interface/widgets/VisualizationSettingsWidget.cpp deleted file mode 100644 index 62cda92aa2..0000000000 --- a/src/interface/widgets/VisualizationSettingsWidget.cpp +++ /dev/null @@ -1,62 +0,0 @@ -// -// Created by mrlukasbos on 7-5-19. -// - -#include "interface/widgets/VisualizationSettingsWidget.h" - -#include "interface/widgets/mainWindow.h" - -namespace rtt::ai::interface { - -VisualizationSettingsWidget::VisualizationSettingsWidget(Visualizer *visualizer, QWidget *parent) { - auto cbVLayout = new QVBoxLayout(); - - for (int i = 0; i < Toggles::toggles.size(); i++) { - auto customToggle = new QWidget; - auto hbox = new QHBoxLayout(); - - // set the label - auto label = new QLabel(Toggles::toggles[i].title); - hbox->addWidget(label); - - // get the strategy names from Switches - auto select = new QComboBox(); - hbox->addWidget(select); - - if (Toggles::toggles[i].showType == GENERAL) { - select->addItem("Off"); - select->addItem("On"); - - std::vector colors = {"red", "green"}; - select->setCurrentIndex(Toggles::toggles[i].generalShowType); - select->setStyleSheet("QComboBox { background-color: " + colors[Toggles::toggles[i].generalShowType] + " }"); - - QObject::connect(select, static_cast(&QComboBox::activated), [=](const int index) { - Toggles::toggles[i].generalShowType = static_cast(index); - select->setStyleSheet("QComboBox { background-color: " + colors[static_cast(index)] + " }"); - }); - } else if (Toggles::toggles[i].showType == ROBOT) { - select->addItem("No robots"); - select->addItem("Selected robots"); - select->addItem("All robots"); - - std::vector colors = {"red", "#888800", "green"}; - select->setCurrentIndex(Toggles::toggles[i].robotShowType); - select->setStyleSheet("QComboBox { background-color: " + colors[Toggles::toggles[i].robotShowType] + " }"); - - QObject::connect(select, static_cast(&QComboBox::activated), [=](const int index) { - Toggles::toggles[i].robotShowType = static_cast(index); - select->setStyleSheet("QComboBox { background-color: " + colors[static_cast(index)] + " }"); - }); - } - - customToggle->setLayout(hbox); - cbVLayout->addWidget(customToggle); - } - - auto cbVSpacer = new QSpacerItem(100, 100, QSizePolicy::Expanding, QSizePolicy::Expanding); - cbVLayout->addSpacerItem(cbVSpacer); - this->setLayout(cbVLayout); -} - -} // namespace rtt::ai::interface diff --git a/src/interface/widgets/mainWindow.cpp b/src/interface/widgets/mainWindow.cpp index da5dfc1731..1b36a0a054 100644 --- a/src/interface/widgets/mainWindow.cpp +++ b/src/interface/widgets/mainWindow.cpp @@ -4,7 +4,6 @@ #include "interface/widgets/MainControlsWidget.h" #include "interface/widgets/PidsWidget.h" -#include "interface/widgets/VisualizationSettingsWidget.h" #include #include namespace rtt::ai::interface { @@ -42,7 +41,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind auto mainControlsWidget = new MainControlsWidget(this, manager); vLayout->addWidget(mainControlsWidget); - auto visualizationSettingsWidget = new VisualizationSettingsWidget(visualizer, this); auto settingsWidget = new SettingsWidget(this); auto pidWidget = new PidsWidget(); @@ -56,7 +54,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind auto SettingsTabWidget = new QTabWidget; SettingsTabWidget->addTab(settingsWidget, tr("General settings")); - SettingsTabWidget->addTab(visualizationSettingsWidget, tr("Visualisation Settings")); SettingsTabWidget->addTab(pidWidget, tr("PID")); tabWidget->addTab(SettingsTabWidget, tr("Settings")); tabWidget->addTab(manualControlWidget, tr("Manual")); diff --git a/src/interface/widgets/widget.cpp b/src/interface/widgets/widget.cpp index dfd447720c..da449ac113 100644 --- a/src/interface/widgets/widget.cpp +++ b/src/interface/widgets/widget.cpp @@ -45,35 +45,6 @@ namespace rtt::ai::interface { if (showBallPlacementMarker) drawBallPlacementTarget(painter); } - bool Visualizer::shouldVisualize(Toggle toggle, int robotId) { - switch (toggle.showType) { - default: - return false; - case GENERAL: { - switch (toggle.generalShowType) { - default: - return false; - case OFF: - return false; - case ON: - return true; - } - break; - } - case ROBOT: { - switch (toggle.robotShowType) { - default: - return false; - case NO_ROBOTS: - return false; - case SELECTED_ROBOTS: - return robotIsSelected(robotId); - case ALL_ROBOTS: - return true; - } - } - } - } /// Calculates the factor variable which is used for mapping field coordinates with screen coordinates. void Visualizer::calculateFieldSizeFactor(const rtt::world::Field &field) { From 447e051632234067a0ae82a35e7825ed4be22cd8 Mon Sep 17 00:00:00 2001 From: rolf Date: Mon, 22 Feb 2021 22:35:05 +0100 Subject: [PATCH 09/40] fix outdated appmanager constructor --- include/roboteam_ai/ApplicationManager.h | 5 +---- src/ApplicationManager.cpp | 4 ---- src/roboteam_ai.cpp | 2 +- 3 files changed, 2 insertions(+), 9 deletions(-) diff --git a/include/roboteam_ai/ApplicationManager.h b/include/roboteam_ai/ApplicationManager.h index a35b30a1c4..02a3b37c33 100644 --- a/include/roboteam_ai/ApplicationManager.h +++ b/include/roboteam_ai/ApplicationManager.h @@ -14,8 +14,6 @@ namespace rtt { class ApplicationManager { - public: - explicit ApplicationManager(ai::interface::MainWindow* mainWindow); private: FRIEND_TEST(ApplicationManagerTest, it_handles_ROS_data); @@ -23,14 +21,13 @@ class ApplicationManager { void runOneLoopCycle(); bool fieldInitialized = false; bool robotsInitialized = false; - ai::interface::MainWindow* mainWindow; std::unique_ptr ai; std::unique_ptr io; public: void start(int ai_id); - + ApplicationManager() = default; ApplicationManager(ApplicationManager const&) = delete; ApplicationManager& operator=(ApplicationManager const&) = delete; }; diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index 6763127319..cce4368fc6 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -112,8 +112,4 @@ void ApplicationManager::runOneLoopCycle() { rtt::ai::control::ControlModule::sendAllCommands(io); io->handleCentralServerConnection(); } - - - -ApplicationManager::ApplicationManager(ai::interface::MainWindow *mainWindow) { this->mainWindow = mainWindow; } } // namespace rtt diff --git a/src/roboteam_ai.cpp b/src/roboteam_ai.cpp index 3213ce78bc..f235c0d62c 100644 --- a/src/roboteam_ai.cpp +++ b/src/roboteam_ai.cpp @@ -8,7 +8,7 @@ namespace ui = rtt::ai::interface; ui::MainWindow* window; void run_application(int ai_id) { - rtt::ApplicationManager app{ window }; + rtt::ApplicationManager app{}; app.start(ai_id); } From cd24d6ff78eceeb8c6b4751bb939baf3c466981f Mon Sep 17 00:00:00 2001 From: rolf Date: Wed, 24 Feb 2021 21:01:37 +0100 Subject: [PATCH 10/40] Remove visualization widget --- CMakeLists.txt | 2 - .../interface/widgets/MainControlsWidget.h | 1 - .../interface/widgets/PidsWidget.h | 2 +- .../interface/widgets/mainWindow.h | 7 - .../roboteam_ai/interface/widgets/widget.h | 102 ---- src/interface/widgets/mainWindow.cpp | 18 +- src/interface/widgets/widget.cpp | 542 ------------------ 7 files changed, 2 insertions(+), 672 deletions(-) delete mode 100644 include/roboteam_ai/interface/widgets/widget.h delete mode 100644 src/interface/widgets/widget.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index a9d75a031b..5f9acbf33c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -203,7 +203,6 @@ set(TEST_SOURCES set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/src/interface/widgets/mainWindow.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/widget.cpp ${PROJECT_SOURCE_DIR}/src/interface/api/Output.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/PidBox.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/PidsWidget.cpp @@ -216,7 +215,6 @@ set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/PidsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/MainControlsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/mainWindow.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/widget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/SettingsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/ManualControlWidget.h ) diff --git a/include/roboteam_ai/interface/widgets/MainControlsWidget.h b/include/roboteam_ai/interface/widgets/MainControlsWidget.h index 426d0b4131..9049e403d6 100644 --- a/include/roboteam_ai/interface/widgets/MainControlsWidget.h +++ b/include/roboteam_ai/interface/widgets/MainControlsWidget.h @@ -13,7 +13,6 @@ #include #include "QLayout" -#include "widget.h" namespace rtt::ai::interface { diff --git a/include/roboteam_ai/interface/widgets/PidsWidget.h b/include/roboteam_ai/interface/widgets/PidsWidget.h index 56790657d8..e733e9b351 100644 --- a/include/roboteam_ai/interface/widgets/PidsWidget.h +++ b/include/roboteam_ai/interface/widgets/PidsWidget.h @@ -6,7 +6,7 @@ #define ROBOTEAM_AI_PIDSWIDGET_H #include "QLayout" -#include "widget.h" +#include namespace rtt::ai::interface { diff --git a/include/roboteam_ai/interface/widgets/mainWindow.h b/include/roboteam_ai/interface/widgets/mainWindow.h index 13d5ec56b0..82edbeaa1d 100644 --- a/include/roboteam_ai/interface/widgets/mainWindow.h +++ b/include/roboteam_ai/interface/widgets/mainWindow.h @@ -24,7 +24,6 @@ #include "QHBoxLayout" #include "QPushButton" #include "QTreeWidgetItemIterator" -#include "widget.h" namespace rtt { class ApplicationManager; @@ -48,18 +47,12 @@ class MainWindow : public QMainWindow { static void configureCheckableMenuItem(QString title, const QString &hint, QMenu *menu, const QObject *receiver, const char *method, bool defaultState); static void clearLayout(QLayout *layout); - - public slots: - void setPlayForRobot(std::string const &str, uint8_t id); - void setTacticForRobot(std::string const &str, uint8_t id); - private: QHBoxLayout *horizontalLayout; QVBoxLayout *mainLayout; QVBoxLayout *vLayout; ManualControlWidget *manualControlWidget; - Visualizer *visualizer; // InvariantsWidget *invariantsWidget; }; diff --git a/include/roboteam_ai/interface/widgets/widget.h b/include/roboteam_ai/interface/widgets/widget.h deleted file mode 100644 index e1b3afb10f..0000000000 --- a/include/roboteam_ai/interface/widgets/widget.h +++ /dev/null @@ -1,102 +0,0 @@ -// -// Created by mrlukasbos on 27-11-18. -// - -#ifndef ROBOTEAM_AI_WIDGET_H -#define ROBOTEAM_AI_WIDGET_H - -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -namespace rtt::ai::interface { - -class Visualizer : public QWidget { - Q_OBJECT - FRIEND_TEST(MainWindowTest, it_shows_the_visualizer_properly); - - public: - explicit Visualizer(QWidget *parent = nullptr); - const std::unordered_map &getSelectedRobots() const; - bool robotIsSelected(rtt::world::view::RobotView robot); - bool robotIsSelected(int id); - void setPlayForRobot(std::string const& view, uint8_t i); - void setTacticForRobot(std::string const& view, uint8_t i); - - public slots: - void setShowRoles(bool showRoles); - void setShowTactics(bool showTactics); - void setShowTacticColors(bool showTacticColors); - void setShowAngles(bool showAngles); - void setShowVelocities(bool showVelocities); - void setShowRobotInvalids(bool showPath); - void setShowBallPlacementMarker(bool showMarker); - void setShowDebugValueInTerminal(bool showDebug); - void toggleSelectedRobot(rtt::world::view::RobotView robot); - void setToggleFieldDirection(bool inversed); - - protected: - void paintEvent(QPaintEvent *event) override; - void mousePressEvent(QMouseEvent *event) override; - - private: - float factor{}; - int fieldmargin = Constants::WINDOW_FIELD_MARGIN(); - void drawBackground(QPainter &painter); - void drawFieldLines(const rtt::world::Field &field, QPainter &painter); - void drawFieldHints(const rtt::world::Field &field, QPainter &painter); - - void drawRobots(QPainter &painter, rtt::world::view::WorldDataView world); - void drawRobot(QPainter &painter, rtt::world::view::RobotView robot, bool ourTeam, std::string role = ""); - void drawBall(QPainter &painter, rtt::world::view::BallView); - void drawBallPlacementTarget(QPainter &painter); - void drawTacticColorForRobot(QPainter &painter, rtt::world::view::RobotView robot); - void drawPlusses(QPainter &painter, std::vector points, double width, double height); - void drawCrosses(QPainter &painter, std::vector points, double width, double height); - void drawPoints(QPainter &painter, std::vector points, double width, double height); - void drawRealLifeSizedPoints(QPainter &painter, std::vector points, double width, double height); // width and height are now in meters - - void drawLines(QPainter &painter, std::vector points); - void drawArrows(QPainter &painter, std::vector points, double factor, double maxSize, bool closedArrow); - - // utitlity functions - std::string getTacticNameForRobot(rtt::world::view::RobotView robot); - std::string getRoleNameForRobot(rtt::world::view::RobotView robot); - rtt::Vector2 toScreenPosition(rtt::Vector2 fieldPos); - rtt::Vector2 toFieldPosition(rtt::Vector2 screenPos); - - void calculateFieldSizeFactor(const rtt::world::Field &field); - - // interface variables - std::vector> tacticColors; // map colors to tactic to visualize which robots work together - int tacticCount = 0; // increases when a new tactic is used - - std::unordered_map selectedRobots; - std::unordered_map rolesForRobots; - std::unordered_map tacticsForRobots; - - // toggles - bool showRoles = Constants::STD_SHOW_ROLES(); - bool showTactics = Constants::STD_SHOW_TACTICS(); - bool showTacticColors = Constants::STD_SHOW_TACTICS_COLORS(); - bool showAngles = Constants::STD_SHOW_ANGLES(); - bool showVelocities = Constants::STD_SHOW_VELOCITIES(); - bool showRobotInvalids = Constants::STD_SHOW_ROBOT_INVALIDS(); - bool showBallPlacementMarker = Constants::STD_SHOW_BALL_PLACEMENT_MARKER(); - bool showDebugValueInTerminal = Constants::STD_SHOW_DEBUG_VALUES(); - bool fieldInversed = false; - std::mutex rolesUpdate; - std::mutex tacticsUpdate; -}; - -} // namespace rtt::ai::interface - -#endif // ROBOTEAM_AI_WIDGET_H diff --git a/src/interface/widgets/mainWindow.cpp b/src/interface/widgets/mainWindow.cpp index 1b36a0a054..a692de5244 100644 --- a/src/interface/widgets/mainWindow.cpp +++ b/src/interface/widgets/mainWindow.cpp @@ -13,7 +13,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind setMinimumHeight(600); // layouts - visualizer = new Visualizer(this); mainLayout = new QVBoxLayout(); horizontalLayout = new QHBoxLayout(); vLayout = new QVBoxLayout(); @@ -23,19 +22,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind menu->addMenu(tr("&File")); auto viewMenu = menu->addMenu(tr("&Visualization")); - MainWindow::configureCheckableMenuItem("show rolenames", "show rolenames", viewMenu, visualizer, SLOT(setShowRoles(bool)), Constants::STD_SHOW_ROLES()); - MainWindow::configureCheckableMenuItem("show tacticnames", "show rolenames", viewMenu, visualizer, SLOT(setShowTactics(bool)), Constants::STD_SHOW_TACTICS()); - MainWindow::configureCheckableMenuItem("show tacticColors", "show rolenames", viewMenu, visualizer, SLOT(setShowTacticColors(bool)), Constants::STD_SHOW_TACTICS_COLORS()); - MainWindow::configureCheckableMenuItem("show angles", "show rolenames", viewMenu, visualizer, SLOT(setShowAngles(bool)), Constants::STD_SHOW_ANGLES()); - MainWindow::configureCheckableMenuItem("show velocities", "show rolenames", viewMenu, visualizer, SLOT(setShowVelocities(bool)), Constants::STD_SHOW_VELOCITIES()); - MainWindow::configureCheckableMenuItem("show robot shortcomings", "show rolenames", viewMenu, visualizer, SLOT(setShowRobotInvalids(bool)), - Constants::STD_SHOW_ROBOT_INVALIDS()); - MainWindow::configureCheckableMenuItem("Show marker for BallPtr Placement", "show rolenames", viewMenu, visualizer, SLOT(setShowBallPlacementMarker(bool)), - Constants::STD_SHOW_BALL_PLACEMENT_MARKER()); - MainWindow::configureCheckableMenuItem("show debug values in terminal", "show rolenames", viewMenu, visualizer, SLOT(setShowDebugValueInTerminal(bool)), - Constants::STD_SHOW_DEBUG_VALUES()); - MainWindow::configureCheckableMenuItem("Inverse interface", "show rolenames", viewMenu, visualizer, SLOT(setToggleFieldDirection(bool)), false); - // the main controls widget for the most crucial buttons // changing strategies, goalie id, etc. auto mainControlsWidget = new MainControlsWidget(this, manager); @@ -63,7 +49,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind // set up the general layout structure // visualizer on the left, sidebar (with maincontrols and tabs) on the right. auto splitter = new QSplitter(); // the splitter is an horizontal view that allows to be changed by the user - splitter->addWidget(visualizer); auto sideBarWidget = new QWidget; sideBarWidget->setLayout(vLayout); splitter->addWidget(sideBarWidget); @@ -127,7 +112,6 @@ void MainWindow::clearLayout(QLayout *layout) { } -void MainWindow::setPlayForRobot(std::string const &str, uint8_t id) { visualizer->setPlayForRobot(str, id); } -void MainWindow::setTacticForRobot(std::string const &str, uint8_t id) { visualizer->setTacticForRobot(str, id); } + } // namespace rtt::ai::interface diff --git a/src/interface/widgets/widget.cpp b/src/interface/widgets/widget.cpp deleted file mode 100644 index da449ac113..0000000000 --- a/src/interface/widgets/widget.cpp +++ /dev/null @@ -1,542 +0,0 @@ -// -// Created by mrlukasbos on 27-11-18. -// - -#include "interface/widgets/widget.h" -#include - -namespace io = rtt::ai::io; -namespace rtt::ai::interface { - - Visualizer::Visualizer(QWidget *parent) - : QWidget(parent) {} - -/// The update loop of the field widget. Invoked by widget->update(); - void Visualizer::paintEvent(QPaintEvent *event) { - QPainter painter(this); - painter.setRenderHint(QPainter::Antialiasing, true); - painter.setRenderHint(QPainter::HighQualityAntialiasing, true); - std::optional world; - std::optional field; - { - auto const&[_, worldPtr] = rtt::world::World::instance(); - world = worldPtr->getWorld(); - field = worldPtr->getField(); - } - - if (!world.has_value() || !world.value()->weHaveRobots()) { - painter.drawText(24, 24, "Waiting for incoming world state"); - return; - } - - if(field.has_value()) { - calculateFieldSizeFactor(field.value()); - drawBackground(painter); - drawFieldHints(field.value(), painter); - drawFieldLines(field.value(), painter); - } - - auto s = QString::fromStdString("We have " + std::to_string(world->getUs().size()) + " robots"); - painter.drawText(24, 48, s.fromStdString("We have " + std::to_string(world->getUs().size()) + " robots")); - - drawRobots(painter, world.value()); - if (world->getBall().has_value()) drawBall(painter, world->getBall().value()); - - if (showBallPlacementMarker) drawBallPlacementTarget(painter); - } - - -/// Calculates the factor variable which is used for mapping field coordinates with screen coordinates. -void Visualizer::calculateFieldSizeFactor(const rtt::world::Field &field) { - fieldmargin = static_cast(Constants::WINDOW_FIELD_MARGIN() + field.getBoundaryWidth()); - - float widthFactor = this->size().width() / field.getFieldLength() - (2 * fieldmargin); - float heightFactor = this->size().height() / field.getFieldWidth() - (2 * fieldmargin); - factor = std::min(widthFactor, heightFactor); - } - -/// draws background of the field - void Visualizer::drawBackground(QPainter &painter) { - painter.setBrush(Constants::FIELD_COLOR()); - painter.drawRect(-10, -10, this->size().width() + 10, this->size().height() + 10); - } - -// draws the field lines -void Visualizer::drawFieldLines(const rtt::world::Field &field, QPainter &painter) { - painter.setPen(Constants::FIELD_LINE_COLOR()); - painter.setBrush(Qt::transparent); - // draw lines - for (const auto &fieldLine : field.getFieldLines()) { - rtt::Vector2 start = toScreenPosition(fieldLine.begin); - rtt::Vector2 end = toScreenPosition(fieldLine.end); - painter.drawLine(start.x, start.y, end.x, end.y); - } - - // draw the circle in the middle - auto centercircle = field.getCenterCircle(); - Vector2 screenPos = toScreenPosition({centercircle.center.x, centercircle.center.y}); - painter.drawEllipse(QPointF(screenPos.x, screenPos.y), centercircle.radius * factor, - centercircle.radius * factor); - - painter.setPen(Qt::red); - auto line = field.getLeftPenaltyLine(); - rtt::Vector2 start = toScreenPosition(line.begin); - rtt::Vector2 end = toScreenPosition(line.end); - painter.drawLine(start.x, start.y, end.x, end.y); - - painter.setPen(Qt::green); - line = field.getRightPenaltyLine(); - start = toScreenPosition(line.begin); - end = toScreenPosition(line.end); - painter.drawLine(start.x, start.y, end.x, end.y); - - painter.setPen(Qt::green); - line = field.getRightLine(); - start = toScreenPosition(line.begin); - end = toScreenPosition(line.end); - painter.drawLine(start.x, start.y, end.x, end.y); - - painter.setPen(Qt::red); - line = field.getLeftLine(); - start = toScreenPosition(line.begin); - end = toScreenPosition(line.end); - painter.drawLine(start.x, start.y, end.x, end.y); - - QPen pen; - pen.setWidth(3); - - // update the we are yellow - bool weAreYellow = SETTINGS.isYellow(); - - // draw the hint for us - LineSegment usGoalLine = FieldComputations::getGoalSides(field, true); - Vector2 ourLineUpper = {usGoalLine.start.x, usGoalLine.start.y}; - Vector2 ourLineLower = {usGoalLine.end.x, usGoalLine.end.y}; - ourLineUpper = toScreenPosition(ourLineUpper); - ourLineLower = toScreenPosition(ourLineLower); - - auto color = weAreYellow ? QColor(255, 255, 0, 255) : QColor(80, 80, 255, 255); - pen.setBrush(color); - pen.setColor(color); - painter.setPen(pen); - painter.drawLine(ourLineUpper.x, ourLineUpper.y, ourLineLower.x, ourLineLower.y); - - LineSegment theirGoalLine = FieldComputations::getGoalSides(field, false); - Vector2 theirLineUpper = {theirGoalLine.start.x, theirGoalLine.start.y}; - Vector2 theirLineLower = {theirGoalLine.end.x, theirGoalLine.end.y}; - theirLineUpper = toScreenPosition(theirLineUpper); - theirLineLower = toScreenPosition(theirLineLower); - - color = weAreYellow ? QColor(80, 80, 255, 255) : QColor(255, 255, 0, 255); - pen.setBrush(color); - pen.setColor(color); - painter.setPen(pen); - painter.drawLine(theirLineUpper.x, theirLineUpper.y, theirLineLower.x, theirLineLower.y); - } - -void Visualizer::drawFieldHints(const rtt::world::Field &field, QPainter &painter) { - QPen pen; - - // draw the position where robots would be for timeout - int inv = rtt::ai::interface::Output::isTimeOutAtTop() ? 1 : -1; - int lineY = (field.getFieldWidth() / 2 + 1) * inv; - - pen.setBrush(Qt::gray); - pen.setColor(Qt::gray); - painter.setPen(pen); - - auto lineStart = toScreenPosition(Vector2(field.getLeftmostX(), lineY)); - auto lineEnd = toScreenPosition(Vector2(0, lineY)); - - painter.drawLine(lineStart.x, lineStart.y, lineEnd.x, lineEnd.y); - } - -// draw the ball on the screen - void Visualizer::drawBall(QPainter &painter, rtt::world::view::BallView ball) { - rtt::Vector2 ballPosition = toScreenPosition(ball->getPos()); - QPointF qballPosition(ballPosition.x, ballPosition.y); - - painter.setBrush(ball->isVisible() ? Constants::BALL_COLOR() : Qt::red); - - // draw a see-through gradient around the ball to make it more visible - painter.setPen(Qt::NoPen); // stroke - painter.setOpacity(0.5); - painter.drawEllipse(qballPosition, Constants::BALL_DRAWING_SIZE(), Constants::BALL_DRAWING_SIZE()); - painter.setOpacity(1); - int ballSize = Constants::BALL_RADIUS() * 2 * factor; - painter.drawEllipse(qballPosition, ballSize, ballSize); - } - -// draw the robots - void Visualizer::drawRobots(QPainter &painter, rtt::world::view::WorldDataView world) { - // draw us - for (auto const &robot : world->getUs()) { - std::string role{}; - if (rolesForRobots.find(robot->getId()) != rolesForRobots.end()) { - std::lock_guard mtx{rolesUpdate}; - role = rolesForRobots[robot->getId()]; - } - drawRobot(painter, robot, true, role); - } - - // draw them - for (auto const &robot : world->getThem()) { - drawRobot(painter, robot, false); - } - } - -// convert field coordinates to screen coordinates - rtt::Vector2 Visualizer::toScreenPosition(rtt::Vector2 fieldPos) { - int inv = fieldInversed ? -1 : 1; - auto x = (fieldPos.x * factor * inv) + static_cast(this->size().width() / 2 + fieldmargin); - auto y = (fieldPos.y * factor * -1 * inv) + static_cast(this->size().height() / 2 + fieldmargin); - return Vector2(x, y); - } - -// convert field coordinates to screen coordinates - rtt::Vector2 Visualizer::toFieldPosition(rtt::Vector2 screenPos) { - int inv = fieldInversed ? -1 : 1; - auto x = (screenPos.x - fieldmargin - static_cast(this->size().width() / 2)) / factor; - auto y = ((screenPos.y - fieldmargin - static_cast(this->size().height() / 2)) / factor) * -1; - return Vector2(x, y) * inv; - } - -// draw a single robot - void - Visualizer::drawRobot(QPainter &painter, rtt::world::view::RobotView robot, bool ourTeam, std::string role) { - Vector2 robotpos = toScreenPosition(robot->getPos()); - - // update the we are yellow - bool weAreYellow = SETTINGS.isYellow(); - - QColor robotColor; - if (ourTeam) { - // our robots have our_color - robotColor = weAreYellow ? Constants::ROBOT_COLOR_YELLOW() : Constants::ROBOT_COLOR_BLUE(); - } else { - // the enemy robot should have the inverse of our_color - robotColor = weAreYellow ? Constants::ROBOT_COLOR_BLUE() : Constants::ROBOT_COLOR_YELLOW(); - } - - if (ourTeam && robot->getId() == GameStateManager::getCurrentGameState().keeperId) { - robotColor = QColor(255, 255, 255); - } - - if (showAngles) { - Vector2 angle = toScreenPosition( - {robot->getPos().x + cos(robot->getAngle()) / 3, robot->getPos().y + sin(robot->getAngle()) / 3}); - QPen pen; - pen.setWidth(2); - pen.setBrush(robotColor); - painter.setPen(pen); - painter.drawLine(robotpos.x, robotpos.y, angle.x, angle.y); - } - - if (showVelocities) { - Vector2 vel = toScreenPosition( - {robot->getPos().x + robot->getVel().x, robot->getPos().y + robot->getVel().y}); - painter.setPen(Qt::white); - painter.drawLine(robotpos.x, robotpos.y, vel.x, vel.y); - } - - if (showTacticColors && ourTeam) { - drawTacticColorForRobot(painter, robot); - } - int ypos = robotpos.y; - if (showTactics && ourTeam) { - painter.setPen(Constants::TEXT_COLOR()); - - painter.drawText(robotpos.x, ypos += 20, QString::fromStdString(getTacticNameForRobot(robot))); - } - - if (showRoles && ourTeam) { - painter.setPen(Constants::TEXT_COLOR()); - painter.drawText(robotpos.x, ypos += 20, QString::fromStdString(getRoleNameForRobot(robot))); - } - - // Todo : Get working stuff in RobotView - if (showRobotInvalids && ourTeam) { - painter.setPen(Qt::red); - QString text; - if (!robot->isWorkingDribbler()) { - text += "DR "; - } - if (!robot->isWorkingBallSensor()) { - text += "BS "; - } - if (robot->isBatteryLow()) { - text += "BATTERY LOW"; - } - painter.drawText(robotpos.x, ypos += 20, text); - painter.drawText(robotpos.x, ypos + 10, QString::fromStdString(role)); - } - - // Todo : Get working feedback in RobotView - // if (ourTeam) { - // if (Constants::FEEDBACK_ENABLED()) { - // if (robot.hasRecentFeedback()) { - // // green to indicate feedback is okay - // painter.setPen(Qt::green); - // painter.setBrush(Qt::green); - // } else { - // // yellow to indicate feedback is not okay - // painter.setPen(Qt::red); - // painter.setBrush(Qt::red); - // } - // painter.drawEllipse({(int)robotpos.x + 10, (int)robotpos.y - 10}, 2, 2); - // } - // } - - // draw the robots - QColor color = (robotIsSelected(robot) && ourTeam) ? Constants::SELECTED_ROBOT_COLOR() : robotColor; - painter.setBrush(color); - painter.setPen(Qt::transparent); - painter.setOpacity(1); - - int robotDrawSize = std::max(Constants::ROBOT_RADIUS() * factor * 2, (double) Constants::ROBOT_DRAWING_SIZE()); - - // draw the shape of the robot with the right angle - QPainterPath rectPath; - rectPath.moveTo(0, -robotDrawSize / 2.0); - rectPath.arcTo(-robotDrawSize / 2.0, -robotDrawSize / 2.0, robotDrawSize, robotDrawSize, 90, 270); - rectPath.closeSubpath(); - - painter.translate(robotpos.x, robotpos.y); // move center of coordinates to the center of robot - - if (fieldInversed) { - painter.rotate(-toDegrees(robot->getAngle()) + 45 + 180); // rotate around the center of robot - } else { - painter.rotate(-toDegrees(robot->getAngle()) + 45); // rotate around the center of robot - } - painter.drawPath(rectPath); - painter.resetTransform(); // reset the translation and rotation - - // draw the id in it - painter.setPen(Qt::black); - painter.setFont(QFont("ubuntu", 9)); // 22 is a number which you have to change - painter.drawText(robotpos.x - 3, robotpos.y + 5, QString::number(robot->getId())); - painter.setFont(QFont("ubuntu", 11)); // 22 is a number which you have to change - } - -// Handle mousePressEvents - void Visualizer::mousePressEvent(QMouseEvent *event) { - Vector2 pos; - pos.x = event->pos().x(); - pos.y = event->pos().y(); - - - std::optional world; - { - auto const& [_, worldPtr] = rtt::world::World::instance(); - world = worldPtr->getWorld(); - } - - if (event->button() == Qt::LeftButton && world.has_value()) { - for (auto &robot : world->getUs()) { - if (pos.dist(toScreenPosition(robot->getPos())) < 10) { - this->toggleSelectedRobot(robot); - } - } - } else if (event->button() == Qt::RightButton) { - Output::setMarkerPosition(toFieldPosition(pos)); - } - } - - void Visualizer::drawTacticColorForRobot(QPainter &painter, rtt::world::view::RobotView robot) { - Vector2 robotpos = toScreenPosition(robot->getPos()); - QPointF qrobotPosition(robotpos.x, robotpos.y); - std::string tacticName = getTacticNameForRobot(robot); - bool tacticExists = false; - QColor c; - for (auto tac : tacticColors) { - if (tac.first == tacticName) { - c = tac.second; - tacticExists = true; - break; - } - } - - if (!tacticExists) { - QColor newColor = Constants::TACTIC_COLORS().at(tacticCount); - tacticCount = (tacticCount + 1) % Constants::TACTIC_COLORS().size(); - tacticColors.push_back({tacticName, newColor}); - c = newColor; - } - - painter.setPen(Qt::transparent); - painter.setBrush(c); - painter.drawEllipse(qrobotPosition, Constants::TACTIC_COLOR_DRAWING_SIZE(), - Constants::TACTIC_COLOR_DRAWING_SIZE()); - } - - std::string Visualizer::getTacticNameForRobot(rtt::world::view::RobotView robot) { - return tacticsForRobots[robot->getId()]; - } - - std::string Visualizer::getRoleNameForRobot(rtt::world::view::RobotView robot) { - return this->rolesForRobots[robot->getId()]; - } - - void Visualizer::setShowRoles(bool showRoles) { this->showRoles = showRoles; } - - void Visualizer::setShowTactics(bool showTactics) { Visualizer::showTactics = showTactics; } - - void Visualizer::setShowTacticColors(bool showTacticColors) { Visualizer::showTacticColors = showTacticColors; } - - const std::unordered_map & - Visualizer::getSelectedRobots() const { return selectedRobots; } - - void Visualizer::setShowAngles(bool showAngles) { Visualizer::showAngles = showAngles; } - - void Visualizer::setShowVelocities(bool showVelocities) { Visualizer::showVelocities = showVelocities; } - - void Visualizer::setShowRobotInvalids(bool show) { Visualizer::showRobotInvalids = show; } - - void Visualizer::toggleSelectedRobot(rtt::world::view::RobotView robot) { - bool robotSelected = (selectedRobots.find(robot->getId()) != selectedRobots.end()); - - if (robotSelected) { - selectedRobots.erase(robot->getId()); - } else { - selectedRobots.insert({robot->getId(), robot}); - } - } - - bool Visualizer::robotIsSelected(rtt::world::view::RobotView robot) { - return (selectedRobots.find(robot->getId()) != selectedRobots.end()); - } - - bool Visualizer::robotIsSelected(int robotId) { return (selectedRobots.find(robotId) != selectedRobots.end()); } - - void Visualizer::drawBallPlacementTarget(QPainter &painter) { - Vector2 marker = toScreenPosition(Output::getInterfaceMarkerPosition()); - painter.setBrush(Qt::transparent); - painter.setPen(Qt::red); - - painter.drawLine(marker.x - 5, marker.y - 5, marker.x + 5, marker.y + 5); - painter.drawLine(marker.x + 5, marker.y - 5, marker.x - 5, marker.y + 5); - - if (Output::usesRefereeCommands()) { - Vector2 ballPlacementTarget = toScreenPosition(Vector2(GameStateManager::getRefereeDesignatedPosition())); - painter.setBrush(Qt::transparent); - painter.setPen(Qt::green); - - painter.drawLine(ballPlacementTarget.x - 5, ballPlacementTarget.y - 5, ballPlacementTarget.x + 5, - ballPlacementTarget.y + 5); - painter.drawLine(ballPlacementTarget.x + 5, ballPlacementTarget.y - 5, ballPlacementTarget.x - 5, - ballPlacementTarget.y + 5); - } - } - - void Visualizer::setShowBallPlacementMarker(bool showMarker) { Visualizer::showBallPlacementMarker = showMarker; } - - void Visualizer::setShowDebugValueInTerminal(bool showDebug) { - Visualizer::showDebugValueInTerminal = showDebug; - Output::setShowDebugValues(showDebug); - } - - void Visualizer::setToggleFieldDirection(bool inversed) { Visualizer::fieldInversed = inversed; } - - void Visualizer::drawPlusses(QPainter &painter, std::vector points, double width, double height) { - for (auto const &point : points) { - Vector2 pointOnScreen = toScreenPosition(point); - - // draw a plus - painter.drawLine(0, pointOnScreen.y - height / 2, 0, pointOnScreen.y + height / 2); - painter.drawLine(pointOnScreen.x + width / 2, 0, pointOnScreen.x - width / 2, 0); - } - } - - void Visualizer::drawArrows(QPainter &painter, std::vector points, double factor, double maxSize, - bool closedArrow) { - if (points.size() >= 2) { - for (int i = 1; i < points.size(); i += 2) { - Vector2 &arrowEnd = points.at(i - 1); - Vector2 &arrowStart = points.at(i); - - double arrowLength = (arrowEnd - arrowStart).length(); - Angle arrowAngle = (arrowEnd - arrowStart).toAngle(); - - double arrowSizeFactor = factor == 4.0 ? 0.2 : std::min(1.0, factor); - double maxArrowSize = maxSize == 4.0 ? 0.2 : std::min(1.0, maxSize); - double arrowSize = - arrowLength > maxArrowSize / arrowSizeFactor ? arrowSizeFactor : arrowSizeFactor * arrowLength; - - Vector2 startPoint = arrowEnd + (arrowStart - arrowEnd).stretchToLength(arrowSize); - Vector2 pointyBitLeft = startPoint + (arrowAngle + Angle(M_PI_2)).toVector2(arrowSize); - Vector2 pointyBitRight = startPoint + (arrowAngle + Angle(M_PI_2)).toVector2(-arrowSize); - - Vector2 arrowStartOnScreen = toScreenPosition(arrowStart); - Vector2 arrowEndOnScreen = toScreenPosition(arrowEnd); - Vector2 pointyBitLeftOnScreen = toScreenPosition(pointyBitLeft); - Vector2 pointyBitRightOnScreen = toScreenPosition(pointyBitRight); - Vector2 startPointOnScreen = toScreenPosition(startPoint); - if (closedArrow) { - painter.drawLine(arrowStartOnScreen.x, arrowStartOnScreen.y, startPointOnScreen.x, - startPointOnScreen.y); - painter.drawLine(arrowEndOnScreen.x, arrowEndOnScreen.y, pointyBitRightOnScreen.x, - pointyBitRightOnScreen.y); - painter.drawLine(arrowEndOnScreen.x, arrowEndOnScreen.y, pointyBitLeftOnScreen.x, - pointyBitLeftOnScreen.y); - painter.drawLine(pointyBitRightOnScreen.x, pointyBitRightOnScreen.y, pointyBitLeftOnScreen.x, - pointyBitLeftOnScreen.y); - } else { - painter.drawLine(arrowStartOnScreen.x, arrowStartOnScreen.y, arrowEndOnScreen.x, - arrowEndOnScreen.y); - painter.drawLine(arrowEndOnScreen.x, arrowEndOnScreen.y, pointyBitRightOnScreen.x, - pointyBitRightOnScreen.y); - painter.drawLine(arrowEndOnScreen.x, arrowEndOnScreen.y, pointyBitLeftOnScreen.x, - pointyBitLeftOnScreen.y); - } - } - } - } - - void Visualizer::drawCrosses(QPainter &painter, std::vector points, double width, double height) { - for (auto const &point : points) { - Vector2 pointOnScreen = toScreenPosition(point); - painter.drawLine(pointOnScreen.x - width / 2, pointOnScreen.y - height / 2, pointOnScreen.x + width / 2, - pointOnScreen.y + height / 2); - painter.drawLine(pointOnScreen.x + width / 2, pointOnScreen.y - height / 2, pointOnScreen.x - width / 2, - pointOnScreen.y + height / 2); - } - } - - void Visualizer::drawPoints(QPainter &painter, std::vector points, double width, double height) { - for (auto const &point : points) { - Vector2 pointOnScreen = toScreenPosition(point); - painter.drawEllipse(pointOnScreen.x - width / 2, pointOnScreen.y - height / 2, width, height); - } - } - - void Visualizer::drawLines(QPainter &painter, std::vector points) { - if (points.size() >= 2) { - for (int i = 1; i < points.size(); i++) { - Vector2 pointOnScreen = toScreenPosition(points.at(i)); - Vector2 prevPointOnScreen = toScreenPosition(points.at(i - 1)); - painter.drawLine(pointOnScreen.x, pointOnScreen.y, prevPointOnScreen.x, prevPointOnScreen.y); - } - } - } - - void - Visualizer::drawRealLifeSizedPoints(QPainter &painter, std::vector points, double width, double height) { - width = width * 2.0 * factor; - height = height * 2.0 * factor; - for (auto const &point : points) { - Vector2 pointOnScreen = toScreenPosition(point); - painter.drawEllipse(pointOnScreen.x - width / 2, pointOnScreen.y - height / 2, width, height); - } - } - - void Visualizer::setPlayForRobot(std::string const &view, uint8_t i) { - std::lock_guard mtx{rolesUpdate}; - rolesForRobots.insert({i, view}); - } - - void Visualizer::setTacticForRobot(std::string const &view, uint8_t i) { - std::lock_guard mtx{tacticsUpdate}; - tacticsForRobots.insert({i, view}); - } - -} // namespace rtt::ai::interface From 5d262bc207f4d888e45b7e580650979d19701a62 Mon Sep 17 00:00:00 2001 From: rolf Date: Wed, 24 Feb 2021 21:09:43 +0100 Subject: [PATCH 11/40] Remove unused statics --- include/roboteam_ai/interface/api/Output.h | 14 ++------------ src/interface/api/Output.cpp | 18 ------------------ 2 files changed, 2 insertions(+), 30 deletions(-) diff --git a/include/roboteam_ai/interface/api/Output.h b/include/roboteam_ai/interface/api/Output.h index f31a0fb6b7..64fb9ddacd 100644 --- a/include/roboteam_ai/interface/api/Output.h +++ b/include/roboteam_ai/interface/api/Output.h @@ -25,11 +25,9 @@ class Output { static std::mutex markerMutex; static std::mutex refMutex; - static std::mutex showDebugMutex; static rtt::Vector2 markerPosition; static bool useRefereeCommands; - static bool showDebugValuesInTerminal; static bool timeOutAtTop; static GameState interfaceGameState; @@ -40,21 +38,13 @@ class Output { static void setInterfaceGameState(GameState interfaceGameState); static const GameState &getInterfaceGameState(); - static bool isTimeOutAtTop(); - static void setShowDebugValues(bool showDebug); - static bool getShowDebugValues(); - static bool showDebugLongestTick(); - static bool showDebugTickTimeTaken(); - static bool showDebugNumTreeTimeTaken(); - static bool showDebugNumTreeInfo(); - static bool showCoachTimeTaken(); - static bool showFullDebugNumTreeInfo(); static bool usesRefereeCommands(); static void setUseRefereeCommands(bool useRefereeCommands); static const rtt::Vector2 &getInterfaceMarkerPosition(); static void setMarkerPosition(const rtt::Vector2 &ballPlacementTarget); - static void setTimeOutTop(bool top); + static bool isTimeOutAtTop(); + static void setTimeOutTop(bool top); static const pidVals &getNumTreePid(); static void setNumTreePid(const pidVals &numTreePid); diff --git a/src/interface/api/Output.cpp b/src/interface/api/Output.cpp index 406cba9593..11a5606731 100644 --- a/src/interface/api/Output.cpp +++ b/src/interface/api/Output.cpp @@ -17,12 +17,10 @@ pidVals Output::keeperInterceptPID = pidVals(0.0, 0.0, 0.0); rtt::Vector2 Output::markerPosition = {0, 0}; // initialize on middle of the field bool Output::useRefereeCommands = false; -bool Output::showDebugValuesInTerminal = true; bool Output::timeOutAtTop = Constants::STD_TIMEOUT_TO_TOP(); std::mutex Output::markerMutex; std::mutex Output::refMutex; -std::mutex Output::showDebugMutex; GameState Output::interfaceGameState("halt_strategy", "default"); @@ -65,27 +63,11 @@ void Output::setUseRefereeCommands(bool useRefereeCommands) { Output::useRefereeCommands = useRefereeCommands; } -void Output::setShowDebugValues(bool showDebug) { - std::lock_guard lock(showDebugMutex); - Output::showDebugValuesInTerminal = showDebug; -} - -bool Output::getShowDebugValues() { - std::lock_guard lock(showDebugMutex); - return Output::showDebugValuesInTerminal; -} - -bool Output::showDebugTickTimeTaken() { return getShowDebugValues() && Constants::SHOW_TICK_TIME_TAKEN(); } -bool Output::showDebugLongestTick() { return getShowDebugValues() && Constants::SHOW_LONGEST_TICK(); } -bool Output::showDebugNumTreeTimeTaken() { return getShowDebugValues() && Constants::SHOW_NUMTREE_TIME_TAKEN(); } -bool Output::showCoachTimeTaken() { return getShowDebugValues() && Constants::SHOW_COACH_TIME_TAKEN(); } -bool Output::showDebugNumTreeInfo() { return getShowDebugValues() && Constants::SHOW_NUMTREE_DEBUG_INFO(); } -bool Output::showFullDebugNumTreeInfo() { return getShowDebugValues() && Constants::SHOW_NUMTREE_DEBUG_INFO() && Constants::SHOW_FULL_NUMTREE_DEBUG_INFO(); } void Output::setTimeOutTop(bool top) { timeOutAtTop = top; } From 97fe2522d26480db069e72ba5a3d682bcbb74cf0 Mon Sep 17 00:00:00 2001 From: rolf Date: Wed, 24 Feb 2021 21:25:14 +0100 Subject: [PATCH 12/40] Remove PID boxes --- CMakeLists.txt | 4 -- include/roboteam_ai/interface/api/Output.h | 7 --- .../roboteam_ai/interface/widgets/PidBox.h | 38 ------------ .../interface/widgets/PidsWidget.h | 21 ------- .../interface/widgets/mainWindow.h | 1 - .../pathTracking/PidTracking.cpp | 12 ++-- src/interface/api/Output.cpp | 9 --- src/interface/widgets/PidBox.cpp | 52 ----------------- src/interface/widgets/PidsWidget.cpp | 58 ------------------- src/interface/widgets/mainWindow.cpp | 3 - 10 files changed, 6 insertions(+), 199 deletions(-) delete mode 100644 include/roboteam_ai/interface/widgets/PidBox.h delete mode 100644 include/roboteam_ai/interface/widgets/PidsWidget.h delete mode 100644 src/interface/widgets/PidBox.cpp delete mode 100644 src/interface/widgets/PidsWidget.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 5f9acbf33c..2014de73cc 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -204,15 +204,11 @@ set(TEST_SOURCES set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/src/interface/widgets/mainWindow.cpp ${PROJECT_SOURCE_DIR}/src/interface/api/Output.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/PidBox.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/PidsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/MainControlsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/SettingsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/ManualControlWidget.cpp #QT wants to know about these headers - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/PidBox.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/PidsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/MainControlsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/mainWindow.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/SettingsWidget.h diff --git a/include/roboteam_ai/interface/api/Output.h b/include/roboteam_ai/interface/api/Output.h index 64fb9ddacd..f1e68f2e86 100644 --- a/include/roboteam_ai/interface/api/Output.h +++ b/include/roboteam_ai/interface/api/Output.h @@ -17,7 +17,6 @@ typedef std::tuple pidVals; class Output { private: - static pidVals numTreePID; static pidVals receivePID; static pidVals interceptPID; static pidVals keeperPID; @@ -46,15 +45,9 @@ class Output { static bool isTimeOutAtTop(); static void setTimeOutTop(bool top); - static const pidVals &getNumTreePid(); - static void setNumTreePid(const pidVals &numTreePid); - static const pidVals &getReceivePid(); static void setReceivePid(const pidVals &receivePid); - static const pidVals &getInterceptPid(); static void setInterceptPid(const pidVals &interceptPid); - static const pidVals &getKeeperPid(); static void setKeeperPid(const pidVals &keeperPid); - static const pidVals &getKeeperInterceptPid(); static void setKeeperInterceptPid(const pidVals &keeperInterceptPid); static void setRuleSetName(std::string name); diff --git a/include/roboteam_ai/interface/widgets/PidBox.h b/include/roboteam_ai/interface/widgets/PidBox.h deleted file mode 100644 index 469ed4b17c..0000000000 --- a/include/roboteam_ai/interface/widgets/PidBox.h +++ /dev/null @@ -1,38 +0,0 @@ -// -// Created by mrlukasbos on 8-4-19. -// - -#ifndef ROBOTEAM_AI_PIDBOX_H -#define ROBOTEAM_AI_PIDBOX_H - -#include -#include -#include -#include - -namespace rtt::ai::interface { - -class PidBox : public QGroupBox { - Q_OBJECT - private: - QHBoxLayout *spinBoxLayout; - QDoubleSpinBox *select_p; - QDoubleSpinBox *select_i; - QDoubleSpinBox *select_d; - pidVals pid; - - public slots: - void updatePID(); - - public: - const pidVals &getPid() const; - void setPid(const pidVals &pid); - explicit PidBox(const QString &title, QWidget *parent = nullptr); - - signals: - void pidChanged(pidVals newPid); -}; - -} // namespace rtt::ai::interface - -#endif // ROBOTEAM_AI_PIDBOX_H diff --git a/include/roboteam_ai/interface/widgets/PidsWidget.h b/include/roboteam_ai/interface/widgets/PidsWidget.h deleted file mode 100644 index e733e9b351..0000000000 --- a/include/roboteam_ai/interface/widgets/PidsWidget.h +++ /dev/null @@ -1,21 +0,0 @@ -// -// Created by mrlukasbos on 7-5-19. -// - -#ifndef ROBOTEAM_AI_PIDSWIDGET_H -#define ROBOTEAM_AI_PIDSWIDGET_H - -#include "QLayout" -#include - -namespace rtt::ai::interface { - -class PidsWidget : public QWidget { - Q_OBJECT - public: - explicit PidsWidget(QWidget *parent = nullptr); -}; - -} // namespace rtt::ai::interface - -#endif // ROBOTEAM_AI_PIDSWIDGET_H diff --git a/include/roboteam_ai/interface/widgets/mainWindow.h b/include/roboteam_ai/interface/widgets/mainWindow.h index 82edbeaa1d..bfeb7e3c03 100644 --- a/include/roboteam_ai/interface/widgets/mainWindow.h +++ b/include/roboteam_ai/interface/widgets/mainWindow.h @@ -19,7 +19,6 @@ #include #include "ManualControlWidget.h" -#include "PidBox.h" #include "QColor" #include "QHBoxLayout" #include "QPushButton" diff --git a/src/control/positionControl/pathTracking/PidTracking.cpp b/src/control/positionControl/pathTracking/PidTracking.cpp index 1e90144d90..798fed4014 100644 --- a/src/control/positionControl/pathTracking/PidTracking.cpp +++ b/src/control/positionControl/pathTracking/PidTracking.cpp @@ -24,7 +24,7 @@ Position PidTracking::trackPath(const Vector2 ¤tPosition, const Vector2 &c } void PidTracking::updatePidValuesFromInterface(bool isKeeper) { - auto newPid = isKeeper ? interface::Output::getKeeperPid() : interface::Output::getNumTreePid(); + auto newPid = isKeeper ? Constants::standardKeeperPID() : Constants::standardNumTreePID(); for (auto pid : pidMapping) { pidMapping[pid.first].first.setPID(newPid); pidMapping[pid.first].second.setPID(newPid); @@ -36,22 +36,22 @@ void PidTracking::updatePIDValues(stp::PIDType pidType, int robotID) { switch (pidType) { case stp::PIDType::DEFAULT: { - newPID = interface::Output::getNumTreePid(); + newPID = Constants::standardNumTreePID(); break; } case stp::PIDType::RECEIVE: { - newPID = interface::Output::getReceivePid(); + newPID = Constants::standardReceivePID(); break; } case stp::PIDType::INTERCEPT: { - newPID = interface::Output::getInterceptPid(); + newPID = Constants::standardInterceptPID(); } case stp::PIDType::KEEPER: { - newPID = interface::Output::getKeeperPid(); + newPID = Constants::standardKeeperPID(); break; } case stp::PIDType::KEEPER_INTERCEPT: { - newPID = interface::Output::getKeeperInterceptPid(); + newPID = Constants::standardKeeperInterceptPID(); break; } } diff --git a/src/interface/api/Output.cpp b/src/interface/api/Output.cpp index 11a5606731..ed608fb2ec 100644 --- a/src/interface/api/Output.cpp +++ b/src/interface/api/Output.cpp @@ -9,7 +9,6 @@ namespace rtt::ai::interface { // these values are default initialized here, but will be updated once mainWidget.cpp constructs the PID widget. -pidVals Output::numTreePID = pidVals(0.0, 0.0, 0.0); pidVals Output::receivePID = pidVals(0.0, 0.0, 0.0); pidVals Output::interceptPID = pidVals(0.0, 0.0, 0.0); pidVals Output::keeperPID = pidVals(0.0, 0.0, 0.0); @@ -85,23 +84,15 @@ void Output::setInterfaceGameState(GameState interfaceGameState) { Output::interfaceGameState = interfaceGameState; } -const pidVals &Output::getNumTreePid() { return numTreePID; } - -void Output::setNumTreePid(const pidVals &numTreePid) { numTreePID = numTreePid; } - -const pidVals &Output::getReceivePid() { return receivePID; } void Output::setReceivePid(const pidVals &receivePid) { receivePID = receivePid; } -const pidVals &Output::getInterceptPid() { return interceptPID; } void Output::setInterceptPid(const pidVals &interceptPid) { interceptPID = interceptPid; } -const pidVals &Output::getKeeperPid() { return keeperPID; } void Output::setKeeperPid(const pidVals &keeperPid) { keeperPID = keeperPid; } -const pidVals &Output::getKeeperInterceptPid() { return keeperInterceptPID; } void Output::setKeeperInterceptPid(const pidVals &keeperInterceptPid) { keeperInterceptPID = keeperInterceptPid; } diff --git a/src/interface/widgets/PidBox.cpp b/src/interface/widgets/PidBox.cpp deleted file mode 100644 index 24c4859b90..0000000000 --- a/src/interface/widgets/PidBox.cpp +++ /dev/null @@ -1,52 +0,0 @@ -// -// Created by mrlukasbos on 8-4-19. -// - -#include - -namespace rtt::ai::interface { - -PidBox::PidBox(const QString &title, QWidget *parent) : QGroupBox(title, parent) { - spinBoxLayout = new QHBoxLayout(); - - select_p = new QDoubleSpinBox(); - select_p->setRange(-20, 20); - select_p->setSingleStep(0.1f); - QObject::connect(select_p, SIGNAL(valueChanged(double)), this, SLOT(updatePID())); - spinBoxLayout->addWidget(select_p); - - select_i = new QDoubleSpinBox(); - select_i->setRange(-20, 20); - select_i->setSingleStep(0.1f); - QObject::connect(select_i, SIGNAL(valueChanged(double)), this, SLOT(updatePID())); - spinBoxLayout->addWidget(select_i); - - select_d = new QDoubleSpinBox(); - select_d->setRange(-20, 20); - select_d->setSingleStep(0.1f); - QObject::connect(select_d, SIGNAL(valueChanged(double)), this, SLOT(updatePID())); - spinBoxLayout->addWidget(select_d); - - this->setLayout(spinBoxLayout); -} - -const pidVals &PidBox::getPid() const { return pid; } - -// update the checkbox values -void PidBox::setPid(const pidVals &pid) { - select_p->setValue(std::get<0>(pid)); - select_i->setValue(std::get<1>(pid)); - select_d->setValue(std::get<2>(pid)); - this->pid = pid; -} - -// update the pid and indicate as an outward signal that a change has occured. -void PidBox::updatePID() { - pidVals newPid = pidVals(select_p->value(), select_i->value(), select_d->value()); - if (this->pid != newPid) { - this->pid = newPid; - emit pidChanged(this->pid); - } -} - -} // namespace rtt::ai::interface diff --git a/src/interface/widgets/PidsWidget.cpp b/src/interface/widgets/PidsWidget.cpp deleted file mode 100644 index 61a8d324b9..0000000000 --- a/src/interface/widgets/PidsWidget.cpp +++ /dev/null @@ -1,58 +0,0 @@ -/* - * - * This file contains the contents of the 'PID' tab in the interface - */ - -#include "interface/widgets/PidsWidget.h" - -#include "interface/widgets/PidBox.h" - -namespace rtt::ai::interface { - -PidsWidget::PidsWidget(QWidget *parent) { - // initialize values for interface to display - Output::setNumTreePid(Constants::standardNumTreePID()); - Output::setReceivePid(Constants::standardReceivePID()); - Output::setInterceptPid(Constants::standardInterceptPID()); - Output::setKeeperPid(Constants::standardKeeperPID()); - Output::setKeeperInterceptPid(Constants::standardKeeperInterceptPID()); - - auto pidVLayout = new QVBoxLayout(); - - // create the widgets for the pids - auto numTreePidBox = new PidBox("NumTree"); - auto receivePidBox = new PidBox("Receive"); - auto interceptPidBox = new PidBox("Intercept"); - auto keeperPidBox = new PidBox("Keeper"); - auto keeperInterceptPidBox = new PidBox("Keeper Intercept"); - - // initialize them with the default values - numTreePidBox->setPid(Output::getNumTreePid()); - receivePidBox->setPid(Output::getReceivePid()); - interceptPidBox->setPid(Output::getInterceptPid()); - keeperPidBox->setPid(Output::getKeeperPid()); - keeperInterceptPidBox->setPid(Output::getKeeperInterceptPid()); - - QObject::connect(numTreePidBox, &PidBox::pidChanged, [=](const pidVals &pid) { Output::setNumTreePid(pid); }); - - QObject::connect(receivePidBox, &PidBox::pidChanged, [=](const pidVals &pid) { Output::setReceivePid(pid); }); - - QObject::connect(interceptPidBox, &PidBox::pidChanged, [=](const pidVals &pid) { Output::setInterceptPid(pid); }); - - QObject::connect(keeperPidBox, &PidBox::pidChanged, [=](const pidVals &pid) { Output::setKeeperPid(pid); }); - - QObject::connect(keeperInterceptPidBox, &PidBox::pidChanged, [=](const pidVals &pid) { Output::setKeeperInterceptPid(pid); }); - - // add the pid widgets to the layout - pidVLayout->addWidget(numTreePidBox); - pidVLayout->addWidget(receivePidBox); - pidVLayout->addWidget(interceptPidBox); - pidVLayout->addWidget(keeperPidBox); - pidVLayout->addWidget(keeperInterceptPidBox); - - auto pidSpacer = new QSpacerItem(100, 100, QSizePolicy::Expanding, QSizePolicy::Expanding); - pidVLayout->addSpacerItem(pidSpacer); - this->setLayout(pidVLayout); -} - -} // namespace rtt::ai::interface diff --git a/src/interface/widgets/mainWindow.cpp b/src/interface/widgets/mainWindow.cpp index a692de5244..5586ee0a43 100644 --- a/src/interface/widgets/mainWindow.cpp +++ b/src/interface/widgets/mainWindow.cpp @@ -3,7 +3,6 @@ #include #include "interface/widgets/MainControlsWidget.h" -#include "interface/widgets/PidsWidget.h" #include #include namespace rtt::ai::interface { @@ -29,7 +28,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind auto settingsWidget = new SettingsWidget(this); - auto pidWidget = new PidsWidget(); manualControlWidget = new ManualControlWidget(this); // add the tab widget @@ -40,7 +38,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind auto SettingsTabWidget = new QTabWidget; SettingsTabWidget->addTab(settingsWidget, tr("General settings")); - SettingsTabWidget->addTab(pidWidget, tr("PID")); tabWidget->addTab(SettingsTabWidget, tr("Settings")); tabWidget->addTab(manualControlWidget, tr("Manual")); From 6e4365b485b69d7a0eb59721c218bac5ee4ec691 Mon Sep 17 00:00:00 2001 From: rolf Date: Wed, 24 Feb 2021 21:26:09 +0100 Subject: [PATCH 13/40] Remove pid set functions --- include/roboteam_ai/interface/api/Output.h | 5 ----- src/interface/api/Output.cpp | 9 --------- 2 files changed, 14 deletions(-) diff --git a/include/roboteam_ai/interface/api/Output.h b/include/roboteam_ai/interface/api/Output.h index f1e68f2e86..35cd5ba890 100644 --- a/include/roboteam_ai/interface/api/Output.h +++ b/include/roboteam_ai/interface/api/Output.h @@ -45,11 +45,6 @@ class Output { static bool isTimeOutAtTop(); static void setTimeOutTop(bool top); - static void setReceivePid(const pidVals &receivePid); - static void setInterceptPid(const pidVals &interceptPid); - static void setKeeperPid(const pidVals &keeperPid); - static void setKeeperInterceptPid(const pidVals &keeperInterceptPid); - static void setRuleSetName(std::string name); static void setKeeperId(int id); }; diff --git a/src/interface/api/Output.cpp b/src/interface/api/Output.cpp index ed608fb2ec..c451ffa587 100644 --- a/src/interface/api/Output.cpp +++ b/src/interface/api/Output.cpp @@ -85,15 +85,6 @@ void Output::setInterfaceGameState(GameState interfaceGameState) { } -void Output::setReceivePid(const pidVals &receivePid) { receivePID = receivePid; } -void Output::setInterceptPid(const pidVals &interceptPid) { interceptPID = interceptPid; } - - -void Output::setKeeperPid(const pidVals &keeperPid) { keeperPID = keeperPid; } - - -void Output::setKeeperInterceptPid(const pidVals &keeperInterceptPid) { keeperInterceptPID = keeperInterceptPid; } - } // namespace rtt::ai::interface \ No newline at end of file From 016ceab1e169d8a6f5128a5119acf63214e6e74c Mon Sep 17 00:00:00 2001 From: rolf Date: Wed, 24 Feb 2021 21:26:50 +0100 Subject: [PATCH 14/40] Remove pid set functions --- include/roboteam_ai/interface/api/Output.h | 4 ---- src/interface/api/Output.cpp | 5 ----- 2 files changed, 9 deletions(-) diff --git a/include/roboteam_ai/interface/api/Output.h b/include/roboteam_ai/interface/api/Output.h index 35cd5ba890..ef9ef37435 100644 --- a/include/roboteam_ai/interface/api/Output.h +++ b/include/roboteam_ai/interface/api/Output.h @@ -17,10 +17,6 @@ typedef std::tuple pidVals; class Output { private: - static pidVals receivePID; - static pidVals interceptPID; - static pidVals keeperPID; - static pidVals keeperInterceptPID; static std::mutex markerMutex; static std::mutex refMutex; diff --git a/src/interface/api/Output.cpp b/src/interface/api/Output.cpp index c451ffa587..ae2f4eb5cb 100644 --- a/src/interface/api/Output.cpp +++ b/src/interface/api/Output.cpp @@ -8,11 +8,6 @@ namespace rtt::ai::interface { -// these values are default initialized here, but will be updated once mainWidget.cpp constructs the PID widget. -pidVals Output::receivePID = pidVals(0.0, 0.0, 0.0); -pidVals Output::interceptPID = pidVals(0.0, 0.0, 0.0); -pidVals Output::keeperPID = pidVals(0.0, 0.0, 0.0); -pidVals Output::keeperInterceptPID = pidVals(0.0, 0.0, 0.0); rtt::Vector2 Output::markerPosition = {0, 0}; // initialize on middle of the field bool Output::useRefereeCommands = false; From 5a562b9457dacb5a14381b563691ec498e2c972f Mon Sep 17 00:00:00 2001 From: rolf Date: Sun, 7 Mar 2021 14:43:14 +0100 Subject: [PATCH 15/40] remove menu --- src/ApplicationManager.cpp | 2 +- src/interface/widgets/mainWindow.cpp | 5 ----- 2 files changed, 1 insertion(+), 6 deletions(-) diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index cce4368fc6..a6db698690 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -108,7 +108,7 @@ void ApplicationManager::runOneLoopCycle() { } std::this_thread::sleep_for(std::chrono::milliseconds(100)); } - //TODO: move to AI + rtt::ai::control::ControlModule::sendAllCommands(io); io->handleCentralServerConnection(); } diff --git a/src/interface/widgets/mainWindow.cpp b/src/interface/widgets/mainWindow.cpp index 5586ee0a43..6accc2ad90 100644 --- a/src/interface/widgets/mainWindow.cpp +++ b/src/interface/widgets/mainWindow.cpp @@ -16,11 +16,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind horizontalLayout = new QHBoxLayout(); vLayout = new QVBoxLayout(); - auto menu = new QMenuBar(this); - this->setMenuBar(menu); - menu->addMenu(tr("&File")); - auto viewMenu = menu->addMenu(tr("&Visualization")); - // the main controls widget for the most crucial buttons // changing strategies, goalie id, etc. auto mainControlsWidget = new MainControlsWidget(this, manager); From a0904fab30eae4a2de66f993931dcbc80a3bb92f Mon Sep 17 00:00:00 2001 From: rolf Date: Sun, 7 Mar 2021 15:23:23 +0100 Subject: [PATCH 16/40] remove marker --- include/roboteam_ai/interface/api/Output.h | 5 +---- src/interface/api/Output.cpp | 11 ----------- 2 files changed, 1 insertion(+), 15 deletions(-) diff --git a/include/roboteam_ai/interface/api/Output.h b/include/roboteam_ai/interface/api/Output.h index ef9ef37435..8de817fbe9 100644 --- a/include/roboteam_ai/interface/api/Output.h +++ b/include/roboteam_ai/interface/api/Output.h @@ -18,10 +18,8 @@ typedef std::tuple pidVals; class Output { private: - static std::mutex markerMutex; static std::mutex refMutex; - static rtt::Vector2 markerPosition; static bool useRefereeCommands; static bool timeOutAtTop; @@ -36,8 +34,7 @@ class Output { static bool usesRefereeCommands(); static void setUseRefereeCommands(bool useRefereeCommands); - static const rtt::Vector2 &getInterfaceMarkerPosition(); - static void setMarkerPosition(const rtt::Vector2 &ballPlacementTarget); + static bool isTimeOutAtTop(); static void setTimeOutTop(bool top); diff --git a/src/interface/api/Output.cpp b/src/interface/api/Output.cpp index ae2f4eb5cb..f84e1c9236 100644 --- a/src/interface/api/Output.cpp +++ b/src/interface/api/Output.cpp @@ -9,11 +9,9 @@ namespace rtt::ai::interface { -rtt::Vector2 Output::markerPosition = {0, 0}; // initialize on middle of the field bool Output::useRefereeCommands = false; bool Output::timeOutAtTop = Constants::STD_TIMEOUT_TO_TOP(); -std::mutex Output::markerMutex; std::mutex Output::refMutex; GameState Output::interfaceGameState("halt_strategy", "default"); @@ -37,15 +35,6 @@ void Output::sendHaltCommand() { } } -const Vector2 &Output::getInterfaceMarkerPosition() { - std::lock_guard lock(markerMutex); - return markerPosition; -} - -void Output::setMarkerPosition(const Vector2 &ballPlacementTarget) { - std::lock_guard lock(markerMutex); - Output::markerPosition = ballPlacementTarget; -} bool Output::usesRefereeCommands() { std::lock_guard lock(refMutex); From d7ea9366708905856b7945f7cd72ce398a75aeb8 Mon Sep 17 00:00:00 2001 From: rolf Date: Sun, 7 Mar 2021 15:25:07 +0100 Subject: [PATCH 17/40] Remove timeout at top --- include/roboteam_ai/interface/api/Output.h | 5 +---- src/interface/api/Output.cpp | 11 ----------- 2 files changed, 1 insertion(+), 15 deletions(-) diff --git a/include/roboteam_ai/interface/api/Output.h b/include/roboteam_ai/interface/api/Output.h index 8de817fbe9..84f687d9ae 100644 --- a/include/roboteam_ai/interface/api/Output.h +++ b/include/roboteam_ai/interface/api/Output.h @@ -13,7 +13,6 @@ namespace rtt::ai::interface { -typedef std::tuple pidVals; class Output { private: @@ -21,7 +20,6 @@ class Output { static std::mutex refMutex; static bool useRefereeCommands; - static bool timeOutAtTop; static GameState interfaceGameState; @@ -35,8 +33,7 @@ class Output { static bool usesRefereeCommands(); static void setUseRefereeCommands(bool useRefereeCommands); - static bool isTimeOutAtTop(); - static void setTimeOutTop(bool top); + static void setRuleSetName(std::string name); static void setKeeperId(int id); diff --git a/src/interface/api/Output.cpp b/src/interface/api/Output.cpp index f84e1c9236..6595facc80 100644 --- a/src/interface/api/Output.cpp +++ b/src/interface/api/Output.cpp @@ -10,7 +10,6 @@ namespace rtt::ai::interface { bool Output::useRefereeCommands = false; -bool Output::timeOutAtTop = Constants::STD_TIMEOUT_TO_TOP(); std::mutex Output::refMutex; @@ -46,16 +45,6 @@ void Output::setUseRefereeCommands(bool useRefereeCommands) { Output::useRefereeCommands = useRefereeCommands; } - - - - - - -void Output::setTimeOutTop(bool top) { timeOutAtTop = top; } - -bool Output::isTimeOutAtTop() { return timeOutAtTop; } - void Output::setRuleSetName(std::string name) { Output::interfaceGameState.ruleSetName = std::move(name); } void Output::setKeeperId(int id) { Output::interfaceGameState.keeperId = id; } From 4cabe2d465cba6495f89cdf72da96c6e4557ad9d Mon Sep 17 00:00:00 2001 From: rolf Date: Sun, 7 Mar 2021 22:16:54 +0100 Subject: [PATCH 18/40] Start removing settings global --- CMakeLists.txt | 2 + include/roboteam_ai/AI.h | 14 ++--- include/roboteam_ai/AISettings.h | 45 ++++++++++++++ include/roboteam_ai/AppSettings.h | 30 ++++++++++ .../interface/widgets/MainControlsWidget.h | 7 +-- .../interface/widgets/SettingsWidget.h | 36 ----------- include/roboteam_ai/utilities/Settings.h | 1 - src/AI.cpp | 3 + src/AISettings.cpp | 60 +++++++++++++++++++ src/AppSettings.cpp | 31 ++++++++++ src/ApplicationManager.cpp | 31 +++------- src/interface/widgets/MainControlsWidget.cpp | 42 ------------- src/interface/widgets/SettingsWidget.cpp | 2 +- src/interface/widgets/mainWindow.cpp | 7 --- src/utilities/IOManager.cpp | 1 + src/utilities/Settings.cpp | 1 - 16 files changed, 187 insertions(+), 126 deletions(-) create mode 100644 include/roboteam_ai/AISettings.h create mode 100644 include/roboteam_ai/AppSettings.h delete mode 100644 include/roboteam_ai/interface/widgets/SettingsWidget.h create mode 100644 src/AISettings.cpp create mode 100644 src/AppSettings.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 2014de73cc..1292f0c2f2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -241,6 +241,8 @@ set(AI_SOURCES ${INTERFACE_SOURCES} ${WORLD_SOURCES} ${MANUAL_SOURCES} + src/AISettings.cpp + src/AppSettings.cpp ) set(AI_LIBS diff --git a/include/roboteam_ai/AI.h b/include/roboteam_ai/AI.h index 86d1450bd7..07ef960848 100644 --- a/include/roboteam_ai/AI.h +++ b/include/roboteam_ai/AI.h @@ -7,11 +7,12 @@ #include "stp/PlayChecker.hpp" #include "stp/PlayDecider.hpp" +#include "AISettings.h" namespace rtt { class AI { public: - AI(); + explicit AI(int id); void decidePlay(world::World *_world); @@ -29,16 +30,13 @@ class AI { * Checks, out of the valid plays, which play is the best to choose */ rtt::ai::stp::PlayDecider playDecider; - /** - * Function that decides whether to change plays given a world and field. - * @param _world the current world state - * @param field the current field state - */ /** - * The vector that contains all plays - */ + * The vector that contains all plays + */ std::vector> plays; + + AISettings settings; }; } #endif //RTT_ROBOTEAM_AI_SRC_AI_H_ diff --git a/include/roboteam_ai/AISettings.h b/include/roboteam_ai/AISettings.h new file mode 100644 index 0000000000..97d76b2dd4 --- /dev/null +++ b/include/roboteam_ai/AISettings.h @@ -0,0 +1,45 @@ +// +// Created by rolf on 07-03-21. +// + +#ifndef RTT_ROBOTEAM_AI_SRC_AISETTINGS_H_ +#define RTT_ROBOTEAM_AI_SRC_AISETTINGS_H_ + +#include + +class AISettings { + public: + explicit AISettings(int id); + enum CommunicationMode{ + SERIAL, + GRSIM + }; + + [[nodiscard]] int getId() const; + void setId(int id); + + [[nodiscard]] bool isYellow() const; + void setYellow(bool isYellow); + + [[nodiscard]] bool isLeft() const; + void setLeft(bool left); + + [[nodiscard]] CommunicationMode getCommunicationMode() const; + void setCommunicationMode(CommunicationMode mode); + + [[nodiscard]] const std::string& getRobothubSendIp() const; + void setRobothubSendIp(const std::string& ip); + + [[nodiscard]] int getRobothubSendPort() const; + void setRobothubSendPort(int port); + private: + int id = 0; + bool is_yellow; + bool is_left; + CommunicationMode mode; + std::string robothub_send_ip; + int robothub_send_port; + +}; + +#endif //RTT_ROBOTEAM_AI_SRC_AISETTINGS_H_ diff --git a/include/roboteam_ai/AppSettings.h b/include/roboteam_ai/AppSettings.h new file mode 100644 index 0000000000..35c0c48f31 --- /dev/null +++ b/include/roboteam_ai/AppSettings.h @@ -0,0 +1,30 @@ +// +// Created by rolf on 07-03-21. +// + +#ifndef RTT_ROBOTEAM_AI_SRC_APPSETTINGS_H_ +#define RTT_ROBOTEAM_AI_SRC_APPSETTINGS_H_ +#include + +class AppSettings { + public: + [[nodiscard]] const std::string& getRefereeIp() const; + void setRefereeIp(const std::string& refereeIp); + + [[nodiscard]] int getRefereePort() const; + void setRefereePort(int port); + + [[nodiscard]] const std::string& getVisionIp() const; + void setVisionIp(const std::string& vision_ip); + + [[nodiscard]] int getVisionPort() const; + void setVisionPort(int port); + private: + std::string referee_ip; + int referee_port; + + std::string vision_ip; + int vision_port; +}; + +#endif //RTT_ROBOTEAM_AI_SRC_APPSETTINGS_H_ diff --git a/include/roboteam_ai/interface/widgets/MainControlsWidget.h b/include/roboteam_ai/interface/widgets/MainControlsWidget.h index 9049e403d6..f7b39ad7cc 100644 --- a/include/roboteam_ai/interface/widgets/MainControlsWidget.h +++ b/include/roboteam_ai/interface/widgets/MainControlsWidget.h @@ -39,14 +39,9 @@ class MainControlsWidget : public QWidget { ApplicationManager *manager; - void setToggleColorBtnLayout() const; - void setToggleSideBtnLayout() const; - void setToggleSerialBtnLayout() const; + public slots: - void toggleOurColorParam(); - void toggleOurSideParam(); - void toggleSerialParam(); void sendPauseSignal(); void updatePause(); void setUseReferee(bool useRef); diff --git a/include/roboteam_ai/interface/widgets/SettingsWidget.h b/include/roboteam_ai/interface/widgets/SettingsWidget.h deleted file mode 100644 index ff10f13a6c..0000000000 --- a/include/roboteam_ai/interface/widgets/SettingsWidget.h +++ /dev/null @@ -1,36 +0,0 @@ -// -// Created by mrlukasbos on 1-9-19. -// - -#ifndef RTT_SETTINGSWIDGET_H -#define RTT_SETTINGSWIDGET_H - -#include -#include -#include -#include - -namespace rtt::ai::interface { - -class SettingsWidget : public QWidget { - Q_OBJECT - - private: - QVBoxLayout *vLayout; - QLineEdit *grsimIpText; - QSpinBox *grsimPort; - - public: - explicit SettingsWidget(QWidget *parent = nullptr); - - public slots: - void changeTeamColor(bool isYellow); - void changeTeamSide(bool isLeft); - void changeMode(bool serial); - void changeGrSimIp(QString ip); - void changeGrSimPort(int port); -}; - -} // namespace rtt::ai::interface - -#endif // RTT_SETTINGSWIDGET_H diff --git a/include/roboteam_ai/utilities/Settings.h b/include/roboteam_ai/utilities/Settings.h index f858011ae8..bae9359606 100644 --- a/include/roboteam_ai/utilities/Settings.h +++ b/include/roboteam_ai/utilities/Settings.h @@ -71,6 +71,5 @@ class Settings { proto::Setting toMessage(); }; -extern Settings SETTINGS; } // namespace rtt #endif // RTT_SETTINGS_H diff --git a/src/AI.cpp b/src/AI.cpp index 3bc7dbceec..2e59c3a528 100644 --- a/src/AI.cpp +++ b/src/AI.cpp @@ -95,3 +95,6 @@ void rtt::AI::decidePlay(rtt::world::World *_world) { currentPlay->update(); //mainWindow->updatePlay(currentPlay); TODO: send to interface } +rtt::AI::AI(int id) { + +} diff --git a/src/AISettings.cpp b/src/AISettings.cpp new file mode 100644 index 0000000000..76e93e928a --- /dev/null +++ b/src/AISettings.cpp @@ -0,0 +1,60 @@ +// +// Created by rolf on 07-03-21. +// + +#include "AISettings.h" +AISettings::AISettings(int initial_id) : +id{initial_id}, +mode{GRSIM}, +robothub_send_ip{"127.0.0.1"}, //local host +robothub_send_port{20011} //grsim default +{ + //these settings are for testing and convenience, basically + if(initial_id == 1){ + is_yellow = false; + is_left = false; + }else{ + is_yellow = true; + is_left = true; + } +} + +int AISettings::getId() const { + return id; +} +void AISettings::setId(int new_id) { + id = new_id; +} +bool AISettings::isYellow() const { + return is_yellow; +} +void AISettings::setYellow(bool isYellow) { + is_yellow = isYellow; + +} +bool AISettings::isLeft() const { + return is_left; +} +void AISettings::setLeft(bool left) { + is_left = left; +} +AISettings::CommunicationMode AISettings::getCommunicationMode() const { + return mode; +} +void AISettings::setCommunicationMode(CommunicationMode new_mode) { + mode = new_mode; +} +const std::string &AISettings::getRobothubSendIp() const { + return robothub_send_ip; +} +void AISettings::setRobothubSendIp(const std::string &ip) { + robothub_send_ip = ip; +} +int AISettings::getRobothubSendPort() const { + return robothub_send_port; +} +void AISettings::setRobothubSendPort(int port) { + robothub_send_port = port; +} + + diff --git a/src/AppSettings.cpp b/src/AppSettings.cpp new file mode 100644 index 0000000000..9aa5d7867e --- /dev/null +++ b/src/AppSettings.cpp @@ -0,0 +1,31 @@ +// +// Created by rolf on 07-03-21. +// + +#include "AppSettings.h" +const std::string &AppSettings::getRefereeIp() const { + return referee_ip; +} +void AppSettings::setRefereeIp(const std::string &refereeIp) { + referee_ip = refereeIp; +} +int AppSettings::getRefereePort() const { + return referee_port; +} +void AppSettings::setRefereePort(int port) { + referee_port = port; +} +const std::string &AppSettings::getVisionIp() const { + return vision_ip; +} +void AppSettings::setVisionIp(const std::string &visionIp) { + vision_ip = visionIp; +} +int AppSettings::getVisionPort() const { + return vision_port; +} +void AppSettings::setVisionPort(int port) { + vision_port = port; +} + + diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index a6db698690..e1e9f347a4 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -15,40 +15,23 @@ namespace rtt { /// Start running behaviour trees. While doing so, publish settings and log the FPS of the system void ApplicationManager::start(int id) { - io = std::make_unique(); + io = std::make_unique(); + rtt::ai::Constants::init(); - RTT_INFO("This AI is initialized with id ", id) - // some default settings for different team ids (saves time while testing) - if (id == 1) { - // standard blue team on right - rtt::SETTINGS.init(id); - rtt::SETTINGS.setYellow(false); - rtt::SETTINGS.setLeft(false); - RTT_INFO("Initially playing as the BLUE team") - RTT_INFO("We are playing on the RIGHT side of the field") - } else { - // standard yellow team on left - rtt::SETTINGS.init(id); - rtt::SETTINGS.setYellow(true); - rtt::SETTINGS.setLeft(true); - RTT_INFO("Initially playing as the YELLOW team") - RTT_INFO("We are playing on the LEFT side of the field") - } - - rtt::SETTINGS.setSerialMode(false); + + rtt::SETTINGS.setVisionIp("127.0.0.1"); rtt::SETTINGS.setVisionPort(10006); rtt::SETTINGS.setRefereeIp("224.5.23.1"); rtt::SETTINGS.setRefereePort(10003); - rtt::SETTINGS.setRobothubSendIp("127.0.0.1"); - rtt::SETTINGS.setRobothubSendPort(20011); - io->init(rtt::SETTINGS.getId()); + + io->init(id); // make sure we start in halt state for safety ai::GameStateManager::forceNewGameState(RefCommand::HALT, std::nullopt); RTT_INFO("Start looping") RTT_INFO("Waiting for field_data and robots...") - ai = std::make_unique(); + ai = std::make_unique(id); roboteam_utils::Timer t; t.loop( diff --git a/src/interface/widgets/MainControlsWidget.cpp b/src/interface/widgets/MainControlsWidget.cpp index dc618ea06e..4fd4f8e458 100644 --- a/src/interface/widgets/MainControlsWidget.cpp +++ b/src/interface/widgets/MainControlsWidget.cpp @@ -133,23 +133,6 @@ void MainControlsWidget::setUseReferee(bool useRef) { } } -/// toggle the setting 'isYellow' -void MainControlsWidget::toggleOurColorParam() { - SETTINGS.setYellow(!SETTINGS.isYellow()); - setToggleColorBtnLayout(); -} - -/// toggle the the setting 'isLeft' -void MainControlsWidget::toggleOurSideParam() { - SETTINGS.setLeft(!SETTINGS.isLeft()); - setToggleSideBtnLayout(); -} - -/// toggle the the setting 'isSerialMode' -void MainControlsWidget::toggleSerialParam() { - SETTINGS.setSerialMode(!SETTINGS.isSerialMode()); - setToggleSerialBtnLayout(); -} /// send a halt signal to stop all trees from executing void MainControlsWidget::sendPauseSignal() { Output::sendHaltCommand(); } @@ -165,31 +148,6 @@ void MainControlsWidget::updatePause() { } } -void MainControlsWidget::setToggleColorBtnLayout() const { - if (SETTINGS.isYellow()) { - toggleColorBtn->setStyleSheet("background-color: orange;"); // orange is more readable - toggleColorBtn->setText("Playing as Yellow"); - } else { - toggleColorBtn->setStyleSheet("background-color: blue;"); - toggleColorBtn->setText("Playing as Blue"); - } -} - -void MainControlsWidget::setToggleSideBtnLayout() const { - if (SETTINGS.isLeft()) { - toggleSideBtn->setText("â—€ Playing as left"); - } else { - toggleSideBtn->setText("Playing as right â–¶"); - } -} - -void MainControlsWidget::setToggleSerialBtnLayout() const { - if (SETTINGS.isSerialMode()) { - toggleSerialBtn->setText("BaseStation"); - } else { - toggleSerialBtn->setText("GrSim"); - } -} void MainControlsWidget::updateContents() { auto ruleSetText = QString::fromStdString(GameStateManager::getCurrentGameState().ruleSetName); diff --git a/src/interface/widgets/SettingsWidget.cpp b/src/interface/widgets/SettingsWidget.cpp index 247a2e107b..d36101c9ac 100644 --- a/src/interface/widgets/SettingsWidget.cpp +++ b/src/interface/widgets/SettingsWidget.cpp @@ -12,7 +12,7 @@ SettingsWidget::SettingsWidget(QWidget *parent) { this->setLayout(vLayout); // grsim ip + port settings - QGroupBox *grsimSettingsGroup = new QGroupBox("grsim transmission ip + port"); + QGroupBox *grsimSettingsGroup = new QGroupBox("grsim transmissin ip + port"); auto grsimSettingsWidgetLayout = new QHBoxLayout(); grsimIpText = new QLineEdit(); grsimIpText->setText(QString::fromStdString(SETTINGS.getRobothubSendIp())); diff --git a/src/interface/widgets/mainWindow.cpp b/src/interface/widgets/mainWindow.cpp index 6accc2ad90..162d47d478 100644 --- a/src/interface/widgets/mainWindow.cpp +++ b/src/interface/widgets/mainWindow.cpp @@ -1,7 +1,5 @@ #include "interface/widgets/mainWindow.h" -#include - #include "interface/widgets/MainControlsWidget.h" #include #include @@ -21,7 +19,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind auto mainControlsWidget = new MainControlsWidget(this, manager); vLayout->addWidget(mainControlsWidget); - auto settingsWidget = new SettingsWidget(this); manualControlWidget = new ManualControlWidget(this); @@ -32,7 +29,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind auto SettingsTabWidget = new QTabWidget; - SettingsTabWidget->addTab(settingsWidget, tr("General settings")); tabWidget->addTab(SettingsTabWidget, tr("Settings")); tabWidget->addTab(manualControlWidget, tr("Manual")); @@ -103,7 +99,4 @@ void MainWindow::clearLayout(QLayout *layout) { } } - - - } // namespace rtt::ai::interface diff --git a/src/utilities/IOManager.cpp b/src/utilities/IOManager.cpp index c3220e98b9..c2e2fd795a 100644 --- a/src/utilities/IOManager.cpp +++ b/src/utilities/IOManager.cpp @@ -40,6 +40,7 @@ void IOManager::init(int teamId) { void IOManager::handleState(proto::State &stateMsg) { std::unique_lock lock(stateMutex); //write lock this->state.CopyFrom(stateMsg); + //TODO: move this to the ai if(state.has_referee()){ roboteam_utils::rotate(state.mutable_referee()); // Our name as specified by ssl-refbox : https://github.com/RoboCup-SSL/ssl-refbox/blob/master/referee.conf diff --git a/src/utilities/Settings.cpp b/src/utilities/Settings.cpp index 5e10c9661a..bc6e76c3b6 100644 --- a/src/utilities/Settings.cpp +++ b/src/utilities/Settings.cpp @@ -5,7 +5,6 @@ #include "include/roboteam_ai/utilities/Settings.h" namespace rtt { -Settings SETTINGS; void Settings::init(int id) { setId(id); From ac299f0f581565041f97812682b226e13efb473c Mon Sep 17 00:00:00 2001 From: rolf Date: Mon, 29 Mar 2021 23:56:57 +0200 Subject: [PATCH 19/40] More changes, refactoring settings --- CMakeLists.txt | 4 - include/roboteam_ai/AI.h | 11 ++- include/roboteam_ai/AISettings.h | 72 +++++++++-------- include/roboteam_ai/ApplicationManager.h | 3 + include/roboteam_ai/interface/api/Output.h | 3 - .../utilities/GameStateManager.hpp | 4 +- include/roboteam_ai/utilities/Pause.h | 34 -------- include/roboteam_ai/utilities/Settings.h | 75 ------------------ include/roboteam_ai/world/World.hpp | 40 +--------- include/roboteam_ai/world/WorldData.hpp | 4 +- src/AI.cpp | 77 ++++++++++++++++--- src/AISettings.cpp | 24 +++--- src/AppSettings.cpp | 9 +++ src/ApplicationManager.cpp | 51 ++---------- src/interface/api/Output.cpp | 19 ----- src/interface/widgets/MainControlsWidget.cpp | 14 ---- src/utilities/GameStateManager.cpp | 19 +++-- src/utilities/IOManager.cpp | 19 ----- src/utilities/Pause.cpp | 38 --------- src/utilities/Settings.cpp | 67 ---------------- src/world/World.cpp | 4 +- src/world/WorldData.cpp | 6 +- 22 files changed, 172 insertions(+), 425 deletions(-) delete mode 100644 include/roboteam_ai/utilities/Pause.h delete mode 100644 include/roboteam_ai/utilities/Settings.h delete mode 100644 src/utilities/Pause.cpp delete mode 100644 src/utilities/Settings.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 1292f0c2f2..bc38fd021f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -35,11 +35,9 @@ find_package(Qt5Widgets REQUIRED) set(UTILS_SOURCES ${PROJECT_SOURCE_DIR}/src/utilities/GameStateManager.cpp ${PROJECT_SOURCE_DIR}/src/utilities/Constants.cpp - ${PROJECT_SOURCE_DIR}/src/utilities/Pause.cpp ${PROJECT_SOURCE_DIR}/src/utilities/RefGameState.cpp ${PROJECT_SOURCE_DIR}/src/utilities/Dealer.cpp ${PROJECT_SOURCE_DIR}/src/utilities/IOManager.cpp - ${PROJECT_SOURCE_DIR}/src/utilities/Settings.cpp ${PROJECT_SOURCE_DIR}/src/utilities/StrategyManager.cpp ) @@ -205,13 +203,11 @@ set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/src/interface/widgets/mainWindow.cpp ${PROJECT_SOURCE_DIR}/src/interface/api/Output.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/MainControlsWidget.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/SettingsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/ManualControlWidget.cpp #QT wants to know about these headers ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/MainControlsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/mainWindow.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/SettingsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/ManualControlWidget.h ) diff --git a/include/roboteam_ai/AI.h b/include/roboteam_ai/AI.h index 07ef960848..09fb81202b 100644 --- a/include/roboteam_ai/AI.h +++ b/include/roboteam_ai/AI.h @@ -8,15 +8,24 @@ #include "stp/PlayChecker.hpp" #include "stp/PlayDecider.hpp" #include "AISettings.h" +#include "world/World.hpp" +#include +#include namespace rtt { class AI { public: explicit AI(int id); - void decidePlay(world::World *_world); + void updateState(const proto::State& state); + proto::AICommand decidePlay(); private: + //updates referee-related information to the game state manager, and makes sure things such as rotation, color etc. are correct + void updateSettingsReferee(const proto::State& state); + + void onSideOrColorChanged(); + std::unique_ptr world = nullptr; /** * Current best play as picked by checker + decider */ diff --git a/include/roboteam_ai/AISettings.h b/include/roboteam_ai/AISettings.h index 97d76b2dd4..7ebc49d73f 100644 --- a/include/roboteam_ai/AISettings.h +++ b/include/roboteam_ai/AISettings.h @@ -6,40 +6,44 @@ #define RTT_ROBOTEAM_AI_SRC_AISETTINGS_H_ #include +namespace rtt { + class AISettings { + public: + explicit AISettings(int id); + enum CommunicationMode { + SERIAL, + GRSIM + }; + + [[nodiscard]] int getId() const; + void setId(int id); + + [[nodiscard]] bool isYellow() const; + void setYellow(bool isYellow); + + [[nodiscard]] bool isLeft() const; + void setLeft(bool left); + + [[nodiscard]] CommunicationMode getCommunicationMode() const; + void setCommunicationMode(CommunicationMode mode); + + [[nodiscard]] const std::string &getRobothubSendIp() const; + void setRobothubSendIp(const std::string &ip); + + [[nodiscard]] int getRobothubSendPort() const; + void setRobothubSendPort(int port); + + [[nodiscard]] bool isPaused() const; + void setPause(bool paused); + private: + int id; + bool is_yellow; + bool is_left; + CommunicationMode mode; + std::string robothub_send_ip; + int robothub_send_port; + bool is_paused; -class AISettings { - public: - explicit AISettings(int id); - enum CommunicationMode{ - SERIAL, - GRSIM }; - - [[nodiscard]] int getId() const; - void setId(int id); - - [[nodiscard]] bool isYellow() const; - void setYellow(bool isYellow); - - [[nodiscard]] bool isLeft() const; - void setLeft(bool left); - - [[nodiscard]] CommunicationMode getCommunicationMode() const; - void setCommunicationMode(CommunicationMode mode); - - [[nodiscard]] const std::string& getRobothubSendIp() const; - void setRobothubSendIp(const std::string& ip); - - [[nodiscard]] int getRobothubSendPort() const; - void setRobothubSendPort(int port); - private: - int id = 0; - bool is_yellow; - bool is_left; - CommunicationMode mode; - std::string robothub_send_ip; - int robothub_send_port; - -}; - +} #endif //RTT_ROBOTEAM_AI_SRC_AISETTINGS_H_ diff --git a/include/roboteam_ai/ApplicationManager.h b/include/roboteam_ai/ApplicationManager.h index 02a3b37c33..4d76360bfb 100644 --- a/include/roboteam_ai/ApplicationManager.h +++ b/include/roboteam_ai/ApplicationManager.h @@ -10,6 +10,7 @@ #include "interface/widgets/mainWindow.h" #include "AI.h" #include "utilities/IOManager.h" +#include "AppSettings.h" namespace rtt { @@ -21,6 +22,8 @@ class ApplicationManager { void runOneLoopCycle(); bool fieldInitialized = false; bool robotsInitialized = false; + + AppSettings settings; std::unique_ptr ai; std::unique_ptr io; diff --git a/include/roboteam_ai/interface/api/Output.h b/include/roboteam_ai/interface/api/Output.h index 84f687d9ae..d1b4cc8e66 100644 --- a/include/roboteam_ai/interface/api/Output.h +++ b/include/roboteam_ai/interface/api/Output.h @@ -9,7 +9,6 @@ #include "roboteam_utils/Vector2.h" #include "utilities/GameState.h" -#include "utilities/Pause.h" namespace rtt::ai::interface { @@ -24,8 +23,6 @@ class Output { static GameState interfaceGameState; public: - static void sendHaltCommand(); - static void setInterfaceGameState(GameState interfaceGameState); static const GameState &getInterfaceGameState(); diff --git a/include/roboteam_ai/utilities/GameStateManager.hpp b/include/roboteam_ai/utilities/GameStateManager.hpp index e1e43c61c8..9ccdd43dbe 100644 --- a/include/roboteam_ai/utilities/GameStateManager.hpp +++ b/include/roboteam_ai/utilities/GameStateManager.hpp @@ -10,12 +10,13 @@ #include "RefGameState.h" #include "StrategyManager.h" #include +#include namespace rtt::ai { class GameStateManager { public: - static void setRefereeData(proto::SSL_Referee refMsg, const rtt::world::World* data); + static void setRefereeData(proto::SSL_Referee refMsg, const rtt::world::World* data, const AISettings& settings); static proto::SSL_Referee getRefereeData(); static GameState getCurrentGameState(); static bool canEnterDefenseArea(int robotId); @@ -25,6 +26,7 @@ class GameStateManager { private: static proto::SSL_Referee refMsg; + static int keeperID; static StrategyManager strategymanager; static std::mutex refMsgLock; }; diff --git a/include/roboteam_ai/utilities/Pause.h b/include/roboteam_ai/utilities/Pause.h deleted file mode 100644 index b25619c749..0000000000 --- a/include/roboteam_ai/utilities/Pause.h +++ /dev/null @@ -1,34 +0,0 @@ -// -// Created by baris on 15-2-19. -// - -#ifndef ROBOTEAM_AI_PAUSE_H -#define ROBOTEAM_AI_PAUSE_H - -#include -#include - -namespace rtt::world { -class World; -} - -namespace rtt::ai { - -namespace io { -class IOManager; -} - -class Pause { - private: - static bool pause; - static std::mutex pauseLock; - - public: - Pause(); - bool getPause(); - void haltRobots(rtt::world::World const* data); - void setPause(bool set); -}; -} // namespace rtt::ai - -#endif // ROBOTEAM_AI_PAUSE_H diff --git a/include/roboteam_ai/utilities/Settings.h b/include/roboteam_ai/utilities/Settings.h deleted file mode 100644 index bae9359606..0000000000 --- a/include/roboteam_ai/utilities/Settings.h +++ /dev/null @@ -1,75 +0,0 @@ -// -// Created by mrlukasbos on 1-9-19. -// - -#ifndef RTT_SETTINGS_H -#define RTT_SETTINGS_H - -#include - -namespace rtt { - -class Settings { - private: - int id = 0; - bool yellow; - bool left; - bool serialMode; - - std::string visionIp; - int visionPort; - std::string refereeIp; - - public: - int getId() const; - - void setId(int id); - - bool isYellow() const; - - void setYellow(bool yellow); - - bool isLeft() const; - - void setLeft(bool left); - - bool isSerialMode() const; - - void setSerialMode(bool serialMode); - - const std::string &getVisionIp() const; - - void setVisionIp(const std::string &visionIp); - - int getVisionPort() const; - - void setVisionPort(int visionPort); - - const std::string &getRefereeIp() const; - - void setRefereeIp(const std::string &refereeIp); - - int getRefereePort() const; - - void setRefereePort(int refereePort); - - const std::string &getRobothubSendIp() const; - - void setRobothubSendIp(const std::string &robothubSendIp); - - int getRobothubSendPort() const; - - void setRobothubSendPort(int robothubSendPort); - - private: - int refereePort; - std::string robothubSendIp; - int robothubSendPort; - - public: - void init(int id); - proto::Setting toMessage(); -}; - -} // namespace rtt -#endif // RTT_SETTINGS_H diff --git a/include/roboteam_ai/world/World.hpp b/include/roboteam_ai/world/World.hpp index cac6d98ebd..175d1ec896 100644 --- a/include/roboteam_ai/world/World.hpp +++ b/include/roboteam_ai/world/World.hpp @@ -4,6 +4,7 @@ #ifndef RTT_WORLD_HPP #define RTT_WORLD_HPP + #include #include "WorldData.hpp" #include "control/positionControl/PositionControl.h" @@ -34,41 +35,11 @@ namespace rtt::world { * one of the only ways to keep a project datarace-free */ class World { - /** - * Structure that provides structured binding support for the world. - * @tparam T Type of data to lock (a pointer to!) - * - * AcquireInfo get_int() { - * static std::mutex mtx; - * static int value; - * return AcquireInfo{ mtx, &value }; - * } - * - * auto const& [_, t_obj] = something::instance(); - * // _ is a lock guard - * // t_obj is a pointer to T - */ - template - struct AcquireInfo { - std::lock_guard mtx; - T* data; - }; public: - /** - * Global singleton for World, scott-meyers style - * @param[in] resetWorld Boolean that marks whether to reset the world before returning - * if set to true, world.clear() is called - * if set to false, worldInstance is simply reset - * @return A pointer to a static World - */ - inline static AcquireInfo instance() { - static World worldInstance{&rtt::SETTINGS}; - return { std::lock_guard(worldInstance.updateMutex), &worldInstance }; - } /** - * Not copyable, movable or assignable, global state + * Not copyable, movable or assignable, global state (this prevents many stupid mistakes) */ World(World const &) = delete; World &operator=(World &) = delete; @@ -90,7 +61,7 @@ class World { * Usage of settings before construction of the applicationmanager will result in undefined * behavior due to uninitialized memory */ - explicit World(Settings *settings); + explicit World(bool we_are_yellow); /** * Updates feedback for a specific robot @@ -200,10 +171,7 @@ class World { */ void toHistory(WorldData &world) noexcept; - /** - * Pointer to GUI settings - */ - Settings *settings; + bool we_are_yellow; /** * Mutex used when constructing robots to prevent updating of updateMap without wanting it diff --git a/include/roboteam_ai/world/WorldData.hpp b/include/roboteam_ai/world/WorldData.hpp index b5e17c1f1e..0a8797f3a1 100644 --- a/include/roboteam_ai/world/WorldData.hpp +++ b/include/roboteam_ai/world/WorldData.hpp @@ -12,8 +12,6 @@ #include #include -#include "include/roboteam_ai/utilities/Settings.h" - namespace rtt::world { class World; @@ -41,7 +39,7 @@ class WorldData { * * Ownership is taken of protoMsg */ - WorldData(const World* data, proto::World &protoMsg, rtt::Settings const &settings, std::unordered_map &feedback) noexcept; + WorldData(const World* data, proto::World &protoMsg, bool we_are_yellow, std::unordered_map &feedback) noexcept; /** * Owning container of robots diff --git a/src/AI.cpp b/src/AI.cpp index 2e59c3a528..896424524c 100644 --- a/src/AI.cpp +++ b/src/AI.cpp @@ -3,6 +3,8 @@ // #include "AI.h" +#include +#include "utilities/GameStateManager.hpp" /** * Plays are included here @@ -32,7 +34,7 @@ #include "stp/plays/TestPlay.h" #include "stp/plays/TimeOut.h" -rtt::AI::AI() { +rtt::AI::AI(int id) : settings(id) { plays = std::vector>{}; /// This play is only used for testing purposes, when needed uncomment this play! @@ -63,18 +65,22 @@ rtt::AI::AI() { plays.emplace_back(std::make_unique()); playChecker.setPlays(plays); + world = std::make_unique(settings.isYellow()); } -void rtt::AI::decidePlay(rtt::world::World *_world) { +proto::AICommand rtt::AI::decidePlay() { + //TODO: collect commands in ControlModule + + world::World * _world = world.get();//TODO: fix ownership, why are we handing out a raw pointer? Maybe const& to unique_ptr makes more sense playChecker.update(_world); // Here for manual change with the interface - if(playDecider.interfacePlayChanged) { - auto validPlays = playChecker.getValidPlays(); - currentPlay = playDecider.decideBestPlay(_world, validPlays); - currentPlay->updateWorld(_world); - currentPlay->initialize(); - playDecider.interfacePlayChanged = false; - } +// if(playDecider.interfacePlayChanged) { //TODO: is this still relevant? We need to write interface handler anyways +// auto validPlays = playChecker.getValidPlays(); +// currentPlay = playDecider.decideBestPlay(_world, validPlays); +// currentPlay->updateWorld(_world); +// currentPlay->initialize(); +// playDecider.interfacePlayChanged = false; +// } // A new play will be chosen if the current play is not valid to keep if (!currentPlay || !currentPlay->isValidPlayToKeep(_world)) { @@ -95,6 +101,57 @@ void rtt::AI::decidePlay(rtt::world::World *_world) { currentPlay->update(); //mainWindow->updatePlay(currentPlay); TODO: send to interface } -rtt::AI::AI(int id) { +void rtt::AI::updateState(const proto::State& state) { + + updateSettingsReferee(state); + + //state has to be rotated to our perspective. + + //TODO: safety checks + + //Note these calls assume the proto field exist. Otherwise, all fields and subfields are initialized as empty!! + auto worldMessage = state.last_seen_world(); + auto fieldMessage = state.field().field(); + if (!settings.isLeft()) { + roboteam_utils::rotate(&worldMessage); + } + world->updateWorld(worldMessage); + world->updateField(fieldMessage); + world->updatePositionControl(); + //world->updateFeedback(feedbackMap); TODO fix feedback +} +void rtt::AI::updateSettingsReferee(const proto::State& state) { + + if(state.has_referee()){ + auto referee = state.referee(); + + roboteam_utils::rotate(&referee); //this only rotates the ball placement marker. + + //TODO: put the following block in an if statement that checks whether we want to automatically listen to the referee or not + //TODO: put the AI name into the settings + { + // Our name as specified by ssl-game-controller : https://github.com/RoboCup-SSL/ssl-game-controller/blob/master/config/engine.yaml + //make sure this matches exactly! + std::string ROBOTEAM_TWENTE = "RoboTeam Twente"; + bool color_changed = false; + if (referee.yellow().name() == ROBOTEAM_TWENTE && !settings.isYellow()) { + settings.setYellow(true); + color_changed = true; + } else if (referee.blue().name() == ROBOTEAM_TWENTE && settings.isYellow()) { + settings.setYellow(false); + color_changed = true; + } + bool we_are_left = !(referee.blue_team_on_positive_half() ^ settings.isYellow()); + //if we changed color or if we are playing on the wrong side, update sides + if (color_changed || we_are_left != settings.isLeft()) { + settings.setLeft(we_are_left); + onSideOrColorChanged(); + } + } + ai::GameStateManager::setRefereeData(referee, world.get(),settings); //TODO: fix world * + } +} +void rtt::AI::onSideOrColorChanged() { + //TODO: reinitialize world, field, referee, and stop play } diff --git a/src/AISettings.cpp b/src/AISettings.cpp index 76e93e928a..4077e3aa59 100644 --- a/src/AISettings.cpp +++ b/src/AISettings.cpp @@ -3,17 +3,18 @@ // #include "AISettings.h" +namespace rtt { AISettings::AISettings(int initial_id) : -id{initial_id}, -mode{GRSIM}, -robothub_send_ip{"127.0.0.1"}, //local host -robothub_send_port{20011} //grsim default -{ + id{initial_id}, + mode{GRSIM}, + robothub_send_ip{"127.0.0.1"}, //local host + robothub_send_port{20011},//grsim default + is_paused(true) { //these settings are for testing and convenience, basically - if(initial_id == 1){ + if (initial_id == 1) { is_yellow = false; is_left = false; - }else{ + } else { is_yellow = true; is_left = true; } @@ -56,5 +57,10 @@ int AISettings::getRobothubSendPort() const { void AISettings::setRobothubSendPort(int port) { robothub_send_port = port; } - - +void AISettings::setPause(bool paused) { + is_paused = paused; //TODO: when the AI is just paused, send a halt command to all robots +} +bool AISettings::isPaused() const { + return is_paused; +} +} diff --git a/src/AppSettings.cpp b/src/AppSettings.cpp index 9aa5d7867e..9c8990d858 100644 --- a/src/AppSettings.cpp +++ b/src/AppSettings.cpp @@ -3,6 +3,8 @@ // #include "AppSettings.h" +#include + const std::string &AppSettings::getRefereeIp() const { return referee_ip; } @@ -27,5 +29,12 @@ int AppSettings::getVisionPort() const { void AppSettings::setVisionPort(int port) { vision_port = port; } +proto::ObserverSettings AppSettings::toMessage() const{ + proto::ObserverSettings settings; + + //TODO: initialize values + + return settings; +} diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index e1e9f347a4..7b9015757b 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -1,7 +1,6 @@ #include "ApplicationManager.h" #include -#include #include "utilities/GameStateManager.hpp" #include "utilities/IOManager.h" @@ -20,10 +19,10 @@ void ApplicationManager::start(int id) { rtt::ai::Constants::init(); - rtt::SETTINGS.setVisionIp("127.0.0.1"); - rtt::SETTINGS.setVisionPort(10006); - rtt::SETTINGS.setRefereeIp("224.5.23.1"); - rtt::SETTINGS.setRefereePort(10003); + settings.setVisionIp("127.0.0.1"); + settings.setVisionPort(10006); + settings.setRefereeIp("224.5.23.1"); + settings.setRefereePort(10003); io->init(id); @@ -51,46 +50,8 @@ void ApplicationManager::start(int id) { /// Run everything with regard to behaviour trees void ApplicationManager::runOneLoopCycle() { auto state = io->getState(); - if (state.has_field()) { - if (!fieldInitialized) RTT_SUCCESS("Received first field message!") - fieldInitialized = true; - - //Note these calls Assume the proto field exist. Otherwise, all fields and subfields are initialized as empty!! - auto worldMessage = state.last_seen_world(); - auto fieldMessage = state.field().field(); - if (!SETTINGS.isLeft()) { - roboteam_utils::rotate(&worldMessage); - } - auto const &[_, world] = world::World::instance(); - world->updateWorld(worldMessage); - - if (!world->getWorld()->getUs().empty()) { - if (!robotsInitialized) { - RTT_SUCCESS("Received robots, starting STP!") - } - robotsInitialized = true; - - - world->updateField(fieldMessage); - world->updatePositionControl(); - //world->updateFeedback(feedbackMap); - - ai->decidePlay(world); - - } else { - if (robotsInitialized) { - RTT_WARNING("No robots found in world. STP is not running") - robotsInitialized = false; - } - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - } - } else { - if (fieldInitialized) { - RTT_WARNING("No field data present!") - fieldInitialized = false; - } - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - } + ai->updateState(state); + ai->decidePlay(); rtt::ai::control::ControlModule::sendAllCommands(io); io->handleCentralServerConnection(); diff --git a/src/interface/api/Output.cpp b/src/interface/api/Output.cpp index 6595facc80..9755e8e78b 100644 --- a/src/interface/api/Output.cpp +++ b/src/interface/api/Output.cpp @@ -15,25 +15,6 @@ std::mutex Output::refMutex; GameState Output::interfaceGameState("halt_strategy", "default"); -void Output::sendHaltCommand() { - rtt::ai::Pause pause; - auto const &[_, world] = rtt::world::World::instance(); - // TODO: This check prevents a segfault when we don't have a world (roobthub_world is off), but it should be checked earlier I think - if (world->getWorld().has_value()) { - if (pause.getPause()) { - // Already halted so unhalt - pause.setPause(false); - } else { - pause.setPause(true); - pause.haltRobots(world); - } - } - - else { - RTT_WARNING("Cannot pause robots, there is no world! Check roboteam_world") - } -} - bool Output::usesRefereeCommands() { std::lock_guard lock(refMutex); diff --git a/src/interface/widgets/MainControlsWidget.cpp b/src/interface/widgets/MainControlsWidget.cpp index 4fd4f8e458..bfa8792bb0 100644 --- a/src/interface/widgets/MainControlsWidget.cpp +++ b/src/interface/widgets/MainControlsWidget.cpp @@ -33,7 +33,6 @@ MainControlsWidget::MainControlsWidget(QWidget *parent, ApplicationManager *appM toggleSerialBtn = new QPushButton("Serial"); QObject::connect(toggleSerialBtn, SIGNAL(clicked()), this, SLOT(toggleSerialParam())); refHorizontalLayout->addWidget(toggleSerialBtn); - setToggleSerialBtnLayout(); vLayout->addLayout(refHorizontalLayout); @@ -78,7 +77,6 @@ MainControlsWidget::MainControlsWidget(QWidget *parent, ApplicationManager *appM QString::fromUtf8("QPushButton:disabled" "{ color: gray }")); - setToggleColorBtnLayout(); toggleSideBtn = new QPushButton("Side"); QObject::connect(toggleSideBtn, SIGNAL(clicked()), this, SLOT(toggleOurSideParam())); @@ -87,7 +85,6 @@ MainControlsWidget::MainControlsWidget(QWidget *parent, ApplicationManager *appM QString::fromUtf8("QPushButton:disabled" "{ color: gray }")); - setToggleSideBtnLayout(); gameStateLayout->addLayout(settingsButtonsLayout); @@ -135,18 +132,7 @@ void MainControlsWidget::setUseReferee(bool useRef) { /// send a halt signal to stop all trees from executing -void MainControlsWidget::sendPauseSignal() { Output::sendHaltCommand(); } -void MainControlsWidget::updatePause() { - rtt::ai::Pause pause; - if (pause.getPause()) { - pauseBtn->setText("Resume"); - pauseBtn->setStyleSheet("background-color: #00b200;"); - } else { - pauseBtn->setText("Stop"); - pauseBtn->setStyleSheet("background-color: #cc0000;"); - } -} void MainControlsWidget::updateContents() { diff --git a/src/utilities/GameStateManager.cpp b/src/utilities/GameStateManager.cpp index 3c1c7cde2e..f5f13a1d31 100644 --- a/src/utilities/GameStateManager.cpp +++ b/src/utilities/GameStateManager.cpp @@ -1,6 +1,5 @@ #include "utilities/GameStateManager.hpp" -#include #include #include @@ -15,12 +14,18 @@ proto::SSL_Referee GameStateManager::getRefereeData() { return GameStateManager::refMsg; } -void GameStateManager::setRefereeData(proto::SSL_Referee refMsg, const rtt_world::World* data) { +void GameStateManager::setRefereeData(proto::SSL_Referee refMsg, const rtt_world::World* data, + const AISettings& settings) { std::lock_guard lock(refMsgLock); GameStateManager::refMsg = refMsg; RefCommand cmd; + if (settings.isYellow()) { + keeperID = refMsg.yellow().goalkeeper(); + } else { + keeperID = refMsg.blue().goalkeeper(); + } // COLOR DEPENDENT STATES - if (SETTINGS.isYellow()) { + if (settings.isYellow()) { switch (refMsg.command()) { case proto::SSL_Referee_Command_HALT: cmd = RefCommand::HALT; @@ -151,6 +156,7 @@ void GameStateManager::setRefereeData(proto::SSL_Referee refMsg, const rtt_world if (world.has_value()) { strategymanager.setCurrentRefGameState(cmd, stage, world->getBall()); } + } // Initialize static variables @@ -159,11 +165,8 @@ GameState GameStateManager::getCurrentGameState() { if (interface::Output::usesRefereeCommands()) { newGameState = static_cast(strategymanager.getCurrentRefGameState()); - if (SETTINGS.isYellow()) { - newGameState.keeperId = getRefereeData().yellow().goalkeeper(); - } else { - newGameState.keeperId = getRefereeData().blue().goalkeeper(); - } + newGameState.keeperId = keeperID; + // if there is a ref we set the interface gamestate to these values as well // this makes sure that when we stop using the referee we don't return to an unknown state, // // so now we keep the same. diff --git a/src/utilities/IOManager.cpp b/src/utilities/IOManager.cpp index c2e2fd795a..5c1e1e3f11 100644 --- a/src/utilities/IOManager.cpp +++ b/src/utilities/IOManager.cpp @@ -1,17 +1,13 @@ #include -#include #include #include "roboteam_utils/normalize.h" -#include "utilities/Pause.h" #include "include/roboteam_ai/world/World.hpp" namespace rtt::ai::io { -IOManager io; - IOManager::~IOManager() { delete central_server_connection; delete settingsPublisher; @@ -41,25 +37,11 @@ void IOManager::handleState(proto::State &stateMsg) { std::unique_lock lock(stateMutex); //write lock this->state.CopyFrom(stateMsg); //TODO: move this to the ai - if(state.has_referee()){ - roboteam_utils::rotate(state.mutable_referee()); - // Our name as specified by ssl-refbox : https://github.com/RoboCup-SSL/ssl-refbox/blob/master/referee.conf - std::string ROBOTEAM_TWENTE = "RoboTeam Twente"; - if (state.referee().yellow().name() == ROBOTEAM_TWENTE) { - SETTINGS.setYellow(true); - } else if (state.referee().blue().name() == ROBOTEAM_TWENTE) { - SETTINGS.setYellow(false); - } - SETTINGS.setLeft(!(state.referee().blue_team_on_positive_half() ^ SETTINGS.isYellow())); - auto const& [_, data] = World::instance(); - ai::GameStateManager::setRefereeData(state.referee(), data); - } } void IOManager::publishSettings(proto::Setting setting) { settingsPublisher->send(setting); } void IOManager::publishAllRobotCommands(const std::vector& robotCommands) { - if(!pause->getPause()) { proto::AICommand command; for(const auto& robotCommand : robotCommands){ proto::RobotCommand * protoCommand = command.mutable_commands()->Add(); @@ -67,7 +49,6 @@ void IOManager::publishAllRobotCommands(const std::vector& } command.mutable_extrapolatedworld()->CopyFrom(getState().command_extrapolated_world()); robotCommandPublisher->send(command); - } } void IOManager::handleCentralServerConnection(){ //first receive any setting changes diff --git a/src/utilities/Pause.cpp b/src/utilities/Pause.cpp deleted file mode 100644 index 0903ef5cbb..0000000000 --- a/src/utilities/Pause.cpp +++ /dev/null @@ -1,38 +0,0 @@ -// -// Created by baris on 15-2-19. -// - -#include -#include "include/roboteam_ai/utilities/IOManager.h" - -namespace rtt::ai { - -bool Pause::pause = false; -std::mutex Pause::pauseLock; - -bool Pause::getPause() { - std::lock_guard lock(pauseLock); - return pause; -} -void Pause::haltRobots(rtt::world::World const* data) { - auto us = data->getWorld()->getUs(); - std::vector commands; - for (const auto &robot : us) { - proto::RobotCommand cmd; - cmd.mutable_vel()->set_x(0); - cmd.mutable_vel()->set_y(0); - cmd.set_id(robot->getId()); - cmd.set_dribbler(0); - cmd.set_use_angle(1); - cmd.set_w(static_cast(robot->getAngle())); - commands.push_back(std::move(cmd)); - } - //io::io.publishAllRobotCommands(commands);TODO: replace -} -void Pause::setPause(bool set) { - std::lock_guard lock(pauseLock); - pause = set; -} -Pause::Pause() {} - -} // namespace rtt::ai \ No newline at end of file diff --git a/src/utilities/Settings.cpp b/src/utilities/Settings.cpp deleted file mode 100644 index bc6e76c3b6..0000000000 --- a/src/utilities/Settings.cpp +++ /dev/null @@ -1,67 +0,0 @@ -/// -// Created by mrlukasbos on 1-9-19. -// - -#include "include/roboteam_ai/utilities/Settings.h" - -namespace rtt { - -void Settings::init(int id) { - setId(id); -} - -proto::Setting Settings::toMessage() { - proto::Setting setting; - setting.set_id(id); - setting.set_isleft(left); - setting.set_isyellow(yellow); - setting.set_serialmode(serialMode); - setting.set_refereeip(refereeIp); - setting.set_refereeport(refereePort); - setting.set_visionip(visionIp); - setting.set_visionport(visionPort); - setting.set_robothubsendip(robothubSendIp); - setting.set_robothubsendport(robothubSendPort); - return setting; -} - -int Settings::getId() const { return id; } - -void Settings::setId(int id) { Settings::id = id; } - -bool Settings::isYellow() const { return yellow; } - -void Settings::setYellow(bool yellow) { Settings::yellow = yellow; } - -bool Settings::isLeft() const { return left; } - -void Settings::setLeft(bool left) { Settings::left = left; } - -bool Settings::isSerialMode() const { return serialMode; } - -void Settings::setSerialMode(bool serialMode) { Settings::serialMode = serialMode; } - -const std::string &Settings::getVisionIp() const { return visionIp; } - -void Settings::setVisionIp(const std::string &visionIp) { Settings::visionIp = visionIp; } - -int Settings::getVisionPort() const { return visionPort; } - -void Settings::setVisionPort(int visionPort) { Settings::visionPort = visionPort; } - -const std::string &Settings::getRefereeIp() const { return refereeIp; } - -void Settings::setRefereeIp(const std::string &refereeIp) { Settings::refereeIp = refereeIp; } - -int Settings::getRefereePort() const { return refereePort; } - -void Settings::setRefereePort(int refereePort) { Settings::refereePort = refereePort; } - -const std::string &Settings::getRobothubSendIp() const { return robothubSendIp; } - -void Settings::setRobothubSendIp(const std::string &robothubSendIp) { Settings::robothubSendIp = robothubSendIp; } - -int Settings::getRobothubSendPort() const { return robothubSendPort; } - -void Settings::setRobothubSendPort(int robothubSendPort) { Settings::robothubSendPort = robothubSendPort; } -} // namespace rtt \ No newline at end of file diff --git a/src/world/World.cpp b/src/world/World.cpp index 7d31a8ee20..b11c66bca3 100644 --- a/src/world/World.cpp +++ b/src/world/World.cpp @@ -62,7 +62,7 @@ namespace rtt::world { } void World::updateWorld(proto::World &protoWorld) { - WorldData data{this, protoWorld, *settings, updateMap}; + WorldData data{this, protoWorld,we_are_yellow, updateMap}; setWorld(data); } @@ -75,7 +75,7 @@ namespace rtt::world { this->currentField = protoField; } - World::World(Settings *settings) : settings{settings}, currentWorld{std::nullopt}, lastTick{0} { + World::World(bool is_yellow) : we_are_yellow{is_yellow}, currentWorld{std::nullopt}, lastTick{0} { history.reserve(HISTORY_SIZE); } diff --git a/src/world/WorldData.cpp b/src/world/WorldData.cpp index c558298803..a30662eb57 100644 --- a/src/world/WorldData.cpp +++ b/src/world/WorldData.cpp @@ -5,9 +5,9 @@ #include "include/roboteam_ai/world/WorldData.hpp" namespace rtt::world { - WorldData::WorldData(const World* data, proto::World &protoMsg, rtt::Settings const &settings, std::unordered_map &feedback) noexcept : time{protoMsg.time()} { - auto &ours = settings.isYellow() ? protoMsg.yellow() : protoMsg.blue(); - auto &others = settings.isYellow() ? protoMsg.blue() : protoMsg.yellow(); + WorldData::WorldData(const World* data, proto::World &protoMsg, bool we_are_yellow, std::unordered_map &feedback) noexcept : time{protoMsg.time()} { + auto &ours = we_are_yellow ? protoMsg.yellow() : protoMsg.blue(); + auto &others = we_are_yellow ? protoMsg.blue() : protoMsg.yellow(); // If there is a ball in the protobuf message, add it to the world ball = ball::Ball{protoMsg.ball(), data}; From 098374996e36fa27fe6986e57fb8ec881dd3824c Mon Sep 17 00:00:00 2001 From: rolf Date: Thu, 8 Apr 2021 00:20:17 +0200 Subject: [PATCH 20/40] move more things to the AI --- include/roboteam_ai/AI.h | 3 ++ include/roboteam_ai/AppSettings.h | 18 +++++++++- include/roboteam_ai/control/ControlModule.h | 3 +- .../interface/widgets/MainControlsWidget.h | 2 -- include/roboteam_ai/utilities/IOManager.h | 2 +- src/AI.cpp | 36 ++++++++++++++----- src/AppSettings.cpp | 23 +++++++++--- src/ApplicationManager.cpp | 8 ++--- src/control/ControlModule.cpp | 19 +++++----- src/interface/widgets/MainControlsWidget.cpp | 6 ++-- src/manual/JoystickManager.cpp | 6 ++-- src/roboteam_ai.cpp | 2 +- src/utilities/GameStateManager.cpp | 1 + src/utilities/IOManager.cpp | 15 ++++---- src/world/World.cpp | 6 ++++ 15 files changed, 103 insertions(+), 47 deletions(-) diff --git a/include/roboteam_ai/AI.h b/include/roboteam_ai/AI.h index 09fb81202b..11680a5fd4 100644 --- a/include/roboteam_ai/AI.h +++ b/include/roboteam_ai/AI.h @@ -11,6 +11,7 @@ #include "world/World.hpp" #include #include +#include "control/ControlModule.h" namespace rtt { class AI { @@ -46,6 +47,8 @@ class AI { std::vector> plays; AISettings settings; + + //std::unique_ptr control_module; TODO: fix staticness }; } #endif //RTT_ROBOTEAM_AI_SRC_AI_H_ diff --git a/include/roboteam_ai/AppSettings.h b/include/roboteam_ai/AppSettings.h index 35c0c48f31..f0a31d5642 100644 --- a/include/roboteam_ai/AppSettings.h +++ b/include/roboteam_ai/AppSettings.h @@ -5,9 +5,16 @@ #ifndef RTT_ROBOTEAM_AI_SRC_APPSETTINGS_H_ #define RTT_ROBOTEAM_AI_SRC_APPSETTINGS_H_ #include - +#include +#include +#include +enum class SerialMode{ + GRSIM = 0, + SERIAL = 1 +}; class AppSettings { public: + [[nodiscard]] const std::string& getRefereeIp() const; void setRefereeIp(const std::string& refereeIp); @@ -19,12 +26,21 @@ class AppSettings { [[nodiscard]] int getVisionPort() const; void setVisionPort(int port); + + [[nodiscard]] proto::Setting toMessage() const; + [[nodiscard]] proto::ObserverSettings obsMessage() const; + + [[nodiscard]] proto::RobotHubSettings rhMessage() const; private: std::string referee_ip; int referee_port; std::string vision_ip; int vision_port; + + std::string robothub_ip; + int robothub_port; + SerialMode mode; }; #endif //RTT_ROBOTEAM_AI_SRC_APPSETTINGS_H_ diff --git a/include/roboteam_ai/control/ControlModule.h b/include/roboteam_ai/control/ControlModule.h index 4b4b385a43..383e834002 100644 --- a/include/roboteam_ai/control/ControlModule.h +++ b/include/roboteam_ai/control/ControlModule.h @@ -10,6 +10,7 @@ #include "stp/StpInfo.h" #include "world/views/RobotView.hpp" #include "utilities/IOManager.h" +#include namespace rtt::ai::control { @@ -55,7 +56,7 @@ namespace rtt::ai::control { /** * */ - static void sendAllCommands(std::unique_ptr& io); + static std::vector sendAllCommands(const AISettings& settings); }; } // namespace rtt::ai::control diff --git a/include/roboteam_ai/interface/widgets/MainControlsWidget.h b/include/roboteam_ai/interface/widgets/MainControlsWidget.h index f7b39ad7cc..45ad5d1697 100644 --- a/include/roboteam_ai/interface/widgets/MainControlsWidget.h +++ b/include/roboteam_ai/interface/widgets/MainControlsWidget.h @@ -42,8 +42,6 @@ class MainControlsWidget : public QWidget { public slots: - void sendPauseSignal(); - void updatePause(); void setUseReferee(bool useRef); void setIgnoreInvariants(bool ignore); void updateContents(); diff --git a/include/roboteam_ai/utilities/IOManager.h b/include/roboteam_ai/utilities/IOManager.h index 0eaa2ae534..1e0878985e 100644 --- a/include/roboteam_ai/utilities/IOManager.h +++ b/include/roboteam_ai/utilities/IOManager.h @@ -41,7 +41,7 @@ class IOManager { public: ~IOManager(); explicit IOManager() = default; - void publishAllRobotCommands(const std::vector& vector); + void publishAICommand(const proto::AICommand& ai_command); void publishSettings(proto::Setting setting); void handleCentralServerConnection(); void init(int teamId); diff --git a/src/AI.cpp b/src/AI.cpp index 896424524c..33fd297ba9 100644 --- a/src/AI.cpp +++ b/src/AI.cpp @@ -66,10 +66,12 @@ rtt::AI::AI(int id) : settings(id) { playChecker.setPlays(plays); world = std::make_unique(settings.isYellow()); + } proto::AICommand rtt::AI::decidePlay() { - //TODO: collect commands in ControlModule - + if(!world->getField().has_value()){ + return proto::AICommand(); + } world::World * _world = world.get();//TODO: fix ownership, why are we handing out a raw pointer? Maybe const& to unique_ptr makes more sense playChecker.update(_world); @@ -89,7 +91,7 @@ proto::AICommand rtt::AI::decidePlay() { RTT_ERROR("No valid plays") currentPlay = playChecker.getPlayForName("Defend Shot"); //TODO Try out different default plays so both teams dont get stuck in Defend Shot when playing against yourself if (!currentPlay) { - return; + return proto::AICommand(); } } else { currentPlay = playDecider.decideBestPlay(_world, validPlays); @@ -99,6 +101,13 @@ proto::AICommand rtt::AI::decidePlay() { } currentPlay->update(); + auto commands = ai::control::ControlModule::sendAllCommands(settings); //TODO: no more statics + proto::AICommand ai_command; + for(const auto& command : commands){ + proto::RobotCommand * protoCommand = ai_command.mutable_commands()->Add(); + protoCommand->CopyFrom(command); + } + return ai_command; //mainWindow->updatePlay(currentPlay); TODO: send to interface } void rtt::AI::updateState(const proto::State& state) { @@ -111,13 +120,22 @@ void rtt::AI::updateState(const proto::State& state) { //TODO: safety checks //Note these calls assume the proto field exist. Otherwise, all fields and subfields are initialized as empty!! - auto worldMessage = state.last_seen_world(); - auto fieldMessage = state.field().field(); - if (!settings.isLeft()) { - roboteam_utils::rotate(&worldMessage); + if(state.has_last_seen_world()){ + auto worldMessage = state.last_seen_world(); + if (!settings.isLeft()) { + roboteam_utils::rotate(&worldMessage); + } + world->updateWorld(worldMessage); } - world->updateWorld(worldMessage); - world->updateField(fieldMessage); + + if(state.has_field()){ + auto fieldMessage = state.field().field(); + if (!settings.isLeft()) { + roboteam_utils::rotate(&fieldMessage); + } + world->updateField(fieldMessage); + } + world->updatePositionControl(); //world->updateFeedback(feedbackMap); TODO fix feedback } diff --git a/src/AppSettings.cpp b/src/AppSettings.cpp index 9c8990d858..8b09d1b45f 100644 --- a/src/AppSettings.cpp +++ b/src/AppSettings.cpp @@ -3,7 +3,6 @@ // #include "AppSettings.h" -#include const std::string &AppSettings::getRefereeIp() const { return referee_ip; @@ -29,11 +28,27 @@ int AppSettings::getVisionPort() const { void AppSettings::setVisionPort(int port) { vision_port = port; } -proto::ObserverSettings AppSettings::toMessage() const{ - proto::ObserverSettings settings; +proto::ObserverSettings AppSettings::obsMessage() const{ - //TODO: initialize values + proto::ObserverSettings settings; + settings.set_visionip(vision_ip); + settings.set_visionport(vision_port); + settings.set_refereeip(referee_ip); + settings.set_refereeport(referee_port); + return settings; +} +proto::Setting AppSettings::toMessage() const { + proto::Setting setting; + setting.mutable_obs_settings()->CopyFrom(obsMessage()); + setting.mutable_rh_settings()->CopyFrom(rhMessage()); + return setting; +} +proto::RobotHubSettings AppSettings::rhMessage() const { + proto::RobotHubSettings settings; + settings.set_robothubip(robothub_ip); + settings.set_robothubport(robothub_port); + settings.set_serialmode(mode == SerialMode::SERIAL);//TODO: extend proto with an enum to support more modes return settings; } diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index 7b9015757b..744ebe5b20 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -4,7 +4,6 @@ #include "utilities/GameStateManager.hpp" #include "utilities/IOManager.h" -#include "control/ControlModule.h" namespace io = rtt::ai::io; @@ -42,7 +41,7 @@ void ApplicationManager::start(int id) { RTT_WARNING("Time allowed: 16 ms") // publish settings, but limit this function call to only run 1 times/s at most - t.limit([&]() { io->publishSettings(SETTINGS.toMessage()); }, 1); + t.limit([&]() { io->publishSettings(settings.toMessage()); }, 1); }, ai::Constants::TICK_RATE()); } @@ -51,9 +50,10 @@ void ApplicationManager::start(int id) { void ApplicationManager::runOneLoopCycle() { auto state = io->getState(); ai->updateState(state); - ai->decidePlay(); - rtt::ai::control::ControlModule::sendAllCommands(io); + proto::AICommand command = ai->decidePlay(); + + io->publishAICommand(command); io->handleCentralServerConnection(); } } // namespace rtt diff --git a/src/control/ControlModule.cpp b/src/control/ControlModule.cpp index 01b0979b5c..7422d83f18 100644 --- a/src/control/ControlModule.cpp +++ b/src/control/ControlModule.cpp @@ -5,8 +5,6 @@ #include "control/ControlModule.h" #include #include "control/ControlUtils.h" -#include "utilities/IOManager.h" -#include "utilities/Settings.h" #include "world/World.hpp" #include "iostream" @@ -65,10 +63,7 @@ namespace rtt::ai::control { void ControlModule::addRobotCommand(std::optional<::rtt::world::view::RobotView> robot, const proto::RobotCommand& command, const rtt::world::World *data) noexcept { proto::RobotCommand robot_command=command; - // If we are not left, commands should be rotated (because we play as right) - if (!SETTINGS.isLeft()) { - rotateRobotCommand(robot_command); - } + //TODO: check for double commands limitRobotCommand(robot_command, robot); // Only add commands with a robotID that is not in the vector yet @@ -77,9 +72,15 @@ namespace rtt::ai::control { } } - void ControlModule::sendAllCommands(std::unique_ptr&io) { - //TODO: check for double commands - io->publishAllRobotCommands(robotCommands); // When vector has all commands, send in one go + std::vector ControlModule::sendAllCommands(const AISettings& settings) { + // If we are not left, commands should be rotated (because we play as right) + std::vector commands = robotCommands; + if(!settings.isLeft()){ + for(auto& command : commands){ + rotateRobotCommand(command); + } + } robotCommands.clear(); + return commands; } } // namespace rtt::ai::stp \ No newline at end of file diff --git a/src/interface/widgets/MainControlsWidget.cpp b/src/interface/widgets/MainControlsWidget.cpp index bfa8792bb0..c1eb267761 100644 --- a/src/interface/widgets/MainControlsWidget.cpp +++ b/src/interface/widgets/MainControlsWidget.cpp @@ -15,13 +15,13 @@ MainControlsWidget::MainControlsWidget(QWidget *parent, ApplicationManager *appM vLayout = new QVBoxLayout(); pauseBtn = new QPushButton("Stop"); - QObject::connect(pauseBtn, SIGNAL(clicked()), this, SLOT(sendPauseSignal())); + //QObject::connect(pauseBtn, SIGNAL(clicked()), this, SLOT(sendPauseSignal())); vLayout->addWidget(pauseBtn); pauseBtn->setStyleSheet("background-color: #cc0000;"); pauseBtn->setMinimumHeight(40); - spaceClick = new QShortcut(QKeySequence(Qt::Key_Space), this, SLOT(sendPauseSignal())); - spaceClick->setAutoRepeat(false); +// spaceClick = new QShortcut(QKeySequence(Qt::Key_Space), this, SLOT(sendPauseSignal())); +// spaceClick->setAutoRepeat(false); auto refHorizontalLayout = new QHBoxLayout(); diff --git a/src/manual/JoystickManager.cpp b/src/manual/JoystickManager.cpp index 573d2449a8..5c0b007085 100644 --- a/src/manual/JoystickManager.cpp +++ b/src/manual/JoystickManager.cpp @@ -119,9 +119,9 @@ void JoystickManager::loop() { void JoystickManager::tickJoystickHandlers() { for (const auto &joystickHandler : joystickHandlers) { joystickHandler.second->tick(); - auto const& [_, world] = world::World::instance(); - auto robot = world->getWorld()->getRobotForId(joystickHandler.second->getCommand().id()); - rtt::ai::control::ControlModule::addRobotCommand(robot, joystickHandler.second->getCommand(), world); +// auto const& [_, world] = world::World::instance(); +// auto robot = world->getWorld()->getRobotForId(joystickHandler.second->getCommand().id()); +// rtt::ai::control::ControlModule::addRobotCommand(robot, joystickHandler.second->getCommand(), world); } } diff --git a/src/roboteam_ai.cpp b/src/roboteam_ai.cpp index f235c0d62c..3bed6cbd9a 100644 --- a/src/roboteam_ai.cpp +++ b/src/roboteam_ai.cpp @@ -66,5 +66,5 @@ int main(int argc, char* argv[]) { window->show(); bool result = a.exec(); - return result; + return result; //TODO: join app_thread } diff --git a/src/utilities/GameStateManager.cpp b/src/utilities/GameStateManager.cpp index f5f13a1d31..3172d2ddf1 100644 --- a/src/utilities/GameStateManager.cpp +++ b/src/utilities/GameStateManager.cpp @@ -8,6 +8,7 @@ namespace rtt::ai { proto::SSL_Referee GameStateManager::refMsg; StrategyManager GameStateManager::strategymanager; std::mutex GameStateManager::refMsgLock; +int GameStateManager::keeperID; proto::SSL_Referee GameStateManager::getRefereeData() { std::lock_guard lock(refMsgLock); diff --git a/src/utilities/IOManager.cpp b/src/utilities/IOManager.cpp index 5c1e1e3f11..86501f5e01 100644 --- a/src/utilities/IOManager.cpp +++ b/src/utilities/IOManager.cpp @@ -41,15 +41,6 @@ void IOManager::handleState(proto::State &stateMsg) { void IOManager::publishSettings(proto::Setting setting) { settingsPublisher->send(setting); } -void IOManager::publishAllRobotCommands(const std::vector& robotCommands) { - proto::AICommand command; - for(const auto& robotCommand : robotCommands){ - proto::RobotCommand * protoCommand = command.mutable_commands()->Add(); - protoCommand->CopyFrom(robotCommand); - } - command.mutable_extrapolatedworld()->CopyFrom(getState().command_extrapolated_world()); - robotCommandPublisher->send(command); -} void IOManager::handleCentralServerConnection(){ //first receive any setting changes bool received = true; @@ -83,4 +74,10 @@ proto::State IOManager::getState(){ proto::State copy = state; return copy; } +void IOManager::publishAICommand(const proto::AICommand& command) { + proto::AICommand ai_command; + ai_command.CopyFrom(command); + ai_command.mutable_extrapolatedworld()->CopyFrom(getState().command_extrapolated_world()); //TODO: move this responsibility to the AI + robotCommandPublisher->send(command); +} } // namespace rtt::ai::io diff --git a/src/world/World.cpp b/src/world/World.cpp index b11c66bca3..22f6062ed6 100644 --- a/src/world/World.cpp +++ b/src/world/World.cpp @@ -98,9 +98,15 @@ namespace rtt::world { } void World::updatePositionControl() { + if(!getWorld()->getRobotsNonOwning().empty()){ std::vector robotPositions(getWorld()->getRobotsNonOwning().size()); std::transform(getWorld()->getRobotsNonOwning().begin(), getWorld()->getRobotsNonOwning().end(), robotPositions.begin(), [](const auto& robot) -> Vector2 { return (robot->getPos()); }); positionControl.setRobotPositions(robotPositions); + }else{ + std::vector positions{}; + positionControl.setRobotPositions(positions); + } + } uint64_t World::getTimeDifference() const noexcept { return tickDuration; } From 7c34df657cf657fe5054de7f10fd64d077296be3 Mon Sep 17 00:00:00 2001 From: rolf Date: Thu, 8 Apr 2021 01:20:27 +0200 Subject: [PATCH 21/40] Remove Output --- CMakeLists.txt | 3 - include/roboteam_ai/AISettings.h | 4 + .../pathTracking/PidTracking.h | 1 - include/roboteam_ai/interface/api/Output.h | 41 ----- .../interface/widgets/MainControlsWidget.h | 51 ------ .../interface/widgets/mainWindow.h | 6 +- include/roboteam_ai/stp/Play.hpp | 3 + .../utilities/GameStateManager.hpp | 1 + src/AI.cpp | 2 +- src/AISettings.cpp | 9 +- src/interface/api/Output.cpp | 44 ----- src/interface/widgets/MainControlsWidget.cpp | 165 ------------------ src/interface/widgets/SettingsWidget.cpp | 48 ----- src/interface/widgets/mainWindow.cpp | 25 +-- src/manual/JoystickManager.cpp | 2 +- src/stp/Play.cpp | 5 +- src/utilities/GameStateManager.cpp | 12 +- 17 files changed, 29 insertions(+), 393 deletions(-) delete mode 100644 include/roboteam_ai/interface/api/Output.h delete mode 100644 include/roboteam_ai/interface/widgets/MainControlsWidget.h delete mode 100644 src/interface/api/Output.cpp delete mode 100644 src/interface/widgets/MainControlsWidget.cpp delete mode 100644 src/interface/widgets/SettingsWidget.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index bc38fd021f..b288eddb22 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -201,12 +201,9 @@ set(TEST_SOURCES set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/src/interface/widgets/mainWindow.cpp - ${PROJECT_SOURCE_DIR}/src/interface/api/Output.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/MainControlsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/ManualControlWidget.cpp #QT wants to know about these headers - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/MainControlsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/mainWindow.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/ManualControlWidget.h ) diff --git a/include/roboteam_ai/AISettings.h b/include/roboteam_ai/AISettings.h index 7ebc49d73f..1d14ccbfed 100644 --- a/include/roboteam_ai/AISettings.h +++ b/include/roboteam_ai/AISettings.h @@ -35,6 +35,9 @@ namespace rtt { [[nodiscard]] bool isPaused() const; void setPause(bool paused); + + [[nodiscard]] bool getListenToReferee() const; + void setListenToReferee(bool listen); private: int id; bool is_yellow; @@ -43,6 +46,7 @@ namespace rtt { std::string robothub_send_ip; int robothub_send_port; bool is_paused; + bool listenToReferee; }; } diff --git a/include/roboteam_ai/control/positionControl/pathTracking/PidTracking.h b/include/roboteam_ai/control/positionControl/pathTracking/PidTracking.h index b69a95d9c1..b0881051dd 100644 --- a/include/roboteam_ai/control/positionControl/pathTracking/PidTracking.h +++ b/include/roboteam_ai/control/positionControl/pathTracking/PidTracking.h @@ -6,7 +6,6 @@ #define RTT_PIDTRACKING_H #include "control/positionControl/PositionControlUtils.h" -#include "interface/api/Output.h" #include "roboteam_utils/Position.h" #include "roboteam_utils/Vector2.h" #include "roboteam_utils/pid.h" diff --git a/include/roboteam_ai/interface/api/Output.h b/include/roboteam_ai/interface/api/Output.h deleted file mode 100644 index d1b4cc8e66..0000000000 --- a/include/roboteam_ai/interface/api/Output.h +++ /dev/null @@ -1,41 +0,0 @@ -// -// Created by mrlukasbos on 18-1-19. -// - -#ifndef ROBOTEAM_AI_OUTPUT_H -#define ROBOTEAM_AI_OUTPUT_H - -#include - -#include "roboteam_utils/Vector2.h" -#include "utilities/GameState.h" - -namespace rtt::ai::interface { - - -class Output { - private: - - static std::mutex refMutex; - - static bool useRefereeCommands; - - static GameState interfaceGameState; - - public: - static void setInterfaceGameState(GameState interfaceGameState); - static const GameState &getInterfaceGameState(); - - - static bool usesRefereeCommands(); - static void setUseRefereeCommands(bool useRefereeCommands); - - - - static void setRuleSetName(std::string name); - static void setKeeperId(int id); -}; - -} // namespace rtt::ai::interface - -#endif // ROBOTEAM_AI_OUTPUT_H diff --git a/include/roboteam_ai/interface/widgets/MainControlsWidget.h b/include/roboteam_ai/interface/widgets/MainControlsWidget.h deleted file mode 100644 index 45ad5d1697..0000000000 --- a/include/roboteam_ai/interface/widgets/MainControlsWidget.h +++ /dev/null @@ -1,51 +0,0 @@ -// -// Created by mrlukasbos on 7-5-19. -// - -#ifndef ROBOTEAM_AI_MAINCONTROLSWIDGET_H -#define ROBOTEAM_AI_MAINCONTROLSWIDGET_H - -#include - -#include -#include -#include -#include - -#include "QLayout" - -namespace rtt::ai::interface { - -class MainControlsWidget : public QWidget { - Q_OBJECT - -public: - void updatePlays(); - explicit MainControlsWidget(QWidget *parent = nullptr, ApplicationManager *manager = nullptr); - - inline static std::atomic ignoreInvariants; - - private: - QVBoxLayout *vLayout; - QPushButton *pauseBtn; - QPushButton *toggleColorBtn; - QPushButton *toggleSideBtn; - QPushButton *toggleSerialBtn; - QShortcut *spaceClick; - - QComboBox *select_play; - QComboBox *select_goalie; - QComboBox *select_ruleset; - - ApplicationManager *manager; - - - - public slots: - void setUseReferee(bool useRef); - void setIgnoreInvariants(bool ignore); - void updateContents(); -}; -} // namespace rtt::ai::interface - -#endif // ROBOTEAM_AI_MAINCONTROLSWIDGET_H diff --git a/include/roboteam_ai/interface/widgets/mainWindow.h b/include/roboteam_ai/interface/widgets/mainWindow.h index bfeb7e3c03..691f7b45db 100644 --- a/include/roboteam_ai/interface/widgets/mainWindow.h +++ b/include/roboteam_ai/interface/widgets/mainWindow.h @@ -40,11 +40,7 @@ class MainWindow : public QMainWindow { public: explicit MainWindow(QWidget *parent = nullptr, rtt::ApplicationManager *manager = nullptr); - // this function is useful everywhere - static void configureCheckBox(const QString &title, QLayout *layout, const QObject *receiver, const char *method, bool defaultState = false); - - static void configureCheckableMenuItem(QString title, const QString &hint, QMenu *menu, const QObject *receiver, const char *method, bool defaultState); - static void clearLayout(QLayout *layout); + static void clearLayout(QLayout *layout); private: QHBoxLayout *horizontalLayout; diff --git a/include/roboteam_ai/stp/Play.hpp b/include/roboteam_ai/stp/Play.hpp index b612e2c385..ba376a1151 100644 --- a/include/roboteam_ai/stp/Play.hpp +++ b/include/roboteam_ai/stp/Play.hpp @@ -144,6 +144,9 @@ class Play { */ virtual bool shouldRoleSkipEndTactic() = 0; + static bool ignore_invariants(){ //TODO: make a proper settting + return false; + } private: /** * This function refreshes the RobotViews, the BallViews and the Fields for all stpInfos. diff --git a/include/roboteam_ai/utilities/GameStateManager.hpp b/include/roboteam_ai/utilities/GameStateManager.hpp index 9ccdd43dbe..e4bc7d4dce 100644 --- a/include/roboteam_ai/utilities/GameStateManager.hpp +++ b/include/roboteam_ai/utilities/GameStateManager.hpp @@ -28,6 +28,7 @@ class GameStateManager { static proto::SSL_Referee refMsg; static int keeperID; static StrategyManager strategymanager; + static GameState interface_gamestate; //TODO: port/refactor static std::mutex refMsgLock; }; diff --git a/src/AI.cpp b/src/AI.cpp index 33fd297ba9..a86c169180 100644 --- a/src/AI.cpp +++ b/src/AI.cpp @@ -69,7 +69,7 @@ rtt::AI::AI(int id) : settings(id) { } proto::AICommand rtt::AI::decidePlay() { - if(!world->getField().has_value()){ + if(!world->getField().has_value() || settings.isPaused()){ //TODO: check if we *just* paused, and if so, send a stop signal to all ID's return proto::AICommand(); } world::World * _world = world.get();//TODO: fix ownership, why are we handing out a raw pointer? Maybe const& to unique_ptr makes more sense diff --git a/src/AISettings.cpp b/src/AISettings.cpp index 4077e3aa59..321a7166b2 100644 --- a/src/AISettings.cpp +++ b/src/AISettings.cpp @@ -9,7 +9,8 @@ AISettings::AISettings(int initial_id) : mode{GRSIM}, robothub_send_ip{"127.0.0.1"}, //local host robothub_send_port{20011},//grsim default - is_paused(true) { + is_paused(true), + listenToReferee(false){ //these settings are for testing and convenience, basically if (initial_id == 1) { is_yellow = false; @@ -63,4 +64,10 @@ void AISettings::setPause(bool paused) { bool AISettings::isPaused() const { return is_paused; } +bool AISettings::getListenToReferee() const { + return listenToReferee; +} +void AISettings::setListenToReferee(bool listen) { + listenToReferee = listen; +} } diff --git a/src/interface/api/Output.cpp b/src/interface/api/Output.cpp deleted file mode 100644 index 9755e8e78b..0000000000 --- a/src/interface/api/Output.cpp +++ /dev/null @@ -1,44 +0,0 @@ -// -// Created by mrlukasbos on 18-1-19. -// - -#include "interface/api/Output.h" - -#include - -namespace rtt::ai::interface { - - -bool Output::useRefereeCommands = false; - -std::mutex Output::refMutex; - -GameState Output::interfaceGameState("halt_strategy", "default"); - - -bool Output::usesRefereeCommands() { - std::lock_guard lock(refMutex); - return useRefereeCommands; -} - -void Output::setUseRefereeCommands(bool useRefereeCommands) { - std::lock_guard lock(refMutex); - Output::useRefereeCommands = useRefereeCommands; -} - -void Output::setRuleSetName(std::string name) { Output::interfaceGameState.ruleSetName = std::move(name); } - -void Output::setKeeperId(int id) { Output::interfaceGameState.keeperId = id; } - -const GameState &Output::getInterfaceGameState() { return Output::interfaceGameState; } - -void Output::setInterfaceGameState(GameState interfaceGameState) { - // keep the keeper the same - interfaceGameState.keeperId = Output::interfaceGameState.keeperId; - Output::interfaceGameState = interfaceGameState; -} - - - - -} // namespace rtt::ai::interface \ No newline at end of file diff --git a/src/interface/widgets/MainControlsWidget.cpp b/src/interface/widgets/MainControlsWidget.cpp deleted file mode 100644 index c1eb267761..0000000000 --- a/src/interface/widgets/MainControlsWidget.cpp +++ /dev/null @@ -1,165 +0,0 @@ -// -// Created by mrlukasbos on 7-5-19. -// - -#include "interface/widgets/MainControlsWidget.h" - -#include - -namespace rtt::ai::interface { - -MainControlsWidget::MainControlsWidget(QWidget *parent, ApplicationManager *appManager) : QWidget(parent), manager{appManager} { - Output::setUseRefereeCommands(Constants::STD_USE_REFEREE()); - - // todo: 2 dropdown menus, fix them to reflect new STP - vLayout = new QVBoxLayout(); - - pauseBtn = new QPushButton("Stop"); - //QObject::connect(pauseBtn, SIGNAL(clicked()), this, SLOT(sendPauseSignal())); - vLayout->addWidget(pauseBtn); - pauseBtn->setStyleSheet("background-color: #cc0000;"); - pauseBtn->setMinimumHeight(40); - -// spaceClick = new QShortcut(QKeySequence(Qt::Key_Space), this, SLOT(sendPauseSignal())); -// spaceClick->setAutoRepeat(false); - - auto refHorizontalLayout = new QHBoxLayout(); - - // todo: the hacks for SLOTS() are unbelievable - // functions to select strategies - MainWindow::configureCheckBox("Use referee", refHorizontalLayout, this, SLOT(setUseReferee(bool)), Constants::STD_USE_REFEREE()); - MainWindow::configureCheckBox("Ignore invariants", refHorizontalLayout, this, SLOT(setIgnoreInvariants(bool)), false); - - toggleSerialBtn = new QPushButton("Serial"); - QObject::connect(toggleSerialBtn, SIGNAL(clicked()), this, SLOT(toggleSerialParam())); - refHorizontalLayout->addWidget(toggleSerialBtn); - - vLayout->addLayout(refHorizontalLayout); - - auto gameStateBox = new QGroupBox(); - auto gameStateLayout = new QVBoxLayout(); - - // get the strategy names from Switches - select_play = new QComboBox(); - gameStateLayout->addWidget(select_play); - select_play->setStyleSheet( - QString::fromUtf8("QComboBox:disabled" - "{ color: gray }")); - - auto keeperHorizontalLayout = new QHBoxLayout(); - - select_goalie = new QComboBox(); - keeperHorizontalLayout->addWidget(select_goalie); - for (int i = 0; i < 16; i++) { - select_goalie->addItem(QString::fromStdString(std::to_string(i))); - } - select_goalie->setMaximumWidth(100); - select_goalie->setStyleSheet( - QString::fromUtf8("QComboBox:disabled" - "{ color: gray }")); - - gameStateLayout->addLayout(keeperHorizontalLayout); - - select_ruleset = new QComboBox(); - gameStateLayout->addWidget(select_ruleset); - for (RuleSet const &ruleSet : Constants::ruleSets()) { - select_ruleset->addItem(QString::fromStdString(ruleSet.title)); - } - select_ruleset->setStyleSheet( - QString::fromUtf8("QComboBox:disabled" - "{ color: gray }")); - - auto settingsButtonsLayout = new QHBoxLayout(); - toggleColorBtn = new QPushButton("Color"); - QObject::connect(toggleColorBtn, SIGNAL(clicked()), this, SLOT(toggleOurColorParam())); - settingsButtonsLayout->addWidget(toggleColorBtn); - toggleColorBtn->setStyleSheet( - QString::fromUtf8("QPushButton:disabled" - "{ color: gray }")); - - - toggleSideBtn = new QPushButton("Side"); - QObject::connect(toggleSideBtn, SIGNAL(clicked()), this, SLOT(toggleOurSideParam())); - settingsButtonsLayout->addWidget(toggleSideBtn); - toggleSideBtn->setStyleSheet( - QString::fromUtf8("QPushButton:disabled" - "{ color: gray }")); - - - gameStateLayout->addLayout(settingsButtonsLayout); - - gameStateBox->setLayout(gameStateLayout); - vLayout->addWidget(gameStateBox); - - // todo: figure out why this cast exists - QObject::connect(select_play, static_cast(&QComboBox::activated), [=](int index) { - // if number == -1 then the plays were refreshed, hence just keep the current play - if (index == -1) { - return; - } - // simply manager->plays[index] because they're inserted in-order - - //stp::PlayDecider::lockInterfacePlay(manager->plays[index].get()); //TODO: make button in new interface - }); - - QObject::connect(select_goalie, static_cast(&QComboBox::activated), [=](const QString &goalieId) { - // http://doc.qt.io/qt-5/qcombobox.html#currentIndexChanged-1 - interface::Output::setKeeperId(goalieId.toInt()); - }); - - QObject::connect(select_ruleset, static_cast(&QComboBox::activated), [=](const QString &rulesetName) { - // http://doc.qt.io/qt-5/qcombobox.html#currentIndexChanged-1 - interface::Output::setRuleSetName(rulesetName.toStdString()); - }); - - setUseReferee(Output::usesRefereeCommands()); - this->setLayout(vLayout); -} - -void MainControlsWidget::setUseReferee(bool useRef) { - Output::setUseRefereeCommands(useRef); - - select_play->setDisabled(useRef); - select_ruleset->setDisabled(useRef); - select_goalie->setDisabled(useRef); - toggleSideBtn->setDisabled(useRef); - toggleColorBtn->setDisabled(useRef); - - if (!useRef) { - updatePlays(); - } -} - - -/// send a halt signal to stop all trees from executing - - - -void MainControlsWidget::updateContents() { - auto ruleSetText = QString::fromStdString(GameStateManager::getCurrentGameState().ruleSetName); - if (ruleSetText != select_ruleset->currentText()) { - select_ruleset->setCurrentText(ruleSetText); - } - - auto goalieIdText = QString::number(GameStateManager::getCurrentGameState().keeperId); - if (goalieIdText != select_goalie->currentText()) { - select_goalie->setCurrentText(goalieIdText); - } - - // visual indication if we have a keeper or not - if (GameStateManager::getCurrentGameState().keeperId == -1) { - select_goalie->setStyleSheet("background-color: #00b200;"); - } else { - select_goalie->setStyleSheet("background-color: #cc0000;"); - } -} - -void MainControlsWidget::updatePlays() { - -} - -void MainControlsWidget::setIgnoreInvariants(bool ignore) { - MainControlsWidget::ignoreInvariants = ignore; -} - -} // namespace rtt::ai::interface diff --git a/src/interface/widgets/SettingsWidget.cpp b/src/interface/widgets/SettingsWidget.cpp deleted file mode 100644 index d36101c9ac..0000000000 --- a/src/interface/widgets/SettingsWidget.cpp +++ /dev/null @@ -1,48 +0,0 @@ - -#include "interface/widgets/SettingsWidget.h" - -#include - -#include "interface/widgets/mainWindow.h" - -namespace rtt::ai::interface { - -SettingsWidget::SettingsWidget(QWidget *parent) { - vLayout = new QVBoxLayout(); - this->setLayout(vLayout); - - // grsim ip + port settings - QGroupBox *grsimSettingsGroup = new QGroupBox("grsim transmissin ip + port"); - auto grsimSettingsWidgetLayout = new QHBoxLayout(); - grsimIpText = new QLineEdit(); - grsimIpText->setText(QString::fromStdString(SETTINGS.getRobothubSendIp())); - QObject::connect(grsimIpText, SIGNAL(textChanged(QString)), this, SLOT(changeGrSimIp(QString))); - grsimSettingsWidgetLayout->addWidget(grsimIpText); - grsimPort = new QSpinBox(); - grsimPort->setRange(0, 999999); - grsimPort->setValue(SETTINGS.getRobothubSendPort()); - grsimSettingsWidgetLayout->addWidget(grsimPort); - grsimSettingsGroup->setLayout(grsimSettingsWidgetLayout); - vLayout->addWidget(grsimSettingsGroup); - - auto spacer = new QSpacerItem(100, 100, QSizePolicy::Expanding, QSizePolicy::Expanding); - vLayout->addSpacerItem(spacer); -} - -void SettingsWidget::changeTeamColor(bool isYellow) { SETTINGS.setYellow(isYellow); } - -void SettingsWidget::changeTeamSide(bool isLeft) { SETTINGS.setLeft(isLeft); } - -void SettingsWidget::changeMode(bool serial) { SETTINGS.setSerialMode(serial); } - -void SettingsWidget::changeGrSimIp(QString ip) { - std::cout << "setting grsimip" << std::endl; - SETTINGS.setRobothubSendIp(ip.toStdString()); -} - -void SettingsWidget::changeGrSimPort(int port) { - std::cout << "setting grsimport" << std::endl; - SETTINGS.setRobothubSendPort(port); -} - -} // namespace rtt::ai::interface diff --git a/src/interface/widgets/mainWindow.cpp b/src/interface/widgets/mainWindow.cpp index 162d47d478..67490d8acd 100644 --- a/src/interface/widgets/mainWindow.cpp +++ b/src/interface/widgets/mainWindow.cpp @@ -1,6 +1,5 @@ #include "interface/widgets/mainWindow.h" -#include "interface/widgets/MainControlsWidget.h" #include #include namespace rtt::ai::interface { @@ -14,12 +13,6 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind horizontalLayout = new QHBoxLayout(); vLayout = new QVBoxLayout(); - // the main controls widget for the most crucial buttons - // changing strategies, goalie id, etc. - auto mainControlsWidget = new MainControlsWidget(this, manager); - vLayout->addWidget(mainControlsWidget); - - manualControlWidget = new ManualControlWidget(this); // add the tab widget @@ -57,8 +50,7 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind // start the UI update cycles // these are slower than the tick rate auto *robotsTimer = new QTimer(this); - connect(robotsTimer, SIGNAL(timeout()), mainControlsWidget, SLOT(updatePause())); - connect(robotsTimer, SIGNAL(timeout()), mainControlsWidget, SLOT(updateContents())); + robotsTimer->start(500); // 2fps auto *graphTimer = new QTimer(this); @@ -67,22 +59,7 @@ MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWind } -/// Set up a checkbox and add it to the layout -void MainWindow::configureCheckBox(const QString &title, QLayout *layout, const QObject *receiver, const char *method, bool defaultState) { - auto checkbox = new QCheckBox(title); - checkbox->setChecked(defaultState); - layout->addWidget(checkbox); - QObject::connect(checkbox, SIGNAL(clicked(bool)), receiver, method); -} -void MainWindow::configureCheckableMenuItem(QString title, const QString &hint, QMenu *menu, const QObject *receiver, const char *method, bool defaultState) { - QAction *action = new QAction(title, menu); - action->setStatusTip(hint); - action->setCheckable(true); - action->setChecked(defaultState); - QObject::connect(action, SIGNAL(triggered(bool)), receiver, method); - menu->addAction(action); -} /// delete a layout and its children void MainWindow::clearLayout(QLayout *layout) { diff --git a/src/manual/JoystickManager.cpp b/src/manual/JoystickManager.cpp index 5c0b007085..ec471ccf9d 100644 --- a/src/manual/JoystickManager.cpp +++ b/src/manual/JoystickManager.cpp @@ -119,7 +119,7 @@ void JoystickManager::loop() { void JoystickManager::tickJoystickHandlers() { for (const auto &joystickHandler : joystickHandlers) { joystickHandler.second->tick(); -// auto const& [_, world] = world::World::instance(); +// auto const& [_, world] = world::World::instance(); TODO; fix by making a joystick part of the AI // auto robot = world->getWorld()->getRobotForId(joystickHandler.second->getCommand().id()); // rtt::ai::control::ControlModule::addRobotCommand(robot, joystickHandler.second->getCommand(), world); } diff --git a/src/stp/Play.cpp b/src/stp/Play.cpp index 950a8d394f..e6154fcf66 100644 --- a/src/stp/Play.cpp +++ b/src/stp/Play.cpp @@ -4,7 +4,6 @@ #include "stp/Play.hpp" -#include "interface/widgets/MainControlsWidget.h" namespace rtt::ai::stp { @@ -121,7 +120,7 @@ void Play::distributeRoles() noexcept { std::unordered_map const& Play::getRoleStatuses() const { return roleStatuses; } bool Play::isValidPlayToKeep(world::World* world) noexcept { - if (!interface::MainControlsWidget::ignoreInvariants) { + if (!ignore_invariants()) { world::Field field = world->getField().value(); return std::all_of(keepPlayInvariants.begin(), keepPlayInvariants.end(), [world, field](auto& x) { return x->checkInvariant(world->getWorld().value(), &field); }); } else { @@ -130,7 +129,7 @@ bool Play::isValidPlayToKeep(world::World* world) noexcept { } bool Play::isValidPlayToStart(world::World* world) const noexcept { - if (!interface::MainControlsWidget::ignoreInvariants) { + if (!ignore_invariants()) { world::Field field = world->getField().value(); return std::all_of(startPlayInvariants.begin(), startPlayInvariants.end(), [world, field](auto& x) { return x->checkInvariant(world->getWorld().value(), &field); }); } else { diff --git a/src/utilities/GameStateManager.cpp b/src/utilities/GameStateManager.cpp index 3172d2ddf1..f58bbbdc28 100644 --- a/src/utilities/GameStateManager.cpp +++ b/src/utilities/GameStateManager.cpp @@ -9,7 +9,7 @@ proto::SSL_Referee GameStateManager::refMsg; StrategyManager GameStateManager::strategymanager; std::mutex GameStateManager::refMsgLock; int GameStateManager::keeperID; - +GameState GameStateManager::interface_gamestate("halt_strategy", "default"); proto::SSL_Referee GameStateManager::getRefereeData() { std::lock_guard lock(refMsgLock); return GameStateManager::refMsg; @@ -163,7 +163,9 @@ void GameStateManager::setRefereeData(proto::SSL_Referee refMsg, const rtt_world // Initialize static variables GameState GameStateManager::getCurrentGameState() { GameState newGameState; - if (interface::Output::usesRefereeCommands()) { + + bool uses_referee_commands = true; //TODO: make setting/listen to settings + if (uses_referee_commands) { //TODO: no more static and clean up distinction between strategymanager/interface state newGameState = static_cast(strategymanager.getCurrentRefGameState()); newGameState.keeperId = keeperID; @@ -171,9 +173,9 @@ GameState GameStateManager::getCurrentGameState() { // if there is a ref we set the interface gamestate to these values as well // this makes sure that when we stop using the referee we don't return to an unknown state, // // so now we keep the same. - interface::Output::setInterfaceGameState(newGameState); + interface_gamestate=newGameState; } else { - newGameState = interface::Output::getInterfaceGameState(); + newGameState = interface_gamestate; } return newGameState; } @@ -182,7 +184,7 @@ void GameStateManager::forceNewGameState(RefCommand cmd, std::optional Date: Thu, 22 Apr 2021 23:10:58 +0200 Subject: [PATCH 22/40] Add initial button declarations --- include/roboteam_ai/AISettings.h | 26 +++----- include/roboteam_ai/AppSettings.h | 7 +- include/roboteam_ai/utilities/IOManager.h | 2 +- src/AISettings.cpp | 78 ++++++++++++++++------- src/AppSettings.cpp | 56 ++++++++++++++++ src/ApplicationManager.cpp | 9 +-- src/utilities/IOManager.cpp | 11 ++-- 7 files changed, 133 insertions(+), 56 deletions(-) diff --git a/include/roboteam_ai/AISettings.h b/include/roboteam_ai/AISettings.h index 1d14ccbfed..fe887287d6 100644 --- a/include/roboteam_ai/AISettings.h +++ b/include/roboteam_ai/AISettings.h @@ -6,17 +6,14 @@ #define RTT_ROBOTEAM_AI_SRC_AISETTINGS_H_ #include +#include namespace rtt { class AISettings { public: explicit AISettings(int id); - enum CommunicationMode { - SERIAL, - GRSIM - }; + [[nodiscard]] int getId() const; - void setId(int id); [[nodiscard]] bool isYellow() const; void setYellow(bool isYellow); @@ -24,27 +21,20 @@ namespace rtt { [[nodiscard]] bool isLeft() const; void setLeft(bool left); - [[nodiscard]] CommunicationMode getCommunicationMode() const; - void setCommunicationMode(CommunicationMode mode); - - [[nodiscard]] const std::string &getRobothubSendIp() const; - void setRobothubSendIp(const std::string &ip); - - [[nodiscard]] int getRobothubSendPort() const; - void setRobothubSendPort(int port); - [[nodiscard]] bool isPaused() const; void setPause(bool paused); [[nodiscard]] bool getListenToReferee() const; void setListenToReferee(bool listen); + + [[nodiscard]] proto::Handshake getButtonDeclarations() const; private: - int id; + [[nodiscard]] std::string name() const; + + const int id; bool is_yellow; bool is_left; - CommunicationMode mode; - std::string robothub_send_ip; - int robothub_send_port; + bool is_paused; bool listenToReferee; diff --git a/include/roboteam_ai/AppSettings.h b/include/roboteam_ai/AppSettings.h index f0a31d5642..3e147d2a6c 100644 --- a/include/roboteam_ai/AppSettings.h +++ b/include/roboteam_ai/AppSettings.h @@ -8,13 +8,16 @@ #include #include #include +#include enum class SerialMode{ GRSIM = 0, SERIAL = 1 }; + +static std::string serialModeName(SerialMode type); class AppSettings { public: - + AppSettings(); [[nodiscard]] const std::string& getRefereeIp() const; void setRefereeIp(const std::string& refereeIp); @@ -27,9 +30,9 @@ class AppSettings { [[nodiscard]] int getVisionPort() const; void setVisionPort(int port); + [[nodiscard]] proto::Handshake getButtonDeclarations() const; [[nodiscard]] proto::Setting toMessage() const; [[nodiscard]] proto::ObserverSettings obsMessage() const; - [[nodiscard]] proto::RobotHubSettings rhMessage() const; private: std::string referee_ip; diff --git a/include/roboteam_ai/utilities/IOManager.h b/include/roboteam_ai/utilities/IOManager.h index 1e0878985e..24d24c94aa 100644 --- a/include/roboteam_ai/utilities/IOManager.h +++ b/include/roboteam_ai/utilities/IOManager.h @@ -43,7 +43,7 @@ class IOManager { explicit IOManager() = default; void publishAICommand(const proto::AICommand& ai_command); void publishSettings(proto::Setting setting); - void handleCentralServerConnection(); + void handleCentralServerConnection(std::vector handshakes); void init(int teamId); proto::State getState(); diff --git a/src/AISettings.cpp b/src/AISettings.cpp index 321a7166b2..83ad81373c 100644 --- a/src/AISettings.cpp +++ b/src/AISettings.cpp @@ -6,9 +6,6 @@ namespace rtt { AISettings::AISettings(int initial_id) : id{initial_id}, - mode{GRSIM}, - robothub_send_ip{"127.0.0.1"}, //local host - robothub_send_port{20011},//grsim default is_paused(true), listenToReferee(false){ //these settings are for testing and convenience, basically @@ -24,9 +21,7 @@ AISettings::AISettings(int initial_id) : int AISettings::getId() const { return id; } -void AISettings::setId(int new_id) { - id = new_id; -} + bool AISettings::isYellow() const { return is_yellow; } @@ -40,24 +35,8 @@ bool AISettings::isLeft() const { void AISettings::setLeft(bool left) { is_left = left; } -AISettings::CommunicationMode AISettings::getCommunicationMode() const { - return mode; -} -void AISettings::setCommunicationMode(CommunicationMode new_mode) { - mode = new_mode; -} -const std::string &AISettings::getRobothubSendIp() const { - return robothub_send_ip; -} -void AISettings::setRobothubSendIp(const std::string &ip) { - robothub_send_ip = ip; -} -int AISettings::getRobothubSendPort() const { - return robothub_send_port; -} -void AISettings::setRobothubSendPort(int port) { - robothub_send_port = port; -} + + void AISettings::setPause(bool paused) { is_paused = paused; //TODO: when the AI is just paused, send a halt command to all robots } @@ -70,4 +49,55 @@ bool AISettings::getListenToReferee() const { void AISettings::setListenToReferee(bool listen) { listenToReferee = listen; } + +std::string AISettings::name() const { + return "ai"+std::to_string(id); +} +proto::Handshake AISettings::getButtonDeclarations() const{ + + proto::UiOptionDeclaration pause_button; + pause_button.set_name("pause_button"); + pause_button.set_is_mutable(false); + proto::Checkbox pause_box; + pause_box.set_text("Pause"); + pause_box.set_default_(is_paused); + pause_button.mutable_checkbox()->CopyFrom(pause_box); + + proto::UiOptionDeclaration listen_to_referee_button; + listen_to_referee_button.set_name("listen_to_referee_button"); + listen_to_referee_button.set_is_mutable(false); + proto::Checkbox referee_box; + referee_box.set_text("Listen to Referee"); + referee_box.set_default_(listenToReferee); + listen_to_referee_button.mutable_checkbox()->CopyFrom(referee_box); + + proto::UiOptionDeclaration side_button; + side_button.set_name("side_button"); + side_button.set_is_mutable(true); + proto::Checkbox side_box; + side_box.set_text("We play left"); + side_box.set_default_(is_left); + side_button.mutable_checkbox()->CopyFrom(side_box); + + proto::UiOptionDeclaration color_button; + color_button.set_name("side_button"); + color_button.set_is_mutable(true); + proto::Checkbox color_box; + color_box.set_text("We are the yellow team"); + color_box.set_default_(is_yellow); + color_button.mutable_checkbox()->CopyFrom(color_box); + + + proto::UiOptionDeclarations declarations; + declarations.mutable_options()->Add(std::move(pause_button)); + declarations.mutable_options()->Add(std::move(listen_to_referee_button)); + declarations.mutable_options()->Add(std::move(side_button)); + declarations.mutable_options()->Add(std::move(color_button)); + + proto::Handshake message; + message.set_module_name(name()); + message.mutable_declarations()->CopyFrom(declarations); + + return message; +} } diff --git a/src/AppSettings.cpp b/src/AppSettings.cpp index 8b09d1b45f..6ae81c9170 100644 --- a/src/AppSettings.cpp +++ b/src/AppSettings.cpp @@ -4,6 +4,23 @@ #include "AppSettings.h" +static std::string serialModeName(SerialMode mode){ + switch (mode) { + case SerialMode::GRSIM: return "GrSim"; + case SerialMode::SERIAL: return "Serial"; + } +} + +AppSettings::AppSettings() : +referee_ip("224.5.23.1"), +referee_port(10003), +vision_ip("224.5.23.2"), +vision_port(10006), +robothub_ip("127.0.0.1"), +robothub_port(20011), +mode{SerialMode::GRSIM}{ + +} const std::string &AppSettings::getRefereeIp() const { return referee_ip; } @@ -51,5 +68,44 @@ proto::RobotHubSettings AppSettings::rhMessage() const { settings.set_serialmode(mode == SerialMode::SERIAL);//TODO: extend proto with an enum to support more modes return settings; } +proto::Handshake AppSettings::getButtonDeclarations() const { + //referee ip + proto::UiOptionDeclarations declarations; + proto::UiOptionDeclaration ref_ip_textbox; + ref_ip_textbox.set_name("referee_ip"); + ref_ip_textbox.set_is_mutable(false); + proto::TextField ref_ip_text; + ref_ip_text.set_text(referee_ip); + ref_ip_textbox.mutable_textfield()->CopyFrom(ref_ip_text); + //referee port + proto::UiOptionDeclaration ref_port_textbox; + ref_port_textbox.set_name("referee_port"); + ref_port_textbox.set_is_mutable(false); + proto::TextField ref_port_text; + ref_port_text.set_text(std::to_string(referee_port)); + ref_port_textbox.mutable_textfield()->CopyFrom(ref_ip_text); + + // serial mode dropdown + proto::UiOptionDeclaration serial_mode_dropdown; + serial_mode_dropdown.set_name("serial_mode"); + serial_mode_dropdown.set_is_mutable(false); + proto::Dropdown dropdown; + dropdown.set_text("serial_mode"); + dropdown.set_default_(0); + dropdown.mutable_options()->Add()->append(serialModeName(SerialMode::GRSIM)); + dropdown.mutable_options()->Add()->append(serialModeName(SerialMode::SERIAL)); + serial_mode_dropdown.mutable_dropdown()->CopyFrom(dropdown); + + + declarations.mutable_options()->Add(std::move(ref_ip_textbox)); + declarations.mutable_options()->Add(std::move(ref_port_textbox)); + declarations.mutable_options()->Add(std::move(serial_mode_dropdown)); + + proto::Handshake message; + message.set_module_name("application"); + message.mutable_declarations()->CopyFrom(declarations); + return message; +} + diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index 744ebe5b20..4392260742 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -17,12 +17,6 @@ void ApplicationManager::start(int id) { rtt::ai::Constants::init(); - - settings.setVisionIp("127.0.0.1"); - settings.setVisionPort(10006); - settings.setRefereeIp("224.5.23.1"); - settings.setRefereePort(10003); - io->init(id); // make sure we start in halt state for safety @@ -54,6 +48,7 @@ void ApplicationManager::runOneLoopCycle() { proto::AICommand command = ai->decidePlay(); io->publishAICommand(command); - io->handleCentralServerConnection(); + std::vector handshakes = {settings.getButtonDeclarations()}; //TODO: only send declarations when + io->handleCentralServerConnection(handshakes); } } // namespace rtt diff --git a/src/utilities/IOManager.cpp b/src/utilities/IOManager.cpp index 86501f5e01..cfd08d91ee 100644 --- a/src/utilities/IOManager.cpp +++ b/src/utilities/IOManager.cpp @@ -41,12 +41,12 @@ void IOManager::handleState(proto::State &stateMsg) { void IOManager::publishSettings(proto::Setting setting) { settingsPublisher->send(setting); } -void IOManager::handleCentralServerConnection(){ +void IOManager::handleCentralServerConnection(std::vector handshakes){ //first receive any setting changes bool received = true; int numReceivedMessages = 0; while(received){ - auto receivedUIOptions = central_server_connection->read_next(); + auto receivedUIOptions = central_server_connection->read_next(); if (receivedUIOptions.is_ok()){ //TODO: process value receivedUIOptions.value().PrintDebugString(); @@ -65,9 +65,12 @@ void IOManager::handleCentralServerConnection(){ proto::ModuleState module_state; { std::lock_guard lock(stateMutex); //read lock - module_state.mutable_system_state()->mutable_state()->CopyFrom(state); + module_state.mutable_system_state()->CopyFrom(state); } - central_server_connection->write(module_state,true); + for(const auto& handshake : handshakes){ + module_state.mutable_handshakes()->Add()->CopyFrom(handshake); + } + central_server_connection->write(module_state,true); } proto::State IOManager::getState(){ std::lock_guard lock(stateMutex);//read lock From d94525a85fb91b33356861e32262df039e521515 Mon Sep 17 00:00:00 2001 From: rolf Date: Sun, 25 Apr 2021 20:10:12 +0200 Subject: [PATCH 23/40] Send ai button declarations as well --- include/roboteam_ai/AI.h | 2 +- src/AI.cpp | 3 +++ src/ApplicationManager.cpp | 2 +- 3 files changed, 5 insertions(+), 2 deletions(-) diff --git a/include/roboteam_ai/AI.h b/include/roboteam_ai/AI.h index 11680a5fd4..583d7e8e01 100644 --- a/include/roboteam_ai/AI.h +++ b/include/roboteam_ai/AI.h @@ -20,7 +20,7 @@ class AI { void updateState(const proto::State& state); proto::AICommand decidePlay(); - + [[nodiscard]] proto::Handshake getButtonDeclarations() const; private: //updates referee-related information to the game state manager, and makes sure things such as rotation, color etc. are correct void updateSettingsReferee(const proto::State& state); diff --git a/src/AI.cpp b/src/AI.cpp index a86c169180..70283dd217 100644 --- a/src/AI.cpp +++ b/src/AI.cpp @@ -173,3 +173,6 @@ void rtt::AI::updateSettingsReferee(const proto::State& state) { void rtt::AI::onSideOrColorChanged() { //TODO: reinitialize world, field, referee, and stop play } +proto::Handshake rtt::AI::getButtonDeclarations() const { + return settings.getButtonDeclarations(); +} diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index 4392260742..532a9b7c8e 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -48,7 +48,7 @@ void ApplicationManager::runOneLoopCycle() { proto::AICommand command = ai->decidePlay(); io->publishAICommand(command); - std::vector handshakes = {settings.getButtonDeclarations()}; //TODO: only send declarations when + std::vector handshakes = {settings.getButtonDeclarations(),ai->getButtonDeclarations()}; //TODO: only send declarations when central server is reconnected io->handleCentralServerConnection(handshakes); } } // namespace rtt From 58ba2a6225cae70ff5bf488021b22679127f97fd Mon Sep 17 00:00:00 2001 From: rolf Date: Wed, 28 Apr 2021 21:29:33 +0200 Subject: [PATCH 24/40] Add application settings functions --- include/roboteam_ai/AppSettings.h | 2 ++ src/AppSettings.cpp | 55 +++++++++++++++++++++++++++++++ src/ApplicationManager.cpp | 3 +- 3 files changed, 59 insertions(+), 1 deletion(-) diff --git a/include/roboteam_ai/AppSettings.h b/include/roboteam_ai/AppSettings.h index 3e147d2a6c..e9c96c0857 100644 --- a/include/roboteam_ai/AppSettings.h +++ b/include/roboteam_ai/AppSettings.h @@ -31,6 +31,8 @@ class AppSettings { void setVisionPort(int port); [[nodiscard]] proto::Handshake getButtonDeclarations() const; + [[nodiscard]] proto::Handshake getValues() const; + void updateValuesFromInterface(const proto::UiValues& values); [[nodiscard]] proto::Setting toMessage() const; [[nodiscard]] proto::ObserverSettings obsMessage() const; [[nodiscard]] proto::RobotHubSettings rhMessage() const; diff --git a/src/AppSettings.cpp b/src/AppSettings.cpp index 6ae81c9170..01c65d13ee 100644 --- a/src/AppSettings.cpp +++ b/src/AppSettings.cpp @@ -3,6 +3,7 @@ // #include "AppSettings.h" +#include static std::string serialModeName(SerialMode mode){ switch (mode) { @@ -106,6 +107,60 @@ proto::Handshake AppSettings::getButtonDeclarations() const { message.mutable_declarations()->CopyFrom(declarations); return message; } +proto::Handshake AppSettings::getValues() const { + + proto::UiValue ref_ip; + ref_ip.set_text_value(referee_ip); + + proto::UiValue ref_port; + ref_port.set_text_value(std::to_string(referee_port)); + + proto::UiValue serial_mode; + serial_mode.set_integer_value(static_cast(mode)); + proto::UiValues values; + (*values.mutable_ui_values())["referee_ip"] = ref_ip; + (*values.mutable_ui_values())["referee_port"] = ref_port; + (*values.mutable_ui_values())["serial_mode"] = serial_mode; + + proto::Handshake message; + message.set_module_name("application"); + message.mutable_values()->CopyFrom(values); + + return message; +} +void AppSettings::updateValuesFromInterface(const proto::UiValues &values) { + if(values.ui_values().contains("referee_ip")){ + proto::UiValue value = values.ui_values().at("referee_ip"); + if(value.value_case() == proto::UiValue::kTextValue){ + referee_ip = value.text_value(); + }else{ + RTT_ERROR("\"referee_ip\" did not have the correct type of \"text\" in received message from interface"); + } + } + + if(values.ui_values().contains("referee_port")){ + proto::UiValue value = values.ui_values().at("referee_port"); + if(value.value_case() == proto::UiValue::kTextValue){ + try { + int found = std::stoi(value.text_value()); + referee_port = found; + }catch (...){ + RTT_ERROR("Could not convert referee_port string to integer"); + } + }else{ + RTT_ERROR("\"referee_port\" did not have the correct type of \"text\" in received message from interface"); + } + } + + if(values.ui_values().contains("serial_mode")){ + proto::UiValue value = values.ui_values().at("serial_mode"); + if(value.value_case() == proto::UiValue::kIntegerValue){ + mode = static_cast(value.integer_value()); //TODO: check if cast is valid + }else{ + RTT_ERROR("\"serial_mode\" did not have the correct type of \"integer\" in received message from interface"); + } + } +} diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index 532a9b7c8e..6804f414fc 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -48,7 +48,8 @@ void ApplicationManager::runOneLoopCycle() { proto::AICommand command = ai->decidePlay(); io->publishAICommand(command); - std::vector handshakes = {settings.getButtonDeclarations(),ai->getButtonDeclarations()}; //TODO: only send declarations when central server is reconnected + std::vector handshakes = {settings.getButtonDeclarations(), + ai->getButtonDeclarations()}; //TODO: only send declarations when central server is reconnected io->handleCentralServerConnection(handshakes); } } // namespace rtt From 0f518e870770504f46ca234c43a1137fb16fb1b6 Mon Sep 17 00:00:00 2001 From: rolf Date: Wed, 28 Apr 2021 21:34:26 +0200 Subject: [PATCH 25/40] More error checking --- src/AppSettings.cpp | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/src/AppSettings.cpp b/src/AppSettings.cpp index 01c65d13ee..0599e75dab 100644 --- a/src/AppSettings.cpp +++ b/src/AppSettings.cpp @@ -155,7 +155,17 @@ void AppSettings::updateValuesFromInterface(const proto::UiValues &values) { if(values.ui_values().contains("serial_mode")){ proto::UiValue value = values.ui_values().at("serial_mode"); if(value.value_case() == proto::UiValue::kIntegerValue){ - mode = static_cast(value.integer_value()); //TODO: check if cast is valid + SerialMode new_mode = static_cast(value.integer_value()); + bool valid = true; + switch(new_mode){ + case SerialMode::GRSIM: + case SerialMode::SERIAL: + break; + default: RTT_ERROR("Wrong integer conversion for serial mode!"); valid = false; + } + if(valid){ + mode = new_mode; + } }else{ RTT_ERROR("\"serial_mode\" did not have the correct type of \"integer\" in received message from interface"); } From f6fd954b9c6ba8d0e1c2054c0a0f4bdf256a0f1e Mon Sep 17 00:00:00 2001 From: rolf Date: Wed, 28 Apr 2021 23:04:13 +0200 Subject: [PATCH 26/40] Finalize sending all settings to central server --- include/roboteam_ai/AI.h | 2 + include/roboteam_ai/AISettings.h | 2 + include/roboteam_ai/AppSettings.h | 1 + include/roboteam_ai/utilities/IOManager.h | 3 +- src/AI.cpp | 6 ++ src/AISettings.cpp | 68 ++++++++++++++++++++++- src/ApplicationManager.cpp | 15 ++++- src/utilities/IOManager.cpp | 37 ++++++------ 8 files changed, 113 insertions(+), 21 deletions(-) diff --git a/include/roboteam_ai/AI.h b/include/roboteam_ai/AI.h index 583d7e8e01..9b8cd005a2 100644 --- a/include/roboteam_ai/AI.h +++ b/include/roboteam_ai/AI.h @@ -21,6 +21,8 @@ class AI { void updateState(const proto::State& state); proto::AICommand decidePlay(); [[nodiscard]] proto::Handshake getButtonDeclarations() const; + [[nodiscard]] proto::Handshake getSettingValues() const; + void updateSettings(const proto::UiValues& values); private: //updates referee-related information to the game state manager, and makes sure things such as rotation, color etc. are correct void updateSettingsReferee(const proto::State& state); diff --git a/include/roboteam_ai/AISettings.h b/include/roboteam_ai/AISettings.h index fe887287d6..576a55981a 100644 --- a/include/roboteam_ai/AISettings.h +++ b/include/roboteam_ai/AISettings.h @@ -28,6 +28,8 @@ namespace rtt { void setListenToReferee(bool listen); [[nodiscard]] proto::Handshake getButtonDeclarations() const; + [[nodiscard]] proto::Handshake getValues() const; + void updateValuesFromInterface(const proto::UiValues& values); private: [[nodiscard]] std::string name() const; diff --git a/include/roboteam_ai/AppSettings.h b/include/roboteam_ai/AppSettings.h index e9c96c0857..d10c43b354 100644 --- a/include/roboteam_ai/AppSettings.h +++ b/include/roboteam_ai/AppSettings.h @@ -33,6 +33,7 @@ class AppSettings { [[nodiscard]] proto::Handshake getButtonDeclarations() const; [[nodiscard]] proto::Handshake getValues() const; void updateValuesFromInterface(const proto::UiValues& values); + [[nodiscard]] proto::Setting toMessage() const; [[nodiscard]] proto::ObserverSettings obsMessage() const; [[nodiscard]] proto::RobotHubSettings rhMessage() const; diff --git a/include/roboteam_ai/utilities/IOManager.h b/include/roboteam_ai/utilities/IOManager.h index 24d24c94aa..7cc1e2da02 100644 --- a/include/roboteam_ai/utilities/IOManager.h +++ b/include/roboteam_ai/utilities/IOManager.h @@ -43,7 +43,8 @@ class IOManager { explicit IOManager() = default; void publishAICommand(const proto::AICommand& ai_command); void publishSettings(proto::Setting setting); - void handleCentralServerConnection(std::vector handshakes); + std::optional centralServerReceive(); + void centralServerSend(std::vector handshakes); void init(int teamId); proto::State getState(); diff --git a/src/AI.cpp b/src/AI.cpp index 70283dd217..140c333ca8 100644 --- a/src/AI.cpp +++ b/src/AI.cpp @@ -176,3 +176,9 @@ void rtt::AI::onSideOrColorChanged() { proto::Handshake rtt::AI::getButtonDeclarations() const { return settings.getButtonDeclarations(); } +proto::Handshake rtt::AI::getSettingValues() const { + return settings.getValues(); +} +void rtt::AI::updateSettings(const proto::UiValues& values){ + return settings.updateValuesFromInterface(values); +} diff --git a/src/AISettings.cpp b/src/AISettings.cpp index 83ad81373c..fba1c5724a 100644 --- a/src/AISettings.cpp +++ b/src/AISettings.cpp @@ -3,6 +3,8 @@ // #include "AISettings.h" +#include + namespace rtt { AISettings::AISettings(int initial_id) : id{initial_id}, @@ -80,7 +82,7 @@ proto::Handshake AISettings::getButtonDeclarations() const{ side_button.mutable_checkbox()->CopyFrom(side_box); proto::UiOptionDeclaration color_button; - color_button.set_name("side_button"); + color_button.set_name("color_button"); color_button.set_is_mutable(true); proto::Checkbox color_box; color_box.set_text("We are the yellow team"); @@ -100,4 +102,68 @@ proto::Handshake AISettings::getButtonDeclarations() const{ return message; } +void AISettings::updateValuesFromInterface(const proto::UiValues& values) { + if(values.ui_values().contains("pause_button")){ + proto::UiValue value = values.ui_values().at("pause_button"); + if(value.value_case() == proto::UiValue::kBoolValue){ + is_paused = value.bool_value(); + }else{ + RTT_ERROR("\"pause_button\" did not have the correct type of \"bool\" in received message from interface"); + } + } + + if(values.ui_values().contains("listen_to_referee_button")){ + proto::UiValue value = values.ui_values().at("listen_to_referee_button"); + if(value.value_case() == proto::UiValue::kBoolValue){ + listenToReferee = value.bool_value(); + }else{ + RTT_ERROR("\"listen_to_referee_button\" did not have the correct type of \"bool\" in received message from interface"); + } + } + + if(!listenToReferee) { + if (values.ui_values().contains("side_button")) { + proto::UiValue value = values.ui_values().at("side_button"); + if (value.value_case() == proto::UiValue::kBoolValue) { + is_left = value.bool_value(); + } else { + RTT_ERROR("\"side_button\" did not have the correct type of \"bool\" in received message from interface"); + } + } + if (values.ui_values().contains("color_button")) { + proto::UiValue value = values.ui_values().at("color_button"); + if (value.value_case() == proto::UiValue::kBoolValue) { + is_yellow = value.bool_value(); + } else { + RTT_ERROR("\"color_button\" did not have the correct type of \"bool\" in received message from interface"); + } + } + } +} +proto::Handshake AISettings::getValues() const { + proto::Handshake handshake; + + proto::UiValues values; + + proto::UiValue pause_value; + pause_value.set_bool_value(is_paused); + (*values.mutable_ui_values())["pause_button"] = pause_value; + + proto::UiValue listen_to_ref_value; + listen_to_ref_value.set_bool_value(listenToReferee); + (*values.mutable_ui_values())["listen_to_referee_button"] = listen_to_ref_value; + + proto::UiValue left_value; + left_value.set_bool_value(is_left); + (*values.mutable_ui_values())["side_button"] = left_value; + + proto::UiValue color_value; + color_value.set_bool_value(is_yellow); + (*values.mutable_ui_values())["color_button"] = color_value; + + handshake.set_module_name(name()); + handshake.mutable_values()->CopyFrom(values); + return handshake; +} + } diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index 6804f414fc..6e0646879b 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -45,11 +45,20 @@ void ApplicationManager::runOneLoopCycle() { auto state = io->getState(); ai->updateState(state); + auto received_values = io->centralServerReceive(); + if(received_values.has_value()){ + settings.updateValuesFromInterface(received_values.value()); + ai->updateSettings(received_values.value()); + } + std::vector handshakes = {settings.getValues(),ai->getSettingValues(), + settings.getButtonDeclarations(),ai->getButtonDeclarations()}; //TODO: only send declarations when central server is reconnected + io->centralServerSend(handshakes); + proto::AICommand command = ai->decidePlay(); io->publishAICommand(command); - std::vector handshakes = {settings.getButtonDeclarations(), - ai->getButtonDeclarations()}; //TODO: only send declarations when central server is reconnected - io->handleCentralServerConnection(handshakes); + + + } } // namespace rtt diff --git a/src/utilities/IOManager.cpp b/src/utilities/IOManager.cpp index cfd08d91ee..a4b833ce5d 100644 --- a/src/utilities/IOManager.cpp +++ b/src/utilities/IOManager.cpp @@ -41,15 +41,15 @@ void IOManager::handleState(proto::State &stateMsg) { void IOManager::publishSettings(proto::Setting setting) { settingsPublisher->send(setting); } -void IOManager::handleCentralServerConnection(std::vector handshakes){ +std::optional IOManager::centralServerReceive(){ //first receive any setting changes bool received = true; int numReceivedMessages = 0; + stx::Result last_message = stx::Err(std::string("")); while(received){ - auto receivedUIOptions = central_server_connection->read_next(); - if (receivedUIOptions.is_ok()){ - //TODO: process value - receivedUIOptions.value().PrintDebugString(); + last_message = central_server_connection->read_next(); + if (last_message.is_ok()){ + last_message.value().PrintDebugString(); numReceivedMessages ++; }else{ received = false; @@ -59,18 +59,10 @@ void IOManager::handleCentralServerConnection(std::vector hand if(numReceivedMessages>0){ std::cout<<"received " << numReceivedMessages <<" packets from central server"< lock(stateMutex); //read lock - module_state.mutable_system_state()->CopyFrom(state); + if(last_message.is_ok()){ + return last_message.value(); } - for(const auto& handshake : handshakes){ - module_state.mutable_handshakes()->Add()->CopyFrom(handshake); - } - central_server_connection->write(module_state,true); + return std::nullopt; } proto::State IOManager::getState(){ std::lock_guard lock(stateMutex);//read lock @@ -83,4 +75,17 @@ void IOManager::publishAICommand(const proto::AICommand& command) { ai_command.mutable_extrapolatedworld()->CopyFrom(getState().command_extrapolated_world()); //TODO: move this responsibility to the AI robotCommandPublisher->send(command); } + +void IOManager::centralServerSend(std::vector handshakes) { + //then, send the current state once + proto::ModuleState module_state; + { + std::lock_guard lock(stateMutex); //read lock + module_state.mutable_system_state()->CopyFrom(state); + } + for(const auto& handshake : handshakes){ + module_state.mutable_handshakes()->Add()->CopyFrom(handshake); + } + central_server_connection->write(module_state,true); +} } // namespace rtt::ai::io From 402e633bb4a29d3cdd4eb4868f34e817aef6aa7f Mon Sep 17 00:00:00 2001 From: rolf Date: Thu, 29 Apr 2021 23:39:47 +0200 Subject: [PATCH 27/40] Testing, only send declarations --- src/ApplicationManager.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index 6e0646879b..cb646ec014 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -50,8 +50,7 @@ void ApplicationManager::runOneLoopCycle() { settings.updateValuesFromInterface(received_values.value()); ai->updateSettings(received_values.value()); } - std::vector handshakes = {settings.getValues(),ai->getSettingValues(), - settings.getButtonDeclarations(),ai->getButtonDeclarations()}; //TODO: only send declarations when central server is reconnected + std::vector handshakes = {settings.getButtonDeclarations()}; //TODO: only send declarations when central server is reconnected io->centralServerSend(handshakes); proto::AICommand command = ai->decidePlay(); From 9aeff234db639b46158a3f2057245eb98daadab8 Mon Sep 17 00:00:00 2001 From: Dawid Kulikowski Date: Thu, 5 Aug 2021 10:26:44 +0200 Subject: [PATCH 28/40] Fix merge errors and get it to compile --- CMakeLists.txt | 25 ----- include/roboteam_ai/AI.h | 2 + include/roboteam_ai/control/ControlModule.h | 2 +- .../interface/widgets/ManualControlWidget.h | 1 - include/roboteam_ai/world/WorldData.hpp | 1 - src/AI.cpp | 105 ++++++++++-------- src/control/ControlModule.cpp | 34 +++--- src/stp/Play.cpp | 8 -- src/utilities/GameStateManager.cpp | 1 - src/utilities/IOManager.cpp | 3 - src/utilities/StrategyManager.cpp | 4 +- src/world/Ball.cpp | 1 - 12 files changed, 79 insertions(+), 108 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f4f91b0efa..ba945328ad 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -222,38 +222,13 @@ set(TEST_SOURCES set(INTERFACE_HEADERS #QT wants to know about these headers - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/PidBox.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/PidsWidget.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/MainControlsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/mainWindow.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/RobotsWidget.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/RuleSetWidget.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/STPVisualizerWidget.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/VisualizationSettingsWidget.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/widget.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/SettingsWidget.h ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/ManualControlWidget.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/PlaysWidget.hpp - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/GraphWidget.h ) set(INTERFACE_SOURCES ${PROJECT_SOURCE_DIR}/src/interface/widgets/mainWindow.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/widget.cpp - ${PROJECT_SOURCE_DIR}/src/interface/api/Input.cpp - ${PROJECT_SOURCE_DIR}/src/interface/api/Output.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/STPVisualizerWidget.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/RobotsWidget.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/PidBox.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/PidsWidget.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/MainControlsWidget.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/VisualizationSettingsWidget.cpp - ${PROJECT_SOURCE_DIR}/src/interface/api/Toggles.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/RuleSetWidget.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/GraphWidget.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/SettingsWidget.cpp ${PROJECT_SOURCE_DIR}/src/interface/widgets/ManualControlWidget.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/PlaysWidget.cpp ) set(WORLD_SOURCES diff --git a/include/roboteam_ai/AI.h b/include/roboteam_ai/AI.h index 9b8cd005a2..2a02d1f9fa 100644 --- a/include/roboteam_ai/AI.h +++ b/include/roboteam_ai/AI.h @@ -43,6 +43,8 @@ class AI { */ rtt::ai::stp::PlayDecider playDecider; + rtt::ai::stp::PlayEvaluator playEvaluator; + /** * The vector that contains all plays */ diff --git a/include/roboteam_ai/control/ControlModule.h b/include/roboteam_ai/control/ControlModule.h index ea035392ed..8b2993f416 100644 --- a/include/roboteam_ai/control/ControlModule.h +++ b/include/roboteam_ai/control/ControlModule.h @@ -62,7 +62,7 @@ namespace rtt::ai::control { * */ - static void simulator_angular_control(const std::optional<::rtt::world::view::RobotView> &robot, + static void simulator_angular_control(const AISettings& settings, const std::optional<::rtt::world::view::RobotView> &robot, proto::RobotCommand &robot_command); static std::vector sendAllCommands(const AISettings& settings); diff --git a/include/roboteam_ai/interface/widgets/ManualControlWidget.h b/include/roboteam_ai/interface/widgets/ManualControlWidget.h index 8cc1ee04b7..ec1236046c 100644 --- a/include/roboteam_ai/interface/widgets/ManualControlWidget.h +++ b/include/roboteam_ai/interface/widgets/ManualControlWidget.h @@ -5,7 +5,6 @@ #ifndef RTT_MANUALCONTROLWIDGET_H #define RTT_MANUALCONTROLWIDGET_H -#include "interface/api/Toggles.h" #include #include #include "manual/JoystickManager.h" diff --git a/include/roboteam_ai/world/WorldData.hpp b/include/roboteam_ai/world/WorldData.hpp index 1fe6e4deb2..151ce1e943 100644 --- a/include/roboteam_ai/world/WorldData.hpp +++ b/include/roboteam_ai/world/WorldData.hpp @@ -12,7 +12,6 @@ #include #include -#include "utilities/Settings.h" namespace rtt::world { class World; diff --git a/src/AI.cpp b/src/AI.cpp index 140c333ca8..15d0a199b8 100644 --- a/src/AI.cpp +++ b/src/AI.cpp @@ -3,36 +3,41 @@ // #include "AI.h" +#include + +#include #include +#include + #include "utilities/GameStateManager.hpp" +#include "utilities/IOManager.h" +#include "control/ControlModule.h" /** * Plays are included here */ -#include "stp/plays/AggressiveStopFormation.h" -#include "stp/plays/Attack.h" -#include "stp/plays/AttackingPass.h" -#include "stp/plays/BallPlacementThem.h" -#include "stp/plays/BallPlacementUs.h" -#include "stp/plays/DefendPass.h" -#include "stp/plays/DefendShot.h" -#include "stp/plays/DefensiveStopFormation.h" -#include "stp/plays/FreeKickThem.h" -#include "stp/plays/GenericPass.h" -#include "stp/plays/GetBallPossession.h" -#include "stp/plays/GetBallRisky.h" -#include "stp/plays/Halt.h" -#include "stp/plays/KickOffThem.h" -#include "stp/plays/KickOffThemPrepare.h" -#include "stp/plays/KickOffUs.h" -#include "stp/plays/KickOffUsPrepare.h" -#include "stp/plays/PenaltyThem.h" -#include "stp/plays/PenaltyThemPrepare.h" -#include "stp/plays/PenaltyUs.h" -#include "stp/plays/PenaltyUsPrepare.h" +#include "stp/plays/referee_specific/AggressiveStopFormation.h" +#include "stp/plays/offensive/Attack.h" +#include "stp/plays/offensive/AttackingPass.h" +#include "stp/plays/referee_specific/BallPlacementThem.h" +#include "stp/plays/referee_specific/BallPlacementUs.h" +#include "stp/plays/defensive/DefendPass.h" +#include "stp/plays/defensive/DefendShot.h" +#include "stp/plays/referee_specific/DefensiveStopFormation.h" +#include "stp/plays/referee_specific/FreeKickThem.h" +#include "stp/plays/offensive/GenericPass.h" +#include "stp/plays/contested/GetBallPossession.h" +#include "stp/plays/contested/GetBallRisky.h" +#include "stp/plays/referee_specific/Halt.h" +#include "stp/plays/referee_specific/KickOffThem.h" +#include "stp/plays/referee_specific/KickOffThemPrepare.h" +#include "stp/plays/referee_specific/KickOffUs.h" +#include "stp/plays/referee_specific/KickOffUsPrepare.h" +#include "stp/plays/referee_specific/PenaltyThem.h" +#include "stp/plays/referee_specific/PenaltyThemPrepare.h" +#include "stp/plays/referee_specific/PenaltyUs.h" +#include "stp/plays/referee_specific/PenaltyUsPrepare.h" #include "stp/plays/ReflectKick.h" -#include "stp/plays/TestPlay.h" -#include "stp/plays/TimeOut.h" rtt::AI::AI(int id) : settings(id) { plays = std::vector>{}; @@ -73,34 +78,36 @@ proto::AICommand rtt::AI::decidePlay() { return proto::AICommand(); } world::World * _world = world.get();//TODO: fix ownership, why are we handing out a raw pointer? Maybe const& to unique_ptr makes more sense - playChecker.update(_world); - - // Here for manual change with the interface -// if(playDecider.interfacePlayChanged) { //TODO: is this still relevant? We need to write interface handler anyways -// auto validPlays = playChecker.getValidPlays(); -// currentPlay = playDecider.decideBestPlay(_world, validPlays); -// currentPlay->updateWorld(_world); -// currentPlay->initialize(); -// playDecider.interfacePlayChanged = false; -// } - - // A new play will be chosen if the current play is not valid to keep - if (!currentPlay || !currentPlay->isValidPlayToKeep(_world)) { - auto validPlays = playChecker.getValidPlays(); - if (validPlays.empty()) { - RTT_ERROR("No valid plays") - currentPlay = playChecker.getPlayForName("Defend Shot"); //TODO Try out different default plays so both teams dont get stuck in Defend Shot when playing against yourself - if (!currentPlay) { - return proto::AICommand(); - } - } else { - currentPlay = playDecider.decideBestPlay(_world, validPlays); + + playEvaluator.clearGlobalScores(); //reset all evaluations + ai::stp::PositionComputations::calculatedScores.clear(); + ai::stp::PositionComputations::calculatedWallPositions.clear(); + + playEvaluator.update(_world); + playChecker.update(playEvaluator); + + + +// A new play will be chosen if the current play is not valid to keep + if (!currentPlay || !currentPlay->isValidPlayToKeep(playEvaluator)) { + auto validPlays = playChecker.getValidPlays(); + ai::stp::gen::PlayInfos previousPlayInfo{}; + if(currentPlay) currentPlay->storePlayInfo(previousPlayInfo); + + if (validPlays.empty()) { + RTT_ERROR("No valid plays") + currentPlay = playChecker.getPlayForName("Defend Shot"); //TODO Try out different default plays so both teams dont get stuck in Defend Shot when playing against yourself + if (!currentPlay) { + return proto::AICommand(); + } + } else { + currentPlay = playDecider.decideBestPlay(validPlays, playEvaluator); + } + currentPlay->updateWorld(_world); + currentPlay->initialize(previousPlayInfo); } - currentPlay->updateWorld(_world); - currentPlay->initialize(); - } + currentPlay->update(); - currentPlay->update(); auto commands = ai::control::ControlModule::sendAllCommands(settings); //TODO: no more statics proto::AICommand ai_command; for(const auto& command : commands){ diff --git a/src/control/ControlModule.cpp b/src/control/ControlModule.cpp index bc21368c6c..54b8e13723 100644 --- a/src/control/ControlModule.cpp +++ b/src/control/ControlModule.cpp @@ -8,12 +8,10 @@ #include "world/World.hpp" #include "iostream" #include "utilities/Constants.h" +#include "AISettings.h" namespace rtt::ai::control { - - std::vector ControlModule::robotCommands; - void ControlModule::rotateRobotCommand(proto::RobotCommand& command){ command.mutable_vel()->set_x(-command.vel().x()); command.mutable_vel()->set_y(-command.vel().y()); @@ -66,26 +64,15 @@ namespace rtt::ai::control { //TODO: check for double commands proto::RobotCommand robot_command = command; - // If we are not left, commands should be rotated (because we play as right) - if (!settings.isLeft()) { - rotateRobotCommand(robot_command); - } - if(robot) limitRobotCommand(robot_command, robot); -// TODO: Check if is simulator - //if we are in simulation; adjust w() to be angular velocity) - if(!settings.isSerialMode()){ - simulator_angular_control(robot, robot_command); - } - if ((robot_command.id() >= 0 && robot_command.id() < 16)) { robotCommands.emplace_back(robot_command); } } - void ControlModule::simulator_angular_control(const std::optional<::rtt::world::view::RobotView> &robot, + void ControlModule::simulator_angular_control(const AISettings& settings, const std::optional<::rtt::world::view::RobotView> &robot, proto::RobotCommand &robot_command) { double ang_velocity_out = 0.0;//in case there is no robot visible, we just adjust the command to not have any angular velocity if(robot) { @@ -120,7 +107,22 @@ namespace rtt::ai::control { std::vector ControlModule::sendAllCommands(const AISettings& settings) { // If we are not left, commands should be rotated (because we play as right) - std::vector commands = robotCommands; + + std::vector commands = robotCommands; + + + +// TODO: Check if is simulator + //if we are in simulation; adjust w() to be angular velocity) +// if(!settings.isSerialMode()){ +// simulator_angular_control(robot, robot_command); +// } + + for(auto& command : commands){ + if (!settings.isLeft()) { + rotateRobotCommand(command); + } + } robotCommands.clear(); return commands; } diff --git a/src/stp/Play.cpp b/src/stp/Play.cpp index a5963c0e82..42a18e7bfb 100644 --- a/src/stp/Play.cpp +++ b/src/stp/Play.cpp @@ -131,14 +131,6 @@ namespace rtt::ai::stp { return lastScore.value_or(0); } -bool Play::isValidPlayToStart(world::World* world) const noexcept { - if (!ignore_invariants()) { - world::Field field = world->getField().value(); - return std::all_of(startPlayInvariants.begin(), startPlayInvariants.end(), [world, field](auto& x) { return x->checkInvariant(world->getWorld().value(), &field); }); - } else { - return true; - } -} void Play::storePlayInfo(gen::PlayInfos &previousPlayInfo) noexcept {} bool Play::shouldEndPlay() noexcept { return false; } diff --git a/src/utilities/GameStateManager.cpp b/src/utilities/GameStateManager.cpp index 81a54bd23f..a6d29266b0 100644 --- a/src/utilities/GameStateManager.cpp +++ b/src/utilities/GameStateManager.cpp @@ -1,6 +1,5 @@ #include "utilities/GameStateManager.hpp" -#include "utilities/Settings.h" #include #include "world/World.hpp" diff --git a/src/utilities/IOManager.cpp b/src/utilities/IOManager.cpp index 2356a1e946..5de2a31bc5 100644 --- a/src/utilities/IOManager.cpp +++ b/src/utilities/IOManager.cpp @@ -1,11 +1,8 @@ #include "utilities/IOManager.h" -#include "utilities/Settings.h" #include "utilities/GameStateManager.hpp" -#include "interface/api/Input.h" #include "roboteam_utils/normalize.h" -#include "utilities/Pause.h" #include "world/World.hpp" namespace rtt::ai::io { diff --git a/src/utilities/StrategyManager.cpp b/src/utilities/StrategyManager.cpp index 2035406f16..3bee1ea64c 100644 --- a/src/utilities/StrategyManager.cpp +++ b/src/utilities/StrategyManager.cpp @@ -7,7 +7,7 @@ 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::SSL_Referee_Stage stage, std::optional<::rtt::world::view::BallView> ballOpt) { // if the stage is shootout, we interpret penalty commands as shootOut penalty commands if (stage == proto::SSL_Referee_Stage_PENALTY_SHOOTOUT) { if (command == RefCommand::PREPARE_PENALTY_US) { @@ -56,7 +56,7 @@ const RefGameState StrategyManager::getRefGameStateForRefCommand(RefCommand comm return gameStates[0]; } -void StrategyManager::forceCurrentRefGameState(RefCommand command, std::optional ballOpt) { +void StrategyManager::forceCurrentRefGameState(RefCommand command, std::optional<::rtt::world::view::BallView> ballOpt) { // we need to change refgamestate here RefGameState newState = getRefGameStateForRefCommand(command); diff --git a/src/world/Ball.cpp b/src/world/Ball.cpp index c42ffbaf50..28529f1147 100644 --- a/src/world/Ball.cpp +++ b/src/world/Ball.cpp @@ -4,7 +4,6 @@ #include "world/Ball.hpp" -#include "interface/api/Input.h" #include "utilities/Constants.h" #include "world/World.hpp" From 8250f835809ced475ad5d55da4f405561570016b Mon Sep 17 00:00:00 2001 From: Dawid Kulikowski Date: Sat, 7 Aug 2021 11:17:00 +0200 Subject: [PATCH 29/40] Gut Qt5 out of AI for good --- CMakeLists.txt | 39 +-------- include/roboteam_ai/ApplicationManager.h | 1 - include/roboteam_ai/InterfaceSetting.h | 24 ++++++ include/roboteam_ai/utilities/Constants.h | 11 --- src/AISettings.cpp | 8 +- src/AppSettings.cpp | 6 +- src/InterfaceSetting.cpp | 16 ++++ src/interface/widgets/ManualControlWidget.cpp | 26 ------ src/interface/widgets/mainWindow.cpp | 79 ------------------- src/roboteam_ai.cpp | 66 ++++++++-------- .../FreedomOfRobotsGlobalEvaluation.cpp | 1 + src/utilities/Constants.cpp | 15 ---- 12 files changed, 83 insertions(+), 209 deletions(-) create mode 100644 include/roboteam_ai/InterfaceSetting.h create mode 100644 src/InterfaceSetting.cpp delete mode 100644 src/interface/widgets/ManualControlWidget.cpp delete mode 100644 src/interface/widgets/mainWindow.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index ba945328ad..69010aae8b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,13 +3,8 @@ project(roboteam_ai) add_subdirectory(src) -set(CMAKE_AUTORCC OFF) -set(CMAKE_AUTOUIC OFF) -set(CMAKE_INCLUDE_CURRENT_DIR OFF) #Find includes in corresponding build directories - #for MacOS X or iOS, watchOS, tvOS(since 3.10.3) if (APPLE) - set(CMAKE_AUTOMOC OFF) set(GTEST_LIB /usr/local/lib/libgtest.a /usr/local/lib/libgtest_main.a @@ -17,14 +12,11 @@ if (APPLE) /usr/local/lib/libgmock_main.a ) else (NOT APPLE) - set(CMAKE_AUTOMOC ON) set(GTEST_LIB PRIVATE gtest PRIVATE gmock) endif () -find_package(Qt5 COMPONENTS Core Widgets Gui Charts REQUIRED) - set(UTILS_SOURCES ${PROJECT_SOURCE_DIR}/src/utilities/GameStateManager.cpp @@ -220,17 +212,6 @@ set(TEST_SOURCES ${PROJECT_SOURCE_DIR}/test/StpTests/TacticTests.cpp test/ControlTests/BBTrajectory/BBTrajectory1DTest.cpp) -set(INTERFACE_HEADERS - #QT wants to know about these headers - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/mainWindow.h - ${PROJECT_SOURCE_DIR}/include/roboteam_ai/interface/widgets/ManualControlWidget.h - ) - -set(INTERFACE_SOURCES - ${PROJECT_SOURCE_DIR}/src/interface/widgets/mainWindow.cpp - ${PROJECT_SOURCE_DIR}/src/interface/widgets/ManualControlWidget.cpp - ) - set(WORLD_SOURCES ${PROJECT_SOURCE_DIR}/src/world/FieldComputations.cpp ${PROJECT_SOURCE_DIR}/src/world/Field.cpp @@ -261,13 +242,9 @@ set(AI_SOURCES ${COMPUTATION_SOURCES} src/AISettings.cpp src/AppSettings.cpp - ) + src/InterfaceSetting.cpp) set(AI_LIBS - PRIVATE Qt5::Core - PRIVATE Qt5::Widgets - PRIVATE Qt5::Gui - PRIVATE Qt5::Charts PRIVATE roboteam_utils PRIVATE NFParam PRIVATE SDL2 @@ -278,18 +255,6 @@ set(AI_INCLUDES PRIVATE include/roboteam_ai ) -# Apple-specific fixes and separate out old interface for performance -if(APPLE) - # AUTOMOC is borked on CMAKE 3.21.0 + moc 5.15.2 + libprotoc 3.17.3 - # AUTOMOC tries to moc *.pb.h and fails because ./moc dislikes strange enums? - QT5_WRAP_CPP(ai_iface_moc ${INTERFACE_HEADERS}) - add_library(ai_iface ${ai_iface_moc}) -else() - add_library(ai_iface ${INTERFACE_HEADERS}) -endif() - -target_link_libraries(ai_iface ${AI_LIBS}) -target_include_directories(ai_iface ${AI_INCLUDES}) add_library(ai_lib ${AI_SOURCES}) target_link_libraries(ai_lib ${AI_LIBS}) @@ -297,7 +262,7 @@ target_include_directories(ai_lib ${AI_INCLUDES}) # Main Executable add_executable(roboteam_ai src/roboteam_ai.cpp) -target_link_libraries(roboteam_ai ${AI_LIBS} ai_lib ai_iface) +target_link_libraries(roboteam_ai ${AI_LIBS} ai_lib) target_include_directories(roboteam_ai ${AI_INCLUDES}) # Testing # diff --git a/include/roboteam_ai/ApplicationManager.h b/include/roboteam_ai/ApplicationManager.h index 4d76360bfb..258baa8dda 100644 --- a/include/roboteam_ai/ApplicationManager.h +++ b/include/roboteam_ai/ApplicationManager.h @@ -7,7 +7,6 @@ #include -#include "interface/widgets/mainWindow.h" #include "AI.h" #include "utilities/IOManager.h" #include "AppSettings.h" diff --git a/include/roboteam_ai/InterfaceSetting.h b/include/roboteam_ai/InterfaceSetting.h new file mode 100644 index 0000000000..d3f22b3441 --- /dev/null +++ b/include/roboteam_ai/InterfaceSetting.h @@ -0,0 +1,24 @@ +// +// Created by Dawid Kulikowski on 07/08/2021. +// + +#ifndef RTT_INTERFACESETTING_H +#define RTT_INTERFACESETTING_H + +#include +#include +#include + +class InterfaceSettingStore { + public: + [[nodiscard]] virtual std::optional getSetting(const std::string& name) const = 0; +}; + +class InterfaceSetting: public InterfaceSettingStore { + private: + proto::UiValues values; + public: + void handleNewData(const proto::ModuleState newState); +}; + +#endif // RTT_INTERFACESETTING_H diff --git a/include/roboteam_ai/utilities/Constants.h b/include/roboteam_ai/utilities/Constants.h index fc109be919..1eb9dee3e0 100644 --- a/include/roboteam_ai/utilities/Constants.h +++ b/include/roboteam_ai/utilities/Constants.h @@ -2,7 +2,6 @@ #ifndef ROBOTEAM_AI_CONSTANTS_H #define ROBOTEAM_AI_CONSTANTS_H -#include #include #include #include "RuleSet.h" @@ -130,16 +129,6 @@ typedef std::tuple pidVals; static bool ROBOT_HAS_WORKING_DRIBBLER(int id); static bool ROBOT_HAS_WORKING_BALL_SENSOR(int id); - static QColor FIELD_COLOR(); - static QColor FIELD_LINE_COLOR(); - static QColor ROBOT_COLOR_BLUE(); // Blue - static QColor ROBOT_COLOR_YELLOW(); // Yellow - static QColor BALL_COLOR(); // Orange - static QColor TEXT_COLOR(); - static QColor SELECTED_ROBOT_COLOR(); - - static std::vector TACTIC_COLORS(); - // Default PID values for the gotoposses/interface static pidVals standardNumTreePID(); static pidVals standardReceivePID(); diff --git a/src/AISettings.cpp b/src/AISettings.cpp index fba1c5724a..97c252d32d 100644 --- a/src/AISettings.cpp +++ b/src/AISettings.cpp @@ -58,7 +58,7 @@ std::string AISettings::name() const { proto::Handshake AISettings::getButtonDeclarations() const{ proto::UiOptionDeclaration pause_button; - pause_button.set_name("pause_button"); + pause_button.set_path("pause_button"); pause_button.set_is_mutable(false); proto::Checkbox pause_box; pause_box.set_text("Pause"); @@ -66,7 +66,7 @@ proto::Handshake AISettings::getButtonDeclarations() const{ pause_button.mutable_checkbox()->CopyFrom(pause_box); proto::UiOptionDeclaration listen_to_referee_button; - listen_to_referee_button.set_name("listen_to_referee_button"); + listen_to_referee_button.set_path("listen_to_referee_button"); listen_to_referee_button.set_is_mutable(false); proto::Checkbox referee_box; referee_box.set_text("Listen to Referee"); @@ -74,7 +74,7 @@ proto::Handshake AISettings::getButtonDeclarations() const{ listen_to_referee_button.mutable_checkbox()->CopyFrom(referee_box); proto::UiOptionDeclaration side_button; - side_button.set_name("side_button"); + side_button.set_path("side_button"); side_button.set_is_mutable(true); proto::Checkbox side_box; side_box.set_text("We play left"); @@ -82,7 +82,7 @@ proto::Handshake AISettings::getButtonDeclarations() const{ side_button.mutable_checkbox()->CopyFrom(side_box); proto::UiOptionDeclaration color_button; - color_button.set_name("color_button"); + color_button.set_path("color_button"); color_button.set_is_mutable(true); proto::Checkbox color_box; color_box.set_text("We are the yellow team"); diff --git a/src/AppSettings.cpp b/src/AppSettings.cpp index 0599e75dab..386eb0d1cb 100644 --- a/src/AppSettings.cpp +++ b/src/AppSettings.cpp @@ -73,14 +73,14 @@ proto::Handshake AppSettings::getButtonDeclarations() const { //referee ip proto::UiOptionDeclarations declarations; proto::UiOptionDeclaration ref_ip_textbox; - ref_ip_textbox.set_name("referee_ip"); + ref_ip_textbox.set_path("referee_ip"); ref_ip_textbox.set_is_mutable(false); proto::TextField ref_ip_text; ref_ip_text.set_text(referee_ip); ref_ip_textbox.mutable_textfield()->CopyFrom(ref_ip_text); //referee port proto::UiOptionDeclaration ref_port_textbox; - ref_port_textbox.set_name("referee_port"); + ref_port_textbox.set_path("referee_port"); ref_port_textbox.set_is_mutable(false); proto::TextField ref_port_text; ref_port_text.set_text(std::to_string(referee_port)); @@ -88,7 +88,7 @@ proto::Handshake AppSettings::getButtonDeclarations() const { // serial mode dropdown proto::UiOptionDeclaration serial_mode_dropdown; - serial_mode_dropdown.set_name("serial_mode"); + serial_mode_dropdown.set_path("serial_mode"); serial_mode_dropdown.set_is_mutable(false); proto::Dropdown dropdown; dropdown.set_text("serial_mode"); diff --git a/src/InterfaceSetting.cpp b/src/InterfaceSetting.cpp new file mode 100644 index 0000000000..899d2282a7 --- /dev/null +++ b/src/InterfaceSetting.cpp @@ -0,0 +1,16 @@ +// +// Created by Dawid Kulikowski on 07/08/2021. +// + +#include "InterfaceSetting.h" +#include + + +void InterfaceSetting::handleNewData(const proto::ModuleState newState) { + if (newState.handshakes_size() != 1) { + throw std::range_error{"No handshakes available"}; + } + + this->values = newState.handshakes().at(0).values(); +} + diff --git a/src/interface/widgets/ManualControlWidget.cpp b/src/interface/widgets/ManualControlWidget.cpp deleted file mode 100644 index ceda71ebf9..0000000000 --- a/src/interface/widgets/ManualControlWidget.cpp +++ /dev/null @@ -1,26 +0,0 @@ -#include "interface/widgets/ManualControlWidget.h" -#include -#include - -namespace rtt::ai::interface { -ManualControlWidget::ManualControlWidget(QWidget *parent) : QWidget(parent) { - auto layout = new QVBoxLayout(); - setLayout(layout); - - auto allowCheckBox = new QCheckBox(); - allowCheckBox->setText("Allow Manual takeover"); - allowCheckBox->setChecked(false); - layout->addWidget(allowCheckBox); - - joyThread = std::thread(&rtt::input::JoystickManager::run, &manager); - - connect(allowCheckBox, &QCheckBox::toggled, [this](bool checked) { - if (checked) { - manager.activate(); - } else { - manager.deactivate(); - } - }); -} - -} // namespace rtt::ai::interface \ No newline at end of file diff --git a/src/interface/widgets/mainWindow.cpp b/src/interface/widgets/mainWindow.cpp deleted file mode 100644 index 67490d8acd..0000000000 --- a/src/interface/widgets/mainWindow.cpp +++ /dev/null @@ -1,79 +0,0 @@ -#include "interface/widgets/mainWindow.h" - -#include -#include -namespace rtt::ai::interface { - -MainWindow::MainWindow(QWidget *parent, ApplicationManager *manager) : QMainWindow(parent) { - setMinimumWidth(800); - setMinimumHeight(600); - - // layouts - mainLayout = new QVBoxLayout(); - horizontalLayout = new QHBoxLayout(); - vLayout = new QVBoxLayout(); - - manualControlWidget = new ManualControlWidget(this); - - // add the tab widget - auto tabWidget = new QTabWidget; - - - - - auto SettingsTabWidget = new QTabWidget; - tabWidget->addTab(SettingsTabWidget, tr("Settings")); - tabWidget->addTab(manualControlWidget, tr("Manual")); - - vLayout->addWidget(tabWidget); - - // set up the general layout structure - // visualizer on the left, sidebar (with maincontrols and tabs) on the right. - auto splitter = new QSplitter(); // the splitter is an horizontal view that allows to be changed by the user - auto sideBarWidget = new QWidget; - sideBarWidget->setLayout(vLayout); - splitter->addWidget(sideBarWidget); - splitter->setSizes({600, 200}); - horizontalLayout->addWidget(splitter); - mainLayout->addLayout(horizontalLayout); - - // apply layout to the window - setCentralWidget(new QWidget); - centralWidget()->setLayout(mainLayout); - - // start the UI update cycles - // update mainwindow and field visualization - auto *timer = new QTimer(this); - connect(timer, SIGNAL(timeout()), this, SLOT(update())); - timer->start(20); // 50fps - - // start the UI update cycles - // these are slower than the tick rate - auto *robotsTimer = new QTimer(this); - - robotsTimer->start(500); // 2fps - - auto *graphTimer = new QTimer(this); - graphTimer->start(500); // 2fps - - -} - - - -/// delete a layout and its children -void MainWindow::clearLayout(QLayout *layout) { - QLayoutItem *item; - while ((item = layout->takeAt(0))) { - if (item->layout()) { - clearLayout(item->layout()); - delete item->layout(); - } - if (item->widget()) { - delete item->widget(); - } - delete item; - } -} - -} // namespace rtt::ai::interface diff --git a/src/roboteam_ai.cpp b/src/roboteam_ai.cpp index e5b051b521..7f658f36f6 100644 --- a/src/roboteam_ai.cpp +++ b/src/roboteam_ai.cpp @@ -2,36 +2,36 @@ #include #include "world/World.hpp" #include "ApplicationManager.h" -#include -#include -namespace ui = rtt::ai::interface; +//#include +//#include +//namespace ui = rtt::ai::interface; -ui::MainWindow* window; +//ui::MainWindow* window; void run_application(int ai_id) { rtt::ApplicationManager app{}; app.start(ai_id); } -void setDarkTheme() { - qApp->setStyle(QStyleFactory::create("Fusion")); - QPalette darkPalette; - darkPalette.setColor(QPalette::Window, QColor(53, 53, 53)); - darkPalette.setColor(QPalette::WindowText, Qt::white); - darkPalette.setColor(QPalette::Base, QColor(25, 25, 25)); - darkPalette.setColor(QPalette::AlternateBase, QColor(53, 53, 53)); - darkPalette.setColor(QPalette::ToolTipBase, Qt::white); - darkPalette.setColor(QPalette::ToolTipText, Qt::white); - darkPalette.setColor(QPalette::Text, Qt::white); - darkPalette.setColor(QPalette::Button, QColor(53, 53, 53)); - darkPalette.setColor(QPalette::ButtonText, Qt::white); - darkPalette.setColor(QPalette::BrightText, Qt::red); - darkPalette.setColor(QPalette::Link, QColor(42, 130, 218)); - darkPalette.setColor(QPalette::Highlight, QColor(42, 130, 218)); - darkPalette.setColor(QPalette::HighlightedText, Qt::black); - qApp->setPalette(darkPalette); - qApp->setStyleSheet("QToolTip { color: #ffffff; background-color: #2a82da; border: 1px solid white; }"); -} +//void setDarkTheme() { +// qApp->setStyle(QStyleFactory::create("Fusion")); +// QPalette darkPalette; +// darkPalette.setColor(QPalette::Window, QColor(53, 53, 53)); +// darkPalette.setColor(QPalette::WindowText, Qt::white); +// darkPalette.setColor(QPalette::Base, QColor(25, 25, 25)); +// darkPalette.setColor(QPalette::AlternateBase, QColor(53, 53, 53)); +// darkPalette.setColor(QPalette::ToolTipBase, Qt::white); +// darkPalette.setColor(QPalette::ToolTipText, Qt::white); +// darkPalette.setColor(QPalette::Text, Qt::white); +// darkPalette.setColor(QPalette::Button, QColor(53, 53, 53)); +// darkPalette.setColor(QPalette::ButtonText, Qt::white); +// darkPalette.setColor(QPalette::BrightText, Qt::red); +// darkPalette.setColor(QPalette::Link, QColor(42, 130, 218)); +// darkPalette.setColor(QPalette::Highlight, QColor(42, 130, 218)); +// darkPalette.setColor(QPalette::HighlightedText, Qt::black); +// qApp->setPalette(darkPalette); +// qApp->setStyleSheet("QToolTip { color: #ffffff; background-color: #2a82da; border: 1px solid white; }"); +//} int main(int argc, char* argv[]) { @@ -55,17 +55,17 @@ int main(int argc, char* argv[]) { } // initialize the interface - QApplication a(argc, argv); - QCoreApplication::setAttribute(Qt::AA_EnableHighDpiScaling); - setDarkTheme(); +// QApplication a(argc, argv); +// QCoreApplication::setAttribute(Qt::AA_EnableHighDpiScaling); +// setDarkTheme(); std::thread app_thread = std::thread(&run_application,id); // Todo make this a not-global-static thingy - window = new ui::MainWindow{ }; - window->setWindowState(Qt::WindowMaximized); - - - window->show(); - bool result = a.exec(); - return result; //TODO: join app_thread +// window = new ui::MainWindow{ }; +// window->setWindowState(Qt::WindowMaximized); +// +// +// window->show(); +// bool result = a.exec(); + app_thread.join(); } diff --git a/src/stp/evaluations/global/FreedomOfRobotsGlobalEvaluation.cpp b/src/stp/evaluations/global/FreedomOfRobotsGlobalEvaluation.cpp index 000613653f..dbe3dcc215 100644 --- a/src/stp/evaluations/global/FreedomOfRobotsGlobalEvaluation.cpp +++ b/src/stp/evaluations/global/FreedomOfRobotsGlobalEvaluation.cpp @@ -5,6 +5,7 @@ // #include "stp/evaluations/global/FreedomOfRobotsGlobalEvaluation.h" +#include namespace rtt::ai::stp::evaluation { diff --git a/src/utilities/Constants.cpp b/src/utilities/Constants.cpp index 22cb07aedd..9da6ff4226 100644 --- a/src/utilities/Constants.cpp +++ b/src/utilities/Constants.cpp @@ -211,21 +211,6 @@ std::map Constants::ROBOTS_WITH_WORKING_BALL_SENSOR() { bool Constants::ROBOT_HAS_WORKING_BALL_SENSOR(int id) { return ROBOTS_WITH_WORKING_BALL_SENSOR()[id]; } bool Constants::ROBOT_HAS_WORKING_DRIBBLER(int id) { return ROBOTS_WITH_WORKING_DRIBBLER()[id]; } -QColor Constants::FIELD_COLOR() { return GRSIM() ? QColor(30, 30, 30, 255) : QColor(50, 0, 0, 255); } - -QColor Constants::FIELD_LINE_COLOR() { return Qt::white; } - -QColor Constants::ROBOT_COLOR_BLUE() { return {150, 150, 255, 255}; } - -QColor Constants::ROBOT_COLOR_YELLOW() { return {255, 255, 0, 255}; } - -QColor Constants::BALL_COLOR() { return {255, 120, 50, 255}; } - -QColor Constants::TEXT_COLOR() { return Qt::white; } - -QColor Constants::SELECTED_ROBOT_COLOR() { return Qt::magenta; } - -std::vector Constants::TACTIC_COLORS() { return {{255, 0, 255, 50}, {0, 255, 255, 50}, {255, 255, 0, 50}, {0, 255, 0, 50}, {0, 0, 255, 100}}; } pidVals Constants::standardNumTreePID() { return GRSIM() ? pidVals(2.5, 0.0, 0) : pidVals(2.5, 0.0, 0); } From 7694cc9d17fb26daba4488a3e355ca17f9fc60ae Mon Sep 17 00:00:00 2001 From: Dawid Kulikowski Date: Tue, 10 Aug 2021 11:54:29 +0200 Subject: [PATCH 30/40] Lay out basic structure of a more versatile basic interface and begin implementing --- CMakeLists.txt | 4 +- include/roboteam_ai/InterfaceSetting.h | 24 ------- include/roboteam_ai/interface/Interface.h | 25 +++++++ .../interface/InterfaceDeclaration.h | 66 +++++++++++++++++++ .../interface/InterfaceDeclarations.h | 35 ++++++++++ .../roboteam_ai/interface/InterfaceDrawer.h | 12 ++++ .../roboteam_ai/interface/InterfaceJoystick.h | 12 ++++ .../roboteam_ai/interface/InterfaceSettings.h | 33 ++++++++++ .../roboteam_ai/interface/InterfaceValue.h | 26 ++++++++ .../interface/widgets/ManualControlWidget.h | 22 ------- .../interface/widgets/mainWindow.h | 56 ---------------- src/AISettings.cpp | 16 ++--- src/AppSettings.cpp | 8 +-- src/InterfaceSetting.cpp | 16 ----- src/interface/Interface.cpp | 26 ++++++++ src/interface/InterfaceDeclaration.cpp | 45 +++++++++++++ src/interface/InterfaceDeclarations.cpp | 53 +++++++++++++++ src/interface/InterfaceSettings.cpp | 42 ++++++++++++ src/interface/InterfaceValue.cpp | 11 ++++ 19 files changed, 401 insertions(+), 131 deletions(-) delete mode 100644 include/roboteam_ai/InterfaceSetting.h create mode 100644 include/roboteam_ai/interface/Interface.h create mode 100644 include/roboteam_ai/interface/InterfaceDeclaration.h create mode 100644 include/roboteam_ai/interface/InterfaceDeclarations.h create mode 100644 include/roboteam_ai/interface/InterfaceDrawer.h create mode 100644 include/roboteam_ai/interface/InterfaceJoystick.h create mode 100644 include/roboteam_ai/interface/InterfaceSettings.h create mode 100644 include/roboteam_ai/interface/InterfaceValue.h delete mode 100644 include/roboteam_ai/interface/widgets/ManualControlWidget.h delete mode 100644 include/roboteam_ai/interface/widgets/mainWindow.h delete mode 100644 src/InterfaceSetting.cpp create mode 100644 src/interface/Interface.cpp create mode 100644 src/interface/InterfaceDeclaration.cpp create mode 100644 src/interface/InterfaceDeclarations.cpp create mode 100644 src/interface/InterfaceSettings.cpp create mode 100644 src/interface/InterfaceValue.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 69010aae8b..4df2ca1925 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -242,7 +242,9 @@ set(AI_SOURCES ${COMPUTATION_SOURCES} src/AISettings.cpp src/AppSettings.cpp - src/InterfaceSetting.cpp) +# src/interface/InterfaceSettings.cpp + src/interface/Interface.cpp + src/interface/InterfaceValue.cpp src/interface/InterfaceSettings.cpp include/roboteam_ai/interface/InterfaceDeclaration.h src/interface/InterfaceDeclarations.cpp src/interface/InterfaceDeclaration.cpp) set(AI_LIBS PRIVATE roboteam_utils diff --git a/include/roboteam_ai/InterfaceSetting.h b/include/roboteam_ai/InterfaceSetting.h deleted file mode 100644 index d3f22b3441..0000000000 --- a/include/roboteam_ai/InterfaceSetting.h +++ /dev/null @@ -1,24 +0,0 @@ -// -// Created by Dawid Kulikowski on 07/08/2021. -// - -#ifndef RTT_INTERFACESETTING_H -#define RTT_INTERFACESETTING_H - -#include -#include -#include - -class InterfaceSettingStore { - public: - [[nodiscard]] virtual std::optional getSetting(const std::string& name) const = 0; -}; - -class InterfaceSetting: public InterfaceSettingStore { - private: - proto::UiValues values; - public: - void handleNewData(const proto::ModuleState newState); -}; - -#endif // RTT_INTERFACESETTING_H diff --git a/include/roboteam_ai/interface/Interface.h b/include/roboteam_ai/interface/Interface.h new file mode 100644 index 0000000000..4ecd30862c --- /dev/null +++ b/include/roboteam_ai/interface/Interface.h @@ -0,0 +1,25 @@ +// +// Created by Dawid Kulikowski on 08/08/2021. +// + +#ifndef RTT_INTERFACE_H +#define RTT_INTERFACE_H + +#include +#include +#include + +class Interface { + private: + std::atomic doesNeedUpdate; + + public: + Interface(); + + void handleUpdate(proto::ModuleState); + + void registerChange(); + std::optional getChanges(); +}; + +#endif // RTT_INTERFACE_H diff --git a/include/roboteam_ai/interface/InterfaceDeclaration.h b/include/roboteam_ai/interface/InterfaceDeclaration.h new file mode 100644 index 0000000000..80b28fb858 --- /dev/null +++ b/include/roboteam_ai/interface/InterfaceDeclaration.h @@ -0,0 +1,66 @@ +// +// Created by Dawid Kulikowski on 10/08/2021. +// + +#ifndef RTT_INTERFACEDECLARATION_H +#define RTT_INTERFACEDECLARATION_H +#include +#include "InterfaceValue.h" +#include + +struct InterfaceSlider { + std::string text; + float min; + float max; + float interval; + + InterfaceSlider(const proto::Slider&); + InterfaceSlider(const std::string, const float, const float, const float); +}; + +struct InterfaceCheckbox { + std::string text; + + InterfaceCheckbox(const proto::Checkbox&); + InterfaceCheckbox(const std::string); +}; + +struct InterfaceDropdown { + std::string text; + std::vector options; + + InterfaceDropdown(const proto::Dropdown&); + InterfaceDropdown(const std::string, const std::vector); + +}; + +struct InterfaceRadio { + std::vector options; + InterfaceRadio(const proto::RadioButton&); + InterfaceRadio(const std::vector); +}; + +struct InterfaceText { + std::string text; + + InterfaceText(const proto::TextField&); + InterfaceText(const std::string); +}; + +typedef std::variant InterfaceOptions; + +struct InterfaceDeclaration { + std::string path; + std::string description; + + bool isMutable; + + InterfaceValue defaultValue; + + InterfaceOptions options; + + InterfaceDeclaration(const proto::UiOptionDeclaration&); + InterfaceDeclaration(const std::string, const std::string, const bool, const InterfaceValue, const InterfaceOptions); +}; + +#endif // RTT_INTERFACEDECLARATION_H diff --git a/include/roboteam_ai/interface/InterfaceDeclarations.h b/include/roboteam_ai/interface/InterfaceDeclarations.h new file mode 100644 index 0000000000..7f939a76cc --- /dev/null +++ b/include/roboteam_ai/interface/InterfaceDeclarations.h @@ -0,0 +1,35 @@ +// +// Created by Dawid Kulikowski on 09/08/2021. +// + +#ifndef RTT_INTERFACEDECLARATIONS_H +#define RTT_INTERFACEDECLARATIONS_H + +#include +#include "InterfaceDeclaration.h" + +class InterfaceDeclarations { + private: + std::vector decls = {}; + + mutable std::mutex mtx; + + void _unsafeAddDeclaration(const InterfaceDeclaration); + void _unsafeRemoveDeclaration(const std::string); + + std::optional _unsafeGetDeclaration(const std::string) const; + public: + void addDeclaration(const InterfaceDeclaration); + void removeDeclaration(const std::string); + + std::vector getDeclarations() const; + std::optional getDeclaration(const std::string) const; + + + void handleData(const proto::UiOptionDeclarations&); + + + +}; + +#endif // RTT_INTERFACEDECLARATIONS_H diff --git a/include/roboteam_ai/interface/InterfaceDrawer.h b/include/roboteam_ai/interface/InterfaceDrawer.h new file mode 100644 index 0000000000..14a0d2911d --- /dev/null +++ b/include/roboteam_ai/interface/InterfaceDrawer.h @@ -0,0 +1,12 @@ +// +// Created by Dawid Kulikowski on 09/08/2021. +// + +#ifndef RTT_INTERFACEDRAWER_H +#define RTT_INTERFACEDRAWER_H + +class InterfaceDrawer { + +}; + +#endif // RTT_INTERFACEDRAWER_H diff --git a/include/roboteam_ai/interface/InterfaceJoystick.h b/include/roboteam_ai/interface/InterfaceJoystick.h new file mode 100644 index 0000000000..c138d1c221 --- /dev/null +++ b/include/roboteam_ai/interface/InterfaceJoystick.h @@ -0,0 +1,12 @@ +// +// Created by Dawid Kulikowski on 09/08/2021. +// + +#ifndef RTT_INTERFACEJOYSTICK_H +#define RTT_INTERFACEJOYSTICK_H + +class InterfaceJoystick { + +}; + +#endif // RTT_INTERFACEJOYSTICK_H diff --git a/include/roboteam_ai/interface/InterfaceSettings.h b/include/roboteam_ai/interface/InterfaceSettings.h new file mode 100644 index 0000000000..c36065f84c --- /dev/null +++ b/include/roboteam_ai/interface/InterfaceSettings.h @@ -0,0 +1,33 @@ +// +// Created by Dawid Kulikowski on 09/08/2021. +// + +#ifndef RTT_INTERFACESETTINGS_H +#define RTT_INTERFACESETTINGS_H +#include "roboteam_proto/UiOptions.pb.h" +#include "InterfaceDeclarations.h" + +enum class InterfaceSettingsPrecedence { + AI, IFACE +}; + +class InterfaceSettings { + private: + std::map values = {}; + std::weak_ptr iface; + + mutable std::mutex mtx; + + + void _unsafeSetSetting(const std::string name, const InterfaceValue newValue); + public: + InterfaceSettings(std::weak_ptr interface): iface(interface) { }; + + const std::optional getSetting(const std::string name) const; + void setSetting(const std::string name, const InterfaceValue newValue); + + + void handleData(const proto::UiValues&, InterfaceDeclarations&, InterfaceSettingsPrecedence = InterfaceSettingsPrecedence::AI); +}; + +#endif // RTT_INTERFACESETTINGS_H diff --git a/include/roboteam_ai/interface/InterfaceValue.h b/include/roboteam_ai/interface/InterfaceValue.h new file mode 100644 index 0000000000..b7f760ddb4 --- /dev/null +++ b/include/roboteam_ai/interface/InterfaceValue.h @@ -0,0 +1,26 @@ +// +// Created by Dawid Kulikowski on 08/08/2021. +// + +#ifndef RTT_INTERFACEVALUE_H +#define RTT_INTERFACEVALUE_H + +#include +#include + +struct InterfaceValue { + public: + InterfaceValue(const proto::UiValue&); + + InterfaceValue(const int64_t v): intValue{v} {}; + InterfaceValue(const bool v): boolValue{v} {}; + InterfaceValue(const float v): floatValue{v} {}; + InterfaceValue(const std::string v): textValue{v} {}; + + std::optional intValue = std::nullopt; + std::optional boolValue = std::nullopt; + std::optional floatValue = std::nullopt; + std::optional textValue = std::nullopt; +}; + +#endif // RTT_INTERFACEVALUE_H diff --git a/include/roboteam_ai/interface/widgets/ManualControlWidget.h b/include/roboteam_ai/interface/widgets/ManualControlWidget.h deleted file mode 100644 index ec1236046c..0000000000 --- a/include/roboteam_ai/interface/widgets/ManualControlWidget.h +++ /dev/null @@ -1,22 +0,0 @@ -// -// Created by Lukas Bos on 14/11/2019. -// - -#ifndef RTT_MANUALCONTROLWIDGET_H -#define RTT_MANUALCONTROLWIDGET_H - -#include -#include -#include "manual/JoystickManager.h" - -namespace rtt::ai::interface { -class ManualControlWidget : public QWidget { - public: - ManualControlWidget(QWidget *parent); - - private: - std::thread joyThread; - rtt::input::JoystickManager manager; -}; -} // namespace rtt -#endif // RTT_MANUALCONTROLWIDGET_H diff --git a/include/roboteam_ai/interface/widgets/mainWindow.h b/include/roboteam_ai/interface/widgets/mainWindow.h deleted file mode 100644 index b3a1ff3d99..0000000000 --- a/include/roboteam_ai/interface/widgets/mainWindow.h +++ /dev/null @@ -1,56 +0,0 @@ -// -// Created by mrlukasbos on 27-11-18. -// - -#ifndef ROBOTEAM_AI_MAINWINDOW_H -#define ROBOTEAM_AI_MAINWINDOW_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include "world/World.hpp" -#include -#include - -#include "ManualControlWidget.h" -#include "QColor" -#include "QHBoxLayout" -#include "QPushButton" -#include "QTreeWidgetItemIterator" - -namespace rtt { -class ApplicationManager; -} - -namespace rtt::ai::interface { - -class MainWindow : public QMainWindow { - Q_OBJECT - FRIEND_TEST(MainWindowTest, it_displays_main_window); - FRIEND_TEST(MainWindowTest, it_shows_the_visualizer_properly); - FRIEND_TEST(TreeVisualizerTest, it_properly_displays_trees); - FRIEND_TEST(TreeVisualizerTest, it_sets_proper_color_for_status); - - public: - explicit MainWindow(QWidget *parent = nullptr, rtt::ApplicationManager *manager = nullptr); - - static void clearLayout(QLayout *layout); - - private: - QHBoxLayout *horizontalLayout; - QVBoxLayout *mainLayout; - QVBoxLayout *vLayout; - ManualControlWidget *manualControlWidget; - -// InvariantsWidget *invariantsWidget; -}; - -} // namespace rtt::ai::interface - -#endif // ROBOTEAM_AI_MAINWINDOW_H diff --git a/src/AISettings.cpp b/src/AISettings.cpp index 97c252d32d..dac59e72d5 100644 --- a/src/AISettings.cpp +++ b/src/AISettings.cpp @@ -62,32 +62,32 @@ proto::Handshake AISettings::getButtonDeclarations() const{ pause_button.set_is_mutable(false); proto::Checkbox pause_box; pause_box.set_text("Pause"); - pause_box.set_default_(is_paused); - pause_button.mutable_checkbox()->CopyFrom(pause_box); +// pause_box.set_default_(is_paused); +// pause_button.mutable_checkbox()->CopyFrom(pause_box); proto::UiOptionDeclaration listen_to_referee_button; listen_to_referee_button.set_path("listen_to_referee_button"); listen_to_referee_button.set_is_mutable(false); proto::Checkbox referee_box; referee_box.set_text("Listen to Referee"); - referee_box.set_default_(listenToReferee); - listen_to_referee_button.mutable_checkbox()->CopyFrom(referee_box); +// referee_box.set_default_(listenToReferee); +// listen_to_referee_button.mutable_checkbox()->CopyFrom(referee_box); proto::UiOptionDeclaration side_button; side_button.set_path("side_button"); side_button.set_is_mutable(true); proto::Checkbox side_box; side_box.set_text("We play left"); - side_box.set_default_(is_left); - side_button.mutable_checkbox()->CopyFrom(side_box); +// side_box.set_default_(is_left); +// side_button.mutable_checkbox()->CopyFrom(side_box); proto::UiOptionDeclaration color_button; color_button.set_path("color_button"); color_button.set_is_mutable(true); proto::Checkbox color_box; color_box.set_text("We are the yellow team"); - color_box.set_default_(is_yellow); - color_button.mutable_checkbox()->CopyFrom(color_box); +// color_box.set_default_(is_yellow); +// color_button.mutable_checkbox()->CopyFrom(color_box); proto::UiOptionDeclarations declarations; diff --git a/src/AppSettings.cpp b/src/AppSettings.cpp index 386eb0d1cb..4918d00bc6 100644 --- a/src/AppSettings.cpp +++ b/src/AppSettings.cpp @@ -77,14 +77,14 @@ proto::Handshake AppSettings::getButtonDeclarations() const { ref_ip_textbox.set_is_mutable(false); proto::TextField ref_ip_text; ref_ip_text.set_text(referee_ip); - ref_ip_textbox.mutable_textfield()->CopyFrom(ref_ip_text); +// ref_ip_textbox.mutable_textfield()->CopyFrom(ref_ip_text); //referee port proto::UiOptionDeclaration ref_port_textbox; ref_port_textbox.set_path("referee_port"); ref_port_textbox.set_is_mutable(false); proto::TextField ref_port_text; ref_port_text.set_text(std::to_string(referee_port)); - ref_port_textbox.mutable_textfield()->CopyFrom(ref_ip_text); +// ref_port_textbox.mutable_textfield()->CopyFrom(ref_ip_text); // serial mode dropdown proto::UiOptionDeclaration serial_mode_dropdown; @@ -92,10 +92,10 @@ proto::Handshake AppSettings::getButtonDeclarations() const { serial_mode_dropdown.set_is_mutable(false); proto::Dropdown dropdown; dropdown.set_text("serial_mode"); - dropdown.set_default_(0); +// dropdown.set_default_(0); dropdown.mutable_options()->Add()->append(serialModeName(SerialMode::GRSIM)); dropdown.mutable_options()->Add()->append(serialModeName(SerialMode::SERIAL)); - serial_mode_dropdown.mutable_dropdown()->CopyFrom(dropdown); +// serial_mode_dropdown.mutable_dropdown()->CopyFrom(dropdown); declarations.mutable_options()->Add(std::move(ref_ip_textbox)); diff --git a/src/InterfaceSetting.cpp b/src/InterfaceSetting.cpp deleted file mode 100644 index 899d2282a7..0000000000 --- a/src/InterfaceSetting.cpp +++ /dev/null @@ -1,16 +0,0 @@ -// -// Created by Dawid Kulikowski on 07/08/2021. -// - -#include "InterfaceSetting.h" -#include - - -void InterfaceSetting::handleNewData(const proto::ModuleState newState) { - if (newState.handshakes_size() != 1) { - throw std::range_error{"No handshakes available"}; - } - - this->values = newState.handshakes().at(0).values(); -} - diff --git a/src/interface/Interface.cpp b/src/interface/Interface.cpp new file mode 100644 index 0000000000..3911e49509 --- /dev/null +++ b/src/interface/Interface.cpp @@ -0,0 +1,26 @@ +// +// Created by Dawid Kulikowski on 08/08/2021. +// + +#include "interface/Interface.h" +#include "roboteam_utils/Print.h" + +void Interface::registerChange() { + this->doesNeedUpdate.store(true); +} + +std::optional Interface::getChanges() { + bool expect = true; + + // It's not very important that this succeeds + bool didExchange = this->doesNeedUpdate.compare_exchange_strong(expect, false); + + if (!didExchange && !expect) { + return std::nullopt; + } + + RTT_WARNING("AI changed interface value!"); +// TODO: Go through each component and compile new ModuleState + + return std::nullopt; +} \ No newline at end of file diff --git a/src/interface/InterfaceDeclaration.cpp b/src/interface/InterfaceDeclaration.cpp new file mode 100644 index 0000000000..1354a458e5 --- /dev/null +++ b/src/interface/InterfaceDeclaration.cpp @@ -0,0 +1,45 @@ +// +// Created by Dawid Kulikowski on 10/08/2021. +// + +#include "interface/InterfaceDeclaration.h" +#include + +InterfaceDeclaration::InterfaceDeclaration(const proto::UiOptionDeclaration &decl): defaultValue(InterfaceValue(decl.default_())) { + this->path = decl.path(); + this->description = decl.description(); + this->isMutable = decl.is_mutable(); + + switch (decl.ui_elements_case()) { + case proto::UiOptionDeclaration::UiElementsCase::kCheckbox: + this->options = decl.checkbox(); + break; + case proto::UiOptionDeclaration::UiElementsCase::kDropdown: + this->options = decl.dropdown(); + break; + case proto::UiOptionDeclaration::UiElementsCase::kRadiobutton: + this->options = decl.radiobutton(); + break; + case proto::UiOptionDeclaration::UiElementsCase::kSlider: + this->options = decl.slider(); + break; + case proto::UiOptionDeclaration::UiElementsCase::kTextfield: + this->options = decl.textfield(); + break; + case proto::UiOptionDeclaration::UiElementsCase::UI_ELEMENTS_NOT_SET: + RTT_ERROR("Can't instantiate interface declaration from incomplete proto message!"); + std::terminate(); + break; + default: + RTT_ERROR("Corrupted proto message!"); + std::terminate(); + break; + } +} + +InterfaceDeclaration::InterfaceDeclaration(const std::string path, const std::string description, const bool isMutable, const InterfaceValue defaultValue, const InterfaceOptions options): defaultValue(defaultValue) { + this->path = path; + this->description = description; + this->isMutable = isMutable; + this->options = options; +} diff --git a/src/interface/InterfaceDeclarations.cpp b/src/interface/InterfaceDeclarations.cpp new file mode 100644 index 0000000000..8c2b1096de --- /dev/null +++ b/src/interface/InterfaceDeclarations.cpp @@ -0,0 +1,53 @@ +// +// Created by Dawid Kulikowski on 10/08/2021. +// +#include "interface/InterfaceDeclarations.h" +#include +#include + +void InterfaceDeclarations::_unsafeAddDeclaration(const InterfaceDeclaration decl) { + this->decls.push_back(decl); +} + +void InterfaceDeclarations::_unsafeRemoveDeclaration(const std::string path) { + this->decls.erase(std::remove_if(this->decls.begin(), this->decls.end(), [&](const auto& item){ + return (item.path == path); + }), this->decls.end()); +} + +std::optional InterfaceDeclarations::_unsafeGetDeclaration(const std::string path) const { + auto found = std::find_if(this->decls.begin(), this->decls.end(), [&](const auto& item){ + return item.path == path; + }); + + return found != this->decls.end() ? std::make_optional(*found) : std::nullopt; +} + +void InterfaceDeclarations::addDeclaration(const InterfaceDeclaration decl) { + std::scoped_lock(this->mtx); + + this->_unsafeAddDeclaration(decl); +} + +void InterfaceDeclarations::removeDeclaration(const std::string path) { + std::scoped_lock(this->mtx); + + this->_unsafeRemoveDeclaration(path); +} + +std::vector InterfaceDeclarations::getDeclarations() const { + std::scoped_lock(this->mtx); + + return this->decls; +} + +std::optional InterfaceDeclarations::getDeclaration(const std::string path) const { + std::scoped_lock(this->mtx); + + return this->_unsafeGetDeclaration(path); +} + +void InterfaceDeclarations::handleData(const proto::UiOptionDeclarations &decls) { + // TODO: Parse proto + +} diff --git a/src/interface/InterfaceSettings.cpp b/src/interface/InterfaceSettings.cpp new file mode 100644 index 0000000000..8bdda28750 --- /dev/null +++ b/src/interface/InterfaceSettings.cpp @@ -0,0 +1,42 @@ +// +// Created by Dawid Kulikowski on 10/08/2021. +// + +#include "interface/InterfaceSettings.h" + +const std::optional InterfaceSettings::getSetting(const std::string name) const { + std::scoped_lock(this->mtx); + + if (!this->values.contains(name)) { + return std::nullopt; + } + + return this->values.at(name); +} +void InterfaceSettings::setSetting(const std::string name, const InterfaceValue newValue) { + std::scoped_lock(this->mtx); + + this->_unsafeSetSetting(name, newValue); +} + +void InterfaceSettings::_unsafeSetSetting(const std::string name, const InterfaceValue newValue) { + this->values.insert_or_assign(name, newValue); +} + +void InterfaceSettings::handleData(const proto::UiValues& values, InterfaceDeclarations& decls, InterfaceSettingsPrecedence precedence) { + std::scoped_lock(this->mtx); + + // TODO: Verify if value is in declarations, and whether it is an allowed value + // Also, if precedence lvl == AI, we are AI and should verify that the value we are changing is modifiable by interface + + if (values.ui_values().size() <= 0) { + RTT_WARNING("[Interface] Values are empty!") + return; + } + + this->values.clear(); + + for(auto entry : values.ui_values()) { + this->_unsafeSetSetting(entry.first, entry.second); + } +} \ No newline at end of file diff --git a/src/interface/InterfaceValue.cpp b/src/interface/InterfaceValue.cpp new file mode 100644 index 0000000000..43a50ce3bb --- /dev/null +++ b/src/interface/InterfaceValue.cpp @@ -0,0 +1,11 @@ +// +// Created by Dawid Kulikowski on 08/08/2021. +// +#include "interface/InterfaceValue.h" + +InterfaceValue::InterfaceValue(const proto::UiValue& val) { + intValue = val.has_integer_value() ? std::make_optional(val.integer_value()) : std::nullopt; + floatValue = val.has_float_value() ? std::make_optional(val.float_value()) : std::nullopt; + boolValue = val.has_bool_value() ? std::make_optional(val.bool_value()) : std::nullopt; + textValue = val.has_text_value() ? std::make_optional(val.text_value()) : std::nullopt; +} From f932cfc3fb95fcdf3820fb6626514e02133747cc Mon Sep 17 00:00:00 2001 From: Dawid Kulikowski Date: Sun, 15 Aug 2021 08:58:45 +0200 Subject: [PATCH 31/40] Implement data structures for the interface --- CMakeLists.txt | 3 +- include/roboteam_ai/interface/Interface.h | 25 ----- .../interface/InterfaceController.h | 35 ++++++ .../interface/InterfaceDeclaration.h | 27 ++++- .../interface/InterfaceDeclarations.h | 29 +++-- .../roboteam_ai/interface/InterfaceDrawer.h | 6 +- .../roboteam_ai/interface/InterfaceJoystick.h | 6 +- .../roboteam_ai/interface/InterfaceSettings.h | 15 ++- .../roboteam_ai/interface/InterfaceValue.h | 20 ++-- ...{Interface.cpp => InterfaceController.cpp} | 18 ++-- src/interface/InterfaceDeclaration.cpp | 101 ++++++++++++++++-- src/interface/InterfaceDeclarations.cpp | 36 ++++--- src/interface/InterfaceSettings.cpp | 20 ++-- src/interface/InterfaceValue.cpp | 57 +++++++++- 14 files changed, 296 insertions(+), 102 deletions(-) delete mode 100644 include/roboteam_ai/interface/Interface.h create mode 100644 include/roboteam_ai/interface/InterfaceController.h rename src/interface/{Interface.cpp => InterfaceController.cpp} (52%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4df2ca1925..a370bd8b76 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -243,13 +243,14 @@ set(AI_SOURCES src/AISettings.cpp src/AppSettings.cpp # src/interface/InterfaceSettings.cpp - src/interface/Interface.cpp + src/interface/InterfaceController.cpp src/interface/InterfaceValue.cpp src/interface/InterfaceSettings.cpp include/roboteam_ai/interface/InterfaceDeclaration.h src/interface/InterfaceDeclarations.cpp src/interface/InterfaceDeclaration.cpp) set(AI_LIBS PRIVATE roboteam_utils PRIVATE NFParam PRIVATE SDL2 + PRIVATE nlohmann_json::nlohmann_json ) set(AI_INCLUDES diff --git a/include/roboteam_ai/interface/Interface.h b/include/roboteam_ai/interface/Interface.h deleted file mode 100644 index 4ecd30862c..0000000000 --- a/include/roboteam_ai/interface/Interface.h +++ /dev/null @@ -1,25 +0,0 @@ -// -// Created by Dawid Kulikowski on 08/08/2021. -// - -#ifndef RTT_INTERFACE_H -#define RTT_INTERFACE_H - -#include -#include -#include - -class Interface { - private: - std::atomic doesNeedUpdate; - - public: - Interface(); - - void handleUpdate(proto::ModuleState); - - void registerChange(); - std::optional getChanges(); -}; - -#endif // RTT_INTERFACE_H diff --git a/include/roboteam_ai/interface/InterfaceController.h b/include/roboteam_ai/interface/InterfaceController.h new file mode 100644 index 0000000000..9e586549e1 --- /dev/null +++ b/include/roboteam_ai/interface/InterfaceController.h @@ -0,0 +1,35 @@ +// +// Created by Dawid Kulikowski on 08/08/2021. +// + +#ifndef RTT_INTERFACECONTROLLER_H +#define RTT_INTERFACECONTROLLER_H + +#include "InterfaceSettings.h" + +#include +#include +#include + +namespace rbtt::Interface { +class InterfaceController { + private: + std::shared_ptr settings; + std::shared_ptr declarations; + + std::atomic doesNeedUpdate = false; + + public: + InterfaceController(): settings(std::make_shared()), declarations(std::make_shared()) {} + InterfaceController(InterfaceSettings npsettings, InterfaceDeclarations decls): settings(std::make_shared(npsettings)), declarations(std::make_shared(decls)) {} + + void handleUpdate(proto::ModuleState); + + void registerChange(); + std::optional getChanges(); + + std::weak_ptr getSettings() {return settings;} +}; +} + +#endif // RTT_INTERFACECONTROLLER_H diff --git a/include/roboteam_ai/interface/InterfaceDeclaration.h b/include/roboteam_ai/interface/InterfaceDeclaration.h index 80b28fb858..ef2208f9ab 100644 --- a/include/roboteam_ai/interface/InterfaceDeclaration.h +++ b/include/roboteam_ai/interface/InterfaceDeclaration.h @@ -7,49 +7,68 @@ #include #include "InterfaceValue.h" #include +#include +namespace rbtt::Interface { struct InterfaceSlider { std::string text; float min; float max; float interval; + InterfaceSlider() = default; InterfaceSlider(const proto::Slider&); InterfaceSlider(const std::string, const float, const float, const float); + + NLOHMANN_DEFINE_TYPE_INTRUSIVE(InterfaceSlider, text, min, max, interval); }; struct InterfaceCheckbox { std::string text; + InterfaceCheckbox() = default; InterfaceCheckbox(const proto::Checkbox&); InterfaceCheckbox(const std::string); + + NLOHMANN_DEFINE_TYPE_INTRUSIVE(InterfaceCheckbox, text); }; struct InterfaceDropdown { std::string text; std::vector options; + InterfaceDropdown() = default; InterfaceDropdown(const proto::Dropdown&); InterfaceDropdown(const std::string, const std::vector); + NLOHMANN_DEFINE_TYPE_INTRUSIVE(InterfaceDropdown, text, options); + }; struct InterfaceRadio { std::vector options; + + InterfaceRadio() = default; InterfaceRadio(const proto::RadioButton&); InterfaceRadio(const std::vector); + + NLOHMANN_DEFINE_TYPE_INTRUSIVE(InterfaceRadio, options); }; struct InterfaceText { std::string text; + InterfaceText() = default; InterfaceText(const proto::TextField&); InterfaceText(const std::string); + + NLOHMANN_DEFINE_TYPE_INTRUSIVE(InterfaceText, text); }; -typedef std::variant InterfaceOptions; +typedef std::variant InterfaceOptions; struct InterfaceDeclaration { + public: std::string path; std::string description; @@ -59,8 +78,14 @@ struct InterfaceDeclaration { InterfaceOptions options; + proto::UiOptionDeclaration toProtoMessage(); + + + InterfaceDeclaration() = default; InterfaceDeclaration(const proto::UiOptionDeclaration&); InterfaceDeclaration(const std::string, const std::string, const bool, const InterfaceValue, const InterfaceOptions); }; +} // namespace rbtt::Interface + #endif // RTT_INTERFACEDECLARATION_H diff --git a/include/roboteam_ai/interface/InterfaceDeclarations.h b/include/roboteam_ai/interface/InterfaceDeclarations.h index 7f939a76cc..e924dd287a 100644 --- a/include/roboteam_ai/interface/InterfaceDeclarations.h +++ b/include/roboteam_ai/interface/InterfaceDeclarations.h @@ -6,30 +6,41 @@ #define RTT_INTERFACEDECLARATIONS_H #include + +#include + +#include "InterfaceController.h" #include "InterfaceDeclaration.h" +namespace rbtt::Interface { class InterfaceDeclarations { private: std::vector decls = {}; + std::weak_ptr iface; + mutable std::mutex mtx; - void _unsafeAddDeclaration(const InterfaceDeclaration); - void _unsafeRemoveDeclaration(const std::string); + void _unsafeAddDeclaration(InterfaceDeclaration); + void _unsafeRemoveDeclaration(std::string); + + std::optional _unsafeGetDeclaration(std::string) const; - std::optional _unsafeGetDeclaration(const std::string) const; public: - void addDeclaration(const InterfaceDeclaration); - void removeDeclaration(const std::string); + InterfaceDeclarations() = default; + InterfaceDeclarations(const proto::UiOptionDeclarations& pdecls) {this->handleData(pdecls);} + explicit InterfaceDeclarations(const std::vector vec, const std::weak_ptr piface) : decls(vec), iface(piface){}; - std::vector getDeclarations() const; - std::optional getDeclaration(const std::string) const; + void addDeclaration(InterfaceDeclaration); + void removeDeclaration(std::string); + std::vector getDeclarations() const; + std::optional getDeclaration(std::string) const; void handleData(const proto::UiOptionDeclarations&); - - + proto::UiOptionDeclarations toProtoMessage(); }; +} #endif // RTT_INTERFACEDECLARATIONS_H diff --git a/include/roboteam_ai/interface/InterfaceDrawer.h b/include/roboteam_ai/interface/InterfaceDrawer.h index 14a0d2911d..d97f71d382 100644 --- a/include/roboteam_ai/interface/InterfaceDrawer.h +++ b/include/roboteam_ai/interface/InterfaceDrawer.h @@ -5,8 +5,8 @@ #ifndef RTT_INTERFACEDRAWER_H #define RTT_INTERFACEDRAWER_H -class InterfaceDrawer { - -}; +namespace rbtt::Interface { +class InterfaceDrawer {}; +} // namespace rbtt::Interface #endif // RTT_INTERFACEDRAWER_H diff --git a/include/roboteam_ai/interface/InterfaceJoystick.h b/include/roboteam_ai/interface/InterfaceJoystick.h index c138d1c221..e310c56456 100644 --- a/include/roboteam_ai/interface/InterfaceJoystick.h +++ b/include/roboteam_ai/interface/InterfaceJoystick.h @@ -5,8 +5,8 @@ #ifndef RTT_INTERFACEJOYSTICK_H #define RTT_INTERFACEJOYSTICK_H -class InterfaceJoystick { - -}; +namespace rbtt::Interface { +class InterfaceJoystick {}; +} // namespace rbtt::Interface #endif // RTT_INTERFACEJOYSTICK_H diff --git a/include/roboteam_ai/interface/InterfaceSettings.h b/include/roboteam_ai/interface/InterfaceSettings.h index c36065f84c..e072332ac9 100644 --- a/include/roboteam_ai/interface/InterfaceSettings.h +++ b/include/roboteam_ai/interface/InterfaceSettings.h @@ -7,27 +7,26 @@ #include "roboteam_proto/UiOptions.pb.h" #include "InterfaceDeclarations.h" -enum class InterfaceSettingsPrecedence { - AI, IFACE -}; +namespace rbtt::Interface { +enum class InterfaceSettingsPrecedence { AI, IFACE }; class InterfaceSettings { private: std::map values = {}; - std::weak_ptr iface; mutable std::mutex mtx; - void _unsafeSetSetting(const std::string name, const InterfaceValue newValue); + public: - InterfaceSettings(std::weak_ptr interface): iface(interface) { }; + InterfaceSettings(); + InterfaceSettings(const proto::UiValues& vals, InterfaceDeclarations& decls, InterfaceSettingsPrecedence prec = InterfaceSettingsPrecedence::AI) {this->handleData(vals, decls, prec);} - const std::optional getSetting(const std::string name) const; + std::optional getSetting(const std::string name) const; void setSetting(const std::string name, const InterfaceValue newValue); - void handleData(const proto::UiValues&, InterfaceDeclarations&, InterfaceSettingsPrecedence = InterfaceSettingsPrecedence::AI); }; +} // namespace rbtt::Interface #endif // RTT_INTERFACESETTINGS_H diff --git a/include/roboteam_ai/interface/InterfaceValue.h b/include/roboteam_ai/interface/InterfaceValue.h index b7f760ddb4..5e37d1d77c 100644 --- a/include/roboteam_ai/interface/InterfaceValue.h +++ b/include/roboteam_ai/interface/InterfaceValue.h @@ -6,21 +6,25 @@ #define RTT_INTERFACEVALUE_H #include +#include +#include #include +#include +#include +namespace rbtt::Interface { struct InterfaceValue { public: + InterfaceValue() = default; InterfaceValue(const proto::UiValue&); - InterfaceValue(const int64_t v): intValue{v} {}; - InterfaceValue(const bool v): boolValue{v} {}; - InterfaceValue(const float v): floatValue{v} {}; - InterfaceValue(const std::string v): textValue{v} {}; + InterfaceValue(const int64_t v) : variant{v} {}; + InterfaceValue(const bool v) : variant{v} {}; + InterfaceValue(const float v) : variant{v} {}; + InterfaceValue(const std::string v) : variant{v} {}; - std::optional intValue = std::nullopt; - std::optional boolValue = std::nullopt; - std::optional floatValue = std::nullopt; - std::optional textValue = std::nullopt; + std::variant variant; }; +} // namespace rbtt::Interface #endif // RTT_INTERFACEVALUE_H diff --git a/src/interface/Interface.cpp b/src/interface/InterfaceController.cpp similarity index 52% rename from src/interface/Interface.cpp rename to src/interface/InterfaceController.cpp index 3911e49509..d5cf55192c 100644 --- a/src/interface/Interface.cpp +++ b/src/interface/InterfaceController.cpp @@ -2,14 +2,15 @@ // Created by Dawid Kulikowski on 08/08/2021. // -#include "interface/Interface.h" +#include "interface/InterfaceController.h" + #include "roboteam_utils/Print.h" -void Interface::registerChange() { - this->doesNeedUpdate.store(true); -} +namespace rbtt::Interface { + +void InterfaceController::registerChange() { this->doesNeedUpdate.store(true); } -std::optional Interface::getChanges() { +std::optional InterfaceController::getChanges() { bool expect = true; // It's not very important that this succeeds @@ -20,7 +21,12 @@ std::optional Interface::getChanges() { } RTT_WARNING("AI changed interface value!"); -// TODO: Go through each component and compile new ModuleState + // TODO: Go through each component and compile new ModuleState return std::nullopt; +} + +//void Interface::handleUpdate(proto::ModuleState) { +// this-> +//} } \ No newline at end of file diff --git a/src/interface/InterfaceDeclaration.cpp b/src/interface/InterfaceDeclaration.cpp index 1354a458e5..c86abe7488 100644 --- a/src/interface/InterfaceDeclaration.cpp +++ b/src/interface/InterfaceDeclaration.cpp @@ -4,8 +4,11 @@ #include "interface/InterfaceDeclaration.h" #include +#include -InterfaceDeclaration::InterfaceDeclaration(const proto::UiOptionDeclaration &decl): defaultValue(InterfaceValue(decl.default_())) { +namespace rbtt::Interface { + +InterfaceDeclaration::InterfaceDeclaration(const proto::UiOptionDeclaration& decl) : defaultValue(InterfaceValue(decl.default_())) { this->path = decl.path(); this->description = decl.description(); this->isMutable = decl.is_mutable(); @@ -27,19 +30,101 @@ InterfaceDeclaration::InterfaceDeclaration(const proto::UiOptionDeclaration &dec this->options = decl.textfield(); break; case proto::UiOptionDeclaration::UiElementsCase::UI_ELEMENTS_NOT_SET: - RTT_ERROR("Can't instantiate interface declaration from incomplete proto message!"); - std::terminate(); - break; default: - RTT_ERROR("Corrupted proto message!"); - std::terminate(); - break; + throw std::logic_error{"Unknown variant type when initialising InterfaceDeclaration!"}; + } +} + +void to_json(nlohmann::json& j, const InterfaceDeclaration& declaration) { + nlohmann::json tmpJson = + nlohmann::json{{"path", declaration.path}, {"description", declaration.description}, {"isMutable", declaration.isMutable}, {"defaultValue", declaration.defaultValue}}; + + if (const auto* slider = std::get_if(&declaration.options)) { + tmpJson["slider"] = slider; + } else if (const auto* checkbox = std::get_if(&declaration.options)) { + tmpJson["checkbox"] = checkbox; + } else if (const auto* dropdown = std::get_if(&declaration.options)) { + tmpJson["dropdown"] = dropdown; + } else if (const auto* radio = std::get_if(&declaration.options)) { + tmpJson["radio"] = radio; + } else if (const auto* text = std::get_if(&declaration.options)) { + tmpJson["text"] = text; + } else { + throw std::logic_error{"Variant was in an invalid state when serialising InterfaceDeclaration to JSON!"}; + } + + j = tmpJson; +} + +void from_json(const nlohmann::json& json, InterfaceDeclaration& declaration) { + json.at("path").get_to(declaration.path); + json.at("description").get_to(declaration.description); + + json.at("isMutable").get_to(declaration.isMutable); + json.at("defaultValue").get_to(declaration.defaultValue); + + // TODO: Replace keys with constants + if (json.contains("slider")) { + declaration.options = json.at("slider").get(); + } else if (json.contains("checkbox")) { + declaration.options = json.at("checkbox").get(); + } else if (json.contains("dropdown")) { + declaration.options = json.at("dropdown").get(); + } else if (json.contains("radio")) { + declaration.options = json.at("radio").get(); + } else if (json.contains("text")) { + declaration.options = json.at("text").get(); + } else { + throw std::domain_error{"Unknown type encountered when deserializing InterfaceDeclaration from JSON!"}; } } -InterfaceDeclaration::InterfaceDeclaration(const std::string path, const std::string description, const bool isMutable, const InterfaceValue defaultValue, const InterfaceOptions options): defaultValue(defaultValue) { +InterfaceDeclaration::InterfaceDeclaration(const std::string path, const std::string description, const bool isMutable, const InterfaceValue defaultValue, + const InterfaceOptions options) + : defaultValue(defaultValue) { this->path = path; this->description = description; this->isMutable = isMutable; this->options = options; } + +InterfaceText::InterfaceText(const proto::TextField& protoTextField) { this->text = protoTextField.text(); } + +InterfaceText::InterfaceText(const std::string text) { this->text = text; } + +InterfaceRadio::InterfaceRadio(const proto::RadioButton& protoRadio) { + // protobuf owns this message, we should copy it + std::copy(protoRadio.options().begin(), protoRadio.options().end(), std::back_inserter(this->options)); +} + +InterfaceRadio::InterfaceRadio(const std::vector options) { this->options = options; } + +InterfaceDropdown::InterfaceDropdown(const proto::Dropdown& protoDropdown) { + this->text = protoDropdown.text(); + + std::copy(protoDropdown.options().begin(), protoDropdown.options().end(), std::back_inserter(this->options)); +} + +InterfaceDropdown::InterfaceDropdown(const std::string text, const std::vector options) { + this->text = text; + this->options = options; +} + +InterfaceCheckbox::InterfaceCheckbox(const proto::Checkbox& protoCheckbox) { this->text = protoCheckbox.text(); } + +InterfaceCheckbox::InterfaceCheckbox(const std::string text) { this->text = text; } + +rbtt::Interface::InterfaceSlider::InterfaceSlider(const proto::Slider& protoSlider) { + this->text = protoSlider.text(); + this->min = protoSlider.min(); + this->max = protoSlider.max(); + this->interval = protoSlider.interval(); +} + +rbtt::Interface::InterfaceSlider::InterfaceSlider(const std::string text, const float min, const float max, const float interval) { + this->text = text; + this->min = min; + this->max = max; + this->interval = interval; +} +} diff --git a/src/interface/InterfaceDeclarations.cpp b/src/interface/InterfaceDeclarations.cpp index 8c2b1096de..198f379818 100644 --- a/src/interface/InterfaceDeclarations.cpp +++ b/src/interface/InterfaceDeclarations.cpp @@ -5,49 +5,51 @@ #include #include -void InterfaceDeclarations::_unsafeAddDeclaration(const InterfaceDeclaration decl) { - this->decls.push_back(decl); -} +namespace rbtt::Interface { + +void InterfaceDeclarations::_unsafeAddDeclaration(const InterfaceDeclaration decl) { this->decls.push_back(decl); } void InterfaceDeclarations::_unsafeRemoveDeclaration(const std::string path) { - this->decls.erase(std::remove_if(this->decls.begin(), this->decls.end(), [&](const auto& item){ - return (item.path == path); - }), this->decls.end()); + this->decls.erase(std::remove_if(this->decls.begin(), this->decls.end(), [&](const auto& item) { return (item.path == path); }), this->decls.end()); } std::optional InterfaceDeclarations::_unsafeGetDeclaration(const std::string path) const { - auto found = std::find_if(this->decls.begin(), this->decls.end(), [&](const auto& item){ - return item.path == path; - }); + auto found = std::find_if(this->decls.begin(), this->decls.end(), [&](const auto& item) { return item.path == path; }); return found != this->decls.end() ? std::make_optional(*found) : std::nullopt; } void InterfaceDeclarations::addDeclaration(const InterfaceDeclaration decl) { - std::scoped_lock(this->mtx); + std::scoped_lock lck(this->mtx); this->_unsafeAddDeclaration(decl); + + if (auto iptr = this->iface.lock()) { + iptr->registerChange(); + } } void InterfaceDeclarations::removeDeclaration(const std::string path) { - std::scoped_lock(this->mtx); + std::scoped_lock lck(this->mtx); this->_unsafeRemoveDeclaration(path); + + if (auto iptr = this->iface.lock()) { + iptr->registerChange(); + } } std::vector InterfaceDeclarations::getDeclarations() const { - std::scoped_lock(this->mtx); + std::scoped_lock lck(this->mtx); return this->decls; } std::optional InterfaceDeclarations::getDeclaration(const std::string path) const { - std::scoped_lock(this->mtx); + std::scoped_lock lck(this->mtx); return this->_unsafeGetDeclaration(path); } -void InterfaceDeclarations::handleData(const proto::UiOptionDeclarations &decls) { - // TODO: Parse proto - -} +void InterfaceDeclarations::handleData(const proto::UiOptionDeclarations&) {} +} \ No newline at end of file diff --git a/src/interface/InterfaceSettings.cpp b/src/interface/InterfaceSettings.cpp index 8bdda28750..ba1f8ccb78 100644 --- a/src/interface/InterfaceSettings.cpp +++ b/src/interface/InterfaceSettings.cpp @@ -4,8 +4,10 @@ #include "interface/InterfaceSettings.h" -const std::optional InterfaceSettings::getSetting(const std::string name) const { - std::scoped_lock(this->mtx); +namespace rbtt::Interface { + +std::optional InterfaceSettings::getSetting(const std::string name) const { + std::scoped_lock lck(this->mtx); if (!this->values.contains(name)) { return std::nullopt; @@ -14,29 +16,29 @@ const std::optional InterfaceSettings::getSetting(const std::str return this->values.at(name); } void InterfaceSettings::setSetting(const std::string name, const InterfaceValue newValue) { - std::scoped_lock(this->mtx); + std::scoped_lock lck(this->mtx); this->_unsafeSetSetting(name, newValue); } -void InterfaceSettings::_unsafeSetSetting(const std::string name, const InterfaceValue newValue) { - this->values.insert_or_assign(name, newValue); -} +void InterfaceSettings::_unsafeSetSetting(const std::string name, const InterfaceValue newValue) { this->values.insert_or_assign(name, newValue); } void InterfaceSettings::handleData(const proto::UiValues& values, InterfaceDeclarations& decls, InterfaceSettingsPrecedence precedence) { - std::scoped_lock(this->mtx); + std::scoped_lock lck(this->mtx); // TODO: Verify if value is in declarations, and whether it is an allowed value // Also, if precedence lvl == AI, we are AI and should verify that the value we are changing is modifiable by interface - if (values.ui_values().size() <= 0) { + if (values.ui_values().empty()) { RTT_WARNING("[Interface] Values are empty!") return; } this->values.clear(); - for(auto entry : values.ui_values()) { + for (const auto& entry : values.ui_values()) { this->_unsafeSetSetting(entry.first, entry.second); } +} + } \ No newline at end of file diff --git a/src/interface/InterfaceValue.cpp b/src/interface/InterfaceValue.cpp index 43a50ce3bb..6e457cc019 100644 --- a/src/interface/InterfaceValue.cpp +++ b/src/interface/InterfaceValue.cpp @@ -3,9 +3,58 @@ // #include "interface/InterfaceValue.h" +namespace rbtt::Interface { + InterfaceValue::InterfaceValue(const proto::UiValue& val) { - intValue = val.has_integer_value() ? std::make_optional(val.integer_value()) : std::nullopt; - floatValue = val.has_float_value() ? std::make_optional(val.float_value()) : std::nullopt; - boolValue = val.has_bool_value() ? std::make_optional(val.bool_value()) : std::nullopt; - textValue = val.has_text_value() ? std::make_optional(val.text_value()) : std::nullopt; + switch (val.value_case()) { + case proto::UiValue::ValueCase::kBoolValue: + this->variant = val.bool_value(); + break; + case proto::UiValue::ValueCase::kFloatValue: + this->variant = val.float_value(); + break; + case proto::UiValue::ValueCase::kIntegerValue: + this->variant = val.integer_value(); + break; + case proto::UiValue::ValueCase::kTextValue: + this->variant = val.text_value(); + break; + case proto::UiValue::ValueCase::VALUE_NOT_SET: + RTT_ERROR("[Interface] Interface value not set (corrupted proto message)"); + std::terminate(); + break; + default: + RTT_ERROR("[Interface] Interface value unknown (corrupted proto message)"); + std::terminate(); + break; + } +} + +void to_json(nlohmann::json& j, const InterfaceValue& p) { + if (auto* intVal = std::get_if(&p.variant)) { + j = nlohmann::json{"int", *intVal}; + } else if (auto* boolVal = std::get_if(&p.variant)) { + j = nlohmann::json{"bool", *boolVal}; + } else if (auto* floatVal = std::get_if(&p.variant)) { + j = nlohmann::json{"float", *floatVal}; + } else if (auto* stringVal = std::get_if(&p.variant)) { + j = nlohmann::json{"string", *stringVal}; + } else { + throw std::logic_error{"Invalid state of InterfaceValue during serialization!"}; + } +} + +void from_json(const nlohmann::json& j, InterfaceValue& p) { + if (j.contains("int")) { + p.variant = j.at("int").get(); + } else if (j.contains("bool")) { + p.variant = j.at("bool").get(); + } else if (j.contains("float")) { + p.variant = j.at("float").get(); + } else if (j.contains("string")) { + p.variant = j.at("string").get(); + } else { + throw std::domain_error{"JSON representation of InterfaceValue contains unknown type of value!"}; + } } +} \ No newline at end of file From b3b6a5d43fcd7b45b71d3d4df279e2633c963d50 Mon Sep 17 00:00:00 2001 From: Dawid Kulikowski Date: Tue, 17 Aug 2021 16:52:17 +0200 Subject: [PATCH 32/40] Fix compilation errors and finish basic implementation --- CMakeLists.txt | 2 +- include/roboteam_ai/ApplicationManager.h | 2 + .../interface/InterfaceController.h | 19 ++++--- .../interface/InterfaceDeclaration.h | 49 +++++++++++++++++-- .../interface/InterfaceDeclarations.h | 16 +++--- .../roboteam_ai/interface/InterfaceDrawer.h | 2 +- .../roboteam_ai/interface/InterfaceJoystick.h | 2 +- .../roboteam_ai/interface/InterfaceSettings.h | 13 +++-- .../interface/InterfaceStateHandler.h | 33 +++++++++++++ .../roboteam_ai/interface/InterfaceValue.h | 7 ++- include/roboteam_ai/utilities/RuleSet.h | 1 + src/ApplicationManager.cpp | 15 +++++- src/interface/InterfaceController.cpp | 30 ++++++------ src/interface/InterfaceDeclaration.cpp | 47 ++++++++++++++---- src/interface/InterfaceDeclarations.cpp | 31 +++++++++--- src/interface/InterfaceSettings.cpp | 22 +++++++-- src/interface/InterfaceValue.cpp | 20 +++++++- src/utilities/IOManager.cpp | 12 +++-- 18 files changed, 256 insertions(+), 67 deletions(-) create mode 100644 include/roboteam_ai/interface/InterfaceStateHandler.h diff --git a/CMakeLists.txt b/CMakeLists.txt index a370bd8b76..59c4795ea7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -244,7 +244,7 @@ set(AI_SOURCES src/AppSettings.cpp # src/interface/InterfaceSettings.cpp src/interface/InterfaceController.cpp - src/interface/InterfaceValue.cpp src/interface/InterfaceSettings.cpp include/roboteam_ai/interface/InterfaceDeclaration.h src/interface/InterfaceDeclarations.cpp src/interface/InterfaceDeclaration.cpp) + src/interface/InterfaceValue.cpp src/interface/InterfaceSettings.cpp include/roboteam_ai/interface/InterfaceDeclaration.h src/interface/InterfaceDeclarations.cpp src/interface/InterfaceDeclaration.cpp include/roboteam_ai/interface/InterfaceStateHandler.h) set(AI_LIBS PRIVATE roboteam_utils diff --git a/include/roboteam_ai/ApplicationManager.h b/include/roboteam_ai/ApplicationManager.h index 258baa8dda..f346a16984 100644 --- a/include/roboteam_ai/ApplicationManager.h +++ b/include/roboteam_ai/ApplicationManager.h @@ -10,6 +10,7 @@ #include "AI.h" #include "utilities/IOManager.h" #include "AppSettings.h" +#include "interface/InterfaceController.h" namespace rtt { @@ -23,6 +24,7 @@ class ApplicationManager { bool robotsInitialized = false; AppSettings settings; + Interface::InterfaceController iface; std::unique_ptr ai; std::unique_ptr io; diff --git a/include/roboteam_ai/interface/InterfaceController.h b/include/roboteam_ai/interface/InterfaceController.h index 9e586549e1..b982c6dcc0 100644 --- a/include/roboteam_ai/interface/InterfaceController.h +++ b/include/roboteam_ai/interface/InterfaceController.h @@ -5,30 +5,33 @@ #ifndef RTT_INTERFACECONTROLLER_H #define RTT_INTERFACECONTROLLER_H -#include "InterfaceSettings.h" +#include "interface/InterfaceSettings.h" +#include "interface/InterfaceStateHandler.h" +#include "interface/InterfaceDeclarations.h" #include #include #include -namespace rbtt::Interface { + +namespace rtt::Interface { class InterfaceController { private: std::shared_ptr settings; std::shared_ptr declarations; - - std::atomic doesNeedUpdate = false; +// + std::shared_ptr stateHandler; public: - InterfaceController(): settings(std::make_shared()), declarations(std::make_shared()) {} - InterfaceController(InterfaceSettings npsettings, InterfaceDeclarations decls): settings(std::make_shared(npsettings)), declarations(std::make_shared(decls)) {} + InterfaceController(): declarations(std::make_shared(stateHandler)), settings(std::make_shared(stateHandler)) {} + + void handleUpdate(proto::UiValues); - void handleUpdate(proto::ModuleState); - void registerChange(); std::optional getChanges(); std::weak_ptr getSettings() {return settings;} + std::weak_ptr getDeclarations() {return declarations;} }; } diff --git a/include/roboteam_ai/interface/InterfaceDeclaration.h b/include/roboteam_ai/interface/InterfaceDeclaration.h index ef2208f9ab..dfde955377 100644 --- a/include/roboteam_ai/interface/InterfaceDeclaration.h +++ b/include/roboteam_ai/interface/InterfaceDeclaration.h @@ -9,7 +9,7 @@ #include #include -namespace rbtt::Interface { +namespace rtt::Interface { struct InterfaceSlider { std::string text; float min; @@ -20,6 +20,17 @@ struct InterfaceSlider { InterfaceSlider(const proto::Slider&); InterfaceSlider(const std::string, const float, const float, const float); + proto::Slider toProto() const { + proto::Slider slider; + + slider.set_text(this->text); + slider.set_min(this->min); + slider.set_max(this->max); + slider.set_interval(this->interval); + + return slider; + } + NLOHMANN_DEFINE_TYPE_INTRUSIVE(InterfaceSlider, text, min, max, interval); }; @@ -30,6 +41,14 @@ struct InterfaceCheckbox { InterfaceCheckbox(const proto::Checkbox&); InterfaceCheckbox(const std::string); + proto::Checkbox toProto() const { + proto::Checkbox checkbox; + + checkbox.set_text(this->text); + + return checkbox; + } + NLOHMANN_DEFINE_TYPE_INTRUSIVE(InterfaceCheckbox, text); }; @@ -41,6 +60,15 @@ struct InterfaceDropdown { InterfaceDropdown(const proto::Dropdown&); InterfaceDropdown(const std::string, const std::vector); + proto::Dropdown toProto() const { + proto::Dropdown dropdown; + + dropdown.set_text(this->text); + dropdown.mutable_options()->Add(options.begin(), options.end()); + + return dropdown; + } + NLOHMANN_DEFINE_TYPE_INTRUSIVE(InterfaceDropdown, text, options); }; @@ -52,6 +80,13 @@ struct InterfaceRadio { InterfaceRadio(const proto::RadioButton&); InterfaceRadio(const std::vector); + proto::RadioButton toProto() const { + proto::RadioButton radio; + + radio.mutable_options()->Add(options.begin(), options.end()); + return radio; + } + NLOHMANN_DEFINE_TYPE_INTRUSIVE(InterfaceRadio, options); }; @@ -62,10 +97,18 @@ struct InterfaceText { InterfaceText(const proto::TextField&); InterfaceText(const std::string); + proto::TextField toProto() const { + proto:: TextField txtField; + + txtField.set_text(text); + + return txtField; + } + NLOHMANN_DEFINE_TYPE_INTRUSIVE(InterfaceText, text); }; -typedef std::variant InterfaceOptions; +typedef std::variant InterfaceOptions; struct InterfaceDeclaration { public: @@ -78,7 +121,7 @@ struct InterfaceDeclaration { InterfaceOptions options; - proto::UiOptionDeclaration toProtoMessage(); + proto::UiOptionDeclaration toProto() const; InterfaceDeclaration() = default; diff --git a/include/roboteam_ai/interface/InterfaceDeclarations.h b/include/roboteam_ai/interface/InterfaceDeclarations.h index e924dd287a..05443f1002 100644 --- a/include/roboteam_ai/interface/InterfaceDeclarations.h +++ b/include/roboteam_ai/interface/InterfaceDeclarations.h @@ -9,18 +9,18 @@ #include -#include "InterfaceController.h" #include "InterfaceDeclaration.h" +#include "InterfaceStateHandler.h" -namespace rbtt::Interface { +namespace rtt::Interface { class InterfaceDeclarations { private: std::vector decls = {}; - std::weak_ptr iface; - mutable std::mutex mtx; + std::weak_ptr stateHandler; + void _unsafeAddDeclaration(InterfaceDeclaration); void _unsafeRemoveDeclaration(std::string); @@ -28,8 +28,10 @@ class InterfaceDeclarations { public: InterfaceDeclarations() = default; - InterfaceDeclarations(const proto::UiOptionDeclarations& pdecls) {this->handleData(pdecls);} - explicit InterfaceDeclarations(const std::vector vec, const std::weak_ptr piface) : decls(vec), iface(piface){}; + InterfaceDeclarations(std::weak_ptr sts): stateHandler(sts) {} + + InterfaceDeclarations(const proto::UiOptionDeclarations& pdecls, std::weak_ptr sts): stateHandler(sts) {this->handleData(pdecls);} + explicit InterfaceDeclarations(const std::vector vec, std::weak_ptr sts) : decls(vec), stateHandler(sts) {}; void addDeclaration(InterfaceDeclaration); void removeDeclaration(std::string); @@ -39,7 +41,7 @@ class InterfaceDeclarations { void handleData(const proto::UiOptionDeclarations&); - proto::UiOptionDeclarations toProtoMessage(); + proto::UiOptionDeclarations toProto() const; }; } diff --git a/include/roboteam_ai/interface/InterfaceDrawer.h b/include/roboteam_ai/interface/InterfaceDrawer.h index d97f71d382..c7531ceefc 100644 --- a/include/roboteam_ai/interface/InterfaceDrawer.h +++ b/include/roboteam_ai/interface/InterfaceDrawer.h @@ -5,7 +5,7 @@ #ifndef RTT_INTERFACEDRAWER_H #define RTT_INTERFACEDRAWER_H -namespace rbtt::Interface { +namespace rtt::Interface { class InterfaceDrawer {}; } // namespace rbtt::Interface diff --git a/include/roboteam_ai/interface/InterfaceJoystick.h b/include/roboteam_ai/interface/InterfaceJoystick.h index e310c56456..f885e33f5b 100644 --- a/include/roboteam_ai/interface/InterfaceJoystick.h +++ b/include/roboteam_ai/interface/InterfaceJoystick.h @@ -5,7 +5,7 @@ #ifndef RTT_INTERFACEJOYSTICK_H #define RTT_INTERFACEJOYSTICK_H -namespace rbtt::Interface { +namespace rtt::Interface { class InterfaceJoystick {}; } // namespace rbtt::Interface diff --git a/include/roboteam_ai/interface/InterfaceSettings.h b/include/roboteam_ai/interface/InterfaceSettings.h index e072332ac9..7d4279b757 100644 --- a/include/roboteam_ai/interface/InterfaceSettings.h +++ b/include/roboteam_ai/interface/InterfaceSettings.h @@ -6,8 +6,10 @@ #define RTT_INTERFACESETTINGS_H #include "roboteam_proto/UiOptions.pb.h" #include "InterfaceDeclarations.h" +#include "InterfaceValue.h" +#include "InterfaceStateHandler.h" -namespace rbtt::Interface { +namespace rtt::Interface { enum class InterfaceSettingsPrecedence { AI, IFACE }; class InterfaceSettings { @@ -16,16 +18,19 @@ class InterfaceSettings { mutable std::mutex mtx; + std::weak_ptr stateHandler; + void _unsafeSetSetting(const std::string name, const InterfaceValue newValue); public: - InterfaceSettings(); - InterfaceSettings(const proto::UiValues& vals, InterfaceDeclarations& decls, InterfaceSettingsPrecedence prec = InterfaceSettingsPrecedence::AI) {this->handleData(vals, decls, prec);} + InterfaceSettings(std::weak_ptr sts): stateHandler(sts) {}; std::optional getSetting(const std::string name) const; void setSetting(const std::string name, const InterfaceValue newValue); - void handleData(const proto::UiValues&, InterfaceDeclarations&, InterfaceSettingsPrecedence = InterfaceSettingsPrecedence::AI); + void handleData(const proto::UiValues&, InterfaceSettingsPrecedence = InterfaceSettingsPrecedence::AI); + + proto::UiValues toProto(); }; } // namespace rbtt::Interface diff --git a/include/roboteam_ai/interface/InterfaceStateHandler.h b/include/roboteam_ai/interface/InterfaceStateHandler.h new file mode 100644 index 0000000000..955de17018 --- /dev/null +++ b/include/roboteam_ai/interface/InterfaceStateHandler.h @@ -0,0 +1,33 @@ +// +// Created by Dawid Kulikowski on 16/08/2021. +// + +#ifndef RTT_INTERFACESTATEHANDLER_H +#define RTT_INTERFACESTATEHANDLER_H + +namespace rtt::Interface { + +class InterfaceStateHandler { + // TODO: This is a pretty slow mechanism, maybe use atomic? + private: + bool didChange = false; + mutable std::mutex mtx; + + public: + void stateDidChange() { + std::scoped_lock lck(mtx); + didChange = true; + } + + void clear() { + std::scoped_lock lck(mtx); + didChange = false; + } + bool getState() const { + std::scoped_lock lck(mtx); + return didChange; + } +}; +} // namespace rtt::Interface + +#endif // RTT_INTERFACESTATEHANDLER_H diff --git a/include/roboteam_ai/interface/InterfaceValue.h b/include/roboteam_ai/interface/InterfaceValue.h index 5e37d1d77c..6d9419234e 100644 --- a/include/roboteam_ai/interface/InterfaceValue.h +++ b/include/roboteam_ai/interface/InterfaceValue.h @@ -12,7 +12,7 @@ #include #include -namespace rbtt::Interface { +namespace rtt::Interface { struct InterfaceValue { public: InterfaceValue() = default; @@ -24,7 +24,12 @@ struct InterfaceValue { InterfaceValue(const std::string v) : variant{v} {}; std::variant variant; + + proto::UiValue toProto() const; }; +void from_json(const nlohmann::json& j, InterfaceValue& p); +void to_json(nlohmann::json& j, const InterfaceValue& p); + } // namespace rbtt::Interface #endif // RTT_INTERFACEVALUE_H diff --git a/include/roboteam_ai/utilities/RuleSet.h b/include/roboteam_ai/utilities/RuleSet.h index 927176ff29..6df93ea689 100644 --- a/include/roboteam_ai/utilities/RuleSet.h +++ b/include/roboteam_ai/utilities/RuleSet.h @@ -4,6 +4,7 @@ #ifndef ROBOTEAM_AI_RULESET_H #define ROBOTEAM_AI_RULESET_H +#include namespace rtt::ai { diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index 0bbe8e633b..1369956769 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -50,9 +50,20 @@ void ApplicationManager::runOneLoopCycle() { auto received_values = io->centralServerReceive(); if(received_values.has_value()){ settings.updateValuesFromInterface(received_values.value()); - ai->updateSettings(received_values.value()); + iface.handleUpdate(received_values.value()); +// ai->updateSettings(received_values.value()); } - std::vector handshakes = {settings.getButtonDeclarations()}; //TODO: only send declarations when central server is reconnected +// std::vector handshakes = {settings.getButtonDeclarations()}; //TODO: only send declarations when central server is reconnected +std::vector handshakes = {}; + if (const auto& decls = iface.getDeclarations().lock()) { + proto::Handshake handshake; + + handshake.mutable_declarations()->CopyFrom(decls->toProto()); + handshakes.emplace_back(handshake); + } else { + RTT_ERROR("Can't get access to interface declarations!"); + } + io->centralServerSend(handshakes); proto::AICommand command = ai->decidePlay(); diff --git a/src/interface/InterfaceController.cpp b/src/interface/InterfaceController.cpp index d5cf55192c..5e0856ee18 100644 --- a/src/interface/InterfaceController.cpp +++ b/src/interface/InterfaceController.cpp @@ -6,27 +6,29 @@ #include "roboteam_utils/Print.h" -namespace rbtt::Interface { - -void InterfaceController::registerChange() { this->doesNeedUpdate.store(true); } +namespace rtt::Interface { std::optional InterfaceController::getChanges() { - bool expect = true; - - // It's not very important that this succeeds - bool didExchange = this->doesNeedUpdate.compare_exchange_strong(expect, false); - - if (!didExchange && !expect) { + if (!this->stateHandler->getState()) { return std::nullopt; } RTT_WARNING("AI changed interface value!"); - // TODO: Go through each component and compile new ModuleState - return std::nullopt; + proto::ModuleState state; + proto::Handshake handshake; + + handshake.set_module_name("_INTERFACE"); + handshake.mutable_declarations()->CopyFrom(this->declarations->toProto()); + handshake.mutable_values()->CopyFrom(this->settings->toProto()); + + state.mutable_handshakes()->AddAllocated(&handshake); + + return state; } -//void Interface::handleUpdate(proto::ModuleState) { -// this-> -//} +void InterfaceController::handleUpdate(proto::UiValues val) { + this->settings->handleData(val); +// this->declarations->handleData(state.handshakes(0).declarations()); +} } \ No newline at end of file diff --git a/src/interface/InterfaceDeclaration.cpp b/src/interface/InterfaceDeclaration.cpp index c86abe7488..05c8558db2 100644 --- a/src/interface/InterfaceDeclaration.cpp +++ b/src/interface/InterfaceDeclaration.cpp @@ -3,10 +3,12 @@ // #include "interface/InterfaceDeclaration.h" +#include "interface/InterfaceValue.h" #include +#include #include -namespace rbtt::Interface { +namespace rtt::Interface { InterfaceDeclaration::InterfaceDeclaration(const proto::UiOptionDeclaration& decl) : defaultValue(InterfaceValue(decl.default_())) { this->path = decl.path(); @@ -39,16 +41,16 @@ void to_json(nlohmann::json& j, const InterfaceDeclaration& declaration) { nlohmann::json tmpJson = nlohmann::json{{"path", declaration.path}, {"description", declaration.description}, {"isMutable", declaration.isMutable}, {"defaultValue", declaration.defaultValue}}; - if (const auto* slider = std::get_if(&declaration.options)) { - tmpJson["slider"] = slider; + if (const auto* slider = std::get_if(&declaration.options)) { + tmpJson["slider"] = *slider; } else if (const auto* checkbox = std::get_if(&declaration.options)) { - tmpJson["checkbox"] = checkbox; + tmpJson["checkbox"] = *checkbox; } else if (const auto* dropdown = std::get_if(&declaration.options)) { - tmpJson["dropdown"] = dropdown; + tmpJson["dropdown"] = *dropdown; } else if (const auto* radio = std::get_if(&declaration.options)) { - tmpJson["radio"] = radio; + tmpJson["radio"] = *radio; } else if (const auto* text = std::get_if(&declaration.options)) { - tmpJson["text"] = text; + tmpJson["text"] = *text; } else { throw std::logic_error{"Variant was in an invalid state when serialising InterfaceDeclaration to JSON!"}; } @@ -65,7 +67,7 @@ void from_json(const nlohmann::json& json, InterfaceDeclaration& declaration) { // TODO: Replace keys with constants if (json.contains("slider")) { - declaration.options = json.at("slider").get(); + declaration.options = json.at("slider").get(); } else if (json.contains("checkbox")) { declaration.options = json.at("checkbox").get(); } else if (json.contains("dropdown")) { @@ -87,6 +89,31 @@ InterfaceDeclaration::InterfaceDeclaration(const std::string path, const std::st this->isMutable = isMutable; this->options = options; } +proto::UiOptionDeclaration InterfaceDeclaration::toProto() const { + + proto::UiOptionDeclaration protoDecl; + + protoDecl.set_path(this->path); + protoDecl.set_description(this->description); + protoDecl.set_is_mutable(this->isMutable); + protoDecl.mutable_default_()->CopyFrom(this->defaultValue.toProto()); + + if (const auto* slider = std::get_if(&this->options)) { + protoDecl.mutable_slider()->CopyFrom(slider->toProto()); + } else if (const auto* checkbox = std::get_if(&this->options)) { + protoDecl.mutable_checkbox()->CopyFrom(checkbox->toProto()); + } else if (const auto* dropdown = std::get_if(&this->options)) { + protoDecl.mutable_dropdown()->CopyFrom(dropdown->toProto()); + } else if (const auto* radio = std::get_if(&this->options)) { + protoDecl.mutable_radiobutton()->CopyFrom(radio->toProto()); + } else if (const auto* text = std::get_if(&this->options)) { + protoDecl.mutable_textfield()->CopyFrom(text->toProto()); + } else { + throw std::logic_error{"Variant was in an invalid state when serialising InterfaceDeclaration to JSON!"}; + } + + return protoDecl; +} InterfaceText::InterfaceText(const proto::TextField& protoTextField) { this->text = protoTextField.text(); } @@ -114,14 +141,14 @@ InterfaceCheckbox::InterfaceCheckbox(const proto::Checkbox& protoCheckbox) { thi InterfaceCheckbox::InterfaceCheckbox(const std::string text) { this->text = text; } -rbtt::Interface::InterfaceSlider::InterfaceSlider(const proto::Slider& protoSlider) { +Interface::InterfaceSlider::InterfaceSlider(const proto::Slider& protoSlider) { this->text = protoSlider.text(); this->min = protoSlider.min(); this->max = protoSlider.max(); this->interval = protoSlider.interval(); } -rbtt::Interface::InterfaceSlider::InterfaceSlider(const std::string text, const float min, const float max, const float interval) { +Interface::InterfaceSlider::InterfaceSlider(const std::string text, const float min, const float max, const float interval) { this->text = text; this->min = min; this->max = max; diff --git a/src/interface/InterfaceDeclarations.cpp b/src/interface/InterfaceDeclarations.cpp index 198f379818..539cf7e4c6 100644 --- a/src/interface/InterfaceDeclarations.cpp +++ b/src/interface/InterfaceDeclarations.cpp @@ -5,7 +5,7 @@ #include #include -namespace rbtt::Interface { +namespace rtt::Interface { void InterfaceDeclarations::_unsafeAddDeclaration(const InterfaceDeclaration decl) { this->decls.push_back(decl); } @@ -24,8 +24,8 @@ void InterfaceDeclarations::addDeclaration(const InterfaceDeclaration decl) { this->_unsafeAddDeclaration(decl); - if (auto iptr = this->iface.lock()) { - iptr->registerChange(); + if (auto iptr = this->stateHandler.lock()) { + iptr->stateDidChange(); } } @@ -34,8 +34,8 @@ void InterfaceDeclarations::removeDeclaration(const std::string path) { this->_unsafeRemoveDeclaration(path); - if (auto iptr = this->iface.lock()) { - iptr->registerChange(); + if (auto iptr = this->stateHandler.lock()) { + iptr->stateDidChange(); } } @@ -51,5 +51,24 @@ std::optional InterfaceDeclarations::getDeclaration(const return this->_unsafeGetDeclaration(path); } -void InterfaceDeclarations::handleData(const proto::UiOptionDeclarations&) {} +void InterfaceDeclarations::handleData(const proto::UiOptionDeclarations& recvDecls) { + std::scoped_lock lck(this->mtx); + + this->decls.clear(); + + for (auto singleDecl: recvDecls.options()) { + this->decls.emplace_back(singleDecl); + } +} +proto::UiOptionDeclarations InterfaceDeclarations::toProto() const { + std::scoped_lock lck(this->mtx); + + proto::UiOptionDeclarations protoDecls; + + for (const auto& entry : this->decls) { + protoDecls.mutable_options()->Add(entry.toProto()); + } + + return protoDecls; +} } \ No newline at end of file diff --git a/src/interface/InterfaceSettings.cpp b/src/interface/InterfaceSettings.cpp index ba1f8ccb78..fd13db990e 100644 --- a/src/interface/InterfaceSettings.cpp +++ b/src/interface/InterfaceSettings.cpp @@ -3,8 +3,9 @@ // #include "interface/InterfaceSettings.h" +#include "roboteam_utils/Print.h" -namespace rbtt::Interface { +namespace rtt::Interface { std::optional InterfaceSettings::getSetting(const std::string name) const { std::scoped_lock lck(this->mtx); @@ -19,18 +20,23 @@ void InterfaceSettings::setSetting(const std::string name, const InterfaceValue std::scoped_lock lck(this->mtx); this->_unsafeSetSetting(name, newValue); + + if (auto iptr = this->stateHandler.lock()) { + iptr->stateDidChange(); + } } void InterfaceSettings::_unsafeSetSetting(const std::string name, const InterfaceValue newValue) { this->values.insert_or_assign(name, newValue); } -void InterfaceSettings::handleData(const proto::UiValues& values, InterfaceDeclarations& decls, InterfaceSettingsPrecedence precedence) { +void InterfaceSettings::handleData(const proto::UiValues& values, InterfaceSettingsPrecedence precedence) { std::scoped_lock lck(this->mtx); // TODO: Verify if value is in declarations, and whether it is an allowed value // Also, if precedence lvl == AI, we are AI and should verify that the value we are changing is modifiable by interface + values.PrintDebugString(); if (values.ui_values().empty()) { - RTT_WARNING("[Interface] Values are empty!") + RTT_WARNING("[Interface] Values are empty!"); return; } @@ -40,5 +46,15 @@ void InterfaceSettings::handleData(const proto::UiValues& values, InterfaceDecla this->_unsafeSetSetting(entry.first, entry.second); } } +proto::UiValues InterfaceSettings::toProto() { + std::scoped_lock lck(this->mtx); + proto::UiValues vals; + + for (const auto& [key, value] : this->values) { + vals.mutable_ui_values()->insert({key, value.toProto()}); + } + + return vals; +} } \ No newline at end of file diff --git a/src/interface/InterfaceValue.cpp b/src/interface/InterfaceValue.cpp index 6e457cc019..07ebef9b8c 100644 --- a/src/interface/InterfaceValue.cpp +++ b/src/interface/InterfaceValue.cpp @@ -2,8 +2,9 @@ // Created by Dawid Kulikowski on 08/08/2021. // #include "interface/InterfaceValue.h" +#include "roboteam_utils/Print.h" -namespace rbtt::Interface { +namespace rtt::Interface { InterfaceValue::InterfaceValue(const proto::UiValue& val) { switch (val.value_case()) { @@ -29,6 +30,23 @@ InterfaceValue::InterfaceValue(const proto::UiValue& val) { break; } } +proto::UiValue InterfaceValue::toProto() const { + proto::UiValue value; + + if (auto* intVal = std::get_if(&this->variant)) { + value.set_integer_value(*intVal); + } else if (auto* boolVal = std::get_if(&this->variant)) { + value.set_bool_value(*boolVal); + } else if (auto* floatVal = std::get_if(&this->variant)) { + value.set_float_value(*floatVal); + } else if (auto* stringVal = std::get_if(&this->variant)) { + value.set_text_value(*stringVal); + } else { + throw std::logic_error{"Invalid state of InterfaceValue during serialization!"}; + } + + return value; +} void to_json(nlohmann::json& j, const InterfaceValue& p) { if (auto* intVal = std::get_if(&p.variant)) { diff --git a/src/utilities/IOManager.cpp b/src/utilities/IOManager.cpp index 5de2a31bc5..c5932f1170 100644 --- a/src/utilities/IOManager.cpp +++ b/src/utilities/IOManager.cpp @@ -47,11 +47,13 @@ std::optional IOManager::centralServerReceive(){ int numReceivedMessages = 0; stx::Result last_message = stx::Err(std::string("")); while(received){ - last_message = central_server_connection->read_next(); - if (last_message.is_ok()){ - last_message.value().PrintDebugString(); - numReceivedMessages ++; - }else{ + auto tmp_last_message = central_server_connection->read_next(); + if (tmp_last_message.is_ok()) { + last_message = std::move(tmp_last_message); + last_message.value().PrintDebugString(); + numReceivedMessages ++; + + } else { received = false; //we don't print the errors as they mark there are no more messages } From 6adfc60551f6c203205580449776c6afeac22614 Mon Sep 17 00:00:00 2001 From: Dawid Kulikowski Date: Wed, 18 Aug 2021 09:45:22 +0200 Subject: [PATCH 33/40] Move shared interface components to roboteam_interface and test json declaration parsing --- CMakeLists.txt | 6 +- .../interface/InterfaceController.h | 6 +- .../interface/InterfaceDeclaration.h | 134 --------------- .../interface/InterfaceDeclarations.h | 48 ------ .../roboteam_ai/interface/InterfaceDrawer.h | 12 -- .../roboteam_ai/interface/InterfaceJoystick.h | 12 -- .../roboteam_ai/interface/InterfaceSettings.h | 37 ----- .../interface/InterfaceStateHandler.h | 33 ---- .../roboteam_ai/interface/InterfaceValue.h | 35 ---- src/interface/InterfaceDeclaration.cpp | 157 ------------------ src/interface/InterfaceDeclarations.cpp | 74 --------- src/interface/InterfaceSettings.cpp | 60 ------- src/interface/InterfaceValue.cpp | 78 --------- 13 files changed, 5 insertions(+), 687 deletions(-) delete mode 100644 include/roboteam_ai/interface/InterfaceDeclaration.h delete mode 100644 include/roboteam_ai/interface/InterfaceDeclarations.h delete mode 100644 include/roboteam_ai/interface/InterfaceDrawer.h delete mode 100644 include/roboteam_ai/interface/InterfaceJoystick.h delete mode 100644 include/roboteam_ai/interface/InterfaceSettings.h delete mode 100644 include/roboteam_ai/interface/InterfaceStateHandler.h delete mode 100644 include/roboteam_ai/interface/InterfaceValue.h delete mode 100644 src/interface/InterfaceDeclaration.cpp delete mode 100644 src/interface/InterfaceDeclarations.cpp delete mode 100644 src/interface/InterfaceSettings.cpp delete mode 100644 src/interface/InterfaceValue.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 59c4795ea7..b38da787cb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -242,15 +242,13 @@ set(AI_SOURCES ${COMPUTATION_SOURCES} src/AISettings.cpp src/AppSettings.cpp -# src/interface/InterfaceSettings.cpp - src/interface/InterfaceController.cpp - src/interface/InterfaceValue.cpp src/interface/InterfaceSettings.cpp include/roboteam_ai/interface/InterfaceDeclaration.h src/interface/InterfaceDeclarations.cpp src/interface/InterfaceDeclaration.cpp include/roboteam_ai/interface/InterfaceStateHandler.h) + src/interface/InterfaceController.cpp) set(AI_LIBS PRIVATE roboteam_utils PRIVATE NFParam PRIVATE SDL2 - PRIVATE nlohmann_json::nlohmann_json + PRIVATE roboteam_interface_lib ) set(AI_INCLUDES diff --git a/include/roboteam_ai/interface/InterfaceController.h b/include/roboteam_ai/interface/InterfaceController.h index b982c6dcc0..5ea8bebdc8 100644 --- a/include/roboteam_ai/interface/InterfaceController.h +++ b/include/roboteam_ai/interface/InterfaceController.h @@ -5,9 +5,9 @@ #ifndef RTT_INTERFACECONTROLLER_H #define RTT_INTERFACECONTROLLER_H -#include "interface/InterfaceSettings.h" -#include "interface/InterfaceStateHandler.h" -#include "interface/InterfaceDeclarations.h" +#include "roboteam_interface/InterfaceSettings.h" +#include "roboteam_interface/InterfaceStateHandler.h" +#include "roboteam_interface/InterfaceDeclarations.h" #include #include diff --git a/include/roboteam_ai/interface/InterfaceDeclaration.h b/include/roboteam_ai/interface/InterfaceDeclaration.h deleted file mode 100644 index dfde955377..0000000000 --- a/include/roboteam_ai/interface/InterfaceDeclaration.h +++ /dev/null @@ -1,134 +0,0 @@ -// -// Created by Dawid Kulikowski on 10/08/2021. -// - -#ifndef RTT_INTERFACEDECLARATION_H -#define RTT_INTERFACEDECLARATION_H -#include -#include "InterfaceValue.h" -#include -#include - -namespace rtt::Interface { -struct InterfaceSlider { - std::string text; - float min; - float max; - float interval; - - InterfaceSlider() = default; - InterfaceSlider(const proto::Slider&); - InterfaceSlider(const std::string, const float, const float, const float); - - proto::Slider toProto() const { - proto::Slider slider; - - slider.set_text(this->text); - slider.set_min(this->min); - slider.set_max(this->max); - slider.set_interval(this->interval); - - return slider; - } - - NLOHMANN_DEFINE_TYPE_INTRUSIVE(InterfaceSlider, text, min, max, interval); -}; - -struct InterfaceCheckbox { - std::string text; - - InterfaceCheckbox() = default; - InterfaceCheckbox(const proto::Checkbox&); - InterfaceCheckbox(const std::string); - - proto::Checkbox toProto() const { - proto::Checkbox checkbox; - - checkbox.set_text(this->text); - - return checkbox; - } - - NLOHMANN_DEFINE_TYPE_INTRUSIVE(InterfaceCheckbox, text); -}; - -struct InterfaceDropdown { - std::string text; - std::vector options; - - InterfaceDropdown() = default; - InterfaceDropdown(const proto::Dropdown&); - InterfaceDropdown(const std::string, const std::vector); - - proto::Dropdown toProto() const { - proto::Dropdown dropdown; - - dropdown.set_text(this->text); - dropdown.mutable_options()->Add(options.begin(), options.end()); - - return dropdown; - } - - NLOHMANN_DEFINE_TYPE_INTRUSIVE(InterfaceDropdown, text, options); - -}; - -struct InterfaceRadio { - std::vector options; - - InterfaceRadio() = default; - InterfaceRadio(const proto::RadioButton&); - InterfaceRadio(const std::vector); - - proto::RadioButton toProto() const { - proto::RadioButton radio; - - radio.mutable_options()->Add(options.begin(), options.end()); - return radio; - } - - NLOHMANN_DEFINE_TYPE_INTRUSIVE(InterfaceRadio, options); -}; - -struct InterfaceText { - std::string text; - - InterfaceText() = default; - InterfaceText(const proto::TextField&); - InterfaceText(const std::string); - - proto::TextField toProto() const { - proto:: TextField txtField; - - txtField.set_text(text); - - return txtField; - } - - NLOHMANN_DEFINE_TYPE_INTRUSIVE(InterfaceText, text); -}; - -typedef std::variant InterfaceOptions; - -struct InterfaceDeclaration { - public: - std::string path; - std::string description; - - bool isMutable; - - InterfaceValue defaultValue; - - InterfaceOptions options; - - proto::UiOptionDeclaration toProto() const; - - - InterfaceDeclaration() = default; - InterfaceDeclaration(const proto::UiOptionDeclaration&); - InterfaceDeclaration(const std::string, const std::string, const bool, const InterfaceValue, const InterfaceOptions); -}; - -} // namespace rbtt::Interface - -#endif // RTT_INTERFACEDECLARATION_H diff --git a/include/roboteam_ai/interface/InterfaceDeclarations.h b/include/roboteam_ai/interface/InterfaceDeclarations.h deleted file mode 100644 index 05443f1002..0000000000 --- a/include/roboteam_ai/interface/InterfaceDeclarations.h +++ /dev/null @@ -1,48 +0,0 @@ -// -// Created by Dawid Kulikowski on 09/08/2021. -// - -#ifndef RTT_INTERFACEDECLARATIONS_H -#define RTT_INTERFACEDECLARATIONS_H - -#include - -#include - -#include "InterfaceDeclaration.h" -#include "InterfaceStateHandler.h" - -namespace rtt::Interface { -class InterfaceDeclarations { - private: - std::vector decls = {}; - - mutable std::mutex mtx; - - std::weak_ptr stateHandler; - - void _unsafeAddDeclaration(InterfaceDeclaration); - void _unsafeRemoveDeclaration(std::string); - - std::optional _unsafeGetDeclaration(std::string) const; - - public: - InterfaceDeclarations() = default; - InterfaceDeclarations(std::weak_ptr sts): stateHandler(sts) {} - - InterfaceDeclarations(const proto::UiOptionDeclarations& pdecls, std::weak_ptr sts): stateHandler(sts) {this->handleData(pdecls);} - explicit InterfaceDeclarations(const std::vector vec, std::weak_ptr sts) : decls(vec), stateHandler(sts) {}; - - void addDeclaration(InterfaceDeclaration); - void removeDeclaration(std::string); - - std::vector getDeclarations() const; - std::optional getDeclaration(std::string) const; - - void handleData(const proto::UiOptionDeclarations&); - - proto::UiOptionDeclarations toProto() const; -}; - -} -#endif // RTT_INTERFACEDECLARATIONS_H diff --git a/include/roboteam_ai/interface/InterfaceDrawer.h b/include/roboteam_ai/interface/InterfaceDrawer.h deleted file mode 100644 index c7531ceefc..0000000000 --- a/include/roboteam_ai/interface/InterfaceDrawer.h +++ /dev/null @@ -1,12 +0,0 @@ -// -// Created by Dawid Kulikowski on 09/08/2021. -// - -#ifndef RTT_INTERFACEDRAWER_H -#define RTT_INTERFACEDRAWER_H - -namespace rtt::Interface { -class InterfaceDrawer {}; -} // namespace rbtt::Interface - -#endif // RTT_INTERFACEDRAWER_H diff --git a/include/roboteam_ai/interface/InterfaceJoystick.h b/include/roboteam_ai/interface/InterfaceJoystick.h deleted file mode 100644 index f885e33f5b..0000000000 --- a/include/roboteam_ai/interface/InterfaceJoystick.h +++ /dev/null @@ -1,12 +0,0 @@ -// -// Created by Dawid Kulikowski on 09/08/2021. -// - -#ifndef RTT_INTERFACEJOYSTICK_H -#define RTT_INTERFACEJOYSTICK_H - -namespace rtt::Interface { -class InterfaceJoystick {}; -} // namespace rbtt::Interface - -#endif // RTT_INTERFACEJOYSTICK_H diff --git a/include/roboteam_ai/interface/InterfaceSettings.h b/include/roboteam_ai/interface/InterfaceSettings.h deleted file mode 100644 index 7d4279b757..0000000000 --- a/include/roboteam_ai/interface/InterfaceSettings.h +++ /dev/null @@ -1,37 +0,0 @@ -// -// Created by Dawid Kulikowski on 09/08/2021. -// - -#ifndef RTT_INTERFACESETTINGS_H -#define RTT_INTERFACESETTINGS_H -#include "roboteam_proto/UiOptions.pb.h" -#include "InterfaceDeclarations.h" -#include "InterfaceValue.h" -#include "InterfaceStateHandler.h" - -namespace rtt::Interface { -enum class InterfaceSettingsPrecedence { AI, IFACE }; - -class InterfaceSettings { - private: - std::map values = {}; - - mutable std::mutex mtx; - - std::weak_ptr stateHandler; - - void _unsafeSetSetting(const std::string name, const InterfaceValue newValue); - - public: - InterfaceSettings(std::weak_ptr sts): stateHandler(sts) {}; - - std::optional getSetting(const std::string name) const; - void setSetting(const std::string name, const InterfaceValue newValue); - - void handleData(const proto::UiValues&, InterfaceSettingsPrecedence = InterfaceSettingsPrecedence::AI); - - proto::UiValues toProto(); -}; -} // namespace rbtt::Interface - -#endif // RTT_INTERFACESETTINGS_H diff --git a/include/roboteam_ai/interface/InterfaceStateHandler.h b/include/roboteam_ai/interface/InterfaceStateHandler.h deleted file mode 100644 index 955de17018..0000000000 --- a/include/roboteam_ai/interface/InterfaceStateHandler.h +++ /dev/null @@ -1,33 +0,0 @@ -// -// Created by Dawid Kulikowski on 16/08/2021. -// - -#ifndef RTT_INTERFACESTATEHANDLER_H -#define RTT_INTERFACESTATEHANDLER_H - -namespace rtt::Interface { - -class InterfaceStateHandler { - // TODO: This is a pretty slow mechanism, maybe use atomic? - private: - bool didChange = false; - mutable std::mutex mtx; - - public: - void stateDidChange() { - std::scoped_lock lck(mtx); - didChange = true; - } - - void clear() { - std::scoped_lock lck(mtx); - didChange = false; - } - bool getState() const { - std::scoped_lock lck(mtx); - return didChange; - } -}; -} // namespace rtt::Interface - -#endif // RTT_INTERFACESTATEHANDLER_H diff --git a/include/roboteam_ai/interface/InterfaceValue.h b/include/roboteam_ai/interface/InterfaceValue.h deleted file mode 100644 index 6d9419234e..0000000000 --- a/include/roboteam_ai/interface/InterfaceValue.h +++ /dev/null @@ -1,35 +0,0 @@ -// -// Created by Dawid Kulikowski on 08/08/2021. -// - -#ifndef RTT_INTERFACEVALUE_H -#define RTT_INTERFACEVALUE_H - -#include -#include -#include -#include -#include -#include - -namespace rtt::Interface { -struct InterfaceValue { - public: - InterfaceValue() = default; - InterfaceValue(const proto::UiValue&); - - InterfaceValue(const int64_t v) : variant{v} {}; - InterfaceValue(const bool v) : variant{v} {}; - InterfaceValue(const float v) : variant{v} {}; - InterfaceValue(const std::string v) : variant{v} {}; - - std::variant variant; - - proto::UiValue toProto() const; -}; -void from_json(const nlohmann::json& j, InterfaceValue& p); -void to_json(nlohmann::json& j, const InterfaceValue& p); - -} // namespace rbtt::Interface - -#endif // RTT_INTERFACEVALUE_H diff --git a/src/interface/InterfaceDeclaration.cpp b/src/interface/InterfaceDeclaration.cpp deleted file mode 100644 index 05c8558db2..0000000000 --- a/src/interface/InterfaceDeclaration.cpp +++ /dev/null @@ -1,157 +0,0 @@ -// -// Created by Dawid Kulikowski on 10/08/2021. -// - -#include "interface/InterfaceDeclaration.h" -#include "interface/InterfaceValue.h" -#include -#include -#include - -namespace rtt::Interface { - -InterfaceDeclaration::InterfaceDeclaration(const proto::UiOptionDeclaration& decl) : defaultValue(InterfaceValue(decl.default_())) { - this->path = decl.path(); - this->description = decl.description(); - this->isMutable = decl.is_mutable(); - - switch (decl.ui_elements_case()) { - case proto::UiOptionDeclaration::UiElementsCase::kCheckbox: - this->options = decl.checkbox(); - break; - case proto::UiOptionDeclaration::UiElementsCase::kDropdown: - this->options = decl.dropdown(); - break; - case proto::UiOptionDeclaration::UiElementsCase::kRadiobutton: - this->options = decl.radiobutton(); - break; - case proto::UiOptionDeclaration::UiElementsCase::kSlider: - this->options = decl.slider(); - break; - case proto::UiOptionDeclaration::UiElementsCase::kTextfield: - this->options = decl.textfield(); - break; - case proto::UiOptionDeclaration::UiElementsCase::UI_ELEMENTS_NOT_SET: - default: - throw std::logic_error{"Unknown variant type when initialising InterfaceDeclaration!"}; - } -} - -void to_json(nlohmann::json& j, const InterfaceDeclaration& declaration) { - nlohmann::json tmpJson = - nlohmann::json{{"path", declaration.path}, {"description", declaration.description}, {"isMutable", declaration.isMutable}, {"defaultValue", declaration.defaultValue}}; - - if (const auto* slider = std::get_if(&declaration.options)) { - tmpJson["slider"] = *slider; - } else if (const auto* checkbox = std::get_if(&declaration.options)) { - tmpJson["checkbox"] = *checkbox; - } else if (const auto* dropdown = std::get_if(&declaration.options)) { - tmpJson["dropdown"] = *dropdown; - } else if (const auto* radio = std::get_if(&declaration.options)) { - tmpJson["radio"] = *radio; - } else if (const auto* text = std::get_if(&declaration.options)) { - tmpJson["text"] = *text; - } else { - throw std::logic_error{"Variant was in an invalid state when serialising InterfaceDeclaration to JSON!"}; - } - - j = tmpJson; -} - -void from_json(const nlohmann::json& json, InterfaceDeclaration& declaration) { - json.at("path").get_to(declaration.path); - json.at("description").get_to(declaration.description); - - json.at("isMutable").get_to(declaration.isMutable); - json.at("defaultValue").get_to(declaration.defaultValue); - - // TODO: Replace keys with constants - if (json.contains("slider")) { - declaration.options = json.at("slider").get(); - } else if (json.contains("checkbox")) { - declaration.options = json.at("checkbox").get(); - } else if (json.contains("dropdown")) { - declaration.options = json.at("dropdown").get(); - } else if (json.contains("radio")) { - declaration.options = json.at("radio").get(); - } else if (json.contains("text")) { - declaration.options = json.at("text").get(); - } else { - throw std::domain_error{"Unknown type encountered when deserializing InterfaceDeclaration from JSON!"}; - } -} - -InterfaceDeclaration::InterfaceDeclaration(const std::string path, const std::string description, const bool isMutable, const InterfaceValue defaultValue, - const InterfaceOptions options) - : defaultValue(defaultValue) { - this->path = path; - this->description = description; - this->isMutable = isMutable; - this->options = options; -} -proto::UiOptionDeclaration InterfaceDeclaration::toProto() const { - - proto::UiOptionDeclaration protoDecl; - - protoDecl.set_path(this->path); - protoDecl.set_description(this->description); - protoDecl.set_is_mutable(this->isMutable); - protoDecl.mutable_default_()->CopyFrom(this->defaultValue.toProto()); - - if (const auto* slider = std::get_if(&this->options)) { - protoDecl.mutable_slider()->CopyFrom(slider->toProto()); - } else if (const auto* checkbox = std::get_if(&this->options)) { - protoDecl.mutable_checkbox()->CopyFrom(checkbox->toProto()); - } else if (const auto* dropdown = std::get_if(&this->options)) { - protoDecl.mutable_dropdown()->CopyFrom(dropdown->toProto()); - } else if (const auto* radio = std::get_if(&this->options)) { - protoDecl.mutable_radiobutton()->CopyFrom(radio->toProto()); - } else if (const auto* text = std::get_if(&this->options)) { - protoDecl.mutable_textfield()->CopyFrom(text->toProto()); - } else { - throw std::logic_error{"Variant was in an invalid state when serialising InterfaceDeclaration to JSON!"}; - } - - return protoDecl; -} - -InterfaceText::InterfaceText(const proto::TextField& protoTextField) { this->text = protoTextField.text(); } - -InterfaceText::InterfaceText(const std::string text) { this->text = text; } - -InterfaceRadio::InterfaceRadio(const proto::RadioButton& protoRadio) { - // protobuf owns this message, we should copy it - std::copy(protoRadio.options().begin(), protoRadio.options().end(), std::back_inserter(this->options)); -} - -InterfaceRadio::InterfaceRadio(const std::vector options) { this->options = options; } - -InterfaceDropdown::InterfaceDropdown(const proto::Dropdown& protoDropdown) { - this->text = protoDropdown.text(); - - std::copy(protoDropdown.options().begin(), protoDropdown.options().end(), std::back_inserter(this->options)); -} - -InterfaceDropdown::InterfaceDropdown(const std::string text, const std::vector options) { - this->text = text; - this->options = options; -} - -InterfaceCheckbox::InterfaceCheckbox(const proto::Checkbox& protoCheckbox) { this->text = protoCheckbox.text(); } - -InterfaceCheckbox::InterfaceCheckbox(const std::string text) { this->text = text; } - -Interface::InterfaceSlider::InterfaceSlider(const proto::Slider& protoSlider) { - this->text = protoSlider.text(); - this->min = protoSlider.min(); - this->max = protoSlider.max(); - this->interval = protoSlider.interval(); -} - -Interface::InterfaceSlider::InterfaceSlider(const std::string text, const float min, const float max, const float interval) { - this->text = text; - this->min = min; - this->max = max; - this->interval = interval; -} -} diff --git a/src/interface/InterfaceDeclarations.cpp b/src/interface/InterfaceDeclarations.cpp deleted file mode 100644 index 539cf7e4c6..0000000000 --- a/src/interface/InterfaceDeclarations.cpp +++ /dev/null @@ -1,74 +0,0 @@ -// -// Created by Dawid Kulikowski on 10/08/2021. -// -#include "interface/InterfaceDeclarations.h" -#include -#include - -namespace rtt::Interface { - -void InterfaceDeclarations::_unsafeAddDeclaration(const InterfaceDeclaration decl) { this->decls.push_back(decl); } - -void InterfaceDeclarations::_unsafeRemoveDeclaration(const std::string path) { - this->decls.erase(std::remove_if(this->decls.begin(), this->decls.end(), [&](const auto& item) { return (item.path == path); }), this->decls.end()); -} - -std::optional InterfaceDeclarations::_unsafeGetDeclaration(const std::string path) const { - auto found = std::find_if(this->decls.begin(), this->decls.end(), [&](const auto& item) { return item.path == path; }); - - return found != this->decls.end() ? std::make_optional(*found) : std::nullopt; -} - -void InterfaceDeclarations::addDeclaration(const InterfaceDeclaration decl) { - std::scoped_lock lck(this->mtx); - - this->_unsafeAddDeclaration(decl); - - if (auto iptr = this->stateHandler.lock()) { - iptr->stateDidChange(); - } -} - -void InterfaceDeclarations::removeDeclaration(const std::string path) { - std::scoped_lock lck(this->mtx); - - this->_unsafeRemoveDeclaration(path); - - if (auto iptr = this->stateHandler.lock()) { - iptr->stateDidChange(); - } -} - -std::vector InterfaceDeclarations::getDeclarations() const { - std::scoped_lock lck(this->mtx); - - return this->decls; -} - -std::optional InterfaceDeclarations::getDeclaration(const std::string path) const { - std::scoped_lock lck(this->mtx); - - return this->_unsafeGetDeclaration(path); -} - -void InterfaceDeclarations::handleData(const proto::UiOptionDeclarations& recvDecls) { - std::scoped_lock lck(this->mtx); - - this->decls.clear(); - - for (auto singleDecl: recvDecls.options()) { - this->decls.emplace_back(singleDecl); - } -} -proto::UiOptionDeclarations InterfaceDeclarations::toProto() const { - std::scoped_lock lck(this->mtx); - - proto::UiOptionDeclarations protoDecls; - - for (const auto& entry : this->decls) { - protoDecls.mutable_options()->Add(entry.toProto()); - } - - return protoDecls; -} -} \ No newline at end of file diff --git a/src/interface/InterfaceSettings.cpp b/src/interface/InterfaceSettings.cpp deleted file mode 100644 index fd13db990e..0000000000 --- a/src/interface/InterfaceSettings.cpp +++ /dev/null @@ -1,60 +0,0 @@ -// -// Created by Dawid Kulikowski on 10/08/2021. -// - -#include "interface/InterfaceSettings.h" -#include "roboteam_utils/Print.h" - -namespace rtt::Interface { - -std::optional InterfaceSettings::getSetting(const std::string name) const { - std::scoped_lock lck(this->mtx); - - if (!this->values.contains(name)) { - return std::nullopt; - } - - return this->values.at(name); -} -void InterfaceSettings::setSetting(const std::string name, const InterfaceValue newValue) { - std::scoped_lock lck(this->mtx); - - this->_unsafeSetSetting(name, newValue); - - if (auto iptr = this->stateHandler.lock()) { - iptr->stateDidChange(); - } -} - -void InterfaceSettings::_unsafeSetSetting(const std::string name, const InterfaceValue newValue) { this->values.insert_or_assign(name, newValue); } - -void InterfaceSettings::handleData(const proto::UiValues& values, InterfaceSettingsPrecedence precedence) { - std::scoped_lock lck(this->mtx); - - // TODO: Verify if value is in declarations, and whether it is an allowed value - // Also, if precedence lvl == AI, we are AI and should verify that the value we are changing is modifiable by interface - - values.PrintDebugString(); - if (values.ui_values().empty()) { - RTT_WARNING("[Interface] Values are empty!"); - return; - } - - this->values.clear(); - - for (const auto& entry : values.ui_values()) { - this->_unsafeSetSetting(entry.first, entry.second); - } -} -proto::UiValues InterfaceSettings::toProto() { - std::scoped_lock lck(this->mtx); - proto::UiValues vals; - - for (const auto& [key, value] : this->values) { - vals.mutable_ui_values()->insert({key, value.toProto()}); - } - - return vals; -} - -} \ No newline at end of file diff --git a/src/interface/InterfaceValue.cpp b/src/interface/InterfaceValue.cpp deleted file mode 100644 index 07ebef9b8c..0000000000 --- a/src/interface/InterfaceValue.cpp +++ /dev/null @@ -1,78 +0,0 @@ -// -// Created by Dawid Kulikowski on 08/08/2021. -// -#include "interface/InterfaceValue.h" -#include "roboteam_utils/Print.h" - -namespace rtt::Interface { - -InterfaceValue::InterfaceValue(const proto::UiValue& val) { - switch (val.value_case()) { - case proto::UiValue::ValueCase::kBoolValue: - this->variant = val.bool_value(); - break; - case proto::UiValue::ValueCase::kFloatValue: - this->variant = val.float_value(); - break; - case proto::UiValue::ValueCase::kIntegerValue: - this->variant = val.integer_value(); - break; - case proto::UiValue::ValueCase::kTextValue: - this->variant = val.text_value(); - break; - case proto::UiValue::ValueCase::VALUE_NOT_SET: - RTT_ERROR("[Interface] Interface value not set (corrupted proto message)"); - std::terminate(); - break; - default: - RTT_ERROR("[Interface] Interface value unknown (corrupted proto message)"); - std::terminate(); - break; - } -} -proto::UiValue InterfaceValue::toProto() const { - proto::UiValue value; - - if (auto* intVal = std::get_if(&this->variant)) { - value.set_integer_value(*intVal); - } else if (auto* boolVal = std::get_if(&this->variant)) { - value.set_bool_value(*boolVal); - } else if (auto* floatVal = std::get_if(&this->variant)) { - value.set_float_value(*floatVal); - } else if (auto* stringVal = std::get_if(&this->variant)) { - value.set_text_value(*stringVal); - } else { - throw std::logic_error{"Invalid state of InterfaceValue during serialization!"}; - } - - return value; -} - -void to_json(nlohmann::json& j, const InterfaceValue& p) { - if (auto* intVal = std::get_if(&p.variant)) { - j = nlohmann::json{"int", *intVal}; - } else if (auto* boolVal = std::get_if(&p.variant)) { - j = nlohmann::json{"bool", *boolVal}; - } else if (auto* floatVal = std::get_if(&p.variant)) { - j = nlohmann::json{"float", *floatVal}; - } else if (auto* stringVal = std::get_if(&p.variant)) { - j = nlohmann::json{"string", *stringVal}; - } else { - throw std::logic_error{"Invalid state of InterfaceValue during serialization!"}; - } -} - -void from_json(const nlohmann::json& j, InterfaceValue& p) { - if (j.contains("int")) { - p.variant = j.at("int").get(); - } else if (j.contains("bool")) { - p.variant = j.at("bool").get(); - } else if (j.contains("float")) { - p.variant = j.at("float").get(); - } else if (j.contains("string")) { - p.variant = j.at("string").get(); - } else { - throw std::domain_error{"JSON representation of InterfaceValue contains unknown type of value!"}; - } -} -} \ No newline at end of file From aebe172cdbda37ce8fda92ef0eec6989feeac3aa Mon Sep 17 00:00:00 2001 From: Dawid Kulikowski Date: Thu, 19 Aug 2021 10:02:58 +0200 Subject: [PATCH 34/40] Load interface declarations from JSON file --- include/roboteam_ai/ApplicationManager.h | 2 +- .../interface/InterfaceController.h | 17 +++++---- include/roboteam_ai/utilities/IOManager.h | 3 +- src/ApplicationManager.cpp | 15 ++++---- src/interface/InterfaceController.cpp | 14 ++++++-- src/utilities/IOManager.cpp | 36 +++++++++++++------ 6 files changed, 59 insertions(+), 28 deletions(-) diff --git a/include/roboteam_ai/ApplicationManager.h b/include/roboteam_ai/ApplicationManager.h index f346a16984..fb09a381b0 100644 --- a/include/roboteam_ai/ApplicationManager.h +++ b/include/roboteam_ai/ApplicationManager.h @@ -24,7 +24,7 @@ class ApplicationManager { bool robotsInitialized = false; AppSettings settings; - Interface::InterfaceController iface; + InterfaceController iface = {"interface_declarations.json"}; std::unique_ptr ai; std::unique_ptr io; diff --git a/include/roboteam_ai/interface/InterfaceController.h b/include/roboteam_ai/interface/InterfaceController.h index 5ea8bebdc8..0103535ee3 100644 --- a/include/roboteam_ai/interface/InterfaceController.h +++ b/include/roboteam_ai/interface/InterfaceController.h @@ -12,26 +12,29 @@ #include #include #include +#include +#include -namespace rtt::Interface { +namespace rtt { class InterfaceController { private: - std::shared_ptr settings; - std::shared_ptr declarations; + std::shared_ptr settings; + std::shared_ptr declarations; // - std::shared_ptr stateHandler; +std::shared_ptr stateHandler; public: - InterfaceController(): declarations(std::make_shared(stateHandler)), settings(std::make_shared(stateHandler)) {} + InterfaceController(const std::string); + InterfaceController(): declarations(std::make_shared(stateHandler)), settings(std::make_shared(stateHandler)) {} void handleUpdate(proto::UiValues); std::optional getChanges(); - std::weak_ptr getSettings() {return settings;} - std::weak_ptr getDeclarations() {return declarations;} + std::weak_ptr getSettings() {return settings;} + std::weak_ptr getDeclarations() {return declarations;} }; } diff --git a/include/roboteam_ai/utilities/IOManager.h b/include/roboteam_ai/utilities/IOManager.h index d20fbc22f1..0f9f8bcdcc 100644 --- a/include/roboteam_ai/utilities/IOManager.h +++ b/include/roboteam_ai/utilities/IOManager.h @@ -42,7 +42,8 @@ class IOManager { explicit IOManager() = default; void publishAICommand(const proto::AICommand& ai_command); void publishSettings(proto::Setting setting); - std::optional centralServerReceive(); + std::vector centralServerReceiveDeltas(); + std::optional centralServerReceiveLastMessage(); void centralServerSend(std::vector handshakes); void init(int teamId); proto::State getState(); diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index 1369956769..83473527a7 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -44,21 +44,24 @@ void ApplicationManager::start(int id) { /// Run everything with regard to behaviour trees void ApplicationManager::runOneLoopCycle() { + auto state = io->getState(); ai->updateState(state); - auto received_values = io->centralServerReceive(); - if(received_values.has_value()){ + auto received_values = io->centralServerReceiveLastMessage(); + if(received_values.has_value()) { settings.updateValuesFromInterface(received_values.value()); iface.handleUpdate(received_values.value()); -// ai->updateSettings(received_values.value()); } -// std::vector handshakes = {settings.getButtonDeclarations()}; //TODO: only send declarations when central server is reconnected -std::vector handshakes = {}; + + //TODO: only send declarations when central server is reconnected + + std::vector handshakes = {}; if (const auto& decls = iface.getDeclarations().lock()) { proto::Handshake handshake; handshake.mutable_declarations()->CopyFrom(decls->toProto()); + handshakes.emplace_back(handshake); } else { RTT_ERROR("Can't get access to interface declarations!"); @@ -70,7 +73,5 @@ std::vector handshakes = {}; io->publishAICommand(command); - - } } // namespace rtt diff --git a/src/interface/InterfaceController.cpp b/src/interface/InterfaceController.cpp index 5e0856ee18..c8e59489b5 100644 --- a/src/interface/InterfaceController.cpp +++ b/src/interface/InterfaceController.cpp @@ -6,7 +6,7 @@ #include "roboteam_utils/Print.h" -namespace rtt::Interface { +namespace rtt { std::optional InterfaceController::getChanges() { if (!this->stateHandler->getState()) { @@ -29,6 +29,16 @@ std::optional InterfaceController::getChanges() { void InterfaceController::handleUpdate(proto::UiValues val) { this->settings->handleData(val); -// this->declarations->handleData(state.handshakes(0).declarations()); } + +InterfaceController::InterfaceController(const std::string pathToDecls) { + + std::ifstream jsonFile(pathToDecls); + nlohmann::json decls; + jsonFile >> decls; + + declarations = std::make_shared(decls, stateHandler); + settings = std::make_shared(stateHandler); +} + } \ No newline at end of file diff --git a/src/utilities/IOManager.cpp b/src/utilities/IOManager.cpp index c5932f1170..419bcb5aaf 100644 --- a/src/utilities/IOManager.cpp +++ b/src/utilities/IOManager.cpp @@ -41,31 +41,47 @@ void IOManager::handleState(proto::State &stateMsg) { void IOManager::publishSettings(proto::Setting setting) { settingsPublisher->send(setting); } -std::optional IOManager::centralServerReceive(){ - //first receive any setting changes +std::optional IOManager::centralServerReceiveLastMessage(){ bool received = true; - int numReceivedMessages = 0; stx::Result last_message = stx::Err(std::string("")); + while(received){ auto tmp_last_message = central_server_connection->read_next(); + if (tmp_last_message.is_ok()) { last_message = std::move(tmp_last_message); - last_message.value().PrintDebugString(); - numReceivedMessages ++; - } else { received = false; //we don't print the errors as they mark there are no more messages } } - if(numReceivedMessages>0){ - std::cout<<"received " << numReceivedMessages <<" packets from central server"< IOManager::centralServerReceiveDeltas() { + bool received = true; + std::vector messages = {}; + + while(received){ + auto tmp_message = central_server_connection->read_next(); + + if (tmp_message.is_ok()) { + messages.emplace_back(std::move(tmp_message.value())); + } else { + received = false; + //we don't print the errors as they mark there are no more messages + } + } + + return messages; +} + + proto::State IOManager::getState(){ std::lock_guard lock(stateMutex);//read lock proto::State copy = state; From 3c8c9198d093f2ec7b7baa24589689e45c038477 Mon Sep 17 00:00:00 2001 From: Dawid Kulikowski Date: Mon, 30 Aug 2021 10:40:26 +0200 Subject: [PATCH 35/40] Add test interface declarations --- interface_declarations.json | 24 ++++++++++++++++++++++++ 1 file changed, 24 insertions(+) create mode 100644 interface_declarations.json diff --git a/interface_declarations.json b/interface_declarations.json new file mode 100644 index 0000000000..ad397441a5 --- /dev/null +++ b/interface_declarations.json @@ -0,0 +1,24 @@ +[ + { + "path": "/hello/hello", + "description": "Some random button", + "isMutable": true, + "defaultValue": { + "string": "I work!" + }, + "text": { + "text": "Some Text" + } + }, + { + "path": "/hello/world", + "description": "Some random button", + "isMutable": true, + "defaultValue": { + "string": "I work!" + }, + "text": { + "text": "Some Text" + } + } +] \ No newline at end of file From 626924b4d09c6e7770c6e54cc775cfe907fbe545 Mon Sep 17 00:00:00 2001 From: Dawid Date: Mon, 13 Sep 2021 12:10:00 +0200 Subject: [PATCH 36/40] Modify controller to only register changes in declarations since we are the single source of truth anyways/don't need to react. --- include/roboteam_ai/interface/InterfaceController.h | 7 ++++--- src/interface/InterfaceController.cpp | 6 +++--- 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/include/roboteam_ai/interface/InterfaceController.h b/include/roboteam_ai/interface/InterfaceController.h index 0103535ee3..138c4ab734 100644 --- a/include/roboteam_ai/interface/InterfaceController.h +++ b/include/roboteam_ai/interface/InterfaceController.h @@ -21,12 +21,13 @@ class InterfaceController { private: std::shared_ptr settings; std::shared_ptr declarations; -// -std::shared_ptr stateHandler; + + std::shared_ptr declarationChanges; public: InterfaceController(const std::string); - InterfaceController(): declarations(std::make_shared(stateHandler)), settings(std::make_shared(stateHandler)) {} + // We don't need status updates from values, only declarations + InterfaceController(): declarations(std::make_shared(declarationChanges)), settings(std::make_shared(std::weak_ptr())) {} void handleUpdate(proto::UiValues); diff --git a/src/interface/InterfaceController.cpp b/src/interface/InterfaceController.cpp index c8e59489b5..e4113169b6 100644 --- a/src/interface/InterfaceController.cpp +++ b/src/interface/InterfaceController.cpp @@ -9,7 +9,7 @@ namespace rtt { std::optional InterfaceController::getChanges() { - if (!this->stateHandler->getState()) { + if (!this->declarationChanges->getState()) { return std::nullopt; } @@ -37,8 +37,8 @@ InterfaceController::InterfaceController(const std::string pathToDecls) { nlohmann::json decls; jsonFile >> decls; - declarations = std::make_shared(decls, stateHandler); - settings = std::make_shared(stateHandler); + declarations = std::make_shared(decls, declarationChanges); + settings = std::make_shared(declarationChanges); } } \ No newline at end of file From 9502dec5d4252a7005c79c1567a244a9671c0184 Mon Sep 17 00:00:00 2001 From: Dawid Date: Mon, 13 Sep 2021 12:24:57 +0200 Subject: [PATCH 37/40] Only send settings when declarations changed --- include/roboteam_ai/interface/InterfaceController.h | 1 + src/ApplicationManager.cpp | 11 ++++++++--- 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/include/roboteam_ai/interface/InterfaceController.h b/include/roboteam_ai/interface/InterfaceController.h index 138c4ab734..c6f4071da5 100644 --- a/include/roboteam_ai/interface/InterfaceController.h +++ b/include/roboteam_ai/interface/InterfaceController.h @@ -36,6 +36,7 @@ class InterfaceController { std::weak_ptr getSettings() {return settings;} std::weak_ptr getDeclarations() {return declarations;} + std::weak_ptr getDeclarationChangeHandler() {return this->declarationChanges;} }; } diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index 83473527a7..74bff0f002 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -54,15 +54,20 @@ void ApplicationManager::runOneLoopCycle() { iface.handleUpdate(received_values.value()); } - //TODO: only send declarations when central server is reconnected - std::vector handshakes = {}; - if (const auto& decls = iface.getDeclarations().lock()) { + + + // TODO: Refactor so the below vars are scoped inside of the if statement + const auto& decls = iface.getDeclarations().lock(); + const auto& changes = iface.getDeclarationChangeHandler().lock(); + if (decls && changes && changes->getState()) { proto::Handshake handshake; handshake.mutable_declarations()->CopyFrom(decls->toProto()); handshakes.emplace_back(handshake); + + changes->clear(); } else { RTT_ERROR("Can't get access to interface declarations!"); } From f8afb9d98dfb6cd0836ce920c6e6a207960703b8 Mon Sep 17 00:00:00 2001 From: Dawid Date: Tue, 14 Sep 2021 19:25:36 +0200 Subject: [PATCH 38/40] * Remove incorrect error message that was kept after refactoring an if statement * Make sure declarations have state change status while values do not --- src/ApplicationManager.cpp | 3 +-- src/interface/InterfaceController.cpp | 3 ++- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/ApplicationManager.cpp b/src/ApplicationManager.cpp index 74bff0f002..fe668043ab 100644 --- a/src/ApplicationManager.cpp +++ b/src/ApplicationManager.cpp @@ -68,10 +68,9 @@ void ApplicationManager::runOneLoopCycle() { handshakes.emplace_back(handshake); changes->clear(); - } else { - RTT_ERROR("Can't get access to interface declarations!"); } + // The field gets added by IOManager io->centralServerSend(handshakes); proto::AICommand command = ai->decidePlay(); diff --git a/src/interface/InterfaceController.cpp b/src/interface/InterfaceController.cpp index e4113169b6..6730afd0f1 100644 --- a/src/interface/InterfaceController.cpp +++ b/src/interface/InterfaceController.cpp @@ -37,8 +37,9 @@ InterfaceController::InterfaceController(const std::string pathToDecls) { nlohmann::json decls; jsonFile >> decls; + declarationChanges = std::make_shared(); declarations = std::make_shared(decls, declarationChanges); - settings = std::make_shared(declarationChanges); + settings = std::make_shared(std::weak_ptr()); } } \ No newline at end of file From ab32e34ace791607690fd034be111a583f509684 Mon Sep 17 00:00:00 2001 From: Dawid Kulikowski Date: Wed, 15 Sep 2021 11:41:12 +0200 Subject: [PATCH 39/40] * Fix AI SIGSEGV when roboteam_observer is not running --- src/world/World.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/world/World.cpp b/src/world/World.cpp index 9d1df337dc..eca3830be6 100644 --- a/src/world/World.cpp +++ b/src/world/World.cpp @@ -98,7 +98,7 @@ namespace rtt::world { } void World::updatePositionControl() { - if(!getWorld()->getRobotsNonOwning().empty()){ + if(auto world = getWorld(); world && !world->getRobotsNonOwning().empty()){ std::vector robotPositions(getWorld()->getRobotsNonOwning().size()); std::transform(getWorld()->getRobotsNonOwning().begin(), getWorld()->getRobotsNonOwning().end(), robotPositions.begin(), [](const auto& robot) -> Vector2 { return (robot->getPos()); }); positionControl.setRobotPositions(robotPositions); From 59fafbb2ec77cb895aa8763f72364f1f25e9673b Mon Sep 17 00:00:00 2001 From: Dawid Date: Thu, 9 Dec 2021 08:16:27 +0100 Subject: [PATCH 40/40] * Add basic interface rendeding capability --- interface_declarations.json | 54 +++++++++++++++++++++++---- src/interface/InterfaceController.cpp | 2 +- 2 files changed, 47 insertions(+), 9 deletions(-) diff --git a/interface_declarations.json b/interface_declarations.json index ad397441a5..01b3bea6ef 100644 --- a/interface_declarations.json +++ b/interface_declarations.json @@ -1,24 +1,62 @@ [ { - "path": "/hello/hello", + "path": "/Main/Team Comp/Goalie", "description": "Some random button", - "isMutable": true, + "isMutable": false, "defaultValue": { - "string": "I work!" + "bool": true }, - "text": { + "checkbox": { "text": "Some Text" } }, { - "path": "/hello/world", + "path": "/STP/Behaviour/SOME_STP_VAR", "description": "Some random button", - "isMutable": true, + "isMutable": false, "defaultValue": { - "string": "I work!" + "float": 1.0 + }, + "slider": { + "text": "Some Text", + "min": 0, + "max": 100, + "interval": 1, + "dpi": 1 + } + }, + { + "path": "/STP/Behaviour/RADIO", + "description": "Some random button", + "isMutable": false, + "defaultValue": { + "int": 2 + }, + "radio": { + "options": ["Hello", "world!"] + } + }, + { + "path": "/STP/Behaviour/DROPDOWN", + "description": "Some random button", + "isMutable": false, + "defaultValue": { + "int": 0 + }, + "dropdown": { + "text": "AA", + "options": ["Hello", "world!"] + } +}, + { + "path": "/STP/Behaviour/TEXT", + "description": "Some random button", + "isMutable": false, + "defaultValue": { + "string": "text" }, "text": { - "text": "Some Text" + "text": "AA" } } ] \ No newline at end of file diff --git a/src/interface/InterfaceController.cpp b/src/interface/InterfaceController.cpp index 6730afd0f1..9f84472303 100644 --- a/src/interface/InterfaceController.cpp +++ b/src/interface/InterfaceController.cpp @@ -28,7 +28,7 @@ std::optional InterfaceController::getChanges() { } void InterfaceController::handleUpdate(proto::UiValues val) { - this->settings->handleData(val); + this->settings->handleData(val, this->declarations); } InterfaceController::InterfaceController(const std::string pathToDecls) {