Skip to content

Commit 8107468

Browse files
committed
feat(planning_data_analyzer): add open-loop AHE and FHE metrics
1 parent 3d8ffeb commit 8107468

3 files changed

Lines changed: 105 additions & 5 deletions

File tree

planning/autoware_planning_data_analyzer/src/open_loop_evaluator.cpp

Lines changed: 42 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -117,6 +117,8 @@ static void fill_horizon_json(
117117
f["Result"]["Frame"] = "Success";
118118
f["Info"]["ADE"] = hm.ade;
119119
f["Info"]["FDE"] = hm.fde;
120+
f["Info"]["AHE"] = hm.ahe;
121+
f["Info"]["FHE"] = hm.fhe;
120122
f["Info"]["average_lateral_deviation"] = hm.average_lateral_deviation;
121123
f["Info"]["max_lateral_deviation"] = hm.max_lateral_deviation;
122124
f["Info"]["average_longitudinal_deviation"] = hm.average_longitudinal_deviation;
@@ -135,6 +137,11 @@ static std::string result_summary(bool has_frame, size_t num_points)
135137
: "Open-loop trajectory metrics unavailable";
136138
}
137139

140+
static double wrap_angle(const double angle)
141+
{
142+
return std::atan2(std::sin(angle), std::cos(angle));
143+
}
144+
138145
// Constructor implementation moved to header file
139146

