44// license that can be found in the LICENSE file or at
55// https://opensource.org/licenses/MIT.
66
7- #include " crane_world_model_publisher/pass_target_selector .hpp"
7+ #include " crane_game_analyzer/metrics/pass_target_metrics .hpp"
88
9+ #include < crane_physics/pass_evaluation.hpp>
910#include < range/v3/algorithm/find_if.hpp>
1011#include < range/v3/algorithm/min.hpp>
1112#include < range/v3/algorithm/sort.hpp>
1213#include < range/v3/functional/comparisons.hpp>
1314#include < range/v3/range/conversion.hpp>
14- #include < range/v3/range/operations.hpp>
1515#include < range/v3/view/filter.hpp>
1616#include < range/v3/view/transform.hpp>
1717
18- namespace crane
18+ namespace crane ::metrics
1919{
2020
21- auto PassTargetSelector::computePassOrigin (
22- const WorldModelWrapper::SharedPtr & world_model,
23- const std::deque<crane_msgs::msg::BallInfo> & ball_history,
24- const crane_msgs::msg::GameAnalysis & analysis_msg) const -> Point
21+ PassTargetMetric::PassTargetMetric () : MetricBase(MetricId::PASS_TARGET, " PassTarget" ) {}
22+
23+ auto PassTargetMetric::computePassOrigin (MetricContext & ctx) const -> Point
2524{
26- const auto & ball = world_model->ball ();
25+ const auto & ball = ctx. world_model ->ball ();
2726 // 検出かつ停止
2827 if (ball.isStopped () && ball.detected ) {
2928 return ball.pos ;
@@ -33,45 +32,47 @@ auto PassTargetSelector::computePassOrigin(
3332 return ball.getPredictedPosition (std::min (ball.getStopTime (), 1.0 ));
3433 }
3534 // 履歴から直近検出
36- for (auto it = ball_history. rbegin (); it != ball_history. rend (); ++it) {
35+ for (auto it = ctx. ball_history -> rbegin (); it != ctx. ball_history -> rend (); ++it) {
3736 if (it->detected ) {
3837 return Point (it->position .x , it->position .y );
3938 }
4039 }
4140 // キック起点
42- if (not analysis_msg .ongoing_kick .empty ()) {
43- const auto & k = analysis_msg .ongoing_kick .front ();
41+ if (not ctx. analysis .ongoing_kick .empty ()) {
42+ const auto & k = ctx. analysis .ongoing_kick .front ();
4443 return Point (k.origin_x , k.origin_y );
4544 }
4645 // フォールバック
4746 return ball.pos ;
4847}
4948
50- auto PassTargetSelector::calcScore (
51- const WorldModelWrapper::SharedPtr & world_model, const Point & pass_origin,
52- const Point & p) const -> double
49+ auto PassTargetMetric::calcScore (
50+ MetricContext & ctx, const Point & pass_origin, const Point & p) const -> double
5351{
5452 double score = 1.0 ;
53+
5554 // 距離(0〜4mで上昇)
5655 const double pass_distance = (p - pass_origin).norm ();
5756 score += std::clamp (pass_distance * 0.5 , 0.0 , 2.0 );
5857
5958 // ゴール角度(敵ゴールに対する見通し)
6059 {
61- auto [best_angle, goal_angle_width] = world_model->getLargestGoalAngleRangeFromPoint (p);
60+ auto [best_angle, goal_angle_width] = ctx. world_model ->getLargestGoalAngleRangeFromPoint (p);
6261 score += std::clamp (goal_angle_width / (M_PI / 12 .), 0.0 , 0.5 );
6362 }
63+
6464 // 自ゴールに対する危険度(大きいほど減点)
6565 {
6666 auto [best_angle, goal_angle_width] =
67- world_model->getLargestGoalAngleRangeFromPoint (p, world_model->getOurGoalPosts (), {});
67+ ctx. world_model ->getLargestGoalAngleRangeFromPoint (p, ctx. world_model ->getOurGoalPosts (), {});
6868 score -= std::clamp (goal_angle_width / (M_PI / 12 .), 0.0 , 0.5 );
6969 }
70+
7071 // 敵ゴールへの接近
7172 {
72- double normed_distance_to_their_goal =
73- ((p - world_model-> getTheirGoalCenter ()). norm () - ( world_model->fieldSize ().x () * 0.5 )) /
74- ( world_model->fieldSize ().x () * 0.5 );
73+ double normed_distance_to_their_goal = ((p - ctx. world_model -> getTheirGoalCenter ()). norm () -
74+ (ctx. world_model ->fieldSize ().x () * 0.5 )) /
75+ (ctx. world_model ->fieldSize ().x () * 0.5 );
7576 score *= (1.0 - normed_distance_to_their_goal * 0.5 );
7677 }
7778
@@ -85,13 +86,13 @@ auto PassTargetSelector::calcScore(
8586 const auto closest = getClosestPointAndDistance (enemy->pose .pos , pass_line);
8687 const double ball_time = (closest.closest_point - pass_origin).norm () / KICK_SPEED;
8788
88- auto slack_result = world_model->getBallSlackTime (
89+ auto slack_result = ctx. world_model ->getBallSlackTime (
8990 pass_origin, ball_velocity, ball_time, {enemy}, enemy_slack_config_);
9091
9192 return slack_result.has_value () ? slack_result->slack_time : 1.0 ;
9293 };
9394
94- auto enemies = world_model->theirs ().robotsWhere ().available ().get ();
95+ auto enemies = ctx. world_model ->theirs ().robotsWhere ().available ().get ();
9596 auto slack_times_view = enemies | ranges::views::filter ([&](const auto & enemy) {
9697 // パス起点から近すぎる敵はチップで飛び越せるので除外
9798 return enemy->getDistance (pass_origin) >= 1.0 ;
@@ -107,64 +108,50 @@ auto PassTargetSelector::calcScore(
107108
108109 score *= intercept_score;
109110
111+ // シャドウ評価: パスライン上の敵による遮蔽効果
112+ const double shadow_score = evaluatePassShadow (pass_origin, p, enemies);
113+ score *= shadow_score;
114+
110115 // ペナルティエリア内は無効
111- if (world_model->point_checker .isPenaltyArea (p)) {
116+ if (ctx. world_model ->point_checker .isPenaltyArea (p)) {
112117 score = 0.0 ;
113118 }
114- return score;
115- }
116119
117- auto PassTargetSelector::visualize (
118- const WorldModelWrapper::SharedPtr & world_model, const Point & pass_origin, uint8_t target_id,
119- const VisualizerMessageBuilder::SharedPtr & pass_builder) -> void
120- {
121- auto receiver = world_model->getOurRobot (target_id);
122- if (world_model->point_checker .isFieldInside (pass_origin)) {
123- pass_builder->drawLine (pass_origin, receiver->pose .pos , " lime" , 40 , 0.8 );
124- pass_builder->drawCircle (pass_origin, 0.12 , " lime" , 10 );
125- }
126- pass_builder->drawStyledCircle (receiver->pose .pos , 0.5 , " lime" , 0.15 , " lime" , 1.0 , 18 );
127- pass_builder->drawText (
128- Point (receiver->pose .pos .x (), receiver->pose .pos .y () + 0.35 ),
129- std::string (" PASS TARGET #" ) + std::to_string (receiver->id ), " lime" , 110.0 , " middle" );
120+ return score;
130121}
131122
132- auto PassTargetSelector::update (
133- const WorldModelWrapper::SharedPtr & world_model,
134- const std::deque<crane_msgs::msg::BallInfo> & ball_history,
135- const VisualizerMessageBuilder::SharedPtr & pass_builder,
136- crane_msgs::msg::GameAnalysis & analysis_msg) -> void
123+ auto PassTargetMetric::compute (MetricContext & ctx) -> void
137124{
138125 // パス起点の決定
139- const Point pass_origin = computePassOrigin (world_model, ball_history, analysis_msg );
126+ const Point pass_origin = computePassOrigin (ctx );
140127
141128 // 候補のスコア算出
142- auto our_robots = world_model->ours ().robotsWhere ().available ().excludeGoalie ().get ();
129+ auto our_robots = ctx. world_model ->ours ().robotsWhere ().available ().excludeGoalie ().get ();
143130 auto score_with_bots =
144131 our_robots | ranges::views::filter ([&](const auto & robot) {
145- return robot->id != world_model->getOurGoalieId () &&
146- robot->pose .pos .x () * world_model->getOurSideSign () <= 0.0 &&
147- !world_model->point_checker .isPenaltyArea (robot->pose .pos );
132+ return robot->id != ctx. world_model ->getOurGoalieId () &&
133+ robot->pose .pos .x () * ctx. world_model ->getOurSideSign () <= 0.0 &&
134+ !ctx. world_model ->point_checker .isPenaltyArea (robot->pose .pos );
148135 }) |
149136 ranges::views::transform ([&](const auto & robot) {
150- return std::make_pair (robot, calcScore (world_model , pass_origin, robot->pose .pos ));
137+ return std::make_pair (robot, calcScore (ctx , pass_origin, robot->pose .pos ));
151138 }) |
152139 ranges::to<std::vector>();
153140
154141 ranges::sort (score_with_bots, ranges::greater{}, [](const auto & p) { return p.second ; });
155142
156- analysis_msg .pass_scores .clear ();
157- analysis_msg .pass_scores .reserve (score_with_bots.size ());
143+ ctx. analysis .pass_scores .clear ();
144+ ctx. analysis .pass_scores .reserve (score_with_bots.size ());
158145 for (const auto & [robot, score] : score_with_bots) {
159146 crane_msgs::msg::FloatWithID msg;
160147 msg.set__id (robot->id ).set__value (score);
161- analysis_msg .pass_scores .push_back (msg);
148+ ctx. analysis .pass_scores .push_back (msg);
162149 }
163150
164151 // ヒステリシスによるターゲット選定
165- analysis_msg .pass_target_id = -1 ;
166- if (!analysis_msg .pass_scores .empty ()) {
167- const auto & best = analysis_msg .pass_scores .front ();
152+ ctx. analysis .pass_target_id = -1 ;
153+ if (!ctx. analysis .pass_scores .empty ()) {
154+ const auto & best = ctx. analysis .pass_scores .front ();
168155 const int best_id = static_cast <int >(best.id );
169156 const double best_score = static_cast <double >(best.value );
170157
@@ -174,10 +161,10 @@ auto PassTargetSelector::update(
174161 double prev_score = -1.0 ;
175162 if (last_pass_target_id_.has_value ()) {
176163 auto it =
177- ranges::find_if (analysis_msg .pass_scores , [&](const crane_msgs::msg::FloatWithID & s) {
164+ ranges::find_if (ctx. analysis .pass_scores , [&](const crane_msgs::msg::FloatWithID & s) {
178165 return s.id == last_pass_target_id_.value ();
179166 });
180- if (it != ranges::end (analysis_msg .pass_scores )) prev_score = it->value ;
167+ if (it != ranges::end (ctx. analysis .pass_scores )) prev_score = it->value ;
181168 }
182169
183170 bool should_switch = true ;
@@ -201,14 +188,28 @@ auto PassTargetSelector::update(
201188 last_switch_time_ = now_time;
202189 }
203190
204- analysis_msg.pass_target_id = last_pass_target_id_.value ();
191+ ctx.analysis .pass_target_id = last_pass_target_id_.value ();
192+ }
193+ }
205194
206- // 可視化
207- if (pass_builder) {
208- visualize (
209- world_model, pass_origin, static_cast < uint8_t >(analysis_msg. pass_target_id ), pass_builder);
210- }
195+ auto PassTargetMetric::visualize (
196+ MetricContext & ctx, const VisualizerMessageBuilder::SharedPtr & visualizer) -> void
197+ {
198+ if (ctx. analysis . pass_target_id < 0 ) {
199+ return ;
211200 }
201+
202+ const Point pass_origin = computePassOrigin (ctx);
203+ auto receiver = ctx.world_model ->getOurRobot (static_cast <uint8_t >(ctx.analysis .pass_target_id ));
204+
205+ if (ctx.world_model ->point_checker .isFieldInside (pass_origin)) {
206+ visualizer->drawLine (pass_origin, receiver->pose .pos , " lime" , 40 , 0.8 );
207+ visualizer->drawCircle (pass_origin, 0.12 , " lime" , 10 );
208+ }
209+ visualizer->drawStyledCircle (receiver->pose .pos , 0.5 , " lime" , 0.15 , " lime" , 1.0 , 18 );
210+ visualizer->drawText (
211+ Point (receiver->pose .pos .x (), receiver->pose .pos .y () + 0.35 ),
212+ std::string (" PASS TARGET #" ) + std::to_string (receiver->id ), " lime" , 110.0 , " middle" );
212213}
213214
214- } // namespace crane
215+ } // namespace crane::metrics
0 commit comments