-
Notifications
You must be signed in to change notification settings - Fork 186
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
Changes from all commits
Commits
Show all changes
4 commits
Select commit
Hold shift + click to select a range
ff57c1f
fix oscillation and added block shot heuristic
jacksherling eea2096
Update soccer/src/soccer/strategy/agent/position/seeker.cpp
jacksherling 8871ca2
Update soccer/src/soccer/strategy/agent/position/seeker.cpp
jacksherling 88eede4
cleanup
jacksherling File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -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{ | ||
|
@@ -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; | ||
|
@@ -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 | ||
|
||
|
@@ -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) { | ||
|
@@ -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; | ||
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) { | ||
|
@@ -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()}; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe 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 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
what does this do?
There was a problem hiding this comment.
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.