Skip to content

Commit f506bec

Browse files
committed
perf: パス評価関数の改善とgame analyzerへの統合
## 概要 パス評価関数を改善し、world_model_publisherからgame analyzerへ移行。 敵速度を考慮したTTI計算とシャドウヒューリスティックを実装。 ## 主な変更 ### 1. 敵速度を考慮したTTI(Time-to-Intercept)計算 - **ファイル**: utility/crane_msg_wrappers/src/world_model_wrapper.cpp - `getBallSlackTime()`で敵ロボットの速度ベクトルを考慮 - `getTravelTimeTrapezoidal()`に位置と速度を明示的に渡すよう変更 - 移動中の敵ロボットに対する予測精度が向上 ### 2. シャドウヒューリスティックの導入 - **新規**: utility/crane_physics/include/crane_physics/pass_evaluation.hpp - `evaluatePassShadow()`関数を実装 - パスライン上の敵による遮蔽効果を評価(0.0=完全遮蔽, 1.0=遮蔽なし) - シンプル版(敵速度は考慮しない)で計算コスト削減 ### 3. game analyzerへの移行 - **新規**: crane_game_analyzer/metrics/pass_target_metrics.{hpp,cpp} - PassTargetSelectorの全機能をPassTargetMetricに移行 - TTI改善とシャドウヒューリスティックを統合 - メトリクスエンジンに登録し、依存関係管理を統一 ### 4. world_model_publisherからの削除 - **削除**: pass_target_selector.{hpp,cpp} - PassTargetSelector関連のコード、パラメータ設定を削除 - パス評価の責務をgame analyzerに移譲 ## 改善効果 - 敵の移動を考慮した精度の高いインターセプト評価 - パスライン上の遮蔽を考慮した現実的なパス選択 - 責務の明確化(パス評価はゲーム分析の一部) - 統一された可視化とメトリクス管理 🤖 Generated with [Claude Code](https://claude.ai/code)
1 parent e828cfb commit f506bec

File tree

11 files changed

+260
-179
lines changed

11 files changed

+260
-179
lines changed

crane_game_analyzer/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@ ament_auto_add_library(${PROJECT_NAME}_component SHARED
3333
src/metrics/slack_metrics.cpp
3434
src/metrics/attacker_metrics.cpp
3535
src/metrics/sub_attacker_metrics.cpp
36+
src/metrics/pass_target_metrics.cpp
3637
)
3738

3839
option(CRANE_UNITY_BUILD "Enable unity build" ON)

crane_game_analyzer/include/crane_game_analyzer/metrics/metric_base.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,9 @@ enum class MetricId {
3636
// 役割決定(新規)
3737
ATTACKER_CANDIDATE, ///< 推奨アタッカー
3838
SUB_ATTACKER_POSITION, ///< SubAttacker推奨位置
39+
40+
// パス評価
41+
PASS_TARGET, ///< パスターゲット選定
3942
};
4043

