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
178 changes: 37 additions & 141 deletions soccer/src/soccer/strategy/agent/position/defense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,16 +2,20 @@

namespace strategy {

Defense::Defense(int r_id) : Position(r_id, "Defense"), marker_{field_dimensions_} {}
Defense::Defense(int r_id) : Position(r_id, "Defense") {}

Check warning on line 5 in soccer/src/soccer/strategy/agent/position/defense.cpp

View workflow job for this annotation

GitHub Actions / build-and-test

constructor does not initialize these fields: next_state

Defense::Defense(const Position& other) : Position{other}, marker_{field_dimensions_} {
Defense::~Defense() {

Check warning on line 7 in soccer/src/soccer/strategy/agent/position/defense.cpp

View workflow job for this annotation

GitHub Actions / build-and-test

an exception may be thrown in function '~Defense' which should not throw exceptions
die();

Check warning on line 8 in soccer/src/soccer/strategy/agent/position/defense.cpp

View workflow job for this annotation

GitHub Actions / build-and-test

Call to virtual method 'Defense::die' during destruction bypasses virtual dispatch
}

Defense::Defense(const Position& other) : Position{other} {

Check warning on line 11 in soccer/src/soccer/strategy/agent/position/defense.cpp

View workflow job for this annotation

GitHub Actions / build-and-test

constructor does not initialize these fields: next_state
position_name_ = "Defense";
walling_robots_ = {};
}

std::optional<RobotIntent> Defense::derived_get_task(RobotIntent intent) {
current_state_ = update_state();
// waller_id_ = get_waller_id();
//waller_id_ = get_waller_id();
return state_to_task(intent);
}

Expand All @@ -20,162 +24,49 @@
}

Defense::State Defense::update_state() {
State next_state = current_state_;
// handle transitions between states
WorldState* world_state = last_world_state_;

rj_geometry::Point robot_position = world_state->get_robot(true, robot_id_).pose.position();
rj_geometry::Point ball_position = world_state->ball.position;
rj_geometry::Point robot_position = last_world_state_->get_robot(true, robot_id_).pose.position();
rj_geometry::Point ball_position = last_world_state_->ball.position;
double distance_to_ball = robot_position.dist_to(ball_position);

if (!Defense::is_alive(robot_id_) ||
(current_state_ == WALLING && waller_id_ == -1)) { // deadlock band-aid :(
Defense::die();
return IDLING;
}

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;
return DEFAULT;
}

switch (current_state_) {
case IDLING:
next_state = JOINING_WALL; // deadlock band-aid :(]
break;
case JOINING_WALL:
send_join_wall_request();
// SPDLOG_INFO("join wall {}", robot_id_);
case DEFAULT: {
return JOINING_WALL;
}
case JOINING_WALL: {
send_join_wall_request(); // sets waller_id_
SPDLOG_INFO("{} joining wall at wall pos {}", robot_id_, waller_id_);
next_state = WALLING;
walling_robots_ = {(u_int8_t)robot_id_};
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;
case RECEIVING:
// transition to idling if we are close enough to the ball
if (distance_to_ball < ball_receive_distance_) {
next_state = IDLING;
}
break;
case PASSING:
// transition to idling if we no longer have the ball (i.e. it was passed or it was
// stolen)
if (check_is_done()) {
next_state = IDLING;
}

if (distance_to_ball > ball_lost_distance_) {
next_state = IDLING;
}
break;
case FACING:
if (check_is_done()) {
next_state = IDLING;
}
case MARKING:
if (marker_.get_target() == -1 || marker_.target_out_of_bounds(world_state)) {
next_state = ENTERING_MARKING;
}
}
case WALLING: {
break;
case ENTERING_MARKING:
marker_.choose_target(world_state);
int target_id = marker_.get_target();
if (target_id == -1) {
next_state = ENTERING_MARKING;
} else {
next_state = MARKING;
}
}
}

return next_state;
}

