diff --git a/.clang-tidy b/.clang-tidy index 36c8dbf9..e5afebf1 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -1,3 +1,7 @@ +Checks: '-*,readability-identifier-naming' + +FormatStyle: 'file' + CheckOptions: # Namespace - key: readability-identifier-naming.NamespaceCase diff --git a/.github/workflows/cpp-checks.yml b/.github/workflows/cpp-checks.yml index 990b692b..9806227c 100644 --- a/.github/workflows/cpp-checks.yml +++ b/.github/workflows/cpp-checks.yml @@ -16,8 +16,6 @@ jobs: steps: - uses: actions/checkout@v4 - with: - submodules: recursive - name: C/C++ Linter uses: cpp-linter/cpp-linter-action@v2 @@ -28,9 +26,5 @@ jobs: files-changed-only: false lines-changed-only: ${{ github.event_name == 'pull_request' }} style: file - tidy-checks: '-*' + tidy-checks: '' step-summary: true - - - name: Fail - if: steps.linter.outputs.checks-failed > 0 - run: exit 1 diff --git a/CMakeLists.txt b/CMakeLists.txt index 1b5b5a73..72d9ff51 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -41,6 +41,7 @@ add_subdirectory(source/vision) add_subdirectory(source/referee) add_subdirectory(source/sender) add_subdirectory(source/soccer) +add_subdirectory(source/cli) add_subdirectory(source/gui) set(CPACK_GENERATOR ZIP) diff --git a/source/cli/CMakeLists.txt b/source/cli/CMakeLists.txt new file mode 100644 index 00000000..d4f28414 --- /dev/null +++ b/source/cli/CMakeLists.txt @@ -0,0 +1,38 @@ +project(${CMAKE_PROJECT_NAME}-cli) + +set(HEADER_FILES + pch.h +) + +set(SOURCE_FILES + main.cpp +) + +add_executable(${PROJECT_NAME} + ${HEADER_FILES} + ${SOURCE_FILES}) + +target_link_libraries(${PROJECT_NAME} PRIVATE + ${CMAKE_PROJECT_NAME}-common + ${CMAKE_PROJECT_NAME}-vision + ${CMAKE_PROJECT_NAME}-referee + ${CMAKE_PROJECT_NAME}-sender + ${CMAKE_PROJECT_NAME}-soccer) + +set_target_properties(${PROJECT_NAME} PROPERTIES UNITY_BUILD ${USE_UNITY_BUILDS}) + +get_target_property(COMMON_PCHS ${CMAKE_PROJECT_NAME}-common INTERFACE_PRECOMPILE_HEADERS) +get_target_property(VISION_PCHS ${CMAKE_PROJECT_NAME}-vision INTERFACE_PRECOMPILE_HEADERS) +get_target_property(REFEREE_PCHS ${CMAKE_PROJECT_NAME}-referee INTERFACE_PRECOMPILE_HEADERS) +get_target_property(SENDER_PCHS ${CMAKE_PROJECT_NAME}-sender INTERFACE_PRECOMPILE_HEADERS) +get_target_property(SOCCER_PCHS ${CMAKE_PROJECT_NAME}-soccer INTERFACE_PRECOMPILE_HEADERS) + +target_precompile_headers(${PROJECT_NAME} + PUBLIC ${COMMON_PCHS} + PUBLIC ${VISION_PCHS} + PUBLIC ${REFEREE_PCHS} + PUBLIC ${SENDER_PCHS} + PUBLIC ${SOCCER_PCHS} + PRIVATE pch.h) + +install(TARGETS ${PROJECT_NAME}) diff --git a/source/cli/main.cpp b/source/cli/main.cpp new file mode 100644 index 00000000..7eba34f4 --- /dev/null +++ b/source/cli/main.cpp @@ -0,0 +1,150 @@ +#define ImmortalsIsTheBest true + +using namespace Tyr; + +int main() +{ + Common::Services::initialize(); + + if (!ImmortalsIsTheBest) + { + Common::logCritical("Immortals is not the best SSL team anymore."); + Common::logCritical("Shutting down the system..."); + } + + Common::WorldState *state = new Common::WorldState(); + Common::RefereeState *referee_state = new Common::RefereeState(); + + Common::logInfo(" Connecting to RefereeBox server at {} on port : {}", Common::setting().referee_address.port, + Common::setting().referee_address.port); + Referee::Referee referee_2018(state, referee_state); + if (referee_2018.connectToRefBox()) + { + Common::logInfo("Connected to RefBox successfully :)"); + } + else + { + Common::logError("Hey you! Put the LAN cable back in its socket, or ..."); + } + + Common::logInfo("Connecting to Vision server at {} on port: {}", Common::setting().vision_address.ip, + Common::setting().vision_address.port); + Vision::Vision vision(state); + if (vision.isConnected()) + { + Common::logInfo("Connected to Vision successfully :)"); + } + else + { + Common::logError("Hey you! Put the LAN cable back in its socket, or ..."); + // return 0; + } + + Sender::Sender *senderBase = new Sender::Sender(); + + Soccer::Ai *aii = new Soccer::Ai(state, referee_state, senderBase); + + auto grsim_fwd = new Sender::Grsim(Common::setting().grsim_address); + + bool exited = false; + std::mutex lock; + + Common::logInfo(" Now it is time, lets rock..."); + + auto ai_func = [&]() + { + Common::Timer timer; + + while (ImmortalsIsTheBest) // Hope it lasts Forever... + { + timer.start(); + + vision.recieveAllCameras(); + + lock.lock(); + + // The vision process + vision.ProcessVision(); + // The AI process + aii->Process(state); + + // TODO #3 comment the GRsim output + // grsim_fwd->SendData((reinterpret_cast(aii))->OwnRobot, Setting::kMaxOnFieldTeamRobots, + // settings->our_color); + + // The sending process + senderBase->sendAll(); + + // debugging (the visualizer written by python) : + Common::debug().broadcast(); + + // LordHippos GUI + // vision.SendGUIData(state,aii->AIDebug); + + lock.unlock(); + Common::logDebug("FPS: {}", 1.0 / timer.interval()); + } + exited = true; + }; + + auto ref_func = [&]() + { + while ((!exited) && (ImmortalsIsTheBest)) // Hope it lasts Forever... + { + if (referee_2018.recieve()) + { + // std::cout << "Referre Boz" << std::endl; + lock.lock(); + referee_2018.process(); + lock.unlock(); + // std::cout << "Referre Boz "<< referee_2018.command_CNT << std::endl; + } + } + }; + + auto str_func = [&]() + { + std::shared_ptr strategyUDP = + std::make_shared(Common::setting().strategy_address); + + while ((!exited) && (ImmortalsIsTheBest)) // Hope it lasts Forever... + { + + auto receivedStrategy = strategyUDP->receiveRaw(); + const std::string strategySrcAdd = strategyUDP->getLastReceiveEndpoint().address().to_string(); + const unsigned short strategySrcPort = strategyUDP->getLastReceiveEndpoint().port(); + if (receivedStrategy.size() > 11) + { + Common::logInfo("Recieved \"strategy.ims\" with size: {} KB, from {} on port {}", + float(receivedStrategy.size()) / 1000.0f, strategySrcAdd, strategySrcPort); + lock.lock(); + aii->read_playBook_str(receivedStrategy.data(), receivedStrategy.size()); + lock.unlock(); + std::string strategy_path(DATA_DIR); + strategy_path.append("/strategy.ims"); + std::ofstream strategyFile(strategy_path.c_str(), std::ios::out | std::ios::binary); + strategyFile.write(receivedStrategy.data(), receivedStrategy.size()); + strategyFile.close(); + } + else + { + Common::logWarning("Invalid \"strategy.ims\" received with size: {}", receivedStrategy.size()); + } + } + }; + + std::thread ai_thread(ai_func); + std::thread ref_thread(ref_func); + std::thread str_thread(str_func); + + ai_thread.join(); + ref_thread.join(); + str_thread.join(); + + delete state; + delete aii; + + Common::Services::shutdown(); + + return 0; +} diff --git a/source/cli/pch.h b/source/cli/pch.h new file mode 100644 index 00000000..0b8744ec --- /dev/null +++ b/source/cli/pch.h @@ -0,0 +1,7 @@ +#pragma once + +#include +#include +#include +#include +#include diff --git a/source/common/CMakeLists.txt b/source/common/CMakeLists.txt index b35e84ea..5f6ca686 100644 --- a/source/common/CMakeLists.txt +++ b/source/common/CMakeLists.txt @@ -7,65 +7,65 @@ find_package(PkgConfig REQUIRED) pkg_check_modules(tomlplusplus REQUIRED IMPORTED_TARGET tomlplusplus) set(HEADER_FILES - pch.h - services.h - setting.h - config/config.h - debugging/common_colors.h - debugging/debug.h - logging/logging.h - logging/macros.h - math/angle.h - math/helpers.h - math/linear.h - math/median_filter.h - math/random.h - math/vector.h - math/geom/circle.h - math/geom/line_segment.h - math/geom/line.h - math/geom/rect.h - network/udp_client.h - network/udp_server.h - state/game_commands.h - state/game.h - state/referee.h - state/world.h - timer/timer.h) + pch.h + services.h + setting.h + config/config.h + debugging/common_colors.h + debugging/debug.h + logging/logging.h + logging/macros.h + math/angle.h + math/helpers.h + math/linear.h + math/median_filter.h + math/random.h + math/vector.h + math/geom/circle.h + math/geom/line_segment.h + math/geom/line.h + math/geom/rect.h + network/udp_client.h + network/udp_server.h + state/game_commands.h + state/game.h + state/referee.h + state/world.h + timer/timer.h) set(SOURCE_FILES - setting.cpp - config/config.cpp - debugging/common_colors.cpp - debugging/debug.cpp - logging/logging.cpp - math/angle.cpp - math/helpers.cpp - math/linear.cpp - math/random.cpp - math/vector.cpp - math/geom/circle.cpp - math/geom/line.cpp - math/geom/rect.cpp - network/udp_client.cpp - network/udp_server.cpp - timer/timer.cpp) + setting.cpp + config/config.cpp + debugging/common_colors.cpp + debugging/debug.cpp + logging/logging.cpp + math/angle.cpp + math/helpers.cpp + math/linear.cpp + math/random.cpp + math/vector.cpp + math/geom/circle.cpp + math/geom/line.cpp + math/geom/rect.cpp + network/udp_client.cpp + network/udp_server.cpp + timer/timer.cpp) add_library(${PROJECT_NAME} - ${SOURCE_FILES} ${HEADER_FILES}) + ${SOURCE_FILES} ${HEADER_FILES}) target_include_directories(${PROJECT_NAME} INTERFACE "${CMAKE_CURRENT_SOURCE_DIR}") source_group(TREE ${CMAKE_CURRENT_SOURCE_DIR} FILES ${SOURCE_FILES} ${HEADER_FILES}) target_link_libraries(${PROJECT_NAME} PUBLIC - ${CMAKE_PROJECT_NAME}-protos - asio::asio - PkgConfig::tomlplusplus - spdlog::spdlog) + ${CMAKE_PROJECT_NAME}-protos + asio::asio + PkgConfig::tomlplusplus + spdlog::spdlog) -if (WIN32) - target_compile_definitions(${PROJECT_NAME} PUBLIC _WIN32_WINNT=_WIN32_WINNT_WIN10) +if(WIN32) + target_compile_definitions(${PROJECT_NAME} PUBLIC _WIN32_WINNT=_WIN32_WINNT_WIN10) endif() target_compile_definitions(${PROJECT_NAME} PUBLIC DATA_DIR="${CMAKE_SOURCE_DIR}/data") @@ -73,4 +73,9 @@ target_compile_definitions(${PROJECT_NAME} PUBLIC LOG_DIR="${CMAKE_SOURCE_DIR}/l set_target_properties(${PROJECT_NAME} PROPERTIES UNITY_BUILD ${USE_UNITY_BUILDS}) -target_precompile_headers(${PROJECT_NAME} PUBLIC pch.h) +get_target_property(PROTOS_PCHS ${CMAKE_PROJECT_NAME}-protos INTERFACE_PRECOMPILE_HEADERS) + +target_precompile_headers(${PROJECT_NAME} + PUBLIC ${PROTOS_PCHS} + PUBLIC pch.h + INTERFACE ${HEADER_FILES}) diff --git a/source/common/config/config.h b/source/common/config/config.h index 8977563e..396c70d0 100644 --- a/source/common/config/config.h +++ b/source/common/config/config.h @@ -1,10 +1,5 @@ #pragma once -#include -#include - -#include - namespace Tyr::Common { class ConfigReader diff --git a/source/common/debugging/debug.h b/source/common/debugging/debug.h index d89aa472..878389c3 100644 --- a/source/common/debugging/debug.h +++ b/source/common/debugging/debug.h @@ -1,10 +1,5 @@ #pragma once -#include -#include - -#include - #include "../math/vector.h" #include "../network/udp_server.h" #include "common_colors.h" diff --git a/source/common/logging/logging.h b/source/common/logging/logging.h index e4d487ba..c2f81e37 100644 --- a/source/common/logging/logging.h +++ b/source/common/logging/logging.h @@ -1,10 +1,5 @@ #pragma once -#include -#include - -#include - namespace Tyr::Common { class Logger diff --git a/source/common/logging/macros.h b/source/common/logging/macros.h index e5dac83c..0d911498 100644 --- a/source/common/logging/macros.h +++ b/source/common/logging/macros.h @@ -1,9 +1,5 @@ #pragma once -#include - -#include - namespace Tyr::Common { diff --git a/source/common/math/angle.h b/source/common/math/angle.h index 5e61c644..da5df2bb 100644 --- a/source/common/math/angle.h +++ b/source/common/math/angle.h @@ -1,9 +1,5 @@ #pragma once -#include - -#include - namespace Tyr::Common { struct Vec2; diff --git a/source/common/math/geom/circle.h b/source/common/math/geom/circle.h index f516022a..e2205c14 100644 --- a/source/common/math/geom/circle.h +++ b/source/common/math/geom/circle.h @@ -1,8 +1,5 @@ #pragma once -#include -#include - #include "../vector.h" namespace Tyr::Common diff --git a/source/common/math/geom/line.h b/source/common/math/geom/line.h index ee562c81..3d27857e 100644 --- a/source/common/math/geom/line.h +++ b/source/common/math/geom/line.h @@ -1,8 +1,5 @@ #pragma once -#include -#include - #include "../angle.h" #include "../vector.h" diff --git a/source/common/math/geom/rect.h b/source/common/math/geom/rect.h index 9f8c0b95..5e19a33d 100644 --- a/source/common/math/geom/rect.h +++ b/source/common/math/geom/rect.h @@ -1,7 +1,5 @@ #pragma once -#include - #include "../vector.h" namespace Tyr::Common diff --git a/source/common/math/helpers.h b/source/common/math/helpers.h index e2553a8e..089c28e6 100644 --- a/source/common/math/helpers.h +++ b/source/common/math/helpers.h @@ -1,8 +1,5 @@ #pragma once -#include -#include - namespace Tyr::Common { bool almostEqual(float t_a, float t_b); diff --git a/source/common/math/linear.cpp b/source/common/math/linear.cpp index 098a934c..ec22e338 100644 --- a/source/common/math/linear.cpp +++ b/source/common/math/linear.cpp @@ -94,7 +94,7 @@ float Linear::getDisToPoint(Vec2 p) return std::fabs(m_b * p.x - p.y + m_a) / sqrt(m_b * m_b + 1.0); } -void Linear::chapeKon(void) +void Linear::chapeKon() { m_a = -m_a / m_b; m_b = 1.0f / m_b; diff --git a/source/common/math/linear.h b/source/common/math/linear.h index 8bd7cfba..0b050614 100644 --- a/source/common/math/linear.h +++ b/source/common/math/linear.h @@ -42,7 +42,7 @@ class Linear float getDisToPoint(Vec2 p); - void chapeKon(void); + void chapeKon(); private: float m_a, m_b, m_coeff, xinter; diff --git a/source/common/math/median_filter.h b/source/common/math/median_filter.h index 6903f96e..ec6e60db 100644 --- a/source/common/math/median_filter.h +++ b/source/common/math/median_filter.h @@ -1,6 +1,4 @@ #pragma once -#include -#include namespace Tyr::Common { @@ -34,7 +32,7 @@ class MedianFilter } } - T GetCurrent(void) + T GetCurrent() { temp = data; std::sort(temp.begin(), temp.end()); @@ -43,7 +41,7 @@ class MedianFilter return temp.at(temp.size() / 2); } - void reset(void) + void reset() { data.clear(); index = false; diff --git a/source/common/math/random.h b/source/common/math/random.h index cd8a1b11..49aa2675 100644 --- a/source/common/math/random.h +++ b/source/common/math/random.h @@ -1,5 +1,4 @@ #pragma once -#include namespace Tyr::Common { diff --git a/source/common/math/vector.h b/source/common/math/vector.h index 79e66537..2d6d3929 100644 --- a/source/common/math/vector.h +++ b/source/common/math/vector.h @@ -1,7 +1,5 @@ #pragma once -#include - namespace Tyr::Common { struct Angle; diff --git a/source/common/network/udp_client.cpp b/source/common/network/udp_client.cpp index ccfa9222..3f4856bb 100644 --- a/source/common/network/udp_client.cpp +++ b/source/common/network/udp_client.cpp @@ -19,6 +19,26 @@ UdpClient::UdpClient(const NetworkAddress &t_address) } } +void UdpClient::Update(const NetworkAddress &t_address) +{ + m_socket->cancel(); + if (m_socket->is_open()) + { + m_socket->close(); + // m_socket = std::make_unique(*m_context); + } + m_address = asio::ip::make_address(t_address.ip); + m_listen_endpoint = asio::ip::udp::endpoint{asio::ip::udp::v4(), t_address.port}; + + m_socket->open(m_listen_endpoint.protocol()); + m_socket->set_option(asio::ip::udp::socket::reuse_address(true)); + m_socket->bind(m_listen_endpoint); + if (m_address.is_multicast()) + { + m_socket->set_option(asio::ip::multicast::join_group(m_address)); + } +} + bool UdpClient::receive(google::protobuf::MessageLite *const t_message) { @@ -37,24 +57,16 @@ bool UdpClient::receive(google::protobuf::MessageLite *const t_message) return false; } -void UdpClient::Update(const NetworkAddress &t_address) +std::span UdpClient::receiveRaw() { - m_socket->cancel(); - if (m_socket->is_open()) - { - m_socket->close(); - // m_socket = std::make_unique(*m_context); - } - m_address = asio::ip::make_address(t_address.ip); - m_listen_endpoint = asio::ip::udp::endpoint{asio::ip::udp::v4(), t_address.port}; + const size_t received_size = m_socket->receive_from(asio::buffer(m_buffer), m_last_receive_endpoint); - m_socket->open(m_listen_endpoint.protocol()); - m_socket->set_option(asio::ip::udp::socket::reuse_address(true)); - m_socket->bind(m_listen_endpoint); - if (m_address.is_multicast()) + if (received_size > 0) { - m_socket->set_option(asio::ip::multicast::join_group(m_address)); + return std::span(m_buffer.data(), received_size); } + + return {}; } } // namespace Tyr::Common diff --git a/source/common/network/udp_client.h b/source/common/network/udp_client.h index dc374bf8..0ed7e9a5 100644 --- a/source/common/network/udp_client.h +++ b/source/common/network/udp_client.h @@ -1,21 +1,5 @@ #pragma once -#include - -#if defined(_WIN32) -#define NOGDI // All GDI defines and routines -#define NOUSER // All USER defines and routines -#endif - -#include - -#if defined(_WIN32) // raylib uses these names as function parameters -#undef near -#undef far -#endif - -#include - #include "../setting.h" namespace Tyr::Common @@ -25,9 +9,11 @@ class UdpClient public: explicit UdpClient(const NetworkAddress &t_address); + void Update(const NetworkAddress &t_address); + bool receive(google::protobuf::MessageLite *t_message); - void Update(const NetworkAddress &t_address); + std::span receiveRaw(); [[nodiscard]] asio::ip::udp::endpoint getListenEndpoint() const { diff --git a/source/common/network/udp_server.h b/source/common/network/udp_server.h index 55069474..98a4ffc7 100644 --- a/source/common/network/udp_server.h +++ b/source/common/network/udp_server.h @@ -1,22 +1,5 @@ #pragma once -#include -#include - -#if defined(_WIN32) -#define NOGDI // All GDI defines and routines -#define NOUSER // All USER defines and routines -#endif - -#include - -#if defined(_WIN32) // raylib uses these names as function parameters -#undef near -#undef far -#endif - -#include - #include "../setting.h" namespace Tyr::Common diff --git a/source/common/pch.h b/source/common/pch.h index cf40a5ef..cf2124ad 100644 --- a/source/common/pch.h +++ b/source/common/pch.h @@ -1,9 +1,39 @@ #pragma once +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include #include #include +#include +#include -#include "services.h" +#if defined(_WIN32) +#define NOGDI // All GDI defines and routines +#define NOUSER // All USER defines and routines +#endif + +#include + +#if defined(_WIN32) // raylib uses these names as function parameters +#undef near +#undef far +#endif + +#include #include "math/angle.h" #include "math/geom/circle.h" @@ -12,3 +42,4 @@ #include "math/geom/rect.h" #include "math/helpers.h" #include "math/vector.h" +#include "services.h" diff --git a/source/common/setting.cpp b/source/common/setting.cpp index 7a9281e7..e734d48c 100644 --- a/source/common/setting.cpp +++ b/source/common/setting.cpp @@ -27,8 +27,13 @@ void Setting::load(const toml::node_view t_node) sender_address.load(network["sender"]); commands_address.load(network["commands"]); + + strategy_address.load(network["strategy"]); + // sender_rec_address.load(network["referee"]); + grsim_address.load(network["grsim"]); + control_simulation_address.load(network["control_simulation"]); blue_robot_simulation_address.load(network["blue_robot_simulation"]); yellow_robot_simulation_address.load(network["yellow_robot_simulation"]); diff --git a/source/common/setting.h b/source/common/setting.h index cc13d658..10d17492 100644 --- a/source/common/setting.h +++ b/source/common/setting.h @@ -1,7 +1,5 @@ #pragma once -#include - #include "config/config.h" namespace Tyr::Common @@ -70,7 +68,7 @@ struct Setting : IConfig static constexpr size_t kMaxUdpPacketSize = 1024 * 16; // TODO what should the size be really? - // The variety of standard patterns that we can have is 12 + // The variety of standard patterns that we can have is 16 static constexpr unsigned kMaxRobots = 16; bool immortals_is_the_best_team = true; @@ -108,14 +106,18 @@ struct Setting : IConfig bool use_kalman_ang = true; // TODO: check if this is in serious need in reality // soccer - static constexpr int kMaxOnFieldTeamRobots = 11; + static constexpr int kMaxOnFieldTeamRobots = 8; NetworkAddress referee_address = {"224.5.23.1", 10003}; NetworkAddress sender_address = {"224.5.92.5", 60005}; NetworkAddress sender_rec_address = {"", 0}; // TODO: unused? - NetworkAddress commands_address = {"224.5.92.6", 60006}; + NetworkAddress commands_address = {"224.5.92.6", 60007}; + + NetworkAddress strategy_address = {"224.5.23.3", 60006}; + + NetworkAddress grsim_address = {"127.0.0.1", 20011}; NetworkAddress control_simulation_address = {"127.0.0.1", 10300}; NetworkAddress blue_robot_simulation_address = {"127.0.0.1", 10301}; diff --git a/source/common/state/game_commands.h b/source/common/state/game_commands.h index e1b04d86..0e98570a 100644 --- a/source/common/state/game_commands.h +++ b/source/common/state/game_commands.h @@ -24,8 +24,6 @@ #pragma once -#include - // play commands #define COMM_HALT Protos::SSL_Referee_Command_HALT #define COMM_STOP Protos::SSL_Referee_Command_STOP diff --git a/source/common/state/world.h b/source/common/state/world.h index ee90616a..885bc65e 100644 --- a/source/common/state/world.h +++ b/source/common/state/world.h @@ -1,7 +1,5 @@ #pragma once -#include - #define COLOR_BLUE false #define COLOR_YELLOW true @@ -10,6 +8,7 @@ #include "../math/angle.h" #include "../math/vector.h" +#include "../setting.h" namespace Tyr::Common { diff --git a/source/common/timer/timer.h b/source/common/timer/timer.h index ea76a576..af7820fe 100644 --- a/source/common/timer/timer.h +++ b/source/common/timer/timer.h @@ -14,8 +14,6 @@ #pragma once -#include - namespace Tyr::Common { class Timer diff --git a/source/gui/CMakeLists.txt b/source/gui/CMakeLists.txt index bf8e1b10..699c3c80 100644 --- a/source/gui/CMakeLists.txt +++ b/source/gui/CMakeLists.txt @@ -30,7 +30,11 @@ target_link_libraries(${PROJECT_NAME} PRIVATE set_target_properties(${PROJECT_NAME} PROPERTIES UNITY_BUILD ${USE_UNITY_BUILDS}) -target_precompile_headers(${PROJECT_NAME} PRIVATE "pch.h") +get_target_property(COMMON_PCHS ${CMAKE_PROJECT_NAME}-common INTERFACE_PRECOMPILE_HEADERS) + +target_precompile_headers(${PROJECT_NAME} + PRIVATE ${COMMON_PCHS} + PRIVATE pch.h) install(TARGETS ${PROJECT_NAME}) diff --git a/source/gui/menu/config_menu.h b/source/gui/menu/config_menu.h index 1b14eed9..57e97ff6 100644 --- a/source/gui/menu/config_menu.h +++ b/source/gui/menu/config_menu.h @@ -21,8 +21,8 @@ class ConfigMenu std::string visionPort; NetworkInput networkNeedsUpdate; - void DrawTabBar(void); - void DrawNetworkTab(void); + void DrawTabBar(); + void DrawNetworkTab(); void SetNetworkInput(std::string _data, NetworkInput _inputType); static int HandleVisionIpChange(ImGuiInputTextCallbackData *_data); @@ -35,6 +35,6 @@ class ConfigMenu std::string GetNetworkParam(NetworkInput _inputType); NetworkInput IsNetworkDataUpdated(); void UpdateNetworkData(); - void Draw(void); + void Draw(); }; } // namespace Tyr::Gui diff --git a/source/gui/pch.h b/source/gui/pch.h index e26a283d..fc01b89d 100644 --- a/source/gui/pch.h +++ b/source/gui/pch.h @@ -14,14 +14,3 @@ #include #include - -#include -#include -#include - -#include -#include -#include -#include -#include -#include diff --git a/source/gui/renderer/renderer.h b/source/gui/renderer/renderer.h index 352d1795..34e87b21 100644 --- a/source/gui/renderer/renderer.h +++ b/source/gui/renderer/renderer.h @@ -6,7 +6,7 @@ class Renderer { public: Renderer(Common::Vec2 _wSize, float _upScalingFactor); - void init(void); + void init(); void drawRect(Common::Rect rect, Color _color, bool _isFilled, float _thickness = 1, unsigned char transparency = 255); @@ -26,7 +26,7 @@ class Renderer void drawRobot(const Protos::SSL_DetectionRobot &robot, Common::TeamColor color); void drawBall(const Protos::SSL_DetectionBall &ball); - void applyShader(void); + void applyShader(); RenderTexture visualizaionTexture, shaderVisualizationTexture; diff --git a/source/protos b/source/protos index 4d00adc7..1a7cc3fe 160000 --- a/source/protos +++ b/source/protos @@ -1 +1 @@ -Subproject commit 4d00adc7f2eac9bc9e9b80ba87ab86fa6180f9f4 +Subproject commit 1a7cc3fe5f719b429673d60992fee6042c3fe461 diff --git a/source/referee/CMakeLists.txt b/source/referee/CMakeLists.txt index 21a74226..0a93a0e2 100644 --- a/source/referee/CMakeLists.txt +++ b/source/referee/CMakeLists.txt @@ -1,14 +1,14 @@ project(${CMAKE_PROJECT_NAME}-referee) set(HEADER_FILES - pch.h - referee.h) + pch.h + referee.h) set(SOURCE_FILES - referee.cpp) + referee.cpp) add_library(${PROJECT_NAME} - ${SOURCE_FILES} ${HEADER_FILES}) + ${SOURCE_FILES} ${HEADER_FILES}) target_include_directories(${PROJECT_NAME} INTERFACE "${CMAKE_CURRENT_SOURCE_DIR}") @@ -19,4 +19,9 @@ target_link_libraries(${PROJECT_NAME} PUBLIC set_target_properties(${PROJECT_NAME} PROPERTIES UNITY_BUILD ${USE_UNITY_BUILDS}) -target_precompile_headers(${PROJECT_NAME} PUBLIC pch.h) +get_target_property(COMMON_PCHS ${CMAKE_PROJECT_NAME}-common INTERFACE_PRECOMPILE_HEADERS) + +target_precompile_headers(${PROJECT_NAME} + PUBLIC ${COMMON_PCHS} + PUBLIC pch.h + INTERFACE ${HEADER_FILES}) diff --git a/source/referee/pch.h b/source/referee/pch.h index 79d24a3f..6f70f09b 100644 --- a/source/referee/pch.h +++ b/source/referee/pch.h @@ -1,4 +1 @@ #pragma once - -#include -#include diff --git a/source/referee/referee.cpp b/source/referee/referee.cpp index 76c0f6e6..e8fcc21c 100644 --- a/source/referee/referee.cpp +++ b/source/referee/referee.cpp @@ -17,7 +17,7 @@ Referee::Referee(Common::WorldState *world_state, Common::RefereeState *referee_ RefState->State->init(Common::setting().our_color); } -bool Referee::connectToRefBox(void) +bool Referee::connectToRefBox() { m_udp = std::make_unique(Common::setting().referee_address); @@ -91,7 +91,7 @@ bool Referee::isKicked(Common::Vec2 ballPos) return false; } -bool Referee::recieve(void) +bool Referee::recieve() { if (!isConnected()) return false; diff --git a/source/referee/referee.h b/source/referee/referee.h index 63475f7e..951e173b 100644 --- a/source/referee/referee.h +++ b/source/referee/referee.h @@ -1,11 +1,5 @@ #pragma once -#include -#include -#include -#include -#include - namespace Tyr::Referee { class Referee @@ -29,11 +23,11 @@ class Referee public: Referee(Common::WorldState *world_state, Common::RefereeState *referee_state); - bool connectToRefBox(void); - bool isConnected(void); - bool recieve(void); + bool connectToRefBox(); + bool isConnected(); + bool recieve(); bool isKicked(Common::Vec2 ballPos); - void process(void); + void process(); int oppGK; }; diff --git a/source/sender/CMakeLists.txt b/source/sender/CMakeLists.txt index 49cfb65a..ef284063 100644 --- a/source/sender/CMakeLists.txt +++ b/source/sender/CMakeLists.txt @@ -1,27 +1,27 @@ project(${CMAKE_PROJECT_NAME}-sender) set(HEADER_FILES - pch.h - grsim.h - sender.h - protocol/data_lite.h - protocol/defines.h - protocol/half.h - protocol/reader.h - protocol/writer.h) + pch.h + grsim.h + sender.h + protocol/data_lite.h + protocol/defines.h + protocol/half.h + protocol/reader.h + protocol/writer.h) set(C_SOURCE_FILES - protocol/half.c - protocol/reader.c - protocol/writer.c) + protocol/half.c + protocol/reader.c + protocol/writer.c) set(SOURCE_FILES - grsim.cpp - sender.cpp - ${C_SOURCE_FILES}) + grsim.cpp + sender.cpp + ${C_SOURCE_FILES}) add_library(${PROJECT_NAME} - ${SOURCE_FILES} ${HEADER_FILES}) + ${SOURCE_FILES} ${HEADER_FILES}) target_include_directories(${PROJECT_NAME} INTERFACE "${CMAKE_CURRENT_SOURCE_DIR}") @@ -32,8 +32,12 @@ target_link_libraries(${PROJECT_NAME} PUBLIC set_target_properties(${PROJECT_NAME} PROPERTIES UNITY_BUILD ${USE_UNITY_BUILDS}) -set_source_files_properties(${C_SOURCE_FILES} PROPERTIES - SKIP_PRECOMPILE_HEADERS TRUE - SKIP_UNITY_BUILD_INCLUSION TRUE) +set_source_files_properties(${C_SOURCE_FILES} PROPERTIES + SKIP_PRECOMPILE_HEADERS TRUE + SKIP_UNITY_BUILD_INCLUSION TRUE) -target_precompile_headers(${PROJECT_NAME} PUBLIC pch.h) +get_target_property(COMMON_PCHS ${CMAKE_PROJECT_NAME}-common INTERFACE_PRECOMPILE_HEADERS) +target_precompile_headers(${PROJECT_NAME} + PUBLIC ${COMMON_PCHS} + PUBLIC pch.h + INTERFACE ${HEADER_FILES}) diff --git a/source/sender/grsim.h b/source/sender/grsim.h index f65c8248..83822645 100644 --- a/source/sender/grsim.h +++ b/source/sender/grsim.h @@ -1,9 +1,5 @@ #pragma once -#include - -#include - namespace Tyr::Sender { class Grsim diff --git a/source/sender/pch.h b/source/sender/pch.h index 4e085a79..6f70f09b 100644 --- a/source/sender/pch.h +++ b/source/sender/pch.h @@ -1,6 +1 @@ #pragma once - -#include -#include - -#include diff --git a/source/sender/sender.h b/source/sender/sender.h index ad813089..85db589b 100644 --- a/source/sender/sender.h +++ b/source/sender/sender.h @@ -1,9 +1,5 @@ #pragma once -#include - -#include - namespace Tyr::Sender { class Sender diff --git a/source/soccer/CMakeLists.txt b/source/soccer/CMakeLists.txt index 6d3a6aa4..1d868cd6 100644 --- a/source/soccer/CMakeLists.txt +++ b/source/soccer/CMakeLists.txt @@ -1,97 +1,97 @@ project(${CMAKE_PROJECT_NAME}-soccer) set(HEADER_FILES - pch.h - ai.h + pch.h + ai.h - dss/dss.h - dss/parabolic.h - dss/trajectory.h - errt/errt.h - errt/tree.h + dss/dss.h + dss/parabolic.h + dss/trajectory.h + errt/errt.h + errt/tree.h - obstacle/obstacle_new.h - obstacle/obstacle.h + obstacle/obstacle_new.h + obstacle/obstacle.h - helpers/one_touch_detector.h + helpers/one_touch_detector.h - robot/robot.h - robot/velocity_profile.h) + robot/robot.h + robot/velocity_profile.h) set(SOURCE_FILES - ai.cpp - ai_process.cpp - internal_finalize.cpp - internal_process_data.cpp - play_book.cpp - - dss/dss.cpp - dss/parabolic.cpp - dss/trajectory.cpp - errt/errt.cpp - errt/set_obstacles.cpp - errt/tree.cpp - - obstacle/obstacle_circle.cpp - obstacle/obstacle_map.cpp - obstacle/obstacle_rect.cpp - obstacle/obstacle.cpp - - helpers/attack_fucking_angle.cpp - helpers/ball_is_goaling.cpp - helpers/ball_trajectory.cpp - helpers/calc_is_defending.cpp - helpers/calculate_mark_cost.cpp - helpers/calculate_opp_threat.cpp - helpers/calculate_swicth_to_attacker_score.cpp - helpers/def_ghuz.cpp - helpers/find_kicker_opp.cpp - helpers/goal_blocked.cpp - helpers/manage_att_roles.cpp - helpers/mark_manager.cpp - helpers/nearest_asshole.cpp - helpers/one_touch_angle.cpp - helpers/open_angle.cpp - helpers/out_of_field.cpp - helpers/robot_check.cpp - helpers/strategy_weight.cpp - - plays/corner_their_global.cpp - plays/halt.cpp - plays/kickoff_their_one_wall.cpp - plays/kickoff_us_chip.cpp - plays/normal_play_att.cpp - plays/normal_play_def.cpp - plays/normal_play.cpp - plays/penalty_their_simple.cpp - plays/penalty_us_shootout.cpp - plays/place_ball.cpp - plays/stop_def.cpp - plays/stop.cpp - plays/strategy_maker.cpp - plays/their_place_ball.cpp - plays/throwin_chip_shoot.cpp - - skills/circle_ball.cpp - skills/def_2018.cpp - skills/def_hi.cpp - skills/defence_wall.cpp - skills/gk_hi.cpp - skills/mark_to_ball.cpp - skills/mark_to_goal.cpp - skills/mark.cpp - skills/navigation.cpp - skills/pass_gool.cpp - skills/pass_omghi.cpp - skills/pass.cpp - skills/recieve_pass.cpp - skills/tech_circle.cpp - - robot/motion_plan.cpp - robot/robot.cpp) + ai.cpp + ai_process.cpp + internal_finalize.cpp + internal_process_data.cpp + play_book.cpp + + dss/dss.cpp + dss/parabolic.cpp + dss/trajectory.cpp + errt/errt.cpp + errt/set_obstacles.cpp + errt/tree.cpp + + obstacle/obstacle_circle.cpp + obstacle/obstacle_map.cpp + obstacle/obstacle_rect.cpp + obstacle/obstacle.cpp + + helpers/attack_fucking_angle.cpp + helpers/ball_is_goaling.cpp + helpers/ball_trajectory.cpp + helpers/calc_is_defending.cpp + helpers/calculate_mark_cost.cpp + helpers/calculate_opp_threat.cpp + helpers/calculate_swicth_to_attacker_score.cpp + helpers/def_ghuz.cpp + helpers/find_kicker_opp.cpp + helpers/goal_blocked.cpp + helpers/manage_att_roles.cpp + helpers/mark_manager.cpp + helpers/nearest_asshole.cpp + helpers/one_touch_angle.cpp + helpers/open_angle.cpp + helpers/out_of_field.cpp + helpers/robot_check.cpp + helpers/strategy_weight.cpp + + plays/corner_their_global.cpp + plays/halt.cpp + plays/kickoff_their_one_wall.cpp + plays/kickoff_us_chip.cpp + plays/normal_play_att.cpp + plays/normal_play_def.cpp + plays/normal_play.cpp + plays/penalty_their_simple.cpp + plays/penalty_us_shootout.cpp + plays/place_ball.cpp + plays/stop_def.cpp + plays/stop.cpp + plays/strategy_maker.cpp + plays/their_place_ball.cpp + plays/throwin_chip_shoot.cpp + + skills/circle_ball.cpp + skills/def_2018.cpp + skills/def_hi.cpp + skills/defence_wall.cpp + skills/gk_hi.cpp + skills/mark_to_ball.cpp + skills/mark_to_goal.cpp + skills/mark.cpp + skills/navigation.cpp + skills/pass_gool.cpp + skills/pass_omghi.cpp + skills/pass.cpp + skills/recieve_pass.cpp + skills/tech_circle.cpp + + robot/motion_plan.cpp + robot/robot.cpp) add_library(${PROJECT_NAME} - ${SOURCE_FILES} ${HEADER_FILES}) + ${SOURCE_FILES} ${HEADER_FILES}) target_include_directories(${PROJECT_NAME} INTERFACE "${CMAKE_CURRENT_SOURCE_DIR}") @@ -103,4 +103,11 @@ target_link_libraries(${PROJECT_NAME} PUBLIC set_target_properties(${PROJECT_NAME} PROPERTIES UNITY_BUILD ${USE_UNITY_BUILDS}) -target_precompile_headers(${PROJECT_NAME} PUBLIC pch.h) +get_target_property(COMMON_PCHS ${CMAKE_PROJECT_NAME}-common INTERFACE_PRECOMPILE_HEADERS) +get_target_property(SENDER_PCHS ${CMAKE_PROJECT_NAME}-sender INTERFACE_PRECOMPILE_HEADERS) + +target_precompile_headers(${PROJECT_NAME} + PUBLIC ${COMMON_PCHS} + PUBLIC ${SENDER_PCHS} + PUBLIC pch.h + INTERFACE ${HEADER_FILES}) diff --git a/source/soccer/dss/dss.cpp b/source/soccer/dss/dss.cpp index c1e5fa1f..719b9b95 100644 --- a/source/soccer/dss/dss.cpp +++ b/source/soccer/dss/dss.cpp @@ -123,7 +123,7 @@ float Dss::ComputeError(const Common::Vec2 &target, const Common::Vec2 ¤t) return target.distanceTo(current); } -void Dss::Reset(void) +void Dss::Reset() { for (int robot_idx = 0; robot_idx < Common::Setting::kMaxOnFieldTeamRobots; ++robot_idx) { diff --git a/source/soccer/dss/dss.h b/source/soccer/dss/dss.h index 538c7c0d..138f6905 100644 --- a/source/soccer/dss/dss.h +++ b/source/soccer/dss/dss.h @@ -36,7 +36,7 @@ class Dss Dss(const Robot *const own_robots, const Common::RobotState *const opp_robots, const float robot_r, const float cmd_dt, const float max_dec, const float max_dec_opp); - void Reset(void); + void Reset(); Common::Vec2 ComputeSafeMotion(const int robot_num, const Common::Vec2 &motion); }; diff --git a/source/soccer/errt/errt.cpp b/source/soccer/errt/errt.cpp index 20903a27..54d7892a 100644 --- a/source/soccer/errt/errt.cpp +++ b/source/soccer/errt/errt.cpp @@ -8,7 +8,7 @@ namespace Tyr::Soccer { -Planner::Planner(void) +Planner::Planner() { waypoints = 0; cached_waypoints = 0; @@ -57,7 +57,7 @@ void Planner::set_field_params(float _w, float _h) field_height = _h; } -Common::Vec2 Planner::random_state(void) +Common::Vec2 Planner::random_state() { // return Common::Vec2 ( ( rnd ( ) * 10000.0 ) - 5000.0 , ( rnd ( ) * 10000.0 ) - 5000.0 ); return Common::Vec2(((random.get() - 0.5f) * 2.0f * (field_width + 250.0f)), @@ -229,7 +229,7 @@ Node *Planner::extend(Node *s, Common::Vec2 &target) return tree.AddNode(new_state, s); } -void Planner::SetWayPoints(void) +void Planner::SetWayPoints() { waypoints = 1; Node *n = tree.NearestNeighbour(final_state); @@ -248,7 +248,7 @@ void Planner::SetWayPoints(void) cache_start = 0; } -void Planner::reverse_waypoints(void) +void Planner::reverse_waypoints() { Common::Vec2 tmp; for (int i = 0; i < waypoints / 2; i++) @@ -266,19 +266,19 @@ Common::Vec2 Planner::GetWayPoint(unsigned int i) return Common::Vec2(); } -unsigned int Planner::GetWayPointNum(void) +unsigned int Planner::GetWayPointNum() { return waypoints; } -bool Planner::IsReached(void) +bool Planner::IsReached() { if (final_state.distanceTo(tree.NearestNeighbour(final_state)->state) <= acceptable_dis) return true; return false; } -Common::Vec2 Planner::Plan(void) +Common::Vec2 Planner::Plan() { // return final_state; if (!collisionDetect(init_state, final_state)) @@ -341,7 +341,7 @@ Common::Vec2 Planner::Plan(void) return ans; } -void Planner::optimize_tree(void) +void Planner::optimize_tree() { for (int i = 0; i < GetWayPointNum(); i++) { diff --git a/source/soccer/errt/errt.h b/source/soccer/errt/errt.h index cc5c5845..04d5c18e 100644 --- a/source/soccer/errt/errt.h +++ b/source/soccer/errt/errt.h @@ -12,7 +12,7 @@ class Planner Common::Vec2 waypoint[MAX_NODES]; unsigned int waypoints, cached_waypoints, cache_start; - void reverse_waypoints(void); + void reverse_waypoints(); float field_width; float field_height; @@ -26,24 +26,24 @@ class Planner float waypoint_target_prob; float acceptable_dis; - Planner(void); - ~Planner(void); + Planner(); + ~Planner(); Tree tree; void set_field_params(float _w, float _h); void init(Common::Vec2 init, Common::Vec2 final, float step); - Common::Vec2 random_state(void); + Common::Vec2 random_state(); Common::Vec2 nearest_free(Common::Vec2 state); Common::Vec2 nearest_free_prob(Common::Vec2 state); Common::Vec2 choose_target(int *type = NULL); Node *extend(Node *s, Common::Vec2 &target); - void SetWayPoints(void); + void SetWayPoints(); Common::Vec2 GetWayPoint(unsigned int i); - unsigned int GetWayPointNum(void); - bool IsReached(void); + unsigned int GetWayPointNum(); + bool IsReached(); - void optimize_tree(void); + void optimize_tree(); - Common::Vec2 Plan(void); + Common::Vec2 Plan(); }; } // namespace Tyr::Soccer diff --git a/source/soccer/errt/tree.cpp b/source/soccer/errt/tree.cpp index ecedc5c8..b4e9576b 100644 --- a/source/soccer/errt/tree.cpp +++ b/source/soccer/errt/tree.cpp @@ -2,12 +2,12 @@ namespace Tyr::Soccer { -Tree::Tree(void) +Tree::Tree() { reset(); } -void Tree::reset(void) +void Tree::reset() { nodes_num = 0; } @@ -51,7 +51,7 @@ Node *Tree::NearestNeighbour(Common::Vec2 &s) return &node[ans]; } -unsigned int Tree::tree_size(void) +unsigned int Tree::tree_size() { return nodes_num; } diff --git a/source/soccer/errt/tree.h b/source/soccer/errt/tree.h index becba27e..fdf8f711 100644 --- a/source/soccer/errt/tree.h +++ b/source/soccer/errt/tree.h @@ -18,11 +18,11 @@ class Tree unsigned int nodes_num; public: - Tree(void); - void reset(void); + Tree(); + void reset(); Node *AddNode(Common::Vec2 &s, Node *p); Node *NearestNeighbour(Common::Vec2 &s); - unsigned int tree_size(void); + unsigned int tree_size(); Node *GetNode(unsigned int num); }; } // namespace Tyr::Soccer diff --git a/source/soccer/helpers/manage_att_roles.cpp b/source/soccer/helpers/manage_att_roles.cpp index da1d26d4..2e5891a5 100644 --- a/source/soccer/helpers/manage_att_roles.cpp +++ b/source/soccer/helpers/manage_att_roles.cpp @@ -4,7 +4,7 @@ namespace Tyr::Soccer { static int attackerChangeHys = 0; -void Ai::ManageAttRoles(void) +void Ai::ManageAttRoles() { if (OwnRobot[attack].State.Position.distanceTo(ball.Position) > 600) // Check if the current attacker has lost the ball, before switching its role diff --git a/source/soccer/helpers/strategy_weight.cpp b/source/soccer/helpers/strategy_weight.cpp index 6ac91bcd..096e90a6 100644 --- a/source/soccer/helpers/strategy_weight.cpp +++ b/source/soccer/helpers/strategy_weight.cpp @@ -2,7 +2,7 @@ namespace Tyr::Soccer { -int Ai::strategy_weight(void) +int Ai::strategy_weight() { if (!playBook) { diff --git a/source/soccer/obstacle/obstacle.cpp b/source/soccer/obstacle/obstacle.cpp index 19860293..b12c15ca 100644 --- a/source/soccer/obstacle/obstacle.cpp +++ b/source/soccer/obstacle/obstacle.cpp @@ -7,7 +7,7 @@ namespace Tyr::Soccer { /*bool obs_lut[605][405]; -void clear_map ( void ) +void clear_map () { for ( int i = 0 ; i < 605 ; i ++ ) for ( int j = 0 ; j < 405 ; j ++ ) @@ -66,7 +66,7 @@ void AddRectangle ( int x , int y , int w , int h ) ObsMap map(100); -void clear_map(void) +void clear_map() { map.resetMap(); } diff --git a/source/soccer/obstacle/obstacle.h b/source/soccer/obstacle/obstacle.h index c973ba44..c2b18821 100644 --- a/source/soccer/obstacle/obstacle.h +++ b/source/soccer/obstacle/obstacle.h @@ -6,7 +6,7 @@ namespace Tyr::Soccer { /*bool obs_lut[605][405]; -void clear_map ( void ) +void clear_map () { for ( int i = 0 ; i < 605 ; i ++ ) for ( int j = 0 ; j < 405 ; j ++ ) @@ -50,7 +50,7 @@ void AddCircle ( int x , int y , int r ) } }*/ -void clear_map(void); +void clear_map(); bool IsInObstacle(Common::Vec2 p); bool collisionDetect(Common::Vec2 p1, Common::Vec2 p2); void AddCircle(float x, float y, float r); diff --git a/source/soccer/obstacle/obstacle_map.cpp b/source/soccer/obstacle/obstacle_map.cpp index 024aaed9..7f99618a 100644 --- a/source/soccer/obstacle/obstacle_map.cpp +++ b/source/soccer/obstacle/obstacle_map.cpp @@ -65,7 +65,7 @@ float ObsMap::NearestDistance(float _x, float _y) return dis; } -void ObsMap::resetMap(void) +void ObsMap::resetMap() { for (int i = 0; i < obsNum; i++) { @@ -79,7 +79,7 @@ void ObsMap::resetMap(void) obsNum = 0; } -int ObsMap::getObsNum(void) +int ObsMap::getObsNum() { return obsNum; } diff --git a/source/soccer/obstacle/obstacle_new.h b/source/soccer/obstacle/obstacle_new.h index acc09706..0ab98f42 100644 --- a/source/soccer/obstacle/obstacle_new.h +++ b/source/soccer/obstacle/obstacle_new.h @@ -62,8 +62,8 @@ class ObsMap bool IsInObstacle(float _x, float _y); float NearestDistance(float _x, float _y); - void resetMap(void); + void resetMap(); - int getObsNum(void); + int getObsNum(); }; } // namespace Tyr::Soccer diff --git a/source/soccer/pch.h b/source/soccer/pch.h index 8dd63d68..d740426d 100644 --- a/source/soccer/pch.h +++ b/source/soccer/pch.h @@ -9,19 +9,3 @@ #include #include #include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -#include diff --git a/source/soccer/play_book.cpp b/source/soccer/play_book.cpp index a89c3e1e..123189dd 100644 --- a/source/soccer/play_book.cpp +++ b/source/soccer/play_book.cpp @@ -2,11 +2,10 @@ namespace Tyr::Soccer { -void Ai::InitAIPlayBook(void) +void Ai::InitAIPlayBook() { AIPlayBook.clear(); - AIPlayBook["my_test"] = &Ai::my_test; AIPlayBook["NewNormalPlay"] = &Ai::NewNormalPlay; AIPlayBook["NormalPlayDef"] = &Ai::NormalPlayDef; AIPlayBook["NormalPlayAtt"] = &Ai::NormalPlayAtt; @@ -20,7 +19,6 @@ void Ai::InitAIPlayBook(void) AIPlayBook["penalty_their_simple"] = &Ai::penalty_their_simple; AIPlayBook["corner_their_global"] = &Ai::corner_their_global; - AIPlayBook["tech_khers_pass"] = &Ai::tech_khers_pass; AIPlayBook["our_place_ball_shoot"] = &Ai::our_place_ball_shoot; AIPlayBook["our_place_ball_shoot_V2"] = &Ai::our_place_ball_shoot_V2; AIPlayBook["our_place_ball_shoot_taki"] = &Ai::our_place_ball_shoot_taki; diff --git a/source/soccer/plays/kickoff_us_chip.cpp b/source/soccer/plays/kickoff_us_chip.cpp index 12fad360..c24bb53a 100644 --- a/source/soccer/plays/kickoff_us_chip.cpp +++ b/source/soccer/plays/kickoff_us_chip.cpp @@ -2,7 +2,7 @@ namespace Tyr::Soccer { -void Ai::kickoff_us_chip(void) +void Ai::kickoff_us_chip() { bool canKickBall = bool(currentPlayParam); GKHi(gk, true); diff --git a/source/soccer/plays/normal_play.cpp b/source/soccer/plays/normal_play.cpp index 969b354f..e2cc9313 100644 --- a/source/soccer/plays/normal_play.cpp +++ b/source/soccer/plays/normal_play.cpp @@ -4,7 +4,7 @@ namespace Tyr::Soccer { Common::Timer activeShootTimer_omid; -void Ai::NewNormalPlay(void) +void Ai::NewNormalPlay() { // GKHi(gk, 0); // side = -side; diff --git a/source/soccer/plays/normal_play_att.cpp b/source/soccer/plays/normal_play_att.cpp index 0d00aee1..5b0c6085 100644 --- a/source/soccer/plays/normal_play_att.cpp +++ b/source/soccer/plays/normal_play_att.cpp @@ -4,7 +4,7 @@ namespace Tyr::Soccer { Common::Timer activeShootTimer; -void Ai::NormalPlayAtt(void) +void Ai::NormalPlayAtt() { ManageAttRoles(); // sets the mid1, mid2, attack diff --git a/source/soccer/plays/normal_play_def.cpp b/source/soccer/plays/normal_play_def.cpp index dc77172f..f8e4f689 100644 --- a/source/soccer/plays/normal_play_def.cpp +++ b/source/soccer/plays/normal_play_def.cpp @@ -2,7 +2,7 @@ namespace Tyr::Soccer { -void Ai::NormalPlayDef(void) +void Ai::NormalPlayDef() { ManageAttRoles(); diff --git a/source/soccer/plays/penalty_their_simple.cpp b/source/soccer/plays/penalty_their_simple.cpp index d5892c6c..0673888d 100644 --- a/source/soccer/plays/penalty_their_simple.cpp +++ b/source/soccer/plays/penalty_their_simple.cpp @@ -2,7 +2,7 @@ namespace Tyr::Soccer { -void Ai::penalty_their_simple(void) +void Ai::penalty_their_simple() { float penalty_x = field_width - 85.0; diff --git a/source/soccer/plays/place_ball.cpp b/source/soccer/plays/place_ball.cpp index c3c29eed..f2e44c09 100644 --- a/source/soccer/plays/place_ball.cpp +++ b/source/soccer/plays/place_ball.cpp @@ -4,7 +4,7 @@ namespace Tyr::Soccer { -void Ai::our_place_ball_shoot(void) +void Ai::our_place_ball_shoot() { GKHi(gk, true); @@ -304,7 +304,7 @@ void Ai::our_place_ball_shoot(void) std::cout << "___DIS___" << targetBallPlacement->distanceTo(ball.Position) << std::endl; } -void Ai::our_place_ball_shoot_V2(void) +void Ai::our_place_ball_shoot_V2() { GKHi(gk, true); @@ -757,7 +757,7 @@ void Ai::our_place_ball_shoot_V2(void) Common::logInfo("__OUT__{}", outOfField(ball.Position)); } -void Ai::our_place_ball_shoot_taki(void) +void Ai::our_place_ball_shoot_taki() { GKHi(gk, true); diff --git a/source/soccer/plays/stop.cpp b/source/soccer/plays/stop.cpp index 77366580..7a6ca875 100644 --- a/source/soccer/plays/stop.cpp +++ b/source/soccer/plays/stop.cpp @@ -2,7 +2,7 @@ namespace Tyr::Soccer { -void Ai::Stop(void) +void Ai::Stop() { #if !mark_in_stop for (std::map::const_iterator i = markMap.begin(); i != markMap.end(); ++i) diff --git a/source/soccer/plays/stop_def.cpp b/source/soccer/plays/stop_def.cpp index 4c80be81..3a9488ed 100644 --- a/source/soccer/plays/stop_def.cpp +++ b/source/soccer/plays/stop_def.cpp @@ -2,7 +2,7 @@ namespace Tyr::Soccer { -void Ai::Stop_def(void) +void Ai::Stop_def() { for (std::map::const_iterator i = markMap.begin(); i != markMap.end(); ++i) { diff --git a/source/soccer/plays/strategy_maker.cpp b/source/soccer/plays/strategy_maker.cpp index 051d933f..a65ecae2 100644 --- a/source/soccer/plays/strategy_maker.cpp +++ b/source/soccer/plays/strategy_maker.cpp @@ -59,7 +59,7 @@ static int curr_str_id = -1; bool recievers_reached = false; -void Ai::strategy_maker(void) +void Ai::strategy_maker() { int str_id = int(currentPlayParam); if (timer.time() < 0.5) diff --git a/source/soccer/robot/robot.cpp b/source/soccer/robot/robot.cpp index b3324253..3ebb613f 100644 --- a/source/soccer/robot/robot.cpp +++ b/source/soccer/robot/robot.cpp @@ -51,7 +51,7 @@ float getCalibratedShootPow(int vision_id, float raw_shoot, float coeffs[Common: return calib_shoot; } -Robot::Robot(void) +Robot::Robot() { oldRobot = false; new_comm_ready = false; @@ -211,7 +211,7 @@ void Robot::MoveByMotion(Common::Vec3 motion) } } -void Robot::makeSendingDataReady(void) +void Robot::makeSendingDataReady() { data[0] = this->vision_id; @@ -288,7 +288,7 @@ void Robot::makeSendingDataReady(void) new_comm_ready = true; } -Common::Vec3 Robot::GetCurrentMotionCommand(void) const +Common::Vec3 Robot::GetCurrentMotionCommand() const { const int motion_idx = static_cast(lastCMDs[10].x); return lastCMDs[motion_idx]; diff --git a/source/soccer/robot/robot.h b/source/soccer/robot/robot.h index a1a7df76..68289702 100644 --- a/source/soccer/robot/robot.h +++ b/source/soccer/robot/robot.h @@ -35,7 +35,7 @@ class Robot int remainingPIDParams; float p, i, iMax, torque; - Robot(void); + Robot(); void sendPID(float _p, float _i, float _iMax, float _torque); @@ -64,8 +64,8 @@ class Robot Common::Vec3 ComputeMotionCommand(bool accurate, float speed, VelocityProfile *velocityProfile); - Common::Vec3 GetCurrentMotionCommand(void) const; + Common::Vec3 GetCurrentMotionCommand() const; - void makeSendingDataReady(void); + void makeSendingDataReady(); }; } // namespace Tyr::Soccer diff --git a/source/vision/CMakeLists.txt b/source/vision/CMakeLists.txt index c53e9459..175e7c6a 100644 --- a/source/vision/CMakeLists.txt +++ b/source/vision/CMakeLists.txt @@ -1,20 +1,20 @@ project(${CMAKE_PROJECT_NAME}-vision) set(HEADER_FILES - pch.h - vision.h - kalman/filtered_object.h) + pch.h + vision.h + kalman/filtered_object.h) set(SOURCE_FILES - vision_ball.cpp - vision_comminucation.cpp - vision_param.cpp - vision_robot.cpp - vision.cpp - kalman/filtered_object.cpp) + vision_ball.cpp + vision_comminucation.cpp + vision_param.cpp + vision_robot.cpp + vision.cpp + kalman/filtered_object.cpp) add_library(${PROJECT_NAME} - ${SOURCE_FILES} ${HEADER_FILES}) + ${SOURCE_FILES} ${HEADER_FILES}) target_include_directories(${PROJECT_NAME} INTERFACE "${CMAKE_CURRENT_SOURCE_DIR}") @@ -25,4 +25,9 @@ target_link_libraries(${PROJECT_NAME} PUBLIC set_target_properties(${PROJECT_NAME} PROPERTIES UNITY_BUILD ${USE_UNITY_BUILDS}) -target_precompile_headers(${PROJECT_NAME} PUBLIC pch.h) +get_target_property(COMMON_PCHS ${CMAKE_PROJECT_NAME}-common INTERFACE_PRECOMPILE_HEADERS) + +target_precompile_headers(${PROJECT_NAME} + PUBLIC ${COMMON_PCHS} + PUBLIC pch.h + INTERFACE ${HEADER_FILES}) diff --git a/source/vision/pch.h b/source/vision/pch.h index 6d6b60af..4dda59a6 100644 --- a/source/vision/pch.h +++ b/source/vision/pch.h @@ -4,14 +4,3 @@ #include #include #include - -#include -#include -#include - -#include -#include -#include -#include -#include -#include diff --git a/source/vision/vision.cpp b/source/vision/vision.cpp index e91cb69b..be0df5a8 100644 --- a/source/vision/vision.cpp +++ b/source/vision/vision.cpp @@ -2,7 +2,7 @@ namespace Tyr::Vision { -VisionModule::VisionModule(Common::WorldState *_State) +Vision::Vision(Common::WorldState *_State) { playState = _State; @@ -44,10 +44,10 @@ VisionModule::VisionModule(Common::WorldState *_State) std::cout << "Failed to connect to Vision UDP" << std::endl; } } -VisionModule::~VisionModule() +Vision::~Vision() {} -void VisionModule::recieveAllCameras(void) +void Vision::recieveAllCameras() { if (!isConnected()) { @@ -76,7 +76,7 @@ void VisionModule::recieveAllCameras(void) } } -void VisionModule::ProcessVision() +void Vision::ProcessVision() { ProcessBalls(this->playState); ProcessRobots(this->playState); diff --git a/source/vision/vision.h b/source/vision/vision.h index 3f3fd4a4..41c89e84 100644 --- a/source/vision/vision.h +++ b/source/vision/vision.h @@ -32,32 +32,32 @@ namespace Tyr::Vision { -class VisionModule +class Vision { public: - VisionModule(Common::WorldState *State); - ~VisionModule(); + Vision(Common::WorldState *State); + ~Vision(); - bool recievePacket(void); - bool connectToVisionServer(void); - void recieveAllCameras(void); - void ProcessVision(void); - bool isConnected(void); + bool recievePacket(); + bool connectToVisionServer(); + void recieveAllCameras(); + void ProcessVision(); + bool isConnected(); void ProcessRobots(Common::WorldState *); - int ExtractBlueRobots(void); - int ExtractYellowRobots(void); + int ExtractBlueRobots(); + int ExtractYellowRobots(); int MergeRobots(int num); void FilterRobots(int num, bool own); void predictRobotsForward(Common::WorldState *); void SendStates(Common::WorldState *); void ProcessBalls(Common::WorldState *); - int ExtractBalls(void); + int ExtractBalls(); int MergeBalls(int num); void FilterBalls(int num, Common::WorldState *); void predictBallForward(Common::WorldState *); - void calculateBallHeight(void); + void calculateBallHeight(); void ProcessParam(Common::WorldState *); diff --git a/source/vision/vision_ball.cpp b/source/vision/vision_ball.cpp index 0f80523c..3784c933 100644 --- a/source/vision/vision_ball.cpp +++ b/source/vision/vision_ball.cpp @@ -4,7 +4,7 @@ namespace Tyr::Vision { -void VisionModule::ProcessBalls(Common::WorldState *state) +void Vision::ProcessBalls(Common::WorldState *state) { int balls_num = 0; @@ -23,7 +23,7 @@ void VisionModule::ProcessBalls(Common::WorldState *state) //Common::logDebug("ball pos: {}", state->ball.Position); } -int VisionModule::ExtractBalls(void) +int Vision::ExtractBalls() { int ans = 0; for (int i = 0; i < Common::Setting::kCamCount; i++) @@ -41,7 +41,7 @@ int VisionModule::ExtractBalls(void) } return ans; } -int VisionModule::MergeBalls(int num) +int Vision::MergeBalls(int num) { int balls_num = 0; for (int i = 0; i < num; i++) @@ -70,7 +70,7 @@ int VisionModule::MergeBalls(int num) return balls_num; } -void VisionModule::FilterBalls(int num, Common::WorldState *state) +void Vision::FilterBalls(int num, Common::WorldState *state) { int id = 100; float dis = 214748364.0f; @@ -160,7 +160,7 @@ void VisionModule::FilterBalls(int num, Common::WorldState *state) } } -void VisionModule::predictBallForward(Common::WorldState *state) +void Vision::predictBallForward(Common::WorldState *state) { state->ball.Position.x /= (float) 100.0; state->ball.Position.y /= (float) 100.0; @@ -260,7 +260,7 @@ void VisionModule::predictBallForward(Common::WorldState *state) // } } -void VisionModule::calculateBallHeight(void) +void Vision::calculateBallHeight() { /*const float XO = -1358.2; const float YO = 60.93; diff --git a/source/vision/vision_comminucation.cpp b/source/vision/vision_comminucation.cpp index 6c771cff..ade3359b 100644 --- a/source/vision/vision_comminucation.cpp +++ b/source/vision/vision_comminucation.cpp @@ -2,13 +2,13 @@ namespace Tyr::Vision { -bool VisionModule::connectToVisionServer(void) +bool Vision::connectToVisionServer() { m_visionUDP = std::make_unique(Common::setting().vision_address); return isConnected(); } -bool VisionModule::recievePacket(void) +bool Vision::recievePacket() { if (!isConnected()) return false; @@ -27,7 +27,7 @@ bool VisionModule::recievePacket(void) return false; } -bool VisionModule::isConnected(void) +bool Vision::isConnected() { return m_visionUDP != nullptr && m_visionUDP->isConnected(); } diff --git a/source/vision/vision_param.cpp b/source/vision/vision_param.cpp index 546ae79c..d84906b0 100644 --- a/source/vision/vision_param.cpp +++ b/source/vision/vision_param.cpp @@ -2,7 +2,7 @@ namespace Tyr::Vision { -void VisionModule::ProcessParam(Common::WorldState *state) +void Vision::ProcessParam(Common::WorldState *state) { double avg = 0; int count = 0; diff --git a/source/vision/vision_robot.cpp b/source/vision/vision_robot.cpp index ac096e42..f271be38 100644 --- a/source/vision/vision_robot.cpp +++ b/source/vision/vision_robot.cpp @@ -14,7 +14,7 @@ std::ofstream outfile("outf.txt"); std::ofstream delay_data("delay.txt"); unsigned int fr_num = 0; -void VisionModule::ProcessRobots(Common::WorldState *state) +void Vision::ProcessRobots(Common::WorldState *state) { int robots_num = 0; @@ -52,7 +52,7 @@ void VisionModule::ProcessRobots(Common::WorldState *state) // delay_data << fr_num++ << " " << state->OwnRobot[6].Position.x << " " << state->OwnRobot[6].Position.y << " " << // state->lastCMDS[6][cmdIndex].x << " " << state->lastCMDS[6][cmdIndex].y << std::endl; } -int VisionModule::ExtractBlueRobots(void) +int Vision::ExtractBlueRobots() { int ans = 0; for (int i = 0; i < Common::Setting::kCamCount; i++) @@ -69,7 +69,7 @@ int VisionModule::ExtractBlueRobots(void) return ans; } -int VisionModule::ExtractYellowRobots(void) +int Vision::ExtractYellowRobots() { int ans = 0; for (int i = 0; i < Common::Setting::kCamCount; i++) @@ -86,7 +86,7 @@ int VisionModule::ExtractYellowRobots(void) return ans; } -int VisionModule::MergeRobots(int num) +int Vision::MergeRobots(int num) { int robots_num = 0; for (int i = 0; i < num; i++) @@ -109,7 +109,7 @@ int VisionModule::MergeRobots(int num) return robots_num; } -void VisionModule::FilterRobots(int num, bool own) +void Vision::FilterRobots(int num, bool own) { float filtout[2][2]; float filtpos[2]; @@ -208,7 +208,7 @@ void VisionModule::FilterRobots(int num, bool own) } } -void VisionModule::predictRobotsForward(Common::WorldState *state) +void Vision::predictRobotsForward(Common::WorldState *state) { for (int own = 1; own < 2; own++) { @@ -281,7 +281,7 @@ void VisionModule::predictRobotsForward(Common::WorldState *state) // outfile << robotState[0][1].AngularVelocity << std::endl; } -void VisionModule::SendStates(Common::WorldState *state) +void Vision::SendStates(Common::WorldState *state) { state->ownRobots_num = 0; for (int i = 0; i < Common::Setting::kMaxRobots; i++)