Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix oscillation and added block shot heuristic #2210

Merged
merged 4 commits into from
Mar 6, 2024
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
51 changes: 35 additions & 16 deletions soccer/src/soccer/strategy/agent/position/seeker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ rj_geometry::Point Seeker::calculate_open_point(double current_prec, double min_
while (current_prec > min_prec) {
rj_geometry::Point ball_pos = world_state->ball.position;
rj_geometry::Point min = current_point;
double min_val = Seeker::eval_point(ball_pos, current_point, world_state);
double min_val = eval_point(ball_pos, current_point, world_state, field_dimensions);
double curr_val{};
// Points in a current_prec radius of the current point, at 45 degree intervals
std::vector<rj_geometry::Point> check_points{
Expand All @@ -60,7 +60,7 @@ rj_geometry::Point Seeker::calculate_open_point(double current_prec, double min_

// Finds the best point out of the ones checked
for (auto point : check_points) {
curr_val = Seeker::eval_point(ball_pos, point, world_state);
curr_val = Seeker::eval_point(ball_pos, point, world_state, field_dimensions);
if (curr_val < min_val) {
min_val = curr_val;
min = point;
Expand Down Expand Up @@ -135,7 +135,7 @@ rj_geometry::Point Seeker::correct_point(rj_geometry::Point p,
}

double Seeker::eval_point(rj_geometry::Point ball_pos, rj_geometry::Point current_point,
const WorldState* world_state) {
const WorldState* world_state, const FieldDimensions& field_dimensions) {
// Determines 'how good' a point is
// A higher value is a worse point

Expand All @@ -148,7 +148,7 @@ double Seeker::eval_point(rj_geometry::Point ball_pos, rj_geometry::Point curren
// Line of Sight Heuristic
double max = 0;
double curr_dp = 0;
for (auto robot : world_state->their_robots) {
for (const RobotState& robot : world_state->their_robots) {
curr_dp = (current_point).norm().dot((robot.pose.position() - ball_pos).norm());
curr_dp *= curr_dp;
if (curr_dp > max) {
Expand All @@ -161,23 +161,31 @@ double Seeker::eval_point(rj_geometry::Point ball_pos, rj_geometry::Point curren
rj_geometry::Segment pass_path{ball_pos, current_point};
double min_robot_dist = 10000;
float min_path_dist = 10000;
for (auto bot : world_state->their_robots) {
rj_geometry::Point opp_pos = bot.pose.position();
min_robot_dist = std::min(min_robot_dist, current_point.dist_to(opp_pos));
min_path_dist = std::min(min_path_dist, pass_path.dist_to(opp_pos));
for (const RobotState& robot : world_state->their_robots) {
rj_geometry::Point opp_pos = robot.pose.position();
auto robot_dist = current_point.dist_to(opp_pos);
min_robot_dist = std::min(min_robot_dist, robot_dist);
auto path_dist = pass_path.dist_to(opp_pos);
min_path_dist = std::min(min_path_dist, path_dist);
}

for (auto bot : world_state->our_robots) {
rj_geometry::Point ally_pos = bot.pose.position();
min_robot_dist = std::min(min_robot_dist, current_point.dist_to(ally_pos));
min_path_dist = std::min(min_path_dist, pass_path.dist_to(ally_pos));
for (const RobotState& robot : world_state->our_robots) {
rj_geometry::Point ally_pos = robot.pose.position();
auto robot_dist = current_point.dist_to(ally_pos);
// if dist is 0, then bot must be seeker (self ) robot, so should ignore
if (robot_dist == 0) {
continue;
}
min_robot_dist = std::min(min_robot_dist, robot_dist);
auto path_dist = pass_path.dist_to(ally_pos);
min_path_dist = std::min(min_path_dist, path_dist);
}

min_path_dist = 0.1f / min_path_dist;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

what does this do?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The oscillation problem occurs because the for loop above includes the current seeker robot. The dist from current point to the current robot is 0, leading to divide by 0 problems. This skips over that case.

min_robot_dist = 0.1 / min_robot_dist;

// More Line of Sight Heuristics
for (auto robot : world_state->our_robots) {
for (const RobotState& robot : world_state->our_robots) {
curr_dp = (current_point - ball_pos).norm().dot((robot.pose.position() - ball_pos).norm());
curr_dp *= curr_dp;
if (curr_dp > max) {
Expand All @@ -186,11 +194,22 @@ double Seeker::eval_point(rj_geometry::Point ball_pos, rj_geometry::Point curren
}

// Additional heuristics for calculating optimal point
double ball_proximity_loss = (current_point - ball_pos).mag() * .002;
double goal_distance_loss = (8.5 - current_point.y()) * 0.15 + abs(current_point.x()) * 0.15;
const double ball_proximity_loss_weight = 0.002;
const double goal_distance_loss_weight = 0.15;
double ball_proximity_loss = (current_point - ball_pos).mag() * ball_proximity_loss_weight;
double goal_distance_loss = (field_dimensions.their_defense_area().miny() - current_point.y()) *
goal_distance_loss_weight;

rj_geometry::Segment ball_goal{ball_pos, field_dimensions.their_goal_loc()};
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this is neat! much easier than projecting vectors manually. didn't know you could do this

double block_shot_dist = ball_goal.dist_to(current_point);
double block_shot_loss = 0;
if (block_shot_dist < 1) {
block_shot_loss = 1;
}

// Final evaluation
return max + ball_proximity_loss + goal_distance_loss + min_path_dist + min_robot_dist;
return max + ball_proximity_loss + goal_distance_loss + min_path_dist + min_robot_dist +
block_shot_loss;
}

} // namespace strategy
3 changes: 2 additions & 1 deletion soccer/src/soccer/strategy/agent/position/seeker.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,8 @@ class Seeker : public RoleInterface {
* @return double The evaluation of that target point
*/
static double eval_point(rj_geometry::Point ball_pos, rj_geometry::Point current_point,
const WorldState* world_state);
const WorldState* world_state,
const FieldDimensions& field_dimensions);
};

} // namespace strategy
Loading