140147
void OpenLoopEvaluator::evaluate(
@@ -436,11 +443,13 @@ OpenLoopTrajectoryMetrics OpenLoopEvaluator::evaluate_trajectory(const Evaluatio
436443
metrics.displacement_errors.resize(metrics.num_points, 0.0);
437444
metrics.ground_truth_poses.resize(metrics.num_points);
438445
metrics.ade.resize(metrics.num_points, 0.0);
446+
metrics.heading_errors.resize(metrics.num_points, 0.0);
439447
metrics.ttc.resize(metrics.num_points, std::numeric_limits<double>::max());
440448

441449
// Running accumulators for per-horizon aggregate metrics
442450
std::vector<double> lat_prefix_sum(metrics.num_points);
443451
std::vector<double> lon_prefix_sum(metrics.num_points);
452+
std::vector<double> heading_prefix_sum(metrics.num_points);
444453
std::vector<double> lat_running_abs_max(metrics.num_points);
445454
std::vector<double> lon_running_abs_max(metrics.num_points);
446455
std::vector<double> ttc_running_min(metrics.num_points);
@@ -449,6 +458,7 @@ OpenLoopTrajectoryMetrics OpenLoopEvaluator::evaluate_trajectory(const Evaluatio
449458
double displacement_sum = 0.0;
450459
double lat_sum = 0.0;
451460
double lon_sum = 0.0;
461+
double heading_sum = 0.0;
452462
double lat_max = 0.0;
453463
double lon_max = 0.0;
454464
double ttc_min = std::numeric_limits<double>::max();
@@ -466,16 +476,22 @@ OpenLoopTrajectoryMetrics OpenLoopEvaluator::evaluate_trajectory(const Evaluatio
466476

467477
const auto [longitudinal_error, lateral_error] =
468478
calculate_errors_in_vehicle_frame(traj_point.pose, gt_pose);
479+
const double pred_yaw = tf2::getYaw(traj_point.pose.orientation);
480+
const double gt_yaw = tf2::getYaw(gt_pose.orientation);
481+
const double heading_error = std::abs(wrap_angle(pred_yaw - gt_yaw));
469482

470483
metrics.longitudinal_deviations[i] = longitudinal_error;
471484
metrics.lateral_deviations[i] = lateral_error;
485+
metrics.heading_errors[i] = heading_error;
472486

473487
lat_sum += std::abs(lateral_error);
474488
lon_sum += std::abs(longitudinal_error);
489+
heading_sum += heading_error;
475490
lat_max = std::max(lat_max, std::abs(lateral_error));
476491
lon_max = std::max(lon_max, std::abs(longitudinal_error));
477492
lat_prefix_sum[i] = lat_sum;
478493
lon_prefix_sum[i] = lon_sum;
494+
heading_prefix_sum[i] = heading_sum;
479495
lat_running_abs_max[i] = lat_max;
480496
lon_running_abs_max[i] = lon_max;
481497

@@ -526,10 +542,16 @@ OpenLoopTrajectoryMetrics OpenLoopEvaluator::evaluate_trajectory(const Evaluatio
526542
constexpr double kHorizonToleranceSec = 0.1;
527543
auto compute_horizon = [&](size_t cutoff) -> HorizonMetrics {
528544
const double n = static_cast<double>(cutoff + 1);
529-
return {metrics.ade[cutoff], metrics.displacement_errors[cutoff],
530-
lat_prefix_sum[cutoff] / n, lat_running_abs_max[cutoff],
531-
lon_prefix_sum[cutoff] / n, lon_running_abs_max[cutoff],
532-
ttc_running_min[cutoff]};
545+
return {
546+
metrics.ade[cutoff],
547+
metrics.displacement_errors[cutoff],
548+
heading_prefix_sum[cutoff] / n,
549+
metrics.heading_errors[cutoff],
550+
lat_prefix_sum[cutoff] / n,
551+
lat_running_abs_max[cutoff],
552+
lon_prefix_sum[cutoff] / n,
553+
lon_running_abs_max[cutoff],
554+
ttc_running_min[cutoff]};
533555
};
534556

535557
if (metrics.num_points > 1u) {
@@ -752,6 +774,14 @@ void OpenLoopEvaluator::save_metrics_to_bag(
752774
array_msg.data = metrics.displacement_errors;
753775
bag_writer.write(array_msg, metric_topic("fde"), message_timestamp);
754776

777+
// AHE
778+
array_msg.data = metrics.heading_errors;
779+
bag_writer.write(array_msg, metric_topic("ahe"), message_timestamp);
780+
781+
// FHE
782+
array_msg.data = metrics.heading_errors;
783+
bag_writer.write(array_msg, metric_topic("fhe"), message_timestamp);
784+
755785
// Lateral deviations array
756786
array_msg.data = metrics.lateral_deviations;
757787
bag_writer.write(array_msg, metric_topic("lateral_deviation"), message_timestamp);
@@ -926,7 +956,7 @@ nlohmann::json OpenLoopEvaluator::get_summary_as_json() const
926956
for (const auto & p : m.horizon_results) all_keys.insert(p.first);
927957
}
928958
for (const auto & tag : all_keys) {
929-
std::vector<double> ade_vals, fde_vals;
959+
std::vector<double> ade_vals, fde_vals, ahe_vals, fhe_vals;
930960
std::vector<double> avg_lat_vals, max_lat_vals, avg_lon_vals, max_lon_vals;
931961
std::vector<double> min_ttc_vals;
932962
for (const auto & m : metrics_list_) {
@@ -937,6 +967,8 @@ nlohmann::json OpenLoopEvaluator::get_summary_as_json() const
937967
const auto & hm = it->second;
938968
ade_vals.push_back(hm.ade);
939969
fde_vals.push_back(hm.fde);
970+
ahe_vals.push_back(hm.ahe);
971+
fhe_vals.push_back(hm.fhe);
940972
avg_lat_vals.push_back(hm.average_lateral_deviation);
941973
max_lat_vals.push_back(hm.max_lateral_deviation);
942974
avg_lon_vals.push_back(hm.average_longitudinal_deviation);
@@ -948,6 +980,8 @@ nlohmann::json OpenLoopEvaluator::get_summary_as_json() const
948980

949981
emit_metric(tag, "ade", "Average Displacement Error within " + tag + " horizon [m]", ade_vals);
950982
emit_metric(tag, "fde", "Final Displacement Error at " + tag + " horizon [m]", fde_vals);
983+
emit_metric(tag, "ahe", "Average Heading Error within " + tag + " horizon [rad]", ahe_vals);
984+
emit_metric(tag, "fhe", "Final Heading Error at " + tag + " horizon [rad]", fhe_vals);
951985
emit_metric(
952986
tag, "average_lateral_deviation", "Average lateral deviation within " + tag + " horizon [m]",
953987
avg_lat_vals);
@@ -1005,6 +1039,7 @@ nlohmann::json OpenLoopEvaluator::get_full_results_as_json() const
10051039

10061040
traj["ade"] = m.ade;
10071041
traj["displacement_errors"] = m.displacement_errors;
1042+
traj["heading_errors"] = m.heading_errors;
10081043
traj["lateral_deviations"] = m.lateral_deviations;
10091044
traj["longitudinal_deviations"] = m.longitudinal_deviations;
10101045
traj["ttc"] = m.ttc;
@@ -1057,6 +1092,8 @@ std::vector<std::pair<std::string, std::string>> OpenLoopEvaluator::get_result_t
10571092
{dlr_result_topic(), "std_msgs/msg/String"},
10581093
{metric_topic("ade"), "std_msgs/msg/Float64MultiArray"},
10591094
{metric_topic("fde"), "std_msgs/msg/Float64MultiArray"},
1095+
{metric_topic("ahe"), "std_msgs/msg/Float64MultiArray"},
1096+
{metric_topic("fhe"), "std_msgs/msg/Float64MultiArray"},
10601097
{metric_topic("ttc"), "std_msgs/msg/Float64MultiArray"},
10611098
{metric_topic("lateral_deviation"), "std_msgs/msg/Float64MultiArray"},
10621099
{metric_topic("longitudinal_deviation"), "std_msgs/msg/Float64MultiArray"},

planning/autoware_planning_data_analyzer/src/open_loop_evaluator.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,8 @@ struct HorizonMetrics
3939
{
4040
double ade;
4141
double fde;
42+
double ahe;
43+
double fhe;
4244
double average_lateral_deviation;
4345
double max_lateral_deviation;
4446
double average_longitudinal_deviation;
@@ -55,6 +57,7 @@ struct OpenLoopTrajectoryMetrics
5557
longitudinal_deviations; // Longitudinal deviation at each trajectory point (in vehicle frame)
5658
std::vector<double> displacement_errors; // Euclidean distance at each trajectory point
5759
std::vector<double> ade; // Average Displacement Error at each trajectory point
60+
std::vector<double> heading_errors; // Absolute heading error at each trajectory point [rad]
5861
std::vector<double> ttc; // Time To Collision at each trajectory point
5962

6063
// Per-horizon metrics in insertion order: "full" first, then "1s", "2s", ...

planning/autoware_planning_data_analyzer/test/test_open_loop_gt_source_mode.cpp

Lines changed: 60 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
#include <gtest/gtest.h>
2323

2424
#include <algorithm>
25+
#include <cmath>
2526
#include <memory>
2627
#include <string>
2728
#include <vector>
@@ -142,6 +143,7 @@ TEST_F(OpenLoopGTSourceModeTest, VariantsNamespaceOpenLoopResultTopics)
142143
evaluator.set_metric_variant("raw");
143144

144145
EXPECT_EQ(evaluator.metric_topic("ade"), "/open_loop/metrics/raw/ade");
146+
EXPECT_EQ(evaluator.metric_topic("ahe"), "/open_loop/metrics/raw/ahe");
145147
EXPECT_EQ(
146148
evaluator.trajectory_metric_topic("lateral_accelerations"),
147149
"/trajectory/raw/lateral_accelerations");
@@ -157,7 +159,65 @@ TEST_F(OpenLoopGTSourceModeTest, VariantsNamespaceOpenLoopResultTopics)
157159
};
158160

159161
EXPECT_TRUE(has_topic("/open_loop/metrics/raw/ade"));
162+
EXPECT_TRUE(has_topic("/open_loop/metrics/raw/ahe"));
163+
EXPECT_TRUE(has_topic("/open_loop/metrics/raw/fhe"));
160164
EXPECT_TRUE(has_topic("/trajectory/raw/lateral_accelerations"));
161165
EXPECT_TRUE(has_topic("/evaluation/compared_trajectory/raw"));
162166
EXPECT_TRUE(has_topic("/driving_log_replayer/time_step_based_trajectory/raw/results"));
163167
}
168+
169+
TEST_F(OpenLoopGTSourceModeTest, HeadingMetricsUseWrappedYawErrorPerHorizon)
170+
{
171+
const rclcpp::Time start_time(40, 0);
172+
auto prediction = make_trajectory(start_time, {0.0, 1.0, 2.0, 3.0});
173+
const auto gt = std::make_shared<Trajectory>(make_trajectory(start_time, {0.0, 1.0, 2.0, 3.0}));
174+
175+
prediction.points[0].pose.orientation.z = std::sin((-M_PI + 0.1) * 0.5);
176+
prediction.points[0].pose.orientation.w = std::cos((-M_PI + 0.1) * 0.5);
177+
gt->points[0].pose.orientation.z = std::sin((M_PI - 0.1) * 0.5);
178+
gt->points[0].pose.orientation.w = std::cos((M_PI - 0.1) * 0.5);
179+
180+
prediction.points[1].pose.orientation.z = std::sin(0.2 * 0.5);
181+
prediction.points[1].pose.orientation.w = std::cos(0.2 * 0.5);
182+
gt->points[1].pose.orientation.w = 1.0;
183+
184+
prediction.points[2].pose.orientation.z = std::sin((-0.3) * 0.5);
185+
prediction.points[2].pose.orientation.w = std::cos((-0.3) * 0.5);
186+
gt->points[2].pose.orientation.w = 1.0;
187+
188+
prediction.points[3].pose.orientation.z = std::sin(0.4 * 0.5);
189+
prediction.points[3].pose.orientation.w = std::cos(0.4 * 0.5);
190+
gt->points[3].pose.orientation.w = 1.0;
191+
192+
std::vector<std::shared_ptr<SynchronizedData>> sync_data_list{make_sync_data(prediction, gt)};
193+
194+
OpenLoopEvaluator evaluator(
195+
rclcpp::get_logger("open_loop_gt_source_test"), nullptr,
196+
OpenLoopEvaluator::GTSourceMode::GT_TRAJECTORY, 200.0);
197+
evaluator.set_evaluation_horizons({0.2});
198+
199+
evaluator.evaluate(sync_data_list, nullptr);
200+
const auto metrics = evaluator.get_metrics();
201+
ASSERT_EQ(metrics.size(), 1u);
202+
ASSERT_EQ(metrics.front().heading_errors.size(), 4u);
203+
204+
EXPECT_NEAR(metrics.front().heading_errors[0], 0.2, 1e-6);
205+
EXPECT_NEAR(metrics.front().heading_errors[1], 0.2, 1e-6);
206+
EXPECT_NEAR(metrics.front().heading_errors[2], 0.3, 1e-6);
207+
EXPECT_NEAR(metrics.front().heading_errors[3], 0.4, 1e-6);
208+
209+
ASSERT_EQ(metrics.front().horizon_results.size(), 2u);
210+
EXPECT_EQ(metrics.front().horizon_results[0].first, "full");
211+
EXPECT_NEAR(metrics.front().horizon_results[0].second.ahe, 0.275, 1e-6);
212+
EXPECT_NEAR(metrics.front().horizon_results[0].second.fhe, 0.4, 1e-6);
213+
214+
EXPECT_EQ(metrics.front().horizon_results[1].first, "0.2s");
215+
EXPECT_NEAR(metrics.front().horizon_results[1].second.ahe, 0.233333333333, 1e-6);
216+
EXPECT_NEAR(metrics.front().horizon_results[1].second.fhe, 0.3, 1e-6);
217+
218+
const auto summary_json = evaluator.get_summary_as_json();
219+
EXPECT_NEAR(summary_json["full/ahe/mean"].get<double>(), 0.275, 1e-6);
220+
EXPECT_NEAR(summary_json["full/fhe/mean"].get<double>(), 0.4, 1e-6);
221+
EXPECT_NEAR(summary_json["0.2s/ahe/mean"].get<double>(), 0.233333333333, 1e-6);
222+
EXPECT_NEAR(summary_json["0.2s/fhe/mean"].get<double>(), 0.3, 1e-6);
223+
}

0 commit comments

Comments
 (0)