4
4
// license that can be found in the LICENSE file or at
5
5
// https://opensource.org/licenses/MIT.
6
6
7
+ #include < crane_basics/ddps.hpp>
7
8
#include < crane_basics/geometry_operations.hpp>
8
9
#include < crane_basics/time.hpp>
9
10
#include < crane_world_model_publisher/world_model_publisher.hpp>
@@ -21,6 +22,9 @@ WorldModelPublisherComponent::WorldModelPublisherComponent(const rclcpp::NodeOpt
21
22
visualizer =
22
23
std::make_unique<crane::CraneVisualizerBuffer::MessageBuilder>(" world_model/trajectory" );
23
24
25
+ pass_score_visualizer =
26
+ std::make_unique<crane::CraneVisualizerBuffer::MessageBuilder>(" world_model/pass_score" );
27
+
24
28
declare_parameter (" position_history_size" , 200 );
25
29
get_parameter<int >(" position_history_size" , history_size);
26
30
@@ -233,6 +237,72 @@ void WorldModelPublisherComponent::postProcessWorldModel(WorldModelWrapper::Shar
233
237
}
234
238
game_analysis_msg.their_slack .push_back (slack_msg);
235
239
}
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
+
236
306
world_model->update (game_analysis_msg);
237
307
}
238
308
0 commit comments