4144
/**
Lines changed: 82 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,82 @@
1+
// Copyright (c) 2025 ibis-ssl
2+
//
3+
// Use of this source code is governed by an MIT-style
4+
// license that can be found in the LICENSE file or at
5+
// https://opensource.org/licenses/MIT.
6+
7+
#ifndef CRANE_GAME_ANALYZER__METRICS__PASS_TARGET_METRICS_HPP_
8+
#define CRANE_GAME_ANALYZER__METRICS__PASS_TARGET_METRICS_HPP_
9+
10+
#include <crane_physics/slack_time_config.hpp>
11+
12+
#include "metric_base.hpp"
13+
14+
namespace crane::metrics
15+
{
16+
17+
/**
18+
* @brief パスターゲット選定メトリクス
19+
*
20+
* パススコアを算出し、ヒステリシス込みでpass_target_idを選定
21+
* 敵インターセプト評価(TTI)とシャドウヒューリスティックを統合
22+
*/
23+
class PassTargetMetric : public MetricBase
24+
{
25+
public:
26+
PassTargetMetric();
27+
28+
[[nodiscard]] auto getDependencies() const -> std::vector<MetricId> override
29+
{
30+
// 依存なし(基礎メトリクス)
31+
return {};
32+
}
33+
34+
auto compute(MetricContext & ctx) -> void override;
35+
auto visualize(MetricContext & ctx, const VisualizerMessageBuilder::SharedPtr & visualizer)
36+
-> void override;
37+
38+
/**
39+
* @brief ヒステリシスパラメータを設定
40+
* @param min_hold_sec ターゲット保持の最短秒数
41+
* @param min_improvement 早期切替のための最小スコア改善幅
42+
*/
43+
auto setHysteresisParams(double min_hold_sec, double min_improvement) -> void
44+
{
45+
min_hold_duration_sec_ = min_hold_sec;
46+
min_improvement_margin_ = min_improvement;
47+
}
48+
49+
auto setEnemySlackConfig(const SlackTimeConfig & config, double slack_scale = 0.5) -> void
50+
{
51+
enemy_slack_config_ = config;
52+
slack_scale_ = slack_scale;
53+
}
54+
55+
private:
56+
// パス起点の計算
57+
[[nodiscard]] auto computePassOrigin(MetricContext & ctx) const -> Point;
58+
59+
// スコア計算
60+
[[nodiscard]] auto calcScore(
61+
MetricContext & ctx, const Point & pass_origin, const Point & p) const -> double;
62+
63+
// ヒステリシス用の内部状態
64+
std::optional<int> last_pass_target_id_{std::nullopt};
65+
rclcpp::Time last_switch_time_{static_cast<int64_t>(0), RCL_ROS_TIME};
66+
rclcpp::Clock ros_clock_{RCL_ROS_TIME};
67+
68+
// ヒステリシスパラメータ
69+
double min_hold_duration_sec_ = 0.5;
70+
double min_improvement_margin_ = 0.2;
71+
72+
// 敵インターセプト評価用パラメータ
73+
SlackTimeConfig enemy_slack_config_{
74+
.robot_max_acceleration = 3.0, // 敵は自チームより高め(安全マージン)
75+
.robot_max_velocity = 5.5 // 敵は自チームより高め(安全マージン)
76+
};
77+
double slack_scale_ = 0.5; // スコア正規化用
78+
};
79+
80+
} // namespace crane::metrics
81+
82+
#endif // CRANE_GAME_ANALYZER__METRICS__PASS_TARGET_METRICS_HPP_

crane_game_analyzer/src/crane_game_analyzer.cpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
#include "crane_game_analyzer/game_analyzer.hpp"
1515
#include "crane_game_analyzer/metrics/attacker_metrics.hpp"
1616
#include "crane_game_analyzer/metrics/ball_horizon_metric.hpp"
17+
#include "crane_game_analyzer/metrics/pass_target_metrics.hpp"
1718
#include "crane_game_analyzer/metrics/slack_metrics.hpp"
1819
#include "crane_game_analyzer/metrics/sub_attacker_metrics.hpp"
1920
#include "crane_game_analyzer/metrics/threat_metrics.hpp"
@@ -122,6 +123,17 @@ GameAnalyzerComponent::GameAnalyzerComponent(const rclcpp::NodeOptions & options
122123
auto sub_attacker_position_metric = std::make_shared<metrics::SubAttackerPositionMetric>();
123124
metric_engine_->registerMetric(sub_attacker_position_metric);
124125

126+
// パスターゲット選定メトリクス
127+
auto pass_target_metric = std::make_shared<metrics::PassTargetMetric>();
128+
// パラメータ設定
129+
declare_parameter("pass_target.min_hold_duration_sec", 0.5);
130+
declare_parameter("pass_target.min_improvement_margin", 0.2);
131+
double min_hold = 0.5, min_improve = 0.2;
132+
get_parameter("pass_target.min_hold_duration_sec", min_hold);
133+
get_parameter("pass_target.min_improvement_margin", min_improve);
134+
pass_target_metric->setHysteresisParams(min_hold, min_improve);
135+
metric_engine_->registerMetric(pass_target_metric);
136+
125137
// メトリクスエンジン初期化(トポロジカルソート・循環依存検出)
126138
if (!metric_engine_->initialize()) {
127139
RCLCPP_FATAL(get_logger(), "Failed to initialize metric engine!");

crane_world_model_publisher/src/pass_target_selector.cpp renamed to crane_game_analyzer/src/metrics/pass_target_metrics.cpp

Lines changed: 64 additions & 63 deletions
Original file line numberDiff line numberDiff line change
@@ -4,26 +4,25 @@
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

crane_world_model_publisher/CMakeLists.txt

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,6 @@ set(WORLD_MODEL_PUBLISHER_SRCS
2929
src/world_model_data_provider.cpp
3030
src/visualization_manager.cpp
3131
src/kick_event_detector.cpp
32-
src/pass_target_selector.cpp
3332
)
3433

3534
if(CRANE_WMP_BUILD_CALIBRATION)

0 commit comments

Comments
 (0)