Skip to content

Commit bb93f57

Browse files
committed
refactor(planning_data_analyzer): extract history comfort metric utility
1 parent 8b8aeb0 commit bb93f57

10 files changed

Lines changed: 234 additions & 113 deletions

planning/autoware_planning_data_analyzer/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
1111
src/or_event_extractor.cpp
1212
src/or_scene_evaluator.cpp
1313
src/metrics/deviation_metrics.cpp
14+
src/metrics/history_comfort.cpp
1415
src/metrics/trajectory_metrics.cpp
1516
src/utils/bag_utils.cpp
1617
src/utils/json_utils.cpp

planning/autoware_planning_data_analyzer/config/planning_data_analyzer.param.yaml

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,16 @@
3434
gt_source_mode: "kinematic_state"
3535
gt_trajectory_topic: "/planning/ground_truth_trajectory"
3636
gt_sync_tolerance_ms: 200.0
37+
hc:
38+
# NAVSIM-aligned default thresholds for the History Comfort (HC) subscore.
39+
finite_difference_epsilon: 0.001
40+
max_longitudinal_acceleration: 2.40
41+
min_longitudinal_acceleration: -4.05
42+
max_lateral_acceleration: 4.89
43+
max_jerk_magnitude: 8.37
44+
max_longitudinal_jerk: 4.13
45+
max_yaw_rate: 0.95
46+
max_yaw_acceleration: 1.93
3747
metric_variant: ""
3848
# DLR result horizon checkpoints in seconds.
3949
# ADE/FDE are reported at these horizons plus "full" (entire trajectory).

planning/autoware_planning_data_analyzer/src/autoware_planning_data_analyzer_node.cpp

Lines changed: 18 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -108,6 +108,22 @@ AutowarePlanningDataAnalyzerNode::AutowarePlanningDataAnalyzerNode(
108108
gt_trajectory_topic_name_ =
109109
get_or_declare_parameter<std::string>(*this, "open_loop.gt_trajectory_topic");
110110
gt_sync_tolerance_ms_ = get_or_declare_parameter<double>(*this, "open_loop.gt_sync_tolerance_ms");
111+
history_comfort_params_.finite_difference_epsilon =
112+
get_or_declare_parameter<double>(*this, "open_loop.hc.finite_difference_epsilon");
113+
history_comfort_params_.max_longitudinal_acceleration =
114+
get_or_declare_parameter<double>(*this, "open_loop.hc.max_longitudinal_acceleration");
115+
history_comfort_params_.min_longitudinal_acceleration =
116+
get_or_declare_parameter<double>(*this, "open_loop.hc.min_longitudinal_acceleration");
117+
history_comfort_params_.max_lateral_acceleration =
118+
get_or_declare_parameter<double>(*this, "open_loop.hc.max_lateral_acceleration");
119+
history_comfort_params_.max_jerk_magnitude =
120+
get_or_declare_parameter<double>(*this, "open_loop.hc.max_jerk_magnitude");
121+
history_comfort_params_.max_longitudinal_jerk =
122+
get_or_declare_parameter<double>(*this, "open_loop.hc.max_longitudinal_jerk");
123+
history_comfort_params_.max_yaw_rate =
124+
get_or_declare_parameter<double>(*this, "open_loop.hc.max_yaw_rate");
125+
history_comfort_params_.max_yaw_acceleration =
126+
get_or_declare_parameter<double>(*this, "open_loop.hc.max_yaw_acceleration");
111127
objects_topic_name_ = get_or_declare_parameter<std::string>(*this, "objects_topic");
112128
tf_topic_name_ = get_or_declare_parameter<std::string>(*this, "tf_topic");
113129
acceleration_topic_name_ = get_or_declare_parameter<std::string>(*this, "acceleration_topic");
@@ -451,7 +467,8 @@ void AutowarePlanningDataAnalyzerNode::run_evaluation()
451467
}
452468
const auto evaluation_horizons =
453469
get_or_declare_parameter<std::vector<double>>(*this, "open_loop.evaluation_horizons");
454-
OpenLoopEvaluator evaluator(get_logger(), route_handler_, gt_mode, gt_sync_tolerance_ms_);
470+
OpenLoopEvaluator evaluator(
471+
get_logger(), route_handler_, gt_mode, gt_sync_tolerance_ms_, history_comfort_params_);
455472
evaluator.set_json_output_dir(output_dir_path.string());
456473
evaluator.set_metric_variant(open_loop_metric_variant);
457474
evaluator.set_evaluation_horizons(evaluation_horizons);

