Skip to content

Commit 97bc5a7

Browse files
feat(planning_evaluator): add evaluation feature of trajectory lateral displacement (#9718)
* feat(planning_evaluator): add evaluation feature of trajectory lateral displacement Signed-off-by: Kyoichi Sugahara <kyoichi.sugahara@tier4.jp> * feat(metrics_calculator): implement lookahead trajectory calculation and remove deprecated method Signed-off-by: Kyoichi Sugahara <kyoichi.sugahara@tier4.jp> * fix(planning_evaluator): rename lateral_trajectory_displacement to trajectory_lateral_displacement for consistency Signed-off-by: Kyoichi Sugahara <kyoichi.sugahara@tier4.jp> --------- Signed-off-by: Kyoichi Sugahara <kyoichi.sugahara@tier4.jp>
1 parent 3bb2df2 commit 97bc5a7

File tree

11 files changed

+164
-53
lines changed

11 files changed

+164
-53
lines changed

evaluator/autoware_planning_evaluator/README.md

+1
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@ Metrics are calculated using the following information:
1313
- the previous trajectory `T(-1)`.
1414
- the _reference_ trajectory assumed to be used as the reference to plan `T(0)`.
1515
- the current ego pose.
16+
- the current ego odometry.
1617
- the set of objects in the environment.
1718

1819
These information are maintained by an instance of class `MetricsCalculator`

evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml

+2-1
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414
- lateral_deviation
1515
- yaw_deviation
1616
- velocity_deviation
17-
- lateral_trajectory_displacement
17+
- trajectory_lateral_displacement
1818
- stability
1919
- stability_frechet
2020
- obstacle_distance
@@ -25,6 +25,7 @@
2525

2626
trajectory:
2727
min_point_dist_m: 0.1 # [m] minimum distance between two successive points to use for angle calculation
28+
evaluation_time_s: 5.0 # [s] time duration for trajectory evaluation in seconds
2829
lookahead:
2930
max_dist_m: 5.0 # [m] maximum distance from ego along the trajectory to use for calculation
3031
max_time_s: 3.0 # [s] maximum time ahead of ego along the trajectory to use for calculation

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

+4
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,7 @@ enum class Metric {
4040
lateral_trajectory_displacement,
4141
stability,
4242
stability_frechet,
43+
trajectory_lateral_displacement,
4344
obstacle_distance,
4445
obstacle_ttc,
4546
modified_goal_longitudinal_deviation,
@@ -66,6 +67,7 @@ static const std::unordered_map<std::string, Metric> str_to_metric = {
6667
{"lateral_trajectory_displacement", Metric::lateral_trajectory_displacement},
6768
{"stability", Metric::stability},
6869
{"stability_frechet", Metric::stability_frechet},
70+
{"trajectory_lateral_displacement", Metric::trajectory_lateral_displacement},
6971
{"obstacle_distance", Metric::obstacle_distance},
7072
{"obstacle_ttc", Metric::obstacle_ttc},
7173
{"modified_goal_longitudinal_deviation", Metric::modified_goal_longitudinal_deviation},
@@ -87,6 +89,7 @@ static const std::unordered_map<Metric, std::string> metric_to_str = {
8789
{Metric::lateral_trajectory_displacement, "lateral_trajectory_displacement"},
8890
{Metric::stability, "stability"},
8991
{Metric::stability_frechet, "stability_frechet"},
92+
{Metric::trajectory_lateral_displacement, "trajectory_lateral_displacement"},
9093
{Metric::obstacle_distance, "obstacle_distance"},
9194
{Metric::obstacle_ttc, "obstacle_ttc"},
9295
{Metric::modified_goal_longitudinal_deviation, "modified_goal_longitudinal_deviation"},
@@ -109,6 +112,7 @@ static const std::unordered_map<Metric, std::string> metric_descriptions = {
109112
{Metric::lateral_trajectory_displacement, "Nearest Pose Lateral Deviation[m]"},
110113
{Metric::stability, "Stability[m]"},
111114
{Metric::stability_frechet, "StabilityFrechet[m]"},
115+
{Metric::trajectory_lateral_displacement, "Trajectory_lateral_displacement[m]"},
112116
{Metric::obstacle_distance, "Obstacle_distance[m]"},
113117
{Metric::obstacle_ttc, "Obstacle_time_to_collision[s]"},
114118
{Metric::modified_goal_longitudinal_deviation, "Modified_goal_longitudinal_deviation[m]"},

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

+24
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@ namespace metrics
2525
namespace utils
2626
{
2727
using autoware_planning_msgs::msg::Trajectory;
28+
using geometry_msgs::msg::Pose;
2829

2930
/**
3031
* @brief find the index in the trajectory at the given distance of the given index
@@ -35,6 +36,29 @@ using autoware_planning_msgs::msg::Trajectory;
3536
*/
3637
size_t getIndexAfterDistance(const Trajectory & traj, const size_t curr_id, const double distance);
3738

39+
/**
40+
* @brief trim a trajectory from the current ego pose to some fixed time or distance
41+
* @param [in] traj input trajectory to trim
42+
* @param [in] max_dist_m [m] maximum distance ahead of the ego pose
43+
* @param [in] max_time_s [s] maximum time ahead of the ego pose
44+
* @return sub-trajectory starting from the ego pose and of maximum length max_dist_m, maximum
45+
* duration max_time_s
46+
*/
47+
Trajectory get_lookahead_trajectory(
48+
const Trajectory & traj, const Pose & ego_pose, const double max_dist_m, const double max_time_s);
49+
50+
/**
51+
* @brief calculate the total distance from ego position to the end of trajectory
52+
* @details finds the nearest point to ego position on the trajectory and calculates
53+
* the cumulative distance by summing up the distances between consecutive points
54+
* from that position to the end of the trajectory.
55+
*
56+
* @param [in] traj input trajectory to calculate distance along
57+
* @param [in] ego_pose current ego vehicle pose
58+
* @return total distance from ego position to trajectory end in meters
59+
*/
60+
double calc_lookahead_trajectory_distance(const Trajectory & traj, const Pose & ego_pose);
61+
3862
} // namespace utils
3963
} // namespace metrics
4064
} // namespace planning_diagnostics

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

+18
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include "autoware/universe_utils/math/accumulator.hpp"
1919

2020
#include "autoware_planning_msgs/msg/trajectory.hpp"
21+
#include <nav_msgs/msg/odometry.hpp>
2122

2223
namespace planning_diagnostics
2324
{
@@ -42,6 +43,23 @@ Accumulator<double> calcFrechetDistance(const Trajectory & traj1, const Trajecto
4243
*/
4344
Accumulator<double> calcLateralDistance(const Trajectory & traj1, const Trajectory & traj2);
4445

46+
/**
47+
* @brief calculate the total lateral displacement between two trajectories
48+
* @details Evaluates the cumulative absolute lateral displacement by sampling points
49+
* along the first trajectory and measuring their offset from the second trajectory.
50+
* The evaluation section length is determined by the ego vehicle's velocity and
51+
* the specified evaluation time.
52+
*
53+
* @param traj1 first trajectory to compare
54+
* @param traj2 second trajectory to compare against
55+
* @param [in] ego_odom current ego vehicle odometry containing pose and velocity
56+
* @param [in] trajectory_eval_time_s time duration for trajectory evaluation in seconds
57+
* @return statistical accumulator containing the total lateral displacement
58+
*/
59+
Accumulator<double> calcTrajectoryLateralDisplacement(
60+
const Trajectory traj1, const Trajectory traj2, const nav_msgs::msg::Odometry & ego_odom,
61+
const double trajectory_eval_time_s);
62+
4563
} // namespace metrics
4664
} // namespace planning_diagnostics
4765

evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics_calculator.hpp

+3-12
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include "autoware_planning_msgs/msg/trajectory.hpp"
2424
#include "autoware_planning_msgs/msg/trajectory_point.hpp"
2525
#include "geometry_msgs/msg/pose.hpp"
26+
#include <nav_msgs/msg/odometry.hpp>
2627

2728
#include <optional>
2829

@@ -74,7 +75,7 @@ class MetricsCalculator
7475
* @brief set the ego pose
7576
* @param [in] traj input previous trajectory
7677
*/
77-
void setEgoPose(const geometry_msgs::msg::Pose & pose);
78+
void setEgoPose(const nav_msgs::msg::Odometry & ego_odometry);
7879

7980
/**
8081
* @brief get the ego pose
@@ -83,23 +84,13 @@ class MetricsCalculator
8384
Pose getEgoPose();
8485

8586
private:
86-
/**
87-
* @brief trim a trajectory from the current ego pose to some fixed time or distance
88-
* @param [in] traj input trajectory to trim
89-
* @param [in] max_dist_m [m] maximum distance ahead of the ego pose
90-
* @param [in] max_time_s [s] maximum time ahead of the ego pose
91-
* @return sub-trajectory starting from the ego pose and of maximum length max_dist_m, maximum
92-
* duration max_time_s
93-
*/
94-
Trajectory getLookaheadTrajectory(
95-
const Trajectory & traj, const double max_dist_m, const double max_time_s) const;
96-
9787
Trajectory reference_trajectory_;
9888
Trajectory reference_trajectory_lookahead_;
9989
Trajectory previous_trajectory_;
10090
Trajectory previous_trajectory_lookahead_;
10191
PredictedObjects dynamic_objects_;
10292
geometry_msgs::msg::Pose ego_pose_;
93+
nav_msgs::msg::Odometry ego_odometry_;
10394
PoseWithUuidStamped modified_goal_;
10495
}; // class MetricsCalculator
10596

evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/parameters.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@ struct Parameters
3131
struct
3232
{
3333
double min_point_dist_m = 0.1;
34+
double evaluation_time_s = 5.0;
3435
struct
3536
{
3637
double max_dist_m = 5.0;

evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp

+49
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,10 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15+
#include "autoware/motion_utils/trajectory/trajectory.hpp"
1516
#include "autoware/planning_evaluator/metrics/trajectory_metrics.hpp"
1617
#include "autoware/universe_utils/geometry/geometry.hpp"
18+
1719
namespace planning_diagnostics
1820
{
1921
namespace metrics
@@ -23,6 +25,7 @@ namespace utils
2325
using autoware::universe_utils::calcDistance2d;
2426
using autoware_planning_msgs::msg::Trajectory;
2527
using autoware_planning_msgs::msg::TrajectoryPoint;
28+
using geometry_msgs::msg::Pose;
2629

2730
size_t getIndexAfterDistance(const Trajectory & traj, const size_t curr_id, const double distance)
2831
{
@@ -41,6 +44,52 @@ size_t getIndexAfterDistance(const Trajectory & traj, const size_t curr_id, cons
4144
return target_id;
4245
}
4346

47+
Trajectory get_lookahead_trajectory(
48+
const Trajectory & traj, const Pose & ego_pose, const double max_dist_m, const double max_time_s)
49+
{
50+
if (traj.points.empty()) {
51+
return traj;
52+
}
53+
54+
const auto ego_index =
55+
autoware::motion_utils::findNearestSegmentIndex(traj.points, ego_pose.position);
56+
Trajectory lookahead_traj;
57+
lookahead_traj.header = traj.header;
58+
double dist = 0.0;
59+
double time = 0.0;
60+
auto curr_point_it = std::next(traj.points.begin(), ego_index);
61+
auto prev_point_it = curr_point_it;
62+
while (curr_point_it != traj.points.end() && dist <= max_dist_m && time <= max_time_s) {
63+
lookahead_traj.points.push_back(*curr_point_it);
64+
const auto d = autoware::universe_utils::calcDistance2d(
65+
prev_point_it->pose.position, curr_point_it->pose.position);
66+
dist += d;
67+
if (prev_point_it->longitudinal_velocity_mps != 0.0) {
68+
time += d / std::abs(prev_point_it->longitudinal_velocity_mps);
69+
}
70+
prev_point_it = curr_point_it;
71+
++curr_point_it;
72+
}
73+
return lookahead_traj;
74+
}
75+
76+
double calc_lookahead_trajectory_distance(const Trajectory & traj, const Pose & ego_pose)
77+
{
78+
const auto ego_index =
79+
autoware::motion_utils::findNearestSegmentIndex(traj.points, ego_pose.position);
80+
double dist = 0.0;
81+
auto curr_point_it = std::next(traj.points.begin(), ego_index);
82+
auto prev_point_it = curr_point_it;
83+
for (size_t i = 0; i < traj.points.size(); ++i) {
84+
const auto d = autoware::universe_utils::calcDistance2d(
85+
prev_point_it->pose.position, curr_point_it->pose.position);
86+
dist += d;
87+
prev_point_it = curr_point_it;
88+
++curr_point_it;
89+
}
90+
91+
return dist;
92+
}
4493
} // namespace utils
4594
} // namespace metrics
4695
} // namespace planning_diagnostics

evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp

+44
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,9 @@
1414

1515
#include "autoware/planning_evaluator/metrics/stability_metrics.hpp"
1616

17+
#include "autoware/motion_utils/resample/resample.hpp"
1718
#include "autoware/motion_utils/trajectory/trajectory.hpp"
19+
#include "autoware/planning_evaluator/metrics/metrics_utils.hpp"
1820
#include "autoware/universe_utils/geometry/geometry.hpp"
1921

2022
#include <Eigen/Core>
@@ -96,5 +98,47 @@ Accumulator<double> calcLateralDistance(const Trajectory & traj1, const Trajecto
9698
return stat;
9799
}
98100

101+
Accumulator<double> calcTrajectoryLateralDisplacement(
102+
const Trajectory traj1, const Trajectory traj2, const nav_msgs::msg::Odometry & ego_odom,
103+
const double trajectory_eval_time_s)
104+
{
105+
Accumulator<double> stat;
106+
107+
if (traj1.points.empty() || traj2.points.empty()) {
108+
return stat;
109+
}
110+
111+
const double ego_velocity =
112+
std::hypot(ego_odom.twist.twist.linear.x, ego_odom.twist.twist.linear.y);
113+
114+
const double evaluation_section_length = trajectory_eval_time_s * std::abs(ego_velocity);
115+
116+
const double traj1_lookahead_distance =
117+
utils::calc_lookahead_trajectory_distance(traj1, ego_odom.pose.pose);
118+
const double traj2_lookahead_distance =
119+
utils::calc_lookahead_trajectory_distance(traj2, ego_odom.pose.pose);
120+
121+
if (
122+
traj1_lookahead_distance < evaluation_section_length ||
123+
traj2_lookahead_distance < evaluation_section_length) {
124+
return stat;
125+
}
126+
127+
constexpr double num_evaluation_points = 10.0;
128+
const double interval = evaluation_section_length / num_evaluation_points;
129+
130+
const auto resampled_traj1 = autoware::motion_utils::resampleTrajectory(
131+
utils::get_lookahead_trajectory(
132+
traj1, ego_odom.pose.pose, evaluation_section_length, trajectory_eval_time_s),
133+
interval);
134+
135+
for (const auto & point : resampled_traj1.points) {
136+
const auto p0 = autoware::universe_utils::getPoint(point);
137+
const double dist = autoware::motion_utils::calcLateralOffset(traj2.points, p0);
138+
stat.add(std::abs(dist));
139+
}
140+
return stat;
141+
}
142+
99143
} // namespace metrics
100144
} // namespace planning_diagnostics

evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp

+15-39
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
#include "autoware/motion_utils/trajectory/trajectory.hpp"
1818
#include "autoware/planning_evaluator/metrics/deviation_metrics.hpp"
19+
#include "autoware/planning_evaluator/metrics/metrics_utils.hpp"
1920
#include "autoware/planning_evaluator/metrics/obstacle_metrics.hpp"
2021
#include "autoware/planning_evaluator/metrics/stability_metrics.hpp"
2122
#include "autoware/planning_evaluator/metrics/trajectory_metrics.hpp"
@@ -53,20 +54,23 @@ std::optional<Accumulator<double>> MetricsCalculator::calculate(
5354
return metrics::calcLateralTrajectoryDisplacement(previous_trajectory_, traj, ego_pose_);
5455
case Metric::stability_frechet:
5556
return metrics::calcFrechetDistance(
56-
getLookaheadTrajectory(
57-
previous_trajectory_, parameters.trajectory.lookahead.max_dist_m,
57+
metrics::utils::get_lookahead_trajectory(
58+
previous_trajectory_, ego_pose_, parameters.trajectory.lookahead.max_dist_m,
5859
parameters.trajectory.lookahead.max_time_s),
59-
getLookaheadTrajectory(
60-
traj, parameters.trajectory.lookahead.max_dist_m,
60+
metrics::utils::get_lookahead_trajectory(
61+
traj, ego_pose_, parameters.trajectory.lookahead.max_dist_m,
6162
parameters.trajectory.lookahead.max_time_s));
6263
case Metric::stability:
6364
return metrics::calcLateralDistance(
64-
getLookaheadTrajectory(
65-
previous_trajectory_, parameters.trajectory.lookahead.max_dist_m,
65+
metrics::utils::get_lookahead_trajectory(
66+
previous_trajectory_, ego_pose_, parameters.trajectory.lookahead.max_dist_m,
6667
parameters.trajectory.lookahead.max_time_s),
67-
getLookaheadTrajectory(
68-
traj, parameters.trajectory.lookahead.max_dist_m,
68+
metrics::utils::get_lookahead_trajectory(
69+
traj, ego_pose_, parameters.trajectory.lookahead.max_dist_m,
6970
parameters.trajectory.lookahead.max_time_s));
71+
case Metric::trajectory_lateral_displacement:
72+
return metrics::calcTrajectoryLateralDisplacement(
73+
previous_trajectory_, traj, ego_odometry_, parameters.trajectory.evaluation_time_s);
7074
case Metric::obstacle_distance:
7175
return metrics::calcDistanceToObstacle(dynamic_objects_, traj);
7276
case Metric::obstacle_ttc:
@@ -107,43 +111,15 @@ void MetricsCalculator::setPredictedObjects(const PredictedObjects & objects)
107111
dynamic_objects_ = objects;
108112
}
109113

110-
void MetricsCalculator::setEgoPose(const geometry_msgs::msg::Pose & pose)
114+
void MetricsCalculator::setEgoPose(const nav_msgs::msg::Odometry & ego_odometry)
111115
{
112-
ego_pose_ = pose;
116+
ego_pose_ = ego_odometry.pose.pose;
117+
ego_odometry_ = ego_odometry;
113118
}
114119

115120
Pose MetricsCalculator::getEgoPose()
116121
{
117122
return ego_pose_;
118123
}
119124

120-
Trajectory MetricsCalculator::getLookaheadTrajectory(
121-
const Trajectory & traj, const double max_dist_m, const double max_time_s) const
122-
{
123-
if (traj.points.empty()) {
124-
return traj;
125-
}
126-
127-
const auto ego_index =
128-
autoware::motion_utils::findNearestSegmentIndex(traj.points, ego_pose_.position);
129-
Trajectory lookahead_traj;
130-
lookahead_traj.header = traj.header;
131-
double dist = 0.0;
132-
double time = 0.0;
133-
auto curr_point_it = std::next(traj.points.begin(), ego_index);
134-
auto prev_point_it = curr_point_it;
135-
while (curr_point_it != traj.points.end() && dist <= max_dist_m && time <= max_time_s) {
136-
lookahead_traj.points.push_back(*curr_point_it);
137-
const auto d = autoware::universe_utils::calcDistance2d(
138-
prev_point_it->pose.position, curr_point_it->pose.position);
139-
dist += d;
140-
if (prev_point_it->longitudinal_velocity_mps != 0.0) {
141-
time += d / std::abs(prev_point_it->longitudinal_velocity_mps);
142-
}
143-
prev_point_it = curr_point_it;
144-
++curr_point_it;
145-
}
146-
return lookahead_traj;
147-
}
148-
149125
} // namespace planning_diagnostics

0 commit comments

Comments
 (0)