Skip to content

Commit

Permalink
Removed unnecessary changes and added comments
Browse files Browse the repository at this point in the history
  • Loading branch information
sanatd33 committed Jan 17, 2024
1 parent 178481b commit c14daaf
Show file tree
Hide file tree
Showing 4 changed files with 58 additions and 9 deletions.
37 changes: 34 additions & 3 deletions soccer/src/soccer/strategy/agent/position/offense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@ Offense::State Offense::update_state() {
double distance_to_ball = robot_position.dist_to(ball_position);

if (current_state_ == IDLING) {
send_scorer_request();
next_state = SEARCHING;
// send_scorer_request();
next_state = AWAITING_SEND_PASS;
} else if (current_state_ == SEARCHING) {
if (scorer_) {
next_state = STEALING;
Expand Down Expand Up @@ -75,6 +75,10 @@ Offense::State Offense::update_state() {
if (check_is_done()) {
next_state = IDLING;
}
} else if (current_state_ == AWAITING_SEND_PASS) {
if (distance_to_ball < ball_lost_distance_){
Position::broadcast_direct_pass_request();
}
}

return next_state;
Expand All @@ -92,7 +96,6 @@ std::optional<RobotIntent> Offense::state_to_task(RobotIntent intent) {
intent.motion_command = empty_motion_cmd;
return intent;
} else if (current_state_ == PASSING) {
// attempt to pass the ball to the target robot
rj_geometry::Point target_robot_pos =
world_state()->get_robot(true, target_robot_id).pose.position();
planning::LinearMotionInstant target{target_robot_pos};
Expand Down Expand Up @@ -172,6 +175,10 @@ std::optional<RobotIntent> Offense::state_to_task(RobotIntent intent) {
planning::MotionCommand{"path_target", current_location_instant, face_ball};
intent.motion_command = face_ball_cmd;
return intent;
} else if (current_state_ == AWAITING_SEND_PASS) {
auto empty_motion_cmd = planning::MotionCommand{};
intent.motion_command = empty_motion_cmd;
return intent;
}

// should be impossible to reach, but this is an EmptyMotionCommand
Expand Down Expand Up @@ -203,6 +210,30 @@ communication::PosAgentResponseWrapper Offense::receive_communication_request(
std::get_if<communication::ResetScorerRequest>(&request.request)) {
communication::Acknowledge response = receive_reset_scorer_request();
comm_response.response = response;
} else if (const communication::PassRequest* pass_request =
std::get_if<communication::PassRequest>(&request.request)) {
//If the robot recieves a PassRequest, only process it if we are oppen

rj_geometry::Point robot_position = world_state()->get_robot(true, robot_id_).pose.position();
rj_geometry::Point from_robot_position = world_state()->get_robot(true, pass_request->from_robot_id).pose.position();
rj_geometry::Segment pass_path{from_robot_position, robot_position};

Check failure on line 219 in soccer/src/soccer/strategy/agent/position/offense.cpp

View workflow job for this annotation

GitHub Actions / build-and-test

use of undeclared identifier 'world_state'; did you mean 'WorldState'?
double min_robot_dist = 10000;

Check failure on line 220 in soccer/src/soccer/strategy/agent/position/offense.cpp

View workflow job for this annotation

GitHub Actions / build-and-test

use of undeclared identifier 'world_state'; did you mean 'WorldState'?
float min_path_dist = 10000;

//Calculates the minimum distance from the current robot to all other robots
//Also calculates the minimum distance from another robot to the passing line
for (auto bot : world_state()->their_robots) {
rj_geometry::Point opp_pos = bot.pose.position();
min_robot_dist = std::min(min_robot_dist, robot_position.dist_to(opp_pos));

Check failure on line 227 in soccer/src/soccer/strategy/agent/position/offense.cpp

View workflow job for this annotation

GitHub Actions / build-and-test

use of undeclared identifier 'world_state'; did you mean 'WorldState'?
min_path_dist = std::min(min_path_dist, pass_path.dist_to(opp_pos));
}

//If the current robot is far enough away from other robots and there are no other robots in the passing line, process the request
//Currently, max_receive_distance is used to determine when we are open, but this may need to change
if (min_robot_dist > max_receive_distance && min_path_dist > max_receive_distance) {
communication::PassResponse response = Position::receive_pass_request(*pass_request);
comm_response.response = response;
}
}

return comm_response;
Expand Down
4 changes: 4 additions & 0 deletions soccer/src/soccer/strategy/agent/position/offense.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ class Offense : public Position {
STEALING, // attempting to intercept the ball from the other team
FACING, // turning to face the ball
SCORER, // overrides everything and will attempt to steal the bal and shoot it
AWAITING_SEND_PASS, //is waiting to send a pass to someone else
};

State update_state();
Expand All @@ -61,6 +62,8 @@ class Offense : public Position {
bool scorer_ = false;
bool last_scorer_ = false;

communication::PassResponse receive_pass_request(communication::PassRequest pass_request);

/**
* @brief Send request to the other robots to see if this robot should be the scorer
*
Expand All @@ -77,6 +80,7 @@ class Offense : public Position {
communication::ScorerResponse receive_scorer_request(
communication::ScorerRequest scorer_request);


/**
* @brief This agent can go through the distance of every other offensive robot from the goal
* to decide whether this robot should become the scorer.
Expand Down
24 changes: 18 additions & 6 deletions soccer/src/soccer/strategy/agent/position/position.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,11 +127,11 @@ void Position::receive_communication_response(communication::AgentPosResponseWra
communication::PosAgentResponseWrapper Position::receive_communication_request(
communication::AgentPosRequestWrapper request) {
communication::PosAgentResponseWrapper comm_response{};
if (const communication::PassRequest* pass_request =
std::get_if<communication::PassRequest>(&request.request)) {
communication::PassResponse pass_response = receive_pass_request(*pass_request);
comm_response.response = pass_response;
} else if (const communication::IncomingBallRequest* incoming_ball_request =
// if (const communication::PassRequest* pass_request =
// std::get_if<communication::PassRequest>(&request.request)) {
// communication::PassResponse pass_response = receive_pass_request(*pass_request);
// comm_response.response = pass_response;
if (const communication::IncomingBallRequest* incoming_ball_request =
std::get_if<communication::IncomingBallRequest>(&request.request)) {
communication::Acknowledge incoming_pass_acknowledge =
acknowledge_pass(*incoming_ball_request);
Expand Down Expand Up @@ -166,14 +166,26 @@ void Position::send_direct_pass_request(std::vector<u_int8_t> target_robots) {
communication_request_ = communication_request;
}

void Position::broadcast_direct_pass_request() {
communication::PassRequest pass_request{};
communication::generate_uid(pass_request);
pass_request.direct = true;
pass_request.from_robot_id = robot_id_;

communication::PosAgentRequestWrapper communication_request{};
communication_request.request = pass_request;
communication_request.urgent = true;
communication_request.broadcast = true;
communication_request_ = communication_request;
}

communication::PassResponse Position::receive_pass_request(
communication::PassRequest pass_request) {
communication::PassResponse pass_response{};
communication::generate_uid(pass_response);

if (pass_request.direct) {
// Handle direct pass request
// TODO: Make this rely on actually being open
pass_response.direct_open = true;
} else {
// TODO: Handle indirect pass request
Expand Down
2 changes: 2 additions & 0 deletions soccer/src/soccer/strategy/agent/position/position.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,8 @@ class Position {
*/
void send_direct_pass_request(std::vector<u_int8_t> target_robots);

void broadcast_direct_pass_request();

/**
* @brief receives and handles a pass_request
*
Expand Down

0 comments on commit c14daaf

Please sign in to comment.