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

Create goal boxes #2224

Merged
merged 4 commits into from
Apr 24, 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
12 changes: 12 additions & 0 deletions rj_common/include/rj_common/field_dimensions.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,9 @@ struct FieldDimensions {

[[nodiscard]] rj_geometry::Point center_point() const { return center_point_; }

[[nodiscard]] rj_geometry::Rect our_goal_area() const { return our_goal_area_; }
[[nodiscard]] rj_geometry::Rect their_goal_area() const { return their_goal_area_; }

/*
* Provides a rect that is a padded version of their goalbox.
* Used as a static obstacle in certain match situations.
Expand Down Expand Up @@ -230,6 +233,13 @@ struct FieldDimensions {
their_left_goal_post_coordinate_ = rj_geometry::Point(-goal_width_ / 2, length_);
their_right_goal_post_coordinate_ = rj_geometry::Point(goal_width_ / 2, length_);

our_goal_area_ =
rj_geometry::Rect(our_left_goal_post_coordinate_,
our_right_goal_post_coordinate_ - rj_geometry::Point(0, goal_depth_));
their_goal_area_ = rj_geometry::Rect(
their_left_goal_post_coordinate_,
their_right_goal_post_coordinate_ + rj_geometry::Point(0, goal_depth_));

our_left_corner_ = rj_geometry::Point(field_x_left_coord_, 0.0);
our_right_corner_ = rj_geometry::Point(field_x_right_coord_, 0.0);
their_left_corner_ = rj_geometry::Point(field_x_left_coord_, length_);
Expand Down Expand Up @@ -322,6 +332,8 @@ struct FieldDimensions {

rj_geometry::Rect our_penalty_area_coordinates_;
rj_geometry::Rect their_penalty_area_coordinates_;
rj_geometry::Rect our_goal_area_;
rj_geometry::Rect their_goal_area_;
rj_geometry::Point our_left_goal_post_coordinate_;
rj_geometry::Point our_right_goal_post_coordinate_;
rj_geometry::Point their_left_goal_post_coordinate_;
Expand Down
7 changes: 7 additions & 0 deletions soccer/src/soccer/planning/global_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,11 @@ rj_geometry::ShapeSet GlobalState::create_defense_area_obstacles() {
auto our_defense_area{
std::make_shared<rj_geometry::Rect>(last_field_dimensions_.our_defense_area())};

auto our_goal_area{std::make_shared<rj_geometry::Rect>(last_field_dimensions_.our_goal_area())};

auto their_goal_area{
std::make_shared<rj_geometry::Rect>(last_field_dimensions_.their_goal_area())};

// Sometimes there is a greater distance we need to keep:
// https://robocup-ssl.github.io/ssl-rules/sslrules.html#_robot_too_close_to_opponent_defense_area
bool is_extra_dist_necessary = (last_play_state_.state() == PlayState::State::Stop ||
Expand All @@ -99,7 +104,9 @@ rj_geometry::ShapeSet GlobalState::create_defense_area_obstacles() {
// Combine both defense areas into ShapeSet
rj_geometry::ShapeSet def_area_obstacles{};
def_area_obstacles.add(our_defense_area);
def_area_obstacles.add(our_goal_area);
def_area_obstacles.add(their_defense_area);
def_area_obstacles.add(their_goal_area);

return def_area_obstacles;
}
Expand Down
Loading