Skip to content

Commit 5e2cc4d

Browse files
Fix Code Style On marking-coordinator (#2472)
automated style fixes Co-authored-by: petergarud <petergarud@users.noreply.github.com>
1 parent dd5a402 commit 5e2cc4d

File tree

3 files changed

+8
-13
lines changed

3 files changed

+8
-13
lines changed

src/rj_strategy/src/agent/position/defense.cpp

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -36,8 +36,7 @@ Defense::State Defense::update_state() {
3636
return IDLING;
3737
}
3838

39-
if (client_handles_->marking->am_i_member() &&
40-
client_handles_->marking->am_i_marking()) {
39+
if (client_handles_->marking->am_i_member() && client_handles_->marking->am_i_marking()) {
4140
return MARKING;
4241
} else {
4342
return IDLING;
@@ -110,12 +109,11 @@ Defense::State Defense::update_state() {
110109
sent_join_marking_group_request_ = true;
111110
request_time_ = RJ::now();
112111

113-
client_handles_->marking->join_group(
114-
[this](const bool is_member) {
115-
if (is_member) {
116-
pending_marking_state_ = true;
117-
}
118-
});
112+
client_handles_->marking->join_group([this](const bool is_member) {
113+
if (is_member) {
114+
pending_marking_state_ = true;
115+
}
116+
});
119117
}
120118
auto elapsed = RJ::now() - request_time_;
121119
if (elapsed > kMarkingGroupJoinTimeout) {

src/rj_strategy/src/coordinator/marking.cpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -32,8 +32,7 @@ void Marking::service_callback(RequestPtr request, ResponsePtr response) {
3232
// Queue is queue of robots that want to join marking but aren't good enough
3333
// Not close enough to mark or we exceeed the max num of markers
3434
for (uint8_t id : unassigned_markers_queue_) {
35-
const auto& i_robot =
36-
last_world_state_.get_robot(true, id);
35+
const auto& i_robot = last_world_state_.get_robot(true, id);
3736
double distance = i_robot.pose.position().dist_to(enemy_robot.pose.position());
3837
if (distance < min) {
3938
min = distance;
@@ -213,7 +212,6 @@ void Marking::update_danger_scores() {
213212

214213
danger_score_[i] = danger_score;
215214
}
216-
217215
}
218216

219217
uint8_t Marking::find_their_robot_in_possession() {

src/rj_strategy/src/coordinator/marking_client.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -49,8 +49,7 @@ void MarkingClient::join_group(StatusCallback callback) {
4949
// Create subscription to track selected kicker.
5050
subscription_ = node_->create_subscription<rj_msgs::msg::Marking>(
5151
"marking_data", rclcpp::QoS(1).transient_local(),
52-
[this](
53-
const rj_msgs::msg::Marking::SharedPtr msg) {
52+
[this](const rj_msgs::msg::Marking::SharedPtr msg) {
5453
selected_robot_marking_id_ = msg->mark_robot_ids[robot_id_];
5554
am_i_marking_ = (selected_robot_marking_id_ != kInvalidRobotId);
5655
});

0 commit comments

Comments
 (0)