std::optional<RobotIntent> 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;
return intent;
// DO NOTHING
} else if (current_state_ == SEARCHING) {
// TODO(https://app.clickup.com/t/8677qektb): Define defensive searching behavior
} else if (current_state_ == RECEIVING) {
// check how far we are from the ball
// TODO(https://app.clickup.com/t/8677rrgjn): Convert RECEIVING state into role_interface
rj_geometry::Point robot_position =
last_world_state_->get_robot(true, robot_id_).pose.position();
rj_geometry::Point ball_position = last_world_state_->ball.position;
double distance_to_ball = robot_position.dist_to(ball_position);
if (distance_to_ball > max_receive_distance && !chasing_ball) {
auto motion_instance =
planning::LinearMotionInstant{robot_position, rj_geometry::Point{0.0, 0.0}};
auto face_ball = planning::FaceBall{};
auto face_ball_cmd = planning::MotionCommand{"path_target", motion_instance, face_ball};
intent.motion_command = face_ball_cmd;
} else {
// intercept the ball
chasing_ball = true;
auto collect_cmd = planning::MotionCommand{"collect"};
intent.motion_command = collect_cmd;
}
return intent;
} else if (current_state_ == PASSING) {
// attempt to pass the ball to the target robot
rj_geometry::Point target_robot_pos =
last_world_state_->get_robot(true, target_robot_id).pose.position();
planning::LinearMotionInstant target{target_robot_pos};
auto line_kick_cmd = planning::MotionCommand{"line_kick", target};
intent.motion_command = line_kick_cmd;
intent.shoot_mode = RobotIntent::ShootMode::KICK;
// NOTE: Check we can actually use break beams
intent.trigger_mode = RobotIntent::TriggerMode::ON_BREAK_BEAM;
// TODO: Adjust the kick speed based on distance
intent.kick_speed = 3.0;
intent.is_active = true;
return intent;
cached_ball_pos_ = get_ball_pos();

if (current_state_ == DEFAULT) {

Check warning on line 60 in soccer/src/soccer/strategy/agent/position/defense.cpp

View workflow job for this annotation

GitHub Actions / build-and-test

repeated branch in conditional chain
return std::nullopt;
} else if (current_state_ == JOINING_WALL) {

Check warning on line 62 in soccer/src/soccer/strategy/agent/position/defense.cpp

View workflow job for this annotation

GitHub Actions / build-and-test

do not use 'else' after 'return'
return std::nullopt;
} else if (current_state_ == WALLING) {
// band-aid fix: ball might be occluded
if (last_world_state_->ball.visible) {
cached_ball_pose = last_world_state_->ball.position;
}
if (!walling_robots_.empty() && waller_id_ != -1) {
Waller waller{waller_id_, walling_robots_};
// return waller.get_task(intent, last_world_state_, this->field_dimensions_);
return waller.get_task_with_ball(intent, last_world_state_, this->field_dimensions_,
cached_ball_pose);
return waller.get_task_with_ball(intent, last_world_state_, this->field_dimensions_, cached_ball_pos_);

Check warning on line 68 in soccer/src/soccer/strategy/agent/position/defense.cpp

View workflow job for this annotation

GitHub Actions / build-and-test

parameter 'intent' is passed by value and only copied once; consider moving it to avoid unnecessary copies
}
} else if (current_state_ == FACING) {
rj_geometry::Point robot_position =
last_world_state_->get_robot(true, robot_id_).pose.position();
auto current_location_instant =
planning::LinearMotionInstant{robot_position, rj_geometry::Point{0.0, 0.0}};
auto face_ball = planning::FaceBall{};
auto face_ball_cmd =
planning::MotionCommand{"path_target", current_location_instant, face_ball};
intent.motion_command = face_ball_cmd;
return intent;
} else if (current_state_ == ENTERING_MARKING) {
// Prepares a robot for marking. NOTE: May update to add move to center of field
auto empty_motion_cmd = planning::MotionCommand{};
intent.motion_command = empty_motion_cmd;
return intent;
} else if (current_state_ == MARKING) {
// Marker marker = Marker((u_int8_t) robot_id_);
return marker_.get_task(intent, last_world_state_, this->field_dimensions_);
}

return std::nullopt;
Expand Down Expand Up @@ -311,14 +202,11 @@
}
}

void Defense::derived_acknowledge_pass() { current_state_ = FACING; }
void Defense::derived_acknowledge_pass() {}

void Defense::derived_pass_ball() { current_state_ = PASSING; }
void Defense::derived_pass_ball() {}

void Defense::derived_acknowledge_ball_in_transit() {
current_state_ = RECEIVING;
chasing_ball = false;
}
void Defense::derived_acknowledge_ball_in_transit() {}

int Defense::get_waller_id() {
return find(walling_robots_.begin(), walling_robots_.end(), robot_id_) -
Expand All @@ -333,4 +221,12 @@

void Defense::revive() { current_state_ = JOINING_WALL; }

rj_geometry::Point Defense::get_ball_pos() const {
if (last_world_state_->ball.visible) {
return last_world_state_->ball.position;
} else {

Check warning on line 227 in soccer/src/soccer/strategy/agent/position/defense.cpp

View workflow job for this annotation

GitHub Actions / build-and-test

do not use 'else' after 'return'
return cached_ball_pos_;
}
}

} // namespace strategy
20 changes: 6 additions & 14 deletions soccer/src/soccer/strategy/agent/position/defense.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
class Defense : public Position {
public:
Defense(int r_id);
~Defense() override = default;
~Defense() override;
Defense(const Position& other);

void receive_communication_response(communication::AgentPosResponseWrapper response) override;
Expand Down Expand Up @@ -60,18 +60,14 @@
std::optional<RobotIntent> derived_get_task(RobotIntent intent) override;

enum State {
IDLING, // simply staying in place
DEFAULT, // simply staying in place
JOINING_WALL, // send message to find its place in the wall
WALLING, // participating in the wall
SEARCHING, // moving around on the field to do something
RECEIVING, // physically intercepting the ball from a pass
PASSING, // physically kicking the ball towards another robot
FACING, // turning to face the passing robot
MARKING, // Following closely to an offense robot
ENTERING_MARKING, // Choosing/waiting for a robot to mark
};

State update_state();
State current_state_ = DEFAULT;
State next_state;

Check warning on line 70 in soccer/src/soccer/strategy/agent/position/defense.hpp

View workflow job for this annotation

GitHub Actions / build-and-test

invalid case style for private member 'next_state'

std::optional<RobotIntent> state_to_task(RobotIntent intent);

Expand Down Expand Up @@ -116,17 +112,13 @@
std::vector<u_int8_t> 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_;

// band-aid function, used to track robot death in live play
bool is_alive(u_int8_t concerned_id);
// this tracks the ball pose (since it can be occluded in play)
rj_geometry::Point cached_ball_pose;
rj_geometry::Point cached_ball_pos_;
rj_geometry::Point get_ball_pos() const;
};

} // namespace strategy
Loading