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

キーパーを除去 #686

Merged
merged 3 commits into from
Jan 11, 2025
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
4 changes: 2 additions & 2 deletions crane_robot_skills/src/attacker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -211,7 +211,7 @@ Attacker::Attacker(RobotCommandWrapperBase::SharedPtr & base)
return false;
}

auto our_robots = world_model()->ours.getAvailableRobots(robot()->id);
auto our_robots = world_model()->ours.getAvailableRobots(robot()->id, true);
const auto enemy_robots = world_model()->theirs.getAvailableRobots();
// TODO(HansRobo): しっかりパス先を選定する
// int receiver_id = getParameter<int>("receiver_id");
Expand Down Expand Up @@ -400,7 +400,7 @@ Attacker::Attacker(RobotCommandWrapperBase::SharedPtr & base)

std::shared_ptr<RobotInfo> Attacker::selectPassReceiver()
{
auto our_robots = world_model()->ours.getAvailableRobots(robot()->id);
auto our_robots = world_model()->ours.getAvailableRobots(robot()->id, true);
const auto enemy_robots = world_model()->theirs.getAvailableRobots();
double best_score = 0.0;
std::shared_ptr<RobotInfo> best_bot = nullptr;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,18 +39,30 @@ struct TeamInfo

uint32_t max_allowed_bots;

[[nodiscard]] auto getAvailableRobots(uint8_t my_id = 255) const -> RobotList
uint8_t goalie_id;

[[nodiscard]] auto getAvailableRobots(uint8_t my_id = 255, bool except_goalie = false) const
-> RobotList
{
return robots | ranges::views::filter([my_id](const auto & robot) {
return robot->available && robot->id != my_id;
return robots | ranges::views::filter([&](const auto & robot) {
if (except_goalie) {
return robot->available && robot->id != my_id && robot->id != goalie_id;
} else {
return robot->available && robot->id != my_id;
}
}) |
ranges::to<std::vector>();
}

[[nodiscard]] auto getAvailableRobotIds(uint8_t my_id = 255) const -> std::vector<uint8_t>
[[nodiscard]] auto getAvailableRobotIds(uint8_t my_id = 255, bool except_goalie = false) const
-> std::vector<uint8_t>
{
return robots | ranges::views::filter([my_id](const auto & robot) {
return robot->available && robot->id != my_id;
return robots | ranges::views::filter([&](const auto & robot) {
if (except_goalie) {
return robot->available && robot->id != my_id && robot->id != goalie_id;
} else {
return robot->available && robot->id != my_id;
}
}) |
ranges::views::transform([](const auto & robot) { return robot->id; }) |
ranges::to<std::vector>();
Expand Down Expand Up @@ -207,9 +219,9 @@ struct WorldModelWrapper
// rule 8.4.3
[[nodiscard]] auto getBallPlacementArea(double offset = 0.) const -> std::optional<Capsule>;

[[nodiscard]] auto getOurGoalieId() const { return latest_msg.our_goalie_id; }
[[nodiscard]] auto getOurGoalieId() const { return ours.goalie_id; }

[[nodiscard]] auto getTheirGoalieId() const { return latest_msg.their_goalie_id; }
[[nodiscard]] auto getTheirGoalieId() const { return theirs.goalie_id; }

/**
*
Expand Down
3 changes: 3 additions & 0 deletions utility/crane_msg_wrappers/src/world_model_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,9 @@ void WorldModelWrapper::update(const crane_msgs::msg::WorldModel & world_model)
}
}

ours.goalie_id = world_model.our_goalie_id;
theirs.goalie_id = world_model.their_goalie_id;

field_size << world_model.field_info.x, world_model.field_info.y;
penalty_area_size << world_model.penalty_area_size.x, world_model.penalty_area_size.y;

Expand Down
Loading