From 26a3c0b9501939ffcc758fee62cecba546a9560c Mon Sep 17 00:00:00 2001 From: petergarud Date: Mon, 24 Nov 2025 02:00:23 +0000 Subject: [PATCH] automated style fixes --- src/rj_strategy/src/agent/position/defense.cpp | 14 ++++++-------- src/rj_strategy/src/coordinator/marking.cpp | 4 +--- src/rj_strategy/src/coordinator/marking_client.cpp | 3 +-- 3 files changed, 8 insertions(+), 13 deletions(-) diff --git a/src/rj_strategy/src/agent/position/defense.cpp b/src/rj_strategy/src/agent/position/defense.cpp index 7ba0cdd498..68df6d1574 100644 --- a/src/rj_strategy/src/agent/position/defense.cpp +++ b/src/rj_strategy/src/agent/position/defense.cpp @@ -36,8 +36,7 @@ Defense::State Defense::update_state() { return IDLING; } - if (client_handles_->marking->am_i_member() && - client_handles_->marking->am_i_marking()) { + if (client_handles_->marking->am_i_member() && client_handles_->marking->am_i_marking()) { return MARKING; } else { return IDLING; @@ -110,12 +109,11 @@ Defense::State Defense::update_state() { sent_join_marking_group_request_ = true; request_time_ = RJ::now(); - client_handles_->marking->join_group( - [this](const bool is_member) { - if (is_member) { - pending_marking_state_ = true; - } - }); + client_handles_->marking->join_group([this](const bool is_member) { + if (is_member) { + pending_marking_state_ = true; + } + }); } auto elapsed = RJ::now() - request_time_; if (elapsed > kMarkingGroupJoinTimeout) { diff --git a/src/rj_strategy/src/coordinator/marking.cpp b/src/rj_strategy/src/coordinator/marking.cpp index 246a86f831..f6c80e7f0d 100644 --- a/src/rj_strategy/src/coordinator/marking.cpp +++ b/src/rj_strategy/src/coordinator/marking.cpp @@ -32,8 +32,7 @@ void Marking::service_callback(RequestPtr request, ResponsePtr response) { // Queue is queue of robots that want to join marking but aren't good enough // Not close enough to mark or we exceeed the max num of markers for (uint8_t id : unassigned_markers_queue_) { - const auto& i_robot = - last_world_state_.get_robot(true, id); + const auto& i_robot = last_world_state_.get_robot(true, id); double distance = i_robot.pose.position().dist_to(enemy_robot.pose.position()); if (distance < min) { min = distance; @@ -213,7 +212,6 @@ void Marking::update_danger_scores() { danger_score_[i] = danger_score; } - } uint8_t Marking::find_their_robot_in_possession() { diff --git a/src/rj_strategy/src/coordinator/marking_client.cpp b/src/rj_strategy/src/coordinator/marking_client.cpp index 56d274719e..87421e15f8 100644 --- a/src/rj_strategy/src/coordinator/marking_client.cpp +++ b/src/rj_strategy/src/coordinator/marking_client.cpp @@ -49,8 +49,7 @@ void MarkingClient::join_group(StatusCallback callback) { // Create subscription to track selected kicker. subscription_ = node_->create_subscription( "marking_data", rclcpp::QoS(1).transient_local(), - [this]( - const rj_msgs::msg::Marking::SharedPtr msg) { + [this](const rj_msgs::msg::Marking::SharedPtr msg) { selected_robot_marking_id_ = msg->mark_robot_ids[robot_id_]; am_i_marking_ = (selected_robot_marking_id_ != kInvalidRobotId); });