Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 6 additions & 8 deletions src/rj_strategy/src/agent/position/defense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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) {
Expand Down
4 changes: 1 addition & 3 deletions src/rj_strategy/src/coordinator/marking.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -213,7 +212,6 @@ void Marking::update_danger_scores() {

danger_score_[i] = danger_score;
}

}

uint8_t Marking::find_their_robot_in_possession() {
Expand Down
3 changes: 1 addition & 2 deletions src/rj_strategy/src/coordinator/marking_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,7 @@ void MarkingClient::join_group(StatusCallback callback) {
// Create subscription to track selected kicker.
subscription_ = node_->create_subscription<rj_msgs::msg::Marking>(
"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);
});
Expand Down