Skip to content

Commit b0625af

Browse files
feat(planning_evaluator): add lateral trajectory displacement metrics (#9674)
* feat(planning_evaluator): add nearest pose deviation msg Signed-off-by: Kasunori-Nakajima <kazunori.nakajima@tier4.jp> * update comment contents Signed-off-by: Kasunori-Nakajima <kazunori.nakajima@tier4.jp> * update variable name Signed-off-by: Kasunori-Nakajima <kazunori.nakajima@tier4.jp> * Revert "update variable name" This reverts commit ee42722. Signed-off-by: Kasunori-Nakajima <kazunori.nakajima@tier4.jp> * move lateral_trajectory_displacement position Signed-off-by: Kasunori-Nakajima <kazunori.nakajima@tier4.jp> * prev.dist -> prev_lateral_deviation Signed-off-by: Kasunori-Nakajima <kazunori.nakajima@tier4.jp> --------- Signed-off-by: Kasunori-Nakajima <kazunori.nakajima@tier4.jp>
1 parent eef298b commit b0625af

File tree

6 files changed

+36
-0
lines changed

6 files changed

+36
-0
lines changed

evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
- lateral_deviation
1515
- yaw_deviation
1616
- velocity_deviation
17+
- lateral_trajectory_displacement
1718
- stability
1819
- stability_frechet
1920
- obstacle_distance

evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/deviation_metrics.hpp

+10
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,16 @@ using geometry_msgs::msg::Pose;
3838
*/
3939
Accumulator<double> calcLateralDeviation(const Trajectory & ref, const Trajectory & traj);
4040

41+
/**
42+
* @brief calculate lateral trajectory displacement from the previous trajectory and the trajectory
43+
* @param [in] prev previous trajectory
44+
* @param [in] traj input trajectory
45+
* @param [in] base_pose base pose
46+
* @return calculated statistics
47+
*/
48+
Accumulator<double> calcLateralTrajectoryDisplacement(
49+
const Trajectory & prev, const Trajectory & traj, const Pose & base_pose);
50+
4151
/**
4252
* @brief calculate yaw deviation of the given trajectory from the reference trajectory
4353
* @param [in] ref reference trajectory

evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metric.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@ enum class Metric {
3737
lateral_deviation,
3838
yaw_deviation,
3939
velocity_deviation,
40+
lateral_trajectory_displacement,
4041
stability,
4142
stability_frechet,
4243
obstacle_distance,
@@ -62,6 +63,7 @@ static const std::unordered_map<std::string, Metric> str_to_metric = {
6263
{"lateral_deviation", Metric::lateral_deviation},
6364
{"yaw_deviation", Metric::yaw_deviation},
6465
{"velocity_deviation", Metric::velocity_deviation},
66+
{"lateral_trajectory_displacement", Metric::lateral_trajectory_displacement},
6567
{"stability", Metric::stability},
6668
{"stability_frechet", Metric::stability_frechet},
6769
{"obstacle_distance", Metric::obstacle_distance},
@@ -82,6 +84,7 @@ static const std::unordered_map<Metric, std::string> metric_to_str = {
8284
{Metric::lateral_deviation, "lateral_deviation"},
8385
{Metric::yaw_deviation, "yaw_deviation"},
8486
{Metric::velocity_deviation, "velocity_deviation"},
87+
{Metric::lateral_trajectory_displacement, "lateral_trajectory_displacement"},
8588
{Metric::stability, "stability"},
8689
{Metric::stability_frechet, "stability_frechet"},
8790
{Metric::obstacle_distance, "obstacle_distance"},
@@ -103,6 +106,7 @@ static const std::unordered_map<Metric, std::string> metric_descriptions = {
103106
{Metric::lateral_deviation, "Lateral_deviation[m]"},
104107
{Metric::yaw_deviation, "Yaw_deviation[rad]"},
105108
{Metric::velocity_deviation, "Velocity_deviation[m/s]"},
109+
{Metric::lateral_trajectory_displacement, "Nearest Pose Lateral Deviation[m]"},
106110
{Metric::stability, "Stability[m]"},
107111
{Metric::stability_frechet, "StabilityFrechet[m]"},
108112
{Metric::obstacle_distance, "Obstacle_distance[m]"},

evaluator/autoware_planning_evaluator/schema/autoware_planning_evaluator.schema.json

+1
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@
3434
"lateral_deviation",
3535
"yaw_deviation",
3636
"velocity_deviation",
37+
"lateral_trajectory_displacement",
3738
"stability",
3839
"stability_frechet",
3940
"obstacle_distance",

evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp

+18
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,24 @@ Accumulator<double> calcLateralDeviation(const Trajectory & ref, const Trajector
4545
return stat;
4646
}
4747

48+
Accumulator<double> calcLateralTrajectoryDisplacement(
49+
const Trajectory & prev, const Trajectory & traj, const Pose & ego_pose)
50+
{
51+
Accumulator<double> stat;
52+
53+
if (prev.points.empty() || traj.points.empty()) {
54+
return stat;
55+
}
56+
57+
const auto prev_lateral_deviation =
58+
autoware::motion_utils::calcLateralOffset(prev.points, ego_pose.position);
59+
const auto traj_lateral_deviation =
60+
autoware::motion_utils::calcLateralOffset(traj.points, ego_pose.position);
61+
const auto lateral_trajectory_displacement = traj_lateral_deviation - prev_lateral_deviation;
62+
stat.add(lateral_trajectory_displacement);
63+
return stat;
64+
}
65+
4866
Accumulator<double> calcYawDeviation(const Trajectory & ref, const Trajectory & traj)
4967
{
5068
Accumulator<double> stat;

evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,8 @@ std::optional<Accumulator<double>> MetricsCalculator::calculate(
4949
return metrics::calcYawDeviation(reference_trajectory_, traj);
5050
case Metric::velocity_deviation:
5151
return metrics::calcVelocityDeviation(reference_trajectory_, traj);
52+
case Metric::lateral_trajectory_displacement:
53+
return metrics::calcLateralTrajectoryDisplacement(previous_trajectory_, traj, ego_pose_);
5254
case Metric::stability_frechet:
5355
return metrics::calcFrechetDistance(
5456
getLookaheadTrajectory(

0 commit comments

Comments
 (0)