Skip to content

Commit 6ecb511

Browse files
authored
Merge branch 'develop' into refactor
2 parents 8dfeb97 + 7f76aee commit 6ecb511

File tree

7 files changed

+102
-47
lines changed

7 files changed

+102
-47
lines changed

crane_msgs/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@ set(msg_files
3737
"msg/analysis/Kick.msg"
3838
"msg/analysis/Slack.msg"
3939
"msg/analysis/SlackWithPoint.msg"
40+
"msg/analysis/FloatWithID.msg"
4041

4142
"msg/planner/PassPlan.msg"
4243
"msg/planner/PassInfo.msg"
+2
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
uint8 id
2+
float32 value

crane_msgs/msg/analysis/GameAnalysis.msg

+3
Original file line numberDiff line numberDiff line change
@@ -5,3 +5,6 @@ Slack[] our_slack
55
Slack[] their_slack
66

77
float32 ball_horizon
8+
9+
# sorted by score
10+
FloatWithID[] pass_scores

crane_robot_skills/src/attacker.cpp

+9-47
Original file line numberDiff line numberDiff line change
@@ -217,58 +217,20 @@ Attacker::Attacker(RobotCommandWrapperBase::SharedPtr & base)
217217

218218
auto our_robots = world_model()->ours.getAvailableRobots(robot()->id, true);
219219
const auto enemy_robots = world_model()->theirs.getAvailableRobots();
220-
// TODO(HansRobo): しっかりパス先を選定する
221-
// int receiver_id = getParameter<int>("receiver_id");
222220
double best_score = 0.0;
223221
Point best_target;
224-
int best_id = -1;
225-
for (auto & our_robot : our_robots) {
226-
// ゴールに近い味方は対象外
227-
if (our_robot->getDistance(world_model()->getOurGoalCenter()) < 3.0) {
222+
for (const auto score_with_id : world_model()->getMsg().game_analysis.pass_scores) {
223+
if (score_with_id.id != robot()->id) {
228224
continue;
229-
}
230-
Segment ball_to_target{world_model()->ball.pos, our_robot->pose.pos};
231-
auto target = our_robot->pose.pos;
232-
double score = 1.0;
233-
// パス先のゴールチャンスが大きい場合はスコアを上げる(30度以上で最大0.5上昇)
234-
auto [best_angle, goal_angle_width] =
235-
world_model()->getLargestGoalAngleRangeFromPoint(target);
236-
score += std::clamp(goal_angle_width / (M_PI / 12.), 0.0, 0.5);
237-
238-
// 敵ゴールに近いときはスコアを上げる
239-
double normed_distance_to_their_goal =
240-
((target - world_model()->getTheirGoalCenter()).norm() -
241-
(world_model()->field_size.x() * 0.5)) /
242-
(world_model()->field_size.x() * 0.5);
243-
// マイナスのときはゴールに近い
244-
score *= (1.0 - normed_distance_to_their_goal);
245-
246-
auto nearest_enemy = world_model()->getNearestRobotWithDistanceFromSegment(
247-
ball_to_target, world_model()->theirs.getAvailableRobots());
248-
// ボールから遠い敵がパスコースを塞いでいる場合は諦める
249-
if (nearest_enemy.has_value()) {
250-
if (
251-
nearest_enemy->robot->getDistance(world_model()->ball.pos) > 1.0 &&
252-
nearest_enemy->distance < 0.4) {
253-
score = 0.0;
254-
}
255-
// パスラインに敵がいるときはスコアを下げる
256-
score *= 1.0 / (1.0 + nearest_enemy->distance);
257-
}
258-
259-
if (score > best_score) {
260-
best_score = score;
261-
best_target = target;
262-
best_id = our_robot->id;
225+
} else if (score_with_id.id != world_model()->getOurGoalieId()) {
226+
continue;
227+
} else {
228+
kick_target = world_model()->getOurRobot(score_with_id.id)->pose.pos;
229+
pass_receiver_id = score_with_id.id;
230+
return true;
263231
}
264232
}
265-
266-
auto ret = best_score > 0.5;
267-
if (ret) {
268-
kick_target = best_target;
269-
pass_receiver_id = best_id;
270-
}
271-
return ret;
233+
return false;
272234
});
273235

274236
addTransition(AttackerState::STANDARD_PASS, AttackerState::ENTRY_POINT, [this]() -> bool {

crane_world_model_publisher/include/crane_world_model_publisher/world_model_publisher.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -96,6 +96,8 @@ class WorldModelPublisherComponent : public rclcpp::Node
9696

9797
CraneVisualizerBuffer::MessageBuilder::UniquePtr visualizer;
9898

99+
CraneVisualizerBuffer::MessageBuilder::UniquePtr pass_score_visualizer;
100+
99101
std::array<std::deque<crane_msgs::msg::RobotInfo>, 20> friend_history;
100102

101103
std::array<std::deque<crane_msgs::msg::RobotInfo>, 20> enemy_history;

crane_world_model_publisher/src/world_model_publisher.cpp

+70
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44
// license that can be found in the LICENSE file or at
55
// https://opensource.org/licenses/MIT.
66

7+
#include <crane_basics/ddps.hpp>
78
#include <crane_basics/geometry_operations.hpp>
89
#include <crane_basics/time.hpp>
910
#include <crane_world_model_publisher/world_model_publisher.hpp>
@@ -21,6 +22,9 @@ WorldModelPublisherComponent::WorldModelPublisherComponent(const rclcpp::NodeOpt
2122
visualizer =
2223
std::make_unique<crane::CraneVisualizerBuffer::MessageBuilder>("world_model/trajectory");
2324

25+
pass_score_visualizer =
26+
std::make_unique<crane::CraneVisualizerBuffer::MessageBuilder>("world_model/pass_score");
27+
2428
declare_parameter("position_history_size", 200);
2529
get_parameter<int>("position_history_size", history_size);
2630

@@ -233,6 +237,72 @@ void WorldModelPublisherComponent::postProcessWorldModel(WorldModelWrapper::Shar
233237
}
234238
game_analysis_msg.their_slack.push_back(slack_msg);
235239
}
240+
241+
auto our_robots = world_model->ours.getAvailableRobots(true);
242+
const auto enemy_robots = world_model->theirs.getAvailableRobots();
243+
244+
auto calc_score = [&](Point p) {
245+
Segment ball_to_target{world_model->ball.pos, p};
246+
double score = 1.0;
247+
// 0~4mで遠くなるほどスコアが高い
248+
score += std::clamp((p - world_model->ball.pos).norm() * 0.5, 0.0, 2.0);
249+
// パス先のゴールチャンスが大きい場合はスコアを上げる(30度以上で最大0.5上昇)
250+
auto [best_angle, goal_angle_width] = world_model->getLargestGoalAngleRangeFromPoint(p);
251+
score += std::clamp(goal_angle_width / (M_PI / 12.), 0.0, 0.5);
252+
// 敵ゴールに近いときはスコアを上げる
253+
double normed_distance_to_their_goal =
254+
((p - world_model->getTheirGoalCenter()).norm() - (world_model->field_size.x() * 0.5)) /
255+
(world_model->field_size.x() * 0.5);
256+
// マイナスのときはゴールに近い
257+
score *= (1.0 - normed_distance_to_their_goal * 0.5);
258+
if (auto nearest_enemy =
259+
world_model->getNearestRobotWithDistanceFromSegment(ball_to_target, enemy_robots);
260+
nearest_enemy) {
261+
// ボールから遠い敵がパスコースを塞いでいる場合は諦める
262+
if (
263+
nearest_enemy->robot->getDistance(world_model->ball.pos) > 1.0 &&
264+
nearest_enemy->distance < 0.4) {
265+
score = 0.0;
266+
}
267+
// パスラインに敵がいるときはスコアを下げる
268+
score *= 1.0 / (1.0 + nearest_enemy->distance);
269+
}
270+
271+
if (world_model->point_checker.isPenaltyArea(p)) {
272+
score = 0.0;
273+
}
274+
return score;
275+
};
276+
277+
constexpr double UNIT = 0.2;
278+
auto grid_points = getPoints(
279+
Point(0, 0), UNIT, UNIT, world_model->field_size.x() / UNIT,
280+
world_model->field_size.y() / UNIT);
281+
auto score_grid =
282+
grid_points |
283+
ranges::views::transform([&](const auto & p) { return std::make_pair(p, calc_score(p)); }) |
284+
ranges::to<std::vector>();
285+
286+
ranges::for_each(score_grid, [&](const auto & pair) {
287+
SvgCircleBuilder circle;
288+
circle.center(pair.first).radius(pair.second * 0.05).stroke("red").strokeWidth(2.);
289+
// pass_score_visualizer->add(circle.getSvgString());
290+
});
291+
pass_score_visualizer->flush();
292+
293+
auto score_with_bots = our_robots | ranges::views::transform([&](const auto & robot) {
294+
return std::make_pair(robot, calc_score(robot->pose.pos));
295+
}) |
296+
ranges::to<std::vector>();
297+
// larger score first
298+
ranges::sort(score_with_bots, [](const auto & a, const auto & b) { return a.second > b.second; });
299+
300+
game_analysis_msg.pass_scores = score_with_bots | ranges::views::transform([](const auto & pair) {
301+
crane_msgs::msg::FloatWithID msg;
302+
return msg.set__id(pair.first->id).set__value(pair.second);
303+
}) |
304+
ranges::to<std::vector>();
305+
236306
world_model->update(game_analysis_msg);
237307
}
238308

utility/crane_basics/include/crane_basics/ddps.hpp

+15
Original file line numberDiff line numberDiff line change
@@ -51,5 +51,20 @@ inline auto getPoints(const Point & center, float unit, int unit_num) -> std::ve
5151
return points;
5252
}
5353

54+
inline auto getPoints(
55+
const Point & center, float unit_x, float unit_y, int unit_num_x, int unit_num_y)
56+
-> std::vector<Point>
57+
{
58+
std::vector<Point> points;
59+
for (float x = center.x() - unit_x * (unit_num_x / 2.f);
60+
x <= center.x() + unit_x * (unit_num_x / 2.f); x += unit_x) {
61+
for (float y = center.y() - unit_y * (unit_num_y / 2.f);
62+
y <= center.y() + unit_y * (unit_num_y / 2.f); y += unit_y) {
63+
points.emplace_back(Point(x, y));
64+
}
65+
}
66+
return points;
67+
}
68+
5469
} // namespace crane
5570
#endif // CRANE_BASICS__DDPS_HPP_

0 commit comments

Comments
 (0)