|
16 | 16 |
|
17 | 17 | #include "autoware/motion_utils/trajectory/trajectory.hpp"
|
18 | 18 | #include "autoware/planning_evaluator/metrics/deviation_metrics.hpp"
|
| 19 | +#include "autoware/planning_evaluator/metrics/metrics_utils.hpp" |
19 | 20 | #include "autoware/planning_evaluator/metrics/obstacle_metrics.hpp"
|
20 | 21 | #include "autoware/planning_evaluator/metrics/stability_metrics.hpp"
|
21 | 22 | #include "autoware/planning_evaluator/metrics/trajectory_metrics.hpp"
|
@@ -53,20 +54,23 @@ std::optional<Accumulator<double>> MetricsCalculator::calculate(
|
53 | 54 | return metrics::calcLateralTrajectoryDisplacement(previous_trajectory_, traj, ego_pose_);
|
54 | 55 | case Metric::stability_frechet:
|
55 | 56 | 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, |
58 | 59 | 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, |
61 | 62 | parameters.trajectory.lookahead.max_time_s));
|
62 | 63 | case Metric::stability:
|
63 | 64 | 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, |
66 | 67 | 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, |
69 | 70 | 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); |
70 | 74 | case Metric::obstacle_distance:
|
71 | 75 | return metrics::calcDistanceToObstacle(dynamic_objects_, traj);
|
72 | 76 | case Metric::obstacle_ttc:
|
@@ -107,43 +111,15 @@ void MetricsCalculator::setPredictedObjects(const PredictedObjects & objects)
|
107 | 111 | dynamic_objects_ = objects;
|
108 | 112 | }
|
109 | 113 |
|
110 |
| -void MetricsCalculator::setEgoPose(const geometry_msgs::msg::Pose & pose) |
| 114 | +void MetricsCalculator::setEgoPose(const nav_msgs::msg::Odometry & ego_odometry) |
111 | 115 | {
|
112 |
| - ego_pose_ = pose; |
| 116 | + ego_pose_ = ego_odometry.pose.pose; |
| 117 | + ego_odometry_ = ego_odometry; |
113 | 118 | }
|
114 | 119 |
|
115 | 120 | Pose MetricsCalculator::getEgoPose()
|
116 | 121 | {
|
117 | 122 | return ego_pose_;
|
118 | 123 | }
|
119 | 124 |
|
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 |
| - |
149 | 125 | } // namespace planning_diagnostics
|
0 commit comments