From f91002a1705484dd38ce02fc9af6253426e2db24 Mon Sep 17 00:00:00 2001 From: jvogt23 Date: Mon, 1 Jul 2024 17:07:35 +0000 Subject: [PATCH] automated style fixes --- .../agent/position/overriding_positions.hpp | 44 +++++++++---------- .../agent/position/robot_factory_position.cpp | 28 ++++++------ .../agent/position/robot_factory_position.hpp | 6 +-- soccer/src/soccer/ui/main_window.cpp | 25 ++++++----- soccer/src/soccer/ui/main_window.hpp | 20 +++------ 5 files changed, 59 insertions(+), 64 deletions(-) diff --git a/soccer/src/soccer/strategy/agent/position/overriding_positions.hpp b/soccer/src/soccer/strategy/agent/position/overriding_positions.hpp index 2cb54dafb8..e0effea2a2 100644 --- a/soccer/src/soccer/strategy/agent/position/overriding_positions.hpp +++ b/soccer/src/soccer/strategy/agent/position/overriding_positions.hpp @@ -3,26 +3,26 @@ #include #include -namespace Strategy -{ - /* - OverridingPositions refers to the positions that can be manually set in the UI. - Normally, all robots are set to Auto. If you want to add a new position, add a new value - to this enum before LENGTH, add a string to the overriding_position_labels vector in main_window.hpp, - and add a case to the check_for_position_override method in RobotFactoryPosition. - */ - enum OverridingPositions { - AUTO, - OFFENSE, - DEFENSE, - FREE_KICKER, - PENALTY_PLAYER, - PENALTY_NON_KICKER, - SOLO_OFFENSE, - SMART_IDLE, - ZONER, - IDLE, - LENGTH, //Do not remove - }; +namespace Strategy { +/* + OverridingPositions refers to the positions that can be manually set in the UI. + Normally, all robots are set to Auto. If you want to add a new position, add a new value + to this enum before LENGTH, add a string to the overriding_position_labels vector in + main_window.hpp, and add a case to the check_for_position_override method in + RobotFactoryPosition. +*/ +enum OverridingPositions { + AUTO, + OFFENSE, + DEFENSE, + FREE_KICKER, + PENALTY_PLAYER, + PENALTY_NON_KICKER, + SOLO_OFFENSE, + SMART_IDLE, + ZONER, + IDLE, + LENGTH, // Do not remove +}; -} // namespace Strategy +} // namespace Strategy diff --git a/soccer/src/soccer/strategy/agent/position/robot_factory_position.cpp b/soccer/src/soccer/strategy/agent/position/robot_factory_position.cpp index 232c5c19fb..eec0553f34 100644 --- a/soccer/src/soccer/strategy/agent/position/robot_factory_position.cpp +++ b/soccer/src/soccer/strategy/agent/position/robot_factory_position.cpp @@ -16,11 +16,11 @@ RobotFactoryPosition::RobotFactoryPosition(int r_id) : Position(r_id, "RobotFact current_position_ = std::make_unique(robot_id_); } - std::string node_name {"robot_factory_position_"}; + std::string node_name{"robot_factory_position_"}; _node = std::make_shared(node_name.append(std::to_string(robot_id_))); test_play_sub_ = _node->create_subscription( - "override_position_for_robot", 1, [this](const rj_msgs::msg::OverridePosition::SharedPtr msg){test_play_callback(msg);} - ); + "override_position_for_robot", 1, + [this](const rj_msgs::msg::OverridePosition::SharedPtr msg) { test_play_callback(msg); }); _executor.add_node(_node); _executor_thread = std::thread([this]() { _executor.spin(); }); } @@ -127,10 +127,10 @@ void RobotFactoryPosition::handle_ready() { } void RobotFactoryPosition::update_position() { - //if (test_play_position_ == Strategy::OverridingPositions::OFFENSE) { - // SPDLOG_INFO("OFFENSE SELECTED"); - //set_current_position(); - //return; + // if (test_play_position_ == Strategy::OverridingPositions::OFFENSE) { + // SPDLOG_INFO("OFFENSE SELECTED"); + // set_current_position(); + // return; //} bool manual_position_set = check_for_position_override(); if (manual_position_set) return; @@ -354,18 +354,20 @@ std::string RobotFactoryPosition::get_current_state() { return current_position_->get_current_state(); } -void RobotFactoryPosition::test_play_callback(const rj_msgs::msg::OverridePosition::SharedPtr message) { - if (message->robot_id == this->robot_id_ && message->overriding_position < Strategy::OverridingPositions::LENGTH) { - test_play_position_ = static_cast(message->overriding_position); +void RobotFactoryPosition::test_play_callback( + const rj_msgs::msg::OverridePosition::SharedPtr message) { + if (message->robot_id == this->robot_id_ && + message->overriding_position < Strategy::OverridingPositions::LENGTH) { + test_play_position_ = + static_cast(message->overriding_position); } } /** * Checks test_play_position_, which automatically updates when an override is set. * If it is anything but auto, set the current position to that position and return true. -*/ + */ bool RobotFactoryPosition::check_for_position_override() { - switch (test_play_position_) { case Strategy::OverridingPositions::OFFENSE: { set_current_position(); @@ -398,7 +400,7 @@ bool RobotFactoryPosition::check_for_position_override() { case Strategy::OverridingPositions::ZONER: { set_current_position(); return true; - } + } case Strategy::OverridingPositions::IDLE: { set_current_position(); return true; diff --git a/soccer/src/soccer/strategy/agent/position/robot_factory_position.hpp b/soccer/src/soccer/strategy/agent/position/robot_factory_position.hpp index 5834cc4c77..7ab43a8b3c 100644 --- a/soccer/src/soccer/strategy/agent/position/robot_factory_position.hpp +++ b/soccer/src/soccer/strategy/agent/position/robot_factory_position.hpp @@ -10,9 +10,9 @@ #include #include "game_state.hpp" +#include "overriding_positions.hpp" #include "planning/instant.hpp" #include "position.hpp" -#include "overriding_positions.hpp" #include "rj_common/field_dimensions.hpp" #include "rj_common/time.hpp" #include "rj_constants/constants.hpp" @@ -112,12 +112,12 @@ class RobotFactoryPosition : public Position { private: std::unique_ptr current_position_; - //subscription for test mode - Allows position overriding + // subscription for test mode - Allows position overriding rclcpp::Subscription::SharedPtr test_play_sub_; rclcpp::executors::SingleThreadedExecutor _executor; std::thread _executor_thread; void test_play_callback(const rj_msgs::msg::OverridePosition::SharedPtr message); - Strategy::OverridingPositions test_play_position_ {Strategy::OverridingPositions::AUTO}; + Strategy::OverridingPositions test_play_position_{Strategy::OverridingPositions::AUTO}; rclcpp::Node::SharedPtr _node; std::optional derived_get_task(RobotIntent intent) override; diff --git a/soccer/src/soccer/ui/main_window.cpp b/soccer/src/soccer/ui/main_window.cpp index 26c317b22d..e8d1d9f775 100644 --- a/soccer/src/soccer/ui/main_window.cpp +++ b/soccer/src/soccer/ui/main_window.cpp @@ -187,16 +187,18 @@ MainWindow::MainWindow(Processor* processor, bool has_external_ref, QWidget* par _set_game_settings = _node->create_client( config_server::topics::kGameSettingsSrv); - test_play_pub_ = _node->create_publisher( - "override_position_for_robot", 1); + test_play_pub_ = + _node->create_publisher("override_position_for_robot", 1); _executor.add_node(_node); _executor_thread = std::thread([this]() { _executor.spin(); }); // Connect up all the test position buttons and dropdowns to their listeners for (int i = 0; i < kNumShells; ++i) { - robot_pos_selectors[i] = findChild(QString::fromStdString("robotPosition_" + std::to_string(i))); - position_reset_buttons[i] = findChild(QString::fromStdString("positionReset_" + std::to_string(i))); + robot_pos_selectors[i] = + findChild(QString::fromStdString("robotPosition_" + std::to_string(i))); + position_reset_buttons[i] = + findChild(QString::fromStdString("positionReset_" + std::to_string(i))); } } @@ -1046,14 +1048,14 @@ void MainWindow::on_actionUse_Multiple_Joysticks_toggled(bool value) { void MainWindow::on_goalieID_currentIndexChanged(int value) { update_cache(_game_settings.request_goalie_id, value - 1, &_game_settings_valid); - //This is a convoluted scheme to figure out who the goalie is - //May not be necessary later + // This is a convoluted scheme to figure out who the goalie is + // May not be necessary later QString goalieNum = _ui.goalieID->currentText(); - bool goalieNumIsInt {false}; + bool goalieNumIsInt{false}; int goalieInt = goalieNum.toInt(&goalieNumIsInt); if (goalieNumIsInt) setGoalieDropdown(goalieInt); - else + else setGoalieDropdown(-1); } @@ -1280,10 +1282,10 @@ void MainWindow::onResetButtonClicked(int robot) { } void MainWindow::onPositionDropdownChanged(int robot, int position_number) { - //This is a convoluted scheme to figure out who the goalie is - //May not be necessary later + // This is a convoluted scheme to figure out who the goalie is + // May not be necessary later QString goalieNum = _ui.goalieID->currentText(); - bool goalieNumIsInt {false}; + bool goalieNumIsInt{false}; int goalieInt = goalieNum.toInt(&goalieNumIsInt); if (!goalieNumIsInt || goalieInt != robot) { rj_msgs::msg::OverridePosition message; @@ -1318,4 +1320,3 @@ void MainWindow::populate_override_position_dropdowns() { } } } - diff --git a/soccer/src/soccer/ui/main_window.hpp b/soccer/src/soccer/ui/main_window.hpp index 12413e65da..dd490e6e63 100644 --- a/soccer/src/soccer/ui/main_window.hpp +++ b/soccer/src/soccer/ui/main_window.hpp @@ -6,17 +6,16 @@ #include #include #include -#include #include #include #include #include #include +#include #include #include #include -#include #include "field_view.hpp" #include "game_state.hpp" @@ -314,18 +313,11 @@ private Q_SLOTS: rj_msgs::msg::GameSettings _game_settings; bool _game_settings_valid = false; - std::vector overriding_position_labels { - "Auto", - "Offense", - "Defense", - "Free Kicker", - "Penalty Player", - "Penalty Non-Kicker", - "Solo Offense", - "Smart Idle", - "Zoner", - "Idle" - }; + std::vector overriding_position_labels{"Auto", "Offense", + "Defense", "Free Kicker", + "Penalty Player", "Penalty Non-Kicker", + "Solo Offense", "Smart Idle", + "Zoner", "Idle"}; void populate_override_position_dropdowns(); };