From 74436879b6fc630f5af2328c6b5aa6cbe9bf9582 Mon Sep 17 00:00:00 2001 From: sdhanyamraju6 Date: Sun, 9 Nov 2025 21:20:08 -0500 Subject: [PATCH 1/8] initial waller coordinator --- src/rj_msgs/msg/Waller.msg | 3 + src/rj_msgs/srv/Waller.srv | 5 + .../rj_strategy/coordinator/waller.hpp | 38 ++++ .../rj_strategy/coordinator/waller_client.hpp | 74 ++++++++ src/rj_strategy/src/coordinator/waller.cpp | 62 +++++++ .../src/coordinator/waller_client.cpp | 166 ++++++++++++++++++ 6 files changed, 348 insertions(+) create mode 100644 src/rj_msgs/msg/Waller.msg create mode 100644 src/rj_msgs/srv/Waller.srv create mode 100644 src/rj_strategy/include/rj_strategy/coordinator/waller.hpp create mode 100644 src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp create mode 100644 src/rj_strategy/src/coordinator/waller.cpp create mode 100644 src/rj_strategy/src/coordinator/waller_client.cpp diff --git a/src/rj_msgs/msg/Waller.msg b/src/rj_msgs/msg/Waller.msg new file mode 100644 index 0000000000..a58613731e --- /dev/null +++ b/src/rj_msgs/msg/Waller.msg @@ -0,0 +1,3 @@ +# This is a message for the waller coordinator +uint8[16] wall_list # Sorted IDs of robots on the wall +uint8 wall_size # Number of robots on the wall \ No newline at end of file diff --git a/src/rj_msgs/srv/Waller.srv b/src/rj_msgs/srv/Waller.srv new file mode 100644 index 0000000000..d2c40501cd --- /dev/null +++ b/src/rj_msgs/srv/Waller.srv @@ -0,0 +1,5 @@ +# Request a robot to be added to or removed from the waller selection group +uint8 robot_id # ID of the robot (0 to kNumShells-1) +bool joining # True to add robot to waller group, false to remove it +--- +bool success # True if the ACTION succeded (True for joining means successfully joined, for leaving means successfully left) \ No newline at end of file diff --git a/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp b/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp new file mode 100644 index 0000000000..40ff022b39 --- /dev/null +++ b/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp @@ -0,0 +1,38 @@ +#pragma + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "rj_strategy/coordinator.hpp" + +namespace strategy { + +class Waller + : public Coordinator { +public: + Waller(); + ~Waller() override = default; + Waller(const Waller&) = delete; + Waller& operator=(const Waller&) = delete; + Waller(Waller&&) = delete; + Waller& operator=(Waller&&) = delete; + + void service_callback(RequestPtr request, ResponsePtr response); +private: + std::array walling_robots_; + u_int8_t num_wallers_ = 0; + WorldState last_world_state_; + rclcpp::Subscription::SharedPtr world_state_sub_; + static constexpr int kMaxWallers = 4; + + void update_wallers(); +}; + +} // namespace strategy \ No newline at end of file diff --git a/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp b/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp new file mode 100644 index 0000000000..b04913c921 --- /dev/null +++ b/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp @@ -0,0 +1,74 @@ +#pragma once + +#include + +#include +#include + +#include +#include +#include + +#include "rj_strategy/coordinator/waller.hpp" + +namespace strategy { + +/** + * @brief Client for interacting with the Waller coordinator. + * + * Manages membership in the waller group and tracks the currently waller list. + */ +class WallerClient { +public: + struct Result { + bool success{false}; + }; + + using StatusCallback = std::function; + + explicit WallerClient(rclcpp::Node::SharedPtr node, uint8_t robot_id); + ~WallerClient() = default; + WallerClient(const WallerClient&) = delete; + WallerClient& operator=(const WallerClient&) = delete; + WallerClient(WallerClient&&) = delete; + WallerClient& operator=(WallerClient&&) = delete; + + /** + * @brief Join the waller group. + * @param callback Called with current membership status after attempt to join. + */ + void join_group(StatusCallback callback = nullptr); + + /** + * @brief Leave the waller group. + * @param callback Called with current membership status after attempt to leave. + */ + void leave_group(StatusCallback callback = nullptr); + + /** + * @brief Check if this robot is a member of the waller group. + */ + [[nodiscard]] bool am_i_member() const; + + /** + * @brief Get the target walling point + * @return target walling point of this robot. + */ + [[nodiscard]] std::optional get_walling_point(const WorldState* world_state, + FieldDimensions field_dimensions) const; + +private: + rclcpp::Node::SharedPtr node_; + const uint8_t robot_id_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members) -- class + // isn't move/copy-able anyway + rclcpp::Client::SharedPtr client_; + rclcpp::Subscription::SharedPtr subscription_; + + bool am_i_member_ = false; + std::array walling_robots_; + int num_wallers_ = 0; + + static constexpr double kRobotDiameterMultiplier = 1.5; +}; + +} // namespace strategy \ No newline at end of file diff --git a/src/rj_strategy/src/coordinator/waller.cpp b/src/rj_strategy/src/coordinator/waller.cpp new file mode 100644 index 0000000000..4a99bc25f6 --- /dev/null +++ b/src/rj_strategy/src/coordinator/waller.cpp @@ -0,0 +1,62 @@ +#include "rj_strategy/coordinator/waller.hpp" + +namespace strategy { + +Waller::Waller() + : Coordinator("waller_srv", "waller_data", "waller_node") { + walling_robots_.fill(-1); + world_state_sub_ = this->create_subscription( + vision_filter::topics::kWorldStateTopic, rclcpp::QoS(1), + [this](rj_msgs::msg::WorldState::SharedPtr world_state) { // NOLINT + last_world_state_ = rj_convert::convert_from_ros(*world_state); + update_wallers(); + }); +} + +void Waller::service_callback(RequestPtr request, ResponsePtr response) { + if (request->joining) { + if (num_wallers_ == kMaxWallers) { + response->success = false; + } else { + if (std::find(walling_robots_.begin(), walling_robots_.end(), request->robot_id) != walling_robots_.end()) { + walling_robots_[num_wallers_] = request->robot_id; + num_wallers_++; + update_wallers(); + } + response->success = true; + } + } else { + auto it = std::find(walling_robots_.begin(), walling_robots_.end(), request->robot_id); + if (it != walling_robots_.end()) { + *it = -1; + num_wallers_--; + response->success = true; + update_wallers(); + } else { + response->success = false; + } + } +} + +void Waller::update_wallers() { + auto prev_wallers = walling_robots_; + std::sort(walling_robots_.begin(), walling_robots_.end()); + auto must_republish = false; + for (int i = 0; i < num_wallers_ && !must_republish; i++) { + if (prev_wallers[i] != walling_robots_[i]) must_republish = true; + } + + if (must_republish) { + publisher_->publish(rj_msgs::msg::Waller().set__wall_list(walling_robots_).set__wall_size(num_wallers_)); + } +} + +} // namespace strategy + +int main(int argc, char** argv) { + rclcpp::init(argc, argv); + auto node = std::make_shared(); + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; +} \ No newline at end of file diff --git a/src/rj_strategy/src/coordinator/waller_client.cpp b/src/rj_strategy/src/coordinator/waller_client.cpp new file mode 100644 index 0000000000..7e877ada3a --- /dev/null +++ b/src/rj_strategy/src/coordinator/waller_client.cpp @@ -0,0 +1,166 @@ +#include "rj_strategy/coordinator/waller_client.hpp" + +namespace strategy { + +WallerClient::WallerClient(rclcpp::Node::SharedPtr node, uint8_t robot_id) : node_{std::move(node)}, robot_id_{robot_id} { + client_ = node_->create_client("waller_srv"); + walling_robots_.fill(-1); +} + +void WallerClient::join_group(StatusCallback callback) { + if (am_i_member_) { + return; + } + + if (!client_->wait_for_service(std::chrono::seconds(1))) { + SPDLOG_ERROR("Waller service not available."); + if (callback) { + callback(Result{false}); + } + return; + } + + auto request = std::make_shared(); + request->robot_id = robot_id_; + request->joining = true; + + client_->async_send_request(request, [this, callback = std::move(callback)]( + rclcpp::Client::SharedFuture future) { // 6 NOLINT(performance-unnecessary-value-param) -- + // ROS2 async callbacks require value capture. + if (!future.valid() || !future.get()->success) { + if (callback) { + callback(Result{false}); + } + } + + am_i_member_ = true; + + subscription_ = node_->create_subscription( + "waller_data", rclcpp::QoS(1).transient_local(), + [this, callback = std::move(callback)] + (const rj_msgs::msg::Waller::SharedPtr msg) { + walling_robots_ = msg->wall_list; + num_wallers_ = msg->wall_size; + + if (callback) { + callback(Result{true}); + } + } + ); + + } + ); +} + +void WallerClient::leave_group(StatusCallback callback) { + if (!am_i_member_) { + if (callback) { + callback(Result{false}); + } + return; + } + + auto request = std::make_shared(); + request->robot_id = robot_id_; + request->joining = false; + + client_->async_send_request( + request, [this, callback = std::move(callback)]( + rclcpp::Client::SharedFuture + future) { // 6 NOLINT(performance-unnecessary-value-param) -- + // ROS2 async callbacks require value capture. + if (!future.valid() || !future.get()->success) { + if (callback) { + callback(Result{false}); + } + return; + } + + am_i_member_ = false; + + subscription_.reset(); + walling_robots_.fill(-1); + num_wallers_ = 0; + + if (callback) { + callback(Result{false}); + } + }); +} + +bool WallerClient::am_i_member() const { return am_i_member_; } + +std::optional WallerClient::get_walling_point(const WorldState* world_state, + FieldDimensions field_dimensions) const { + if (!am_i_member_) return nullopt; + + // Creates Minimum wall radius is slightly greater than box bounds + // Dimension accessors should be edited when we figure out how we are doing dimensions realtime + // from vision + float box_w{field_dimensions.penalty_long_dist()}; + float box_h{field_dimensions.penalty_short_dist()}; + float line_w{field_dimensions.line_width()}; + double min_wall_rad{(kRobotRadius * 4.0f) + line_w + + hypot(static_cast(box_w) / 2, static_cast((box_h)))}; + + auto ball_pos = world_state->ball.position; + + auto robot_pos = world_state->get_robot(true, robot_id_).pose.position(); + auto goal_pos = rj_geometry::Point{0, 0}; + + // Find ball_direction unit vector + rj_geometry::Point ball_dir_vector{(ball_pos - goal_pos)}; + + ball_dir_vector = ball_dir_vector.normalized(); + + // Find target Point + rj_geometry::Point mid_point{(goal_pos) + (ball_dir_vector * min_wall_rad)}; + + auto wall_spacing = kRobotDiameterMultiplier * kRobotDiameter + kBallRadius; + + auto it = std::find(walling_robots_.begin(), walling_robots_.end(), robot_id_); + if (it == walling_robots_.end()) return std::nullopt; + auto waller_pos = std::distance(walling_robots_.begin(), it); + + rj_geometry::Point target_point{}; + auto angle = (mid_point - goal_pos).angle(); + auto delta_angle = (wall_spacing * (waller_pos - num_wallers_ / 2. - 0.5)) / min_wall_rad; + auto target_angle = angle - delta_angle; + + target_point = + (goal_pos + rj_geometry::Point{1, 0}).normalized(min_wall_rad).rotated(target_angle); + + if (abs(robot_pos.dist_to(goal_pos) - min_wall_rad) < kRobotRadius && + robot_pos.dist_to(target_point) > kRobotRadius) { + uint8_t parent_id = + [&]() { // Assigning a value to avoid any undefined behavior; will be changed + if (target_point.x() < robot_pos.x() && waller_pos > 1 && + waller_pos <= num_wallers_) { + return static_cast(walling_robots_[waller_pos - 2]); + } else if (target_point.x() >= robot_pos.x() && waller_pos >= 1 && + waller_pos < num_wallers_) { + return static_cast(walling_robots_[waller_pos]); + } else { + return static_cast(robot_id_); + } + }(); + + if ((target_point.x() < robot_pos.x() && waller_pos != 1) || + (target_point.x() > robot_pos.x() && waller_pos != num_wallers_)) { + auto parent_point = world_state->get_robot(true, parent_id).pose.position(); + angle = (parent_point - goal_pos).angle(); + delta_angle = wall_spacing / min_wall_rad; + target_angle = + angle + delta_angle * (signbit(target_point.x() - robot_pos.x()) ? -1 : 1); + + target_point = (goal_pos + rj_geometry::Point{1, 0}) + .normalized(min_wall_rad) + .rotated(target_angle); + } + } + + return target_point; +} + + +} // namespace strategy From f54f23fd6d442abe2a5c7c8dc0df0b16a5bf4d8e Mon Sep 17 00:00:00 2001 From: sdhanyamraju6 Date: Tue, 18 Nov 2025 21:56:06 -0500 Subject: [PATCH 2/8] temp waller --- install/setup.bash | 2 +- install/setup.zsh | 2 +- launch/soccer.launch.py | 7 + src/rj_msgs/CMakeLists.txt | 2 + src/rj_strategy/CMakeLists.txt | 21 ++- .../include/rj_strategy/agent/position.hpp | 2 + .../rj_strategy/agent/position/defense.hpp | 48 +----- .../rj_strategy/agent/position/waller.hpp | 49 ------ .../rj_strategy/coordinator/waller.hpp | 5 +- .../rj_strategy/coordinator/waller_client.hpp | 1 + .../src/agent/position/defense.cpp | 152 ++---------------- .../agent/position/robot_factory_position.cpp | 2 + src/rj_strategy/src/agent/position/waller.cpp | 86 ---------- src/rj_strategy/src/coordinator/waller.cpp | 6 +- .../src/coordinator/waller_client.cpp | 7 +- 15 files changed, 62 insertions(+), 330 deletions(-) delete mode 100644 src/rj_strategy/include/rj_strategy/agent/position/waller.hpp delete mode 100644 src/rj_strategy/src/agent/position/waller.cpp diff --git a/install/setup.bash b/install/setup.bash index da36e7c200..10ea0f7c07 100644 --- a/install/setup.bash +++ b/install/setup.bash @@ -28,4 +28,4 @@ COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null _colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash" unset COLCON_CURRENT_PREFIX -unset _colcon_prefix_chain_bash_source_script \ No newline at end of file +unset _colcon_prefix_chain_bash_source_script diff --git a/install/setup.zsh b/install/setup.zsh index a1ba46044b..54799fde6f 100644 --- a/install/setup.zsh +++ b/install/setup.zsh @@ -28,4 +28,4 @@ COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && p _colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh" unset COLCON_CURRENT_PREFIX -unset _colcon_prefix_chain_zsh_source_script \ No newline at end of file +unset _colcon_prefix_chain_zsh_source_script diff --git a/launch/soccer.launch.py b/launch/soccer.launch.py index f8f992d0f8..646f0a80a6 100644 --- a/launch/soccer.launch.py +++ b/launch/soccer.launch.py @@ -237,6 +237,13 @@ def generate_launch_description(): output="screen", parameters=[param_config_filepath], on_exit=Shutdown(), + ), + Node( + package="rj_strategy", + executable="waller_node", + output="screen", + parameters=[param_config_filepath], + on_exit=Shutdown(), ) ] ) diff --git a/src/rj_msgs/CMakeLists.txt b/src/rj_msgs/CMakeLists.txt index 8d7117d82f..32ba6aa23b 100644 --- a/src/rj_msgs/CMakeLists.txt +++ b/src/rj_msgs/CMakeLists.txt @@ -59,6 +59,7 @@ rosidl_generate_interfaces( # Coordinators msg/KickerPicker.msg + msg/Waller.msg # Agent Request Messages request/JoinWallRequest.msg @@ -84,6 +85,7 @@ rosidl_generate_interfaces( # Services srv/AgentCommunication.srv srv/KickerPicker.srv + srv/Waller.srv srv/ListJoysticks.srv srv/PlanHypotheticalPath.srv srv/QuickCommands.srv diff --git a/src/rj_strategy/CMakeLists.txt b/src/rj_strategy/CMakeLists.txt index b00d47d05a..e8c1758dda 100644 --- a/src/rj_strategy/CMakeLists.txt +++ b/src/rj_strategy/CMakeLists.txt @@ -56,7 +56,6 @@ set(RJ_STRATEGY_SRC src/agent/position/seeker.cpp src/agent/position/smartidling.cpp src/agent/position/solo_offense.cpp - src/agent/position/waller.cpp src/agent/position/zoner.cpp # Communication @@ -64,6 +63,7 @@ set(RJ_STRATEGY_SRC # Coordinators src/coordinator/kicker_picker_client.cpp + src/coordinator/waller_client.cpp ) # rj_strategy library @@ -115,6 +115,23 @@ ament_target_dependencies(kicker_picker_node ${RJ_STRATEGY_DEPS} ) +# Waller Node +add_executable(waller_node + ${RJ_STRATEGY_SRC} + src/coordinator/waller_client.cpp + src/coordinator/waller.cpp +) + +target_include_directories(waller_node + PUBLIC + $ + $ +) + +ament_target_dependencies(waller_node + ${RJ_STRATEGY_DEPS} +) + # Agent Action Clients add_executable(agent_action_clients ${RJ_STRATEGY_SRC} @@ -146,7 +163,7 @@ install( ) install( - TARGETS straight_line_test_node kicker_picker_node agent_action_clients + TARGETS straight_line_test_node kicker_picker_node waller_node agent_action_clients DESTINATION lib/${PROJECT_NAME} ) diff --git a/src/rj_strategy/include/rj_strategy/agent/position.hpp b/src/rj_strategy/include/rj_strategy/agent/position.hpp index e384a74ce6..900e4eea55 100644 --- a/src/rj_strategy/include/rj_strategy/agent/position.hpp +++ b/src/rj_strategy/include/rj_strategy/agent/position.hpp @@ -42,6 +42,7 @@ // Coordinators #include "rj_strategy/coordinator/kicker_picker_client.hpp" +#include "rj_strategy/coordinator/waller_client.hpp" // tell compiler this class exists, but no need to import the whole header class AgentActionClient; @@ -51,6 +52,7 @@ namespace strategy { // Client Handles for coordinators struct ClientHandles { std::unique_ptr kicker_picker; + std::unique_ptr waller; }; /* diff --git a/src/rj_strategy/include/rj_strategy/agent/position/defense.hpp b/src/rj_strategy/include/rj_strategy/agent/position/defense.hpp index 280ba778a9..e842c82bdd 100644 --- a/src/rj_strategy/include/rj_strategy/agent/position/defense.hpp +++ b/src/rj_strategy/include/rj_strategy/agent/position/defense.hpp @@ -17,7 +17,6 @@ #include "rj_strategy/agent/position.hpp" #include "rj_strategy/agent/position/marker.hpp" -#include "rj_strategy/agent/position/waller.hpp" namespace strategy { @@ -72,54 +71,9 @@ class Defense : public Position { }; State update_state(); - + State current_state_ = IDLING; std::optional state_to_task(RobotIntent intent); - /** - * @brief Sends a JoinWallRequest in broadcast to the other robots - */ - void send_join_wall_request(); - - /** - * @brief Sends a LeaveWallRequest to each of the robots in walling_robots_. - */ - void send_leave_wall_request(); - - /** - * @brief Adds the new waller to this robot's list of wallers and updates this robot's position - * in the wall. - * - * @param join_request the request received from another robot about joining the wall - * @return communication::JoinWallResponse A confirmation for the other robot to join the wall - * with this robot's ID - */ - communication::JoinWallResponse handle_join_wall_request( - communication::JoinWallRequest join_request); - - /** - * @brief Removes a given robot from this robot's list of wallers. - * - * @param leave_request the request from the robot who is leaving the wall - * @return communication::Acknowledge acknowledgement of the other robot's communication - */ - communication::Acknowledge handle_leave_wall_request( - communication::LeaveWallRequest leave_request); - - /** - * @brief Handles the response from the currently walling robots to find this robot's place in - * the wall. - * - * @param join_response the response from another robot that this robot can join the wall - */ - void handle_join_wall_response(communication::JoinWallResponse join_response); - - std::vector walling_robots_ = {}; - int waller_id_ = -1; - - // current state of the defense agent (state machine) - int get_waller_id(); - State current_state_ = JOINING_WALL; - int get_marker_target_id(); Marker marker_; }; diff --git a/src/rj_strategy/include/rj_strategy/agent/position/waller.hpp b/src/rj_strategy/include/rj_strategy/agent/position/waller.hpp deleted file mode 100644 index 70400725f9..0000000000 --- a/src/rj_strategy/include/rj_strategy/agent/position/waller.hpp +++ /dev/null @@ -1,49 +0,0 @@ -#pragma once - -#include - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include - -#include "rj_strategy/agent/position.hpp" -#include "rj_strategy/agent/position/role_interface.hpp" - -namespace strategy { - -/* - * The Waller role provides the implementation for a defensive robot that implements - * this class to have a waller-like behavior where it aims to serve as a wall between - * the ball and the goal. - */ -class Waller : public RoleInterface { -public: - Waller(int waller_num, std::vector walling_robots); - ~Waller() = default; - - /** - * @brief Returns a waller behavior which aims to intercept the path - * between the ball and the center of the goal - * - * @param [RobotIntent intent] [RobotIntent of the Defensive Robot] - * @return [RobotIntent with next target point for the robot] - */ - std::optional get_task(RobotIntent intent, const WorldState* world_state, - FieldDimensions field_dimensions) override; - -private: - std::string defense_type_; - int waller_pos_; - static constexpr double kRobotDiameterMultiplier = 1.5; - std::vector walling_robots_; -}; - -} // namespace strategy diff --git a/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp b/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp index 40ff022b39..5a9958c262 100644 --- a/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp +++ b/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp @@ -1,7 +1,10 @@ -#pragma +#pragma once #include +#include +#include + #include #include #include diff --git a/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp b/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp index b04913c921..d6763e2592 100644 --- a/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp +++ b/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp @@ -65,6 +65,7 @@ class WallerClient { rclcpp::Subscription::SharedPtr subscription_; bool am_i_member_ = false; + bool request_pending_ = false; std::array walling_robots_; int num_wallers_ = 0; diff --git a/src/rj_strategy/src/agent/position/defense.cpp b/src/rj_strategy/src/agent/position/defense.cpp index eb80336a45..1da25f015d 100644 --- a/src/rj_strategy/src/agent/position/defense.cpp +++ b/src/rj_strategy/src/agent/position/defense.cpp @@ -6,13 +6,10 @@ Defense::Defense(int r_id) : Position(r_id, "Defense"), marker_{field_dimensions Defense::Defense(Position&& other) : Position{std::move(other)}, marker_{field_dimensions_} { position_name_ = "Defense"; - walling_robots_ = {}; } std::optional Defense::derived_get_task(RobotIntent intent) { - // SPDLOG_INFO("waller length (sus) {}, {}", walling_robots_.size(), robot_id_); current_state_ = update_state(); - // waller_id_ = get_waller_id(); return state_to_task(intent); } @@ -29,31 +26,21 @@ Defense::State Defense::update_state() { rj_geometry::Point ball_position = world_state->ball.position; double distance_to_ball = robot_position.dist_to(ball_position); - if (current_state_ != WALLING && current_state_ != JOINING_WALL && waller_id_ != -1) { - send_leave_wall_request(); - walling_robots_ = {(u_int8_t)robot_id_}; - waller_id_ = -1; + if (current_state_ != WALLING && current_state_ != JOINING_WALL) { + client_handles_->waller->leave_group(); } switch (current_state_) { case IDLING: + next_state = JOINING_WALL; break; case JOINING_WALL: - send_join_wall_request(); - // SPDLOG_INFO("join wall {}", robot_id_); - next_state = WALLING; - walling_robots_ = {(u_int8_t)robot_id_}; + client_handles_->waller->join_group([this](WallerClient::Result result) { + if (result.success) current_state_ = WALLING; + else current_state_ = ENTERING_MARKING; + }); break; case WALLING: - // If a wall is already full, - // Remove the robot with the highest ID from a wall - // and make them a marker instead. - if (walling_robots_.size() > kMaxWallers && - this->robot_id_ == *max_element(walling_robots_.begin(), walling_robots_.end())) { - send_leave_wall_request(); - // SPDLOG_INFO("leave wall {}", robot_id_); - next_state = ENTERING_MARKING; - } break; case SEARCHING: break; @@ -97,9 +84,6 @@ Defense::State Defense::update_state() { } std::optional Defense::state_to_task(RobotIntent intent) { - // if (robot_id_ == 2) { - // SPDLOG_INFO("{} current state of 2", current_state_); - // } if (current_state_ == IDLING) { auto empty_motion_cmd = planning::MotionCommand{}; intent.motion_command = empty_motion_cmd; @@ -142,10 +126,13 @@ std::optional Defense::state_to_task(RobotIntent intent) { intent.is_active = true; return intent; } else if (current_state_ == WALLING) { - if (!walling_robots_.empty() && waller_id_ != -1) { - Waller waller{waller_id_, walling_robots_}; - return waller.get_task(intent, last_world_state_, this->field_dimensions_); + auto walling_point = client_handles_->waller->get_walling_point(last_world_state_, field_dimensions_); + if (walling_point) { + planning::LinearMotionInstant target{walling_point.value()}; + intent.motion_command = planning::MotionCommand{"path_target", target, planning::FaceBall{}}; } + else intent.motion_command = planning::MotionCommand{}; + return intent; } else if (current_state_ == FACING) { rj_geometry::Point robot_position = last_world_state_->get_robot(true, robot_id_).pose.position(); @@ -172,17 +159,6 @@ std::optional Defense::state_to_task(RobotIntent intent) { void Defense::receive_communication_response(communication::AgentPosResponseWrapper response) { // Call to super Position::receive_communication_response(response); - - // Handle join wall response - if (const communication::JoinWallRequest* join_request = - std::get_if(&response.associated_request)) { - for (communication::AgentResponseVariant response : response.responses) { - if (const communication::JoinWallResponse* join_response = - std::get_if(&response)) { - handle_join_wall_response(*join_response); - } - } - } } communication::PosAgentResponseWrapper Defense::receive_communication_request( @@ -191,106 +167,10 @@ communication::PosAgentResponseWrapper Defense::receive_communication_request( communication::PosAgentResponseWrapper response = Position::receive_communication_request(request); - // Handle join and leave wall request - if (const communication::JoinWallRequest* join_request = - std::get_if(&request.request)) { - response.response = handle_join_wall_request(*join_request); - } else if (const communication::LeaveWallRequest* leave_request = - std::get_if(&request.request)) { - response.response = handle_leave_wall_request(*leave_request); - } - // Return the response return response; } -void Defense::send_join_wall_request() { - communication::JoinWallRequest join_request{}; - join_request.robot_id = robot_id_; - communication::generate_uid(join_request); - - communication::PosAgentRequestWrapper communication_request{}; - communication_request.request = join_request; - communication_request.target_agents = {}; - communication_request.urgent = false; - communication_request.broadcast = true; - - communication_requests_.push_back(communication_request); - - current_state_ = WALLING; -} - -void Defense::send_leave_wall_request() { - communication::LeaveWallRequest leave_request{}; - leave_request.robot_id = robot_id_; - communication::generate_uid(leave_request); - - communication::PosAgentRequestWrapper communication_request{}; - communication_request.request = leave_request; - communication_request.target_agents = walling_robots_; - communication_request.urgent = true; - communication_request.broadcast = false; - - communication_requests_.push_back(communication_request); -} - -communication::JoinWallResponse Defense::handle_join_wall_request( - communication::JoinWallRequest join_request) { - for (size_t i = 0; i < walling_robots_.size(); i++) { - if (walling_robots_[i] == join_request.robot_id) { - break; - } else if (walling_robots_[i] > join_request.robot_id) { - walling_robots_.insert(walling_robots_.begin() + i, join_request.robot_id); - waller_id_ = get_waller_id(); - break; - } else if (i == walling_robots_.size() - 1) { - walling_robots_.push_back(join_request.robot_id); - waller_id_ = get_waller_id(); - } - } - - communication::JoinWallResponse join_response{}; - join_response.robot_id = robot_id_; - communication::generate_uid(join_response); - - return join_response; -} - -communication::Acknowledge Defense::handle_leave_wall_request( - communication::LeaveWallRequest leave_request) { - if (robot_id_ != leave_request.robot_id) { - for (int i = walling_robots_.size() - 1; i > 0; i--) { - if (walling_robots_[i] == leave_request.robot_id) { - walling_robots_.erase(walling_robots_.begin() + i); - waller_id_ = get_waller_id(); - break; - } else if (walling_robots_[i] < leave_request.robot_id) { - break; - } - } - } - - communication::Acknowledge acknowledge_response{}; - communication::generate_uid(acknowledge_response); - - return acknowledge_response; -} - -void Defense::handle_join_wall_response(communication::JoinWallResponse join_response) { - for (size_t i = 0; i < walling_robots_.size(); i++) { - if (walling_robots_[i] == join_response.robot_id) { - return; - } else if (walling_robots_[i] > join_response.robot_id) { - walling_robots_.insert(walling_robots_.begin() + i, join_response.robot_id); - waller_id_ = get_waller_id(); - return; - } else if (i == walling_robots_.size() - 1) { - walling_robots_.push_back(join_response.robot_id); - waller_id_ = get_waller_id(); - } - } -} - void Defense::derived_acknowledge_pass() { current_state_ = FACING; } void Defense::derived_pass_ball() { current_state_ = PASSING; } @@ -300,14 +180,10 @@ void Defense::derived_acknowledge_ball_in_transit() { chasing_ball = false; } -int Defense::get_waller_id() { - return find(walling_robots_.begin(), walling_robots_.end(), robot_id_) - - walling_robots_.begin() + 1; -} void Defense::die() { if (current_state_ == WALLING) { - send_leave_wall_request(); + client_handles_->waller->leave_group(); } } diff --git a/src/rj_strategy/src/agent/position/robot_factory_position.cpp b/src/rj_strategy/src/agent/position/robot_factory_position.cpp index 350c8653ce..6de6e7d21c 100644 --- a/src/rj_strategy/src/agent/position/robot_factory_position.cpp +++ b/src/rj_strategy/src/agent/position/robot_factory_position.cpp @@ -5,6 +5,8 @@ namespace strategy { RobotFactoryPosition::RobotFactoryPosition(int r_id, rclcpp::Node::SharedPtr node) : Position(r_id, "RobotFactoryPosition") { client_handles_->kicker_picker = std::make_unique(node, r_id); + client_handles_->waller = std::make_unique(node, r_id); + if (robot_id_ == 0) { current_position_ = std::make_unique(robot_id_); } else if (robot_id_ == 1 || robot_id_ == 2) { diff --git a/src/rj_strategy/src/agent/position/waller.cpp b/src/rj_strategy/src/agent/position/waller.cpp deleted file mode 100644 index 76f364a346..0000000000 --- a/src/rj_strategy/src/agent/position/waller.cpp +++ /dev/null @@ -1,86 +0,0 @@ -#include "rj_strategy/agent/position/waller.hpp" - -namespace strategy { - -Waller::Waller(int waller_num, std::vector walling_robots) { - defense_type_ = "Waller"; - waller_pos_ = waller_num; - walling_robots_ = walling_robots; -} - -std::optional Waller::get_task(RobotIntent intent, const WorldState* world_state, - FieldDimensions field_dimensions) { - // Creates Minimum wall radius is slightly greater than box bounds - // Dimension accessors should be edited when we figure out how we are doing dimensions realtime - // from vision - float box_w{field_dimensions.penalty_long_dist()}; - float box_h{field_dimensions.penalty_short_dist()}; - float line_w{field_dimensions.line_width()}; - double min_wall_rad{(kRobotRadius * 4.0f) + line_w + - hypot(static_cast(box_w) / 2, static_cast((box_h)))}; - - auto ball_pos = world_state->ball.position; - - auto robot_id = intent.robot_id; - - auto robot_pos = world_state->get_robot(true, robot_id).pose.position(); - auto goal_pos = rj_geometry::Point{0, 0}; - auto num_wallers = walling_robots_.size(); - - // Find ball_direction unit vector - rj_geometry::Point ball_dir_vector{(ball_pos - goal_pos)}; - - ball_dir_vector = ball_dir_vector.normalized(); - - // Find target Point - rj_geometry::Point mid_point{(goal_pos) + (ball_dir_vector * min_wall_rad)}; - - auto wall_spacing = kRobotDiameterMultiplier * kRobotDiameter + kBallRadius; - - rj_geometry::Point target_point{}; - auto angle = (mid_point - goal_pos).angle(); - auto delta_angle = (wall_spacing * (waller_pos_ - num_wallers / 2. - 0.5)) / min_wall_rad; - auto target_angle = angle - delta_angle; - - target_point = - (goal_pos + rj_geometry::Point{1, 0}).normalized(min_wall_rad).rotated(target_angle); - - if (abs(robot_pos.dist_to(goal_pos) - min_wall_rad) < kRobotRadius && - robot_pos.dist_to(target_point) > kRobotRadius) { - uint8_t parent_id = - [&]() { // Assigning a value to avoid any undefined behavior; will be changed - if (target_point.x() < robot_pos.x() && waller_pos_ > 1 && - waller_pos_ <= num_wallers) { - return static_cast(walling_robots_[waller_pos_ - 2]); - } else if (target_point.x() >= robot_pos.x() && waller_pos_ >= 1 && - waller_pos_ < num_wallers) { - return static_cast(walling_robots_[waller_pos_]); - } else { - return static_cast(robot_id); - } - }(); - - if ((target_point.x() < robot_pos.x() && waller_pos_ != 1) || - (target_point.x() > robot_pos.x() && waller_pos_ != num_wallers)) { - auto parent_point = world_state->get_robot(true, parent_id).pose.position(); - angle = (parent_point - goal_pos).angle(); - delta_angle = wall_spacing / min_wall_rad; - target_angle = - angle + delta_angle * (signbit(target_point.x() - robot_pos.x()) ? -1 : 1); - - target_point = (goal_pos + rj_geometry::Point{1, 0}) - .normalized(min_wall_rad) - .rotated(target_angle); - } - } - - auto location_instant = planning::LinearMotionInstant{target_point, rj_geometry::Point{}}; - - auto target_cmd = - planning::MotionCommand{"path_target", location_instant, planning::FaceBall{}}; - intent.motion_command = target_cmd; - - return intent; -} - -} // namespace strategy diff --git a/src/rj_strategy/src/coordinator/waller.cpp b/src/rj_strategy/src/coordinator/waller.cpp index 4a99bc25f6..7083fd23b4 100644 --- a/src/rj_strategy/src/coordinator/waller.cpp +++ b/src/rj_strategy/src/coordinator/waller.cpp @@ -15,10 +15,10 @@ Waller::Waller() void Waller::service_callback(RequestPtr request, ResponsePtr response) { if (request->joining) { - if (num_wallers_ == kMaxWallers) { + if (num_wallers_ == kMaxWallers) { response->success = false; } else { - if (std::find(walling_robots_.begin(), walling_robots_.end(), request->robot_id) != walling_robots_.end()) { + if (std::find(walling_robots_.begin(), walling_robots_.end(), request->robot_id) == walling_robots_.end()) { walling_robots_[num_wallers_] = request->robot_id; num_wallers_++; update_wallers(); @@ -28,8 +28,8 @@ void Waller::service_callback(RequestPtr request, ResponsePtr response) { } else { auto it = std::find(walling_robots_.begin(), walling_robots_.end(), request->robot_id); if (it != walling_robots_.end()) { - *it = -1; num_wallers_--; + *it = -1; response->success = true; update_wallers(); } else { diff --git a/src/rj_strategy/src/coordinator/waller_client.cpp b/src/rj_strategy/src/coordinator/waller_client.cpp index 7e877ada3a..69eae83f40 100644 --- a/src/rj_strategy/src/coordinator/waller_client.cpp +++ b/src/rj_strategy/src/coordinator/waller_client.cpp @@ -8,7 +8,7 @@ WallerClient::WallerClient(rclcpp::Node::SharedPtr node, uint8_t robot_id) : nod } void WallerClient::join_group(StatusCallback callback) { - if (am_i_member_) { + if (am_i_member_ || request_pending_) { return; } @@ -24,9 +24,11 @@ void WallerClient::join_group(StatusCallback callback) { request->robot_id = robot_id_; request->joining = true; + request_pending_ = true; client_->async_send_request(request, [this, callback = std::move(callback)]( rclcpp::Client::SharedFuture future) { // 6 NOLINT(performance-unnecessary-value-param) -- // ROS2 async callbacks require value capture. + request_pending_ = false; if (!future.valid() || !future.get()->success) { if (callback) { callback(Result{false}); @@ -41,9 +43,10 @@ void WallerClient::join_group(StatusCallback callback) { (const rj_msgs::msg::Waller::SharedPtr msg) { walling_robots_ = msg->wall_list; num_wallers_ = msg->wall_size; + am_i_member_ = std::find(walling_robots_.begin(), walling_robots_.end(), robot_id_) != walling_robots_.end(); if (callback) { - callback(Result{true}); + callback(Result{am_i_member_}); } } ); From fdff555c2f9208bc9c1cd9a4a9ad20a210a32a92 Mon Sep 17 00:00:00 2001 From: sdhanyamraju6 Date: Wed, 19 Nov 2025 18:27:15 -0500 Subject: [PATCH 3/8] working waller coord --- .../rj_strategy/coordinator/waller.hpp | 2 -- .../src/agent/position/defense.cpp | 9 ++------- .../src/agent/position/offense.cpp | 2 +- src/rj_strategy/src/coordinator/waller.cpp | 19 ++----------------- .../src/coordinator/waller_client.cpp | 9 ++++----- 5 files changed, 9 insertions(+), 32 deletions(-) diff --git a/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp b/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp index 5a9958c262..ce55f20b9b 100644 --- a/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp +++ b/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp @@ -31,8 +31,6 @@ class Waller private: std::array walling_robots_; u_int8_t num_wallers_ = 0; - WorldState last_world_state_; - rclcpp::Subscription::SharedPtr world_state_sub_; static constexpr int kMaxWallers = 4; void update_wallers(); diff --git a/src/rj_strategy/src/agent/position/defense.cpp b/src/rj_strategy/src/agent/position/defense.cpp index 1da25f015d..f4567c7379 100644 --- a/src/rj_strategy/src/agent/position/defense.cpp +++ b/src/rj_strategy/src/agent/position/defense.cpp @@ -26,10 +26,6 @@ Defense::State Defense::update_state() { rj_geometry::Point ball_position = world_state->ball.position; double distance_to_ball = robot_position.dist_to(ball_position); - if (current_state_ != WALLING && current_state_ != JOINING_WALL) { - client_handles_->waller->leave_group(); - } - switch (current_state_) { case IDLING: next_state = JOINING_WALL; @@ -65,6 +61,7 @@ Defense::State Defense::update_state() { if (check_is_done()) { next_state = IDLING; } + break; case MARKING: if (marker_.get_target() == -1 || marker_.target_out_of_bounds(world_state)) { next_state = ENTERING_MARKING; @@ -182,9 +179,7 @@ void Defense::derived_acknowledge_ball_in_transit() { void Defense::die() { - if (current_state_ == WALLING) { - client_handles_->waller->leave_group(); - } + client_handles_->waller->leave_group(); } void Defense::revive() { current_state_ = JOINING_WALL; } diff --git a/src/rj_strategy/src/agent/position/offense.cpp b/src/rj_strategy/src/agent/position/offense.cpp index b63fd8c590..0c5e722e94 100644 --- a/src/rj_strategy/src/agent/position/offense.cpp +++ b/src/rj_strategy/src/agent/position/offense.cpp @@ -15,7 +15,7 @@ std::optional Offense::derived_get_task(RobotIntent intent) { if (current_state_ != new_state) { reset_timeout(); - SPDLOG_INFO("Robot {}: now {}", robot_id_, state_to_name(current_state_)); + // SPDLOG_INFO("Robot {}: now {}", robot_id_, state_to_name(current_state_)); if (current_state_ == SEEKING) { broadcast_seeker_request(rj_geometry::Point{}, false); } diff --git a/src/rj_strategy/src/coordinator/waller.cpp b/src/rj_strategy/src/coordinator/waller.cpp index 7083fd23b4..9af18fd188 100644 --- a/src/rj_strategy/src/coordinator/waller.cpp +++ b/src/rj_strategy/src/coordinator/waller.cpp @@ -5,12 +5,6 @@ namespace strategy { Waller::Waller() : Coordinator("waller_srv", "waller_data", "waller_node") { walling_robots_.fill(-1); - world_state_sub_ = this->create_subscription( - vision_filter::topics::kWorldStateTopic, rclcpp::QoS(1), - [this](rj_msgs::msg::WorldState::SharedPtr world_state) { // NOLINT - last_world_state_ = rj_convert::convert_from_ros(*world_state); - update_wallers(); - }); } void Waller::service_callback(RequestPtr request, ResponsePtr response) { @@ -30,25 +24,16 @@ void Waller::service_callback(RequestPtr request, ResponsePtr response) { if (it != walling_robots_.end()) { num_wallers_--; *it = -1; - response->success = true; update_wallers(); - } else { - response->success = false; } + response->success = true; } } void Waller::update_wallers() { auto prev_wallers = walling_robots_; std::sort(walling_robots_.begin(), walling_robots_.end()); - auto must_republish = false; - for (int i = 0; i < num_wallers_ && !must_republish; i++) { - if (prev_wallers[i] != walling_robots_[i]) must_republish = true; - } - - if (must_republish) { - publisher_->publish(rj_msgs::msg::Waller().set__wall_list(walling_robots_).set__wall_size(num_wallers_)); - } + publisher_->publish(rj_msgs::msg::Waller().set__wall_list(walling_robots_).set__wall_size(num_wallers_)); } } // namespace strategy diff --git a/src/rj_strategy/src/coordinator/waller_client.cpp b/src/rj_strategy/src/coordinator/waller_client.cpp index 69eae83f40..614dafe796 100644 --- a/src/rj_strategy/src/coordinator/waller_client.cpp +++ b/src/rj_strategy/src/coordinator/waller_client.cpp @@ -44,7 +44,7 @@ void WallerClient::join_group(StatusCallback callback) { walling_robots_ = msg->wall_list; num_wallers_ = msg->wall_size; am_i_member_ = std::find(walling_robots_.begin(), walling_robots_.end(), robot_id_) != walling_robots_.end(); - + if (callback) { callback(Result{am_i_member_}); } @@ -56,7 +56,7 @@ void WallerClient::join_group(StatusCallback callback) { } void WallerClient::leave_group(StatusCallback callback) { - if (!am_i_member_) { + if (!am_i_member_ && !request_pending_) { if (callback) { callback(Result{false}); } @@ -95,7 +95,7 @@ bool WallerClient::am_i_member() const { return am_i_member_; } std::optional WallerClient::get_walling_point(const WorldState* world_state, FieldDimensions field_dimensions) const { - if (!am_i_member_) return nullopt; + if (!am_i_member_) return std::nullopt; // Creates Minimum wall radius is slightly greater than box bounds // Dimension accessors should be edited when we figure out how we are doing dimensions realtime @@ -122,8 +122,7 @@ std::optional WallerClient::get_walling_point(const WorldSta auto wall_spacing = kRobotDiameterMultiplier * kRobotDiameter + kBallRadius; auto it = std::find(walling_robots_.begin(), walling_robots_.end(), robot_id_); - if (it == walling_robots_.end()) return std::nullopt; - auto waller_pos = std::distance(walling_robots_.begin(), it); + auto waller_pos = std::distance(walling_robots_.begin(), it)+1; rj_geometry::Point target_point{}; auto angle = (mid_point - goal_pos).angle(); From 2c4ffa9e6aa260174da6db9b62e1ff40a11977e1 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Wed, 19 Nov 2025 20:14:18 -0500 Subject: [PATCH 4/8] Fix Code Style On waller-coordinator (#2468) automated style fixes Co-authored-by: sanatd33 --- .../rj_strategy/coordinator/waller.hpp | 18 ++++---- .../rj_strategy/coordinator/waller_client.hpp | 8 ++-- .../src/agent/position/defense.cpp | 21 +++++---- .../agent/position/robot_factory_position.cpp | 2 +- src/rj_strategy/src/coordinator/waller.cpp | 11 +++-- .../src/coordinator/waller_client.cpp | 46 +++++++++---------- 6 files changed, 54 insertions(+), 52 deletions(-) diff --git a/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp b/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp index ce55f20b9b..aec64e207d 100644 --- a/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp +++ b/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp @@ -1,24 +1,23 @@ #pragma once -#include - -#include #include +#include + +#include -#include -#include -#include -#include #include #include +#include #include +#include +#include +#include #include "rj_strategy/coordinator.hpp" namespace strategy { -class Waller - : public Coordinator { +class Waller : public Coordinator { public: Waller(); ~Waller() override = default; @@ -28,6 +27,7 @@ class Waller Waller& operator=(Waller&&) = delete; void service_callback(RequestPtr request, ResponsePtr response); + private: std::array walling_robots_; u_int8_t num_wallers_ = 0; diff --git a/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp b/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp index d6763e2592..95ed1d5b2d 100644 --- a/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp +++ b/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp @@ -5,9 +5,9 @@ #include #include +#include #include #include -#include #include "rj_strategy/coordinator/waller.hpp" @@ -51,11 +51,11 @@ class WallerClient { [[nodiscard]] bool am_i_member() const; /** - * @brief Get the target walling point + * @brief Get the target walling point * @return target walling point of this robot. */ - [[nodiscard]] std::optional get_walling_point(const WorldState* world_state, - FieldDimensions field_dimensions) const; + [[nodiscard]] std::optional get_walling_point( + const WorldState* world_state, FieldDimensions field_dimensions) const; private: rclcpp::Node::SharedPtr node_; diff --git a/src/rj_strategy/src/agent/position/defense.cpp b/src/rj_strategy/src/agent/position/defense.cpp index f4567c7379..6491548da8 100644 --- a/src/rj_strategy/src/agent/position/defense.cpp +++ b/src/rj_strategy/src/agent/position/defense.cpp @@ -32,8 +32,10 @@ Defense::State Defense::update_state() { break; case JOINING_WALL: client_handles_->waller->join_group([this](WallerClient::Result result) { - if (result.success) current_state_ = WALLING; - else current_state_ = ENTERING_MARKING; + if (result.success) + current_state_ = WALLING; + else + current_state_ = ENTERING_MARKING; }); break; case WALLING: @@ -123,12 +125,14 @@ std::optional Defense::state_to_task(RobotIntent intent) { intent.is_active = true; return intent; } else if (current_state_ == WALLING) { - auto walling_point = client_handles_->waller->get_walling_point(last_world_state_, field_dimensions_); + auto walling_point = + client_handles_->waller->get_walling_point(last_world_state_, field_dimensions_); if (walling_point) { planning::LinearMotionInstant target{walling_point.value()}; - intent.motion_command = planning::MotionCommand{"path_target", target, planning::FaceBall{}}; - } - else intent.motion_command = planning::MotionCommand{}; + intent.motion_command = + planning::MotionCommand{"path_target", target, planning::FaceBall{}}; + } else + intent.motion_command = planning::MotionCommand{}; return intent; } else if (current_state_ == FACING) { rj_geometry::Point robot_position = @@ -177,10 +181,7 @@ void Defense::derived_acknowledge_ball_in_transit() { chasing_ball = false; } - -void Defense::die() { - client_handles_->waller->leave_group(); -} +void Defense::die() { client_handles_->waller->leave_group(); } void Defense::revive() { current_state_ = JOINING_WALL; } diff --git a/src/rj_strategy/src/agent/position/robot_factory_position.cpp b/src/rj_strategy/src/agent/position/robot_factory_position.cpp index 6de6e7d21c..d2ac855d51 100644 --- a/src/rj_strategy/src/agent/position/robot_factory_position.cpp +++ b/src/rj_strategy/src/agent/position/robot_factory_position.cpp @@ -6,7 +6,7 @@ RobotFactoryPosition::RobotFactoryPosition(int r_id, rclcpp::Node::SharedPtr nod : Position(r_id, "RobotFactoryPosition") { client_handles_->kicker_picker = std::make_unique(node, r_id); client_handles_->waller = std::make_unique(node, r_id); - + if (robot_id_ == 0) { current_position_ = std::make_unique(robot_id_); } else if (robot_id_ == 1 || robot_id_ == 2) { diff --git a/src/rj_strategy/src/coordinator/waller.cpp b/src/rj_strategy/src/coordinator/waller.cpp index 9af18fd188..4850f015d4 100644 --- a/src/rj_strategy/src/coordinator/waller.cpp +++ b/src/rj_strategy/src/coordinator/waller.cpp @@ -2,17 +2,17 @@ namespace strategy { -Waller::Waller() - : Coordinator("waller_srv", "waller_data", "waller_node") { +Waller::Waller() : Coordinator("waller_srv", "waller_data", "waller_node") { walling_robots_.fill(-1); } void Waller::service_callback(RequestPtr request, ResponsePtr response) { if (request->joining) { - if (num_wallers_ == kMaxWallers) { + if (num_wallers_ == kMaxWallers) { response->success = false; } else { - if (std::find(walling_robots_.begin(), walling_robots_.end(), request->robot_id) == walling_robots_.end()) { + if (std::find(walling_robots_.begin(), walling_robots_.end(), request->robot_id) == + walling_robots_.end()) { walling_robots_[num_wallers_] = request->robot_id; num_wallers_++; update_wallers(); @@ -33,7 +33,8 @@ void Waller::service_callback(RequestPtr request, ResponsePtr response) { void Waller::update_wallers() { auto prev_wallers = walling_robots_; std::sort(walling_robots_.begin(), walling_robots_.end()); - publisher_->publish(rj_msgs::msg::Waller().set__wall_list(walling_robots_).set__wall_size(num_wallers_)); + publisher_->publish( + rj_msgs::msg::Waller().set__wall_list(walling_robots_).set__wall_size(num_wallers_)); } } // namespace strategy diff --git a/src/rj_strategy/src/coordinator/waller_client.cpp b/src/rj_strategy/src/coordinator/waller_client.cpp index 614dafe796..9864e5ac16 100644 --- a/src/rj_strategy/src/coordinator/waller_client.cpp +++ b/src/rj_strategy/src/coordinator/waller_client.cpp @@ -1,8 +1,9 @@ #include "rj_strategy/coordinator/waller_client.hpp" namespace strategy { - -WallerClient::WallerClient(rclcpp::Node::SharedPtr node, uint8_t robot_id) : node_{std::move(node)}, robot_id_{robot_id} { + +WallerClient::WallerClient(rclcpp::Node::SharedPtr node, uint8_t robot_id) + : node_{std::move(node)}, robot_id_{robot_id} { client_ = node_->create_client("waller_srv"); walling_robots_.fill(-1); } @@ -25,9 +26,11 @@ void WallerClient::join_group(StatusCallback callback) { request->joining = true; request_pending_ = true; - client_->async_send_request(request, [this, callback = std::move(callback)]( - rclcpp::Client::SharedFuture future) { // 6 NOLINT(performance-unnecessary-value-param) -- - // ROS2 async callbacks require value capture. + client_->async_send_request( + request, [this, callback = std::move(callback)]( + rclcpp::Client::SharedFuture + future) { // 6 NOLINT(performance-unnecessary-value-param) -- + // ROS2 async callbacks require value capture. request_pending_ = false; if (!future.valid() || !future.get()->success) { if (callback) { @@ -39,20 +42,18 @@ void WallerClient::join_group(StatusCallback callback) { subscription_ = node_->create_subscription( "waller_data", rclcpp::QoS(1).transient_local(), - [this, callback = std::move(callback)] - (const rj_msgs::msg::Waller::SharedPtr msg) { - walling_robots_ = msg->wall_list; - num_wallers_ = msg->wall_size; - am_i_member_ = std::find(walling_robots_.begin(), walling_robots_.end(), robot_id_) != walling_robots_.end(); - - if (callback) { - callback(Result{am_i_member_}); - } + [this, callback = std::move(callback)](const rj_msgs::msg::Waller::SharedPtr msg) { + walling_robots_ = msg->wall_list; + num_wallers_ = msg->wall_size; + am_i_member_ = std::find(walling_robots_.begin(), walling_robots_.end(), + robot_id_) != walling_robots_.end(); + + if (callback) { + callback(Result{am_i_member_}); } - ); + }); - } - ); + }); } void WallerClient::leave_group(StatusCallback callback) { @@ -93,10 +94,10 @@ void WallerClient::leave_group(StatusCallback callback) { bool WallerClient::am_i_member() const { return am_i_member_; } -std::optional WallerClient::get_walling_point(const WorldState* world_state, - FieldDimensions field_dimensions) const { +std::optional WallerClient::get_walling_point( + const WorldState* world_state, FieldDimensions field_dimensions) const { if (!am_i_member_) return std::nullopt; - + // Creates Minimum wall radius is slightly greater than box bounds // Dimension accessors should be edited when we figure out how we are doing dimensions realtime // from vision @@ -122,7 +123,7 @@ std::optional WallerClient::get_walling_point(const WorldSta auto wall_spacing = kRobotDiameterMultiplier * kRobotDiameter + kBallRadius; auto it = std::find(walling_robots_.begin(), walling_robots_.end(), robot_id_); - auto waller_pos = std::distance(walling_robots_.begin(), it)+1; + auto waller_pos = std::distance(walling_robots_.begin(), it) + 1; rj_geometry::Point target_point{}; auto angle = (mid_point - goal_pos).angle(); @@ -164,5 +165,4 @@ std::optional WallerClient::get_walling_point(const WorldSta return target_point; } - -} // namespace strategy +} // namespace strategy From a495dc0c75ad08e389d4ac2b5258c6ad135887de Mon Sep 17 00:00:00 2001 From: sdhanyamraju6 Date: Sun, 23 Nov 2025 20:46:26 -0500 Subject: [PATCH 5/8] fix comments, break up big function --- .../rj_strategy/coordinator/waller.hpp | 4 +- .../rj_strategy/coordinator/waller_client.hpp | 15 +- src/rj_strategy/src/coordinator/waller.cpp | 4 +- .../src/coordinator/waller_client.cpp | 131 ++++++++++-------- 4 files changed, 94 insertions(+), 60 deletions(-) diff --git a/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp b/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp index aec64e207d..2a4d55d544 100644 --- a/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp +++ b/src/rj_strategy/include/rj_strategy/coordinator/waller.hpp @@ -29,8 +29,8 @@ class Waller : public Coordinator walling_robots_; - u_int8_t num_wallers_ = 0; + std::array walling_robots_; + uint8_t num_wallers_ = 0; static constexpr int kMaxWallers = 4; void update_wallers(); diff --git a/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp b/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp index 95ed1d5b2d..84bbb26893 100644 --- a/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp +++ b/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp @@ -66,10 +66,23 @@ class WallerClient { bool am_i_member_ = false; bool request_pending_ = false; - std::array walling_robots_; + std::array walling_robots_; int num_wallers_ = 0; static constexpr double kRobotDiameterMultiplier = 1.5; + + struct WallerGeometry { + double min_wall_radius; + double wall_spacing; + rj_geometry::Point goal_pos; + rj_geometry::Point ball_pos; + rj_geometry::Point robot_pos; + }; + + WallerGeometry calculate_wall_geometry(const WorldState* world_state, FieldDimensions dimensions) const; + rj_geometry::Point get_target_position(WallerGeometry& waller_geometry, long waller_pos) const; + std::optional get_parent_id(WallerGeometry& waller_geometry, rj_geometry::Point target_point, long waller_pos) const; + rj_geometry::Point get_target_position_with_parent(WallerGeometry& waller_geometry, rj_geometry::Point target_point, rj_geometry::Point parent_point) const; }; } // namespace strategy \ No newline at end of file diff --git a/src/rj_strategy/src/coordinator/waller.cpp b/src/rj_strategy/src/coordinator/waller.cpp index 4850f015d4..dcea23913c 100644 --- a/src/rj_strategy/src/coordinator/waller.cpp +++ b/src/rj_strategy/src/coordinator/waller.cpp @@ -3,7 +3,7 @@ namespace strategy { Waller::Waller() : Coordinator("waller_srv", "waller_data", "waller_node") { - walling_robots_.fill(-1); + walling_robots_.fill(std::numeric_limits::max()); } void Waller::service_callback(RequestPtr request, ResponsePtr response) { @@ -23,7 +23,7 @@ void Waller::service_callback(RequestPtr request, ResponsePtr response) { auto it = std::find(walling_robots_.begin(), walling_robots_.end(), request->robot_id); if (it != walling_robots_.end()) { num_wallers_--; - *it = -1; + *it = std::numeric_limits::max(); update_wallers(); } response->success = true; diff --git a/src/rj_strategy/src/coordinator/waller_client.cpp b/src/rj_strategy/src/coordinator/waller_client.cpp index 9864e5ac16..56e228ddd6 100644 --- a/src/rj_strategy/src/coordinator/waller_client.cpp +++ b/src/rj_strategy/src/coordinator/waller_client.cpp @@ -87,7 +87,7 @@ void WallerClient::leave_group(StatusCallback callback) { num_wallers_ = 0; if (callback) { - callback(Result{false}); + callback(Result{true}); } }); } @@ -98,71 +98,92 @@ std::optional WallerClient::get_walling_point( const WorldState* world_state, FieldDimensions field_dimensions) const { if (!am_i_member_) return std::nullopt; + auto waller_geometry = calculate_wall_geometry(world_state, field_dimensions); + auto waller_pos = std::distance(walling_robots_.begin(), + std::find(walling_robots_.begin(), walling_robots_.end(), robot_id_)); + + // Target point where the waller should end up + auto target_point = get_target_position(waller_geometry, waller_pos); + + // If we can, follow our parent instead of going directly to the target + if (auto parent_id = get_parent_id(waller_geometry, target_point, waller_pos)) { + auto parent_point = world_state->get_robot(true, *parent_id).pose.position(); + return get_target_position_with_parent(waller_geometry, target_point, parent_point); + } + + return target_point; +} + +WallerClient::WallerGeometry WallerClient::calculate_wall_geometry(const WorldState* world_state, FieldDimensions field_dimensions) const { + WallerGeometry waller_geometry{}; + // Creates Minimum wall radius is slightly greater than box bounds // Dimension accessors should be edited when we figure out how we are doing dimensions realtime // from vision float box_w{field_dimensions.penalty_long_dist()}; float box_h{field_dimensions.penalty_short_dist()}; float line_w{field_dimensions.line_width()}; - double min_wall_rad{(kRobotRadius * 4.0f) + line_w + - hypot(static_cast(box_w) / 2, static_cast((box_h)))}; - - auto ball_pos = world_state->ball.position; - - auto robot_pos = world_state->get_robot(true, robot_id_).pose.position(); - auto goal_pos = rj_geometry::Point{0, 0}; - - // Find ball_direction unit vector - rj_geometry::Point ball_dir_vector{(ball_pos - goal_pos)}; - - ball_dir_vector = ball_dir_vector.normalized(); - - // Find target Point - rj_geometry::Point mid_point{(goal_pos) + (ball_dir_vector * min_wall_rad)}; - - auto wall_spacing = kRobotDiameterMultiplier * kRobotDiameter + kBallRadius; + waller_geometry.min_wall_radius = (kRobotRadius * 4.0f) + line_w + + hypot(static_cast(box_w) / 2, static_cast((box_h))); + + waller_geometry.robot_pos = world_state->get_robot(true, robot_id_).pose.position(); + waller_geometry.goal_pos = field_dimensions.our_goal_loc(); + waller_geometry.ball_pos = world_state->ball.position; + waller_geometry.wall_spacing = kRobotDiameterMultiplier * kRobotDiameter + kBallRadius; + + return waller_geometry; +} - auto it = std::find(walling_robots_.begin(), walling_robots_.end(), robot_id_); - auto waller_pos = std::distance(walling_robots_.begin(), it) + 1; +rj_geometry::Point WallerClient::get_target_position(WallerGeometry& waller_geometry, long waller_pos) const { + // Find target point of this robot + rj_geometry::Point ball_dir_vector = rj_geometry::Point(waller_geometry.ball_pos - waller_geometry.goal_pos).normalized(); + + // This serves as the center of the wall arc + rj_geometry::Point mid_point{(waller_geometry.goal_pos) + (ball_dir_vector * waller_geometry.min_wall_radius)}; + auto angle = (mid_point - waller_geometry.goal_pos).angle(); - rj_geometry::Point target_point{}; - auto angle = (mid_point - goal_pos).angle(); - auto delta_angle = (wall_spacing * (waller_pos - num_wallers_ / 2. - 0.5)) / min_wall_rad; + // Wallers are distributed evenly across the wall arc based on their position in the wall list + auto delta_angle = (waller_geometry.wall_spacing * (waller_pos - num_wallers_ / 2. - 0.5)) / waller_geometry.min_wall_radius; auto target_angle = angle - delta_angle; - target_point = - (goal_pos + rj_geometry::Point{1, 0}).normalized(min_wall_rad).rotated(target_angle); - - if (abs(robot_pos.dist_to(goal_pos) - min_wall_rad) < kRobotRadius && - robot_pos.dist_to(target_point) > kRobotRadius) { - uint8_t parent_id = - [&]() { // Assigning a value to avoid any undefined behavior; will be changed - if (target_point.x() < robot_pos.x() && waller_pos > 1 && - waller_pos <= num_wallers_) { - return static_cast(walling_robots_[waller_pos - 2]); - } else if (target_point.x() >= robot_pos.x() && waller_pos >= 1 && - waller_pos < num_wallers_) { - return static_cast(walling_robots_[waller_pos]); - } else { - return static_cast(robot_id_); - } - }(); - - if ((target_point.x() < robot_pos.x() && waller_pos != 1) || - (target_point.x() > robot_pos.x() && waller_pos != num_wallers_)) { - auto parent_point = world_state->get_robot(true, parent_id).pose.position(); - angle = (parent_point - goal_pos).angle(); - delta_angle = wall_spacing / min_wall_rad; - target_angle = - angle + delta_angle * (signbit(target_point.x() - robot_pos.x()) ? -1 : 1); - - target_point = (goal_pos + rj_geometry::Point{1, 0}) - .normalized(min_wall_rad) - .rotated(target_angle); - } - } + // Calculate the target point using polar coordinates with wall radius and target angle + return rj_geometry::Point(1, 0).normalized(waller_geometry.min_wall_radius).rotated(target_angle); +} - return target_point; +std::optional WallerClient::get_parent_id(WallerGeometry& waller_geometry, rj_geometry::Point target_point, long waller_pos) const { + // Finds the parent point along the wall + auto distance_from_arc = abs(waller_geometry.robot_pos.dist_to(waller_geometry.goal_pos) - waller_geometry.min_wall_radius); + auto distance_from_target = waller_geometry.robot_pos.dist_to(target_point); + + // We are not along the wall arco or we are close to our target, do not follow the parent + if (distance_from_arc >= kRobotRadius || distance_from_target <= kRobotRadius) return std::nullopt; + + // We need to move to the left so our parent is the robot to the left of us + if (target_point.x() < waller_geometry.robot_pos.x() && waller_pos > 0) + return static_cast(walling_robots_[waller_pos - 1]); + // We need to move to the right so our parent is the robot to the right of us + else if (target_point.x() >= waller_geometry.robot_pos.x() && waller_pos < num_wallers_ - 1) + return static_cast(walling_robots_[waller_pos + 1]); + + // We are the first robot in the arc, we should not follow anyone + return std::nullopt; +} + +rj_geometry::Point WallerClient::get_target_position_with_parent(WallerGeometry& waller_geometry, rj_geometry::Point target_point, rj_geometry::Point parent_point) const { + // Find target point of this robot by following some parent robot + auto angle = (parent_point - waller_geometry.goal_pos).angle(); + + // Go to {wall_spacing} behind the parent + // Uses signbit() to determine whether the parent is to the left or to the right + auto delta_angle = waller_geometry.wall_spacing / waller_geometry.min_wall_radius; + auto target_angle = + angle + delta_angle * (signbit(target_point.x() - waller_geometry.robot_pos.x()) ? -1 : 1); + + // Calculate the target position using polar coordinates + return rj_geometry::Point(1, 0) + .normalized(waller_geometry.min_wall_radius) + .rotated(target_angle); } + } // namespace strategy From 2586b92c1e4acce5129e3c4420dfad7e97f0bde7 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sun, 23 Nov 2025 20:47:52 -0500 Subject: [PATCH 6/8] Fix Code Style On waller-coordinator (#2471) automated style fixes Co-authored-by: sanatd33 --- .../rj_strategy/coordinator/waller_client.hpp | 10 +++- .../src/coordinator/waller_client.cpp | 58 ++++++++++++------- 2 files changed, 43 insertions(+), 25 deletions(-) diff --git a/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp b/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp index 84bbb26893..c610ab7991 100644 --- a/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp +++ b/src/rj_strategy/include/rj_strategy/coordinator/waller_client.hpp @@ -79,10 +79,14 @@ class WallerClient { rj_geometry::Point robot_pos; }; - WallerGeometry calculate_wall_geometry(const WorldState* world_state, FieldDimensions dimensions) const; + WallerGeometry calculate_wall_geometry(const WorldState* world_state, + FieldDimensions dimensions) const; rj_geometry::Point get_target_position(WallerGeometry& waller_geometry, long waller_pos) const; - std::optional get_parent_id(WallerGeometry& waller_geometry, rj_geometry::Point target_point, long waller_pos) const; - rj_geometry::Point get_target_position_with_parent(WallerGeometry& waller_geometry, rj_geometry::Point target_point, rj_geometry::Point parent_point) const; + std::optional get_parent_id(WallerGeometry& waller_geometry, + rj_geometry::Point target_point, long waller_pos) const; + rj_geometry::Point get_target_position_with_parent(WallerGeometry& waller_geometry, + rj_geometry::Point target_point, + rj_geometry::Point parent_point) const; }; } // namespace strategy \ No newline at end of file diff --git a/src/rj_strategy/src/coordinator/waller_client.cpp b/src/rj_strategy/src/coordinator/waller_client.cpp index 56e228ddd6..835d0fb083 100644 --- a/src/rj_strategy/src/coordinator/waller_client.cpp +++ b/src/rj_strategy/src/coordinator/waller_client.cpp @@ -99,10 +99,11 @@ std::optional WallerClient::get_walling_point( if (!am_i_member_) return std::nullopt; auto waller_geometry = calculate_wall_geometry(world_state, field_dimensions); - auto waller_pos = std::distance(walling_robots_.begin(), - std::find(walling_robots_.begin(), walling_robots_.end(), robot_id_)); + auto waller_pos = + std::distance(walling_robots_.begin(), + std::find(walling_robots_.begin(), walling_robots_.end(), robot_id_)); - // Target point where the waller should end up + // Target point where the waller should end up auto target_point = get_target_position(waller_geometry, waller_pos); // If we can, follow our parent instead of going directly to the target @@ -114,7 +115,8 @@ std::optional WallerClient::get_walling_point( return target_point; } -WallerClient::WallerGeometry WallerClient::calculate_wall_geometry(const WorldState* world_state, FieldDimensions field_dimensions) const { +WallerClient::WallerGeometry WallerClient::calculate_wall_geometry( + const WorldState* world_state, FieldDimensions field_dimensions) const { WallerGeometry waller_geometry{}; // Creates Minimum wall radius is slightly greater than box bounds @@ -123,9 +125,10 @@ WallerClient::WallerGeometry WallerClient::calculate_wall_geometry(const WorldSt float box_w{field_dimensions.penalty_long_dist()}; float box_h{field_dimensions.penalty_short_dist()}; float line_w{field_dimensions.line_width()}; - waller_geometry.min_wall_radius = (kRobotRadius * 4.0f) + line_w + - hypot(static_cast(box_w) / 2, static_cast((box_h))); - + waller_geometry.min_wall_radius = + (kRobotRadius * 4.0f) + line_w + + hypot(static_cast(box_w) / 2, static_cast((box_h))); + waller_geometry.robot_pos = world_state->get_robot(true, robot_id_).pose.position(); waller_geometry.goal_pos = field_dimensions.our_goal_loc(); waller_geometry.ball_pos = world_state->ball.position; @@ -134,29 +137,39 @@ WallerClient::WallerGeometry WallerClient::calculate_wall_geometry(const WorldSt return waller_geometry; } -rj_geometry::Point WallerClient::get_target_position(WallerGeometry& waller_geometry, long waller_pos) const { +rj_geometry::Point WallerClient::get_target_position(WallerGeometry& waller_geometry, + long waller_pos) const { // Find target point of this robot - rj_geometry::Point ball_dir_vector = rj_geometry::Point(waller_geometry.ball_pos - waller_geometry.goal_pos).normalized(); - + rj_geometry::Point ball_dir_vector = + rj_geometry::Point(waller_geometry.ball_pos - waller_geometry.goal_pos).normalized(); + // This serves as the center of the wall arc - rj_geometry::Point mid_point{(waller_geometry.goal_pos) + (ball_dir_vector * waller_geometry.min_wall_radius)}; + rj_geometry::Point mid_point{(waller_geometry.goal_pos) + + (ball_dir_vector * waller_geometry.min_wall_radius)}; auto angle = (mid_point - waller_geometry.goal_pos).angle(); // Wallers are distributed evenly across the wall arc based on their position in the wall list - auto delta_angle = (waller_geometry.wall_spacing * (waller_pos - num_wallers_ / 2. - 0.5)) / waller_geometry.min_wall_radius; + auto delta_angle = (waller_geometry.wall_spacing * (waller_pos - num_wallers_ / 2. - 0.5)) / + waller_geometry.min_wall_radius; auto target_angle = angle - delta_angle; // Calculate the target point using polar coordinates with wall radius and target angle - return rj_geometry::Point(1, 0).normalized(waller_geometry.min_wall_radius).rotated(target_angle); + return rj_geometry::Point(1, 0) + .normalized(waller_geometry.min_wall_radius) + .rotated(target_angle); } -std::optional WallerClient::get_parent_id(WallerGeometry& waller_geometry, rj_geometry::Point target_point, long waller_pos) const { +std::optional WallerClient::get_parent_id(WallerGeometry& waller_geometry, + rj_geometry::Point target_point, + long waller_pos) const { // Finds the parent point along the wall - auto distance_from_arc = abs(waller_geometry.robot_pos.dist_to(waller_geometry.goal_pos) - waller_geometry.min_wall_radius); + auto distance_from_arc = abs(waller_geometry.robot_pos.dist_to(waller_geometry.goal_pos) - + waller_geometry.min_wall_radius); auto distance_from_target = waller_geometry.robot_pos.dist_to(target_point); // We are not along the wall arco or we are close to our target, do not follow the parent - if (distance_from_arc >= kRobotRadius || distance_from_target <= kRobotRadius) return std::nullopt; + if (distance_from_arc >= kRobotRadius || distance_from_target <= kRobotRadius) + return std::nullopt; // We need to move to the left so our parent is the robot to the left of us if (target_point.x() < waller_geometry.robot_pos.x() && waller_pos > 0) @@ -167,10 +180,12 @@ std::optional WallerClient::get_parent_id(WallerGeometry& waller_geomet // We are the first robot in the arc, we should not follow anyone return std::nullopt; -} +} -rj_geometry::Point WallerClient::get_target_position_with_parent(WallerGeometry& waller_geometry, rj_geometry::Point target_point, rj_geometry::Point parent_point) const { - // Find target point of this robot by following some parent robot +rj_geometry::Point WallerClient::get_target_position_with_parent( + WallerGeometry& waller_geometry, rj_geometry::Point target_point, + rj_geometry::Point parent_point) const { + // Find target point of this robot by following some parent robot auto angle = (parent_point - waller_geometry.goal_pos).angle(); // Go to {wall_spacing} behind the parent @@ -181,9 +196,8 @@ rj_geometry::Point WallerClient::get_target_position_with_parent(WallerGeometry& // Calculate the target position using polar coordinates return rj_geometry::Point(1, 0) - .normalized(waller_geometry.min_wall_radius) - .rotated(target_angle); + .normalized(waller_geometry.min_wall_radius) + .rotated(target_angle); } - } // namespace strategy From 870b37ec6d55b3bd3234c0a99f5346957865ec48 Mon Sep 17 00:00:00 2001 From: sdhanyamraju6 Date: Tue, 3 Feb 2026 21:24:46 -0500 Subject: [PATCH 7/8] fixed pr comments --- .../include/rj_strategy/agent/position/defense.hpp | 4 ---- src/rj_strategy/src/agent/position/defense.cpp | 3 +++ src/rj_strategy/src/coordinator/waller.cpp | 1 - src/rj_strategy/src/coordinator/waller_client.cpp | 4 ++-- 4 files changed, 5 insertions(+), 7 deletions(-) diff --git a/src/rj_strategy/include/rj_strategy/agent/position/defense.hpp b/src/rj_strategy/include/rj_strategy/agent/position/defense.hpp index e842c82bdd..6676f06785 100644 --- a/src/rj_strategy/include/rj_strategy/agent/position/defense.hpp +++ b/src/rj_strategy/include/rj_strategy/agent/position/defense.hpp @@ -43,10 +43,6 @@ class Defense : public Position { void revive() override; private: - // static constexpr int kMaxWallers{6}; - static constexpr int kMaxWallers{ - static_cast(kNumShells)}; // This effectively turns off marking - /** * @brief The derived_get_task method returns the task for the defensive robot * to do based on the game situation. The method will continuously look to assign diff --git a/src/rj_strategy/src/agent/position/defense.cpp b/src/rj_strategy/src/agent/position/defense.cpp index 6491548da8..403dded567 100644 --- a/src/rj_strategy/src/agent/position/defense.cpp +++ b/src/rj_strategy/src/agent/position/defense.cpp @@ -28,6 +28,7 @@ Defense::State Defense::update_state() { switch (current_state_) { case IDLING: + // Defensive Priority goes Walling > Marking > Zoning > Idle next_state = JOINING_WALL; break; case JOINING_WALL: @@ -39,6 +40,8 @@ Defense::State Defense::update_state() { }); break; case WALLING: + if (!client_handles_->waller->am_i_member()) + next_state = IDLING; break; case SEARCHING: break; diff --git a/src/rj_strategy/src/coordinator/waller.cpp b/src/rj_strategy/src/coordinator/waller.cpp index dcea23913c..6df1ed60d7 100644 --- a/src/rj_strategy/src/coordinator/waller.cpp +++ b/src/rj_strategy/src/coordinator/waller.cpp @@ -31,7 +31,6 @@ void Waller::service_callback(RequestPtr request, ResponsePtr response) { } void Waller::update_wallers() { - auto prev_wallers = walling_robots_; std::sort(walling_robots_.begin(), walling_robots_.end()); publisher_->publish( rj_msgs::msg::Waller().set__wall_list(walling_robots_).set__wall_size(num_wallers_)); diff --git a/src/rj_strategy/src/coordinator/waller_client.cpp b/src/rj_strategy/src/coordinator/waller_client.cpp index 835d0fb083..59d7da9614 100644 --- a/src/rj_strategy/src/coordinator/waller_client.cpp +++ b/src/rj_strategy/src/coordinator/waller_client.cpp @@ -5,7 +5,7 @@ namespace strategy { WallerClient::WallerClient(rclcpp::Node::SharedPtr node, uint8_t robot_id) : node_{std::move(node)}, robot_id_{robot_id} { client_ = node_->create_client("waller_srv"); - walling_robots_.fill(-1); + walling_robots_.fill(std::numeric_limits::max()); } void WallerClient::join_group(StatusCallback callback) { @@ -83,7 +83,7 @@ void WallerClient::leave_group(StatusCallback callback) { am_i_member_ = false; subscription_.reset(); - walling_robots_.fill(-1); + walling_robots_.fill(std::numeric_limits::max()); num_wallers_ = 0; if (callback) { From 5734e415de12351b2cdfc734227e91d9c51d74c1 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Tue, 3 Feb 2026 21:27:19 -0500 Subject: [PATCH 8/8] Fix Code Style On waller-coordinator (#2486) automated style fixes Co-authored-by: sanatd33 --- src/rj_strategy/src/agent/position/defense.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/rj_strategy/src/agent/position/defense.cpp b/src/rj_strategy/src/agent/position/defense.cpp index 403dded567..591e2d4641 100644 --- a/src/rj_strategy/src/agent/position/defense.cpp +++ b/src/rj_strategy/src/agent/position/defense.cpp @@ -40,8 +40,7 @@ Defense::State Defense::update_state() { }); break; case WALLING: - if (!client_handles_->waller->am_i_member()) - next_state = IDLING; + if (!client_handles_->waller->am_i_member()) next_state = IDLING; break; case SEARCHING: break;