planning/autoware_planning_data_analyzer/src/autoware_planning_data_analyzer_node.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
#define AUTOWARE_PLANNING_DATA_ANALYZER_NODE_HPP_
1717

1818
#include "bag_handler.hpp"
19+
#include "metrics/trajectory_metrics.hpp"
1920
#include "rosbag2_cpp/reader.hpp"
2021
#include "rosbag2_cpp/writer.hpp"
2122
#include "serialized_bag_message.hpp"
@@ -84,6 +85,7 @@ class AutowarePlanningDataAnalyzerNode : public rclcpp::Node
8485
std::string gt_source_mode_;
8586
std::string gt_trajectory_topic_name_;
8687
double gt_sync_tolerance_ms_ = 200.0;
88+
metrics::HistoryComfortParameters history_comfort_params_;
8789
std::string objects_topic_name_;
8890
std::string tf_topic_name_;
8991
std::string acceleration_topic_name_;
Lines changed: 146 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,146 @@
1+
// Copyright 2025 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "history_comfort.hpp"
16+
17+
#include <autoware_utils_math/normalization.hpp>
18+
19+
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
20+
#include <tf2/utils.h>
21+
22+
#include <algorithm>
23+
#include <cmath>
24+
25+
namespace autoware::planning_data_analyzer::metrics
26+
{
27+
28+
namespace
29+
{
30+
31+
double calculate_time_resolution(
32+
const autoware_planning_msgs::msg::TrajectoryPoint & point,
33+
const autoware_planning_msgs::msg::TrajectoryPoint & next_point, const double epsilon)
34+
{
35+
const double time_diff = rclcpp::Duration(next_point.time_from_start).seconds() -
36+
rclcpp::Duration(point.time_from_start).seconds();
37+
return time_diff > epsilon ? time_diff : epsilon;
38+
}
39+
40+
void backfill_last_value_from_previous(std::vector<double> & values)
41+
{
42+
if (values.size() > 1U) {
43+
values.back() = values[values.size() - 2];
44+
}
45+
}
46+
47+
} // namespace
48+
49+
void calculate_history_comfort_metrics(
50+
const autoware_planning_msgs::msg::Trajectory & trajectory,
51+
const HistoryComfortParameters & history_comfort_params, TrajectoryPointMetrics & metrics)
52+
{
53+
const size_t num_points = trajectory.points.size();
54+
if (num_points == 0U) {
55+
return;
56+
}
57+
58+
metrics.longitudinal_accelerations.resize(num_points, 0.0);
59+
metrics.lateral_accelerations.resize(num_points, 0.0);
60+
metrics.lateral_jerks.resize(num_points, 0.0);
61+
metrics.jerk_magnitudes.resize(num_points, 0.0);
62+
metrics.longitudinal_jerks.resize(num_points, 0.0);
63+
metrics.yaw_rates.resize(num_points, 0.0);
64+
metrics.yaw_accelerations.resize(num_points, 0.0);
65+
66+
for (size_t i = 0; i < num_points - 1; ++i) {
67+
const double time_resolution = calculate_time_resolution(
68+
trajectory.points[i], trajectory.points[i + 1],
69+
history_comfort_params.finite_difference_epsilon);
70+
71+
metrics.longitudinal_accelerations[i] = (trajectory.points[i + 1].longitudinal_velocity_mps -
72+
trajectory.points[i].longitudinal_velocity_mps) /
73+
time_resolution;
74+
metrics.lateral_accelerations[i] =
75+
(trajectory.points[i + 1].lateral_velocity_mps - trajectory.points[i].lateral_velocity_mps) /
76+
time_resolution;
77+
78+
const double yaw_delta = autoware_utils_math::normalize_radian(
79+
tf2::getYaw(trajectory.points[i + 1].pose.orientation) -
80+
tf2::getYaw(trajectory.points[i].pose.orientation));
81+
metrics.yaw_rates[i] = yaw_delta / time_resolution;
82+
}
83+
backfill_last_value_from_previous(metrics.longitudinal_accelerations);
84+
backfill_last_value_from_previous(metrics.lateral_accelerations);
85+
backfill_last_value_from_previous(metrics.yaw_rates);
86+
87+
for (size_t i = 0; i < num_points - 1; ++i) {
88+
const double time_resolution = calculate_time_resolution(
89+
trajectory.points[i], trajectory.points[i + 1],
90+
history_comfort_params.finite_difference_epsilon);
91+
92+
metrics.longitudinal_jerks[i] =
93+
(metrics.longitudinal_accelerations[i + 1] - metrics.longitudinal_accelerations[i]) /
94+
time_resolution;
95+
metrics.lateral_jerks[i] =
96+
(metrics.lateral_accelerations[i + 1] - metrics.lateral_accelerations[i]) / time_resolution;
97+
metrics.jerk_magnitudes[i] =
98+
std::hypot(metrics.longitudinal_jerks[i], metrics.lateral_jerks[i]);
99+
metrics.yaw_accelerations[i] =
100+
(metrics.yaw_rates[i + 1] - metrics.yaw_rates[i]) / time_resolution;
101+
}
102+
backfill_last_value_from_previous(metrics.longitudinal_jerks);
103+
backfill_last_value_from_previous(metrics.lateral_jerks);
104+
backfill_last_value_from_previous(metrics.jerk_magnitudes);
105+
backfill_last_value_from_previous(metrics.yaw_accelerations);
106+
107+
const bool longitudinal_acceleration_ok = std::all_of(
108+
metrics.longitudinal_accelerations.begin(), metrics.longitudinal_accelerations.end(),
109+
[&history_comfort_params](const double ax) {
110+
return history_comfort_params.min_longitudinal_acceleration < ax &&
111+
ax < history_comfort_params.max_longitudinal_acceleration;
112+
});
113+
const bool lateral_acceleration_ok = std::all_of(
114+
metrics.lateral_accelerations.begin(), metrics.lateral_accelerations.end(),
115+
[&history_comfort_params](const double ay) {
116+
return std::abs(ay) < history_comfort_params.max_lateral_acceleration;
117+
});
118+
const bool jerk_magnitude_ok = std::all_of(
119+
metrics.jerk_magnitudes.begin(), metrics.jerk_magnitudes.end(),
120+
[&history_comfort_params](const double jerk) {
121+
return std::abs(jerk) < history_comfort_params.max_jerk_magnitude;
122+
});
123+
const bool longitudinal_jerk_ok = std::all_of(
124+
metrics.longitudinal_jerks.begin(), metrics.longitudinal_jerks.end(),
125+
[&history_comfort_params](const double jerk) {
126+
return std::abs(jerk) < history_comfort_params.max_longitudinal_jerk;
127+
});
128+
const bool yaw_rate_ok = std::all_of(
129+
metrics.yaw_rates.begin(), metrics.yaw_rates.end(),
130+
[&history_comfort_params](const double yaw_rate) {
131+
return std::abs(yaw_rate) < history_comfort_params.max_yaw_rate;
132+
});
133+
const bool yaw_acceleration_ok = std::all_of(
134+
metrics.yaw_accelerations.begin(), metrics.yaw_accelerations.end(),
135+
[&history_comfort_params](const double yaw_accel) {
136+
return std::abs(yaw_accel) < history_comfort_params.max_yaw_acceleration;
137+
});
138+
139+
metrics.history_comfort = longitudinal_acceleration_ok && lateral_acceleration_ok &&
140+
jerk_magnitude_ok && longitudinal_jerk_ok && yaw_rate_ok &&
141+
yaw_acceleration_ok
142+
? 1.0
143+
: 0.0;
144+
}
145+
146+
} // namespace autoware::planning_data_analyzer::metrics
Lines changed: 31 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,31 @@
1+
// Copyright 2025 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef METRICS__HISTORY_COMFORT_HPP_
16+
#define METRICS__HISTORY_COMFORT_HPP_
17+
18+
#include "trajectory_metrics.hpp"
19+
20+
#include <autoware_planning_msgs/msg/trajectory.hpp>
21+
22+
namespace autoware::planning_data_analyzer::metrics
23+
{
24+
25+
void calculate_history_comfort_metrics(
26+
const autoware_planning_msgs::msg::Trajectory & trajectory,
27+
const HistoryComfortParameters & history_comfort_params, TrajectoryPointMetrics & metrics);
28+
29+
} // namespace autoware::planning_data_analyzer::metrics
30+
31+
#endif // METRICS__HISTORY_COMFORT_HPP_

0 commit comments

Comments
 (0)