Skip to content

feat(planning_data_analyzer): add open-loop lane keeping metric#383

Merged
beomseok-kimm merged 2 commits intoautowarefoundation:mainfrom
tier4:feat/epdms-lk
Mar 31, 2026
Merged

feat(planning_data_analyzer): add open-loop lane keeping metric#383
beomseok-kimm merged 2 commits intoautowarefoundation:mainfrom
tier4:feat/epdms-lk

Conversation

@beomseok-kimm
Copy link
Copy Markdown
Contributor

@beomseok-kimm beomseok-kimm commented Mar 31, 2026

Description

This PR is the next implementation step in a series toward full EPDMS support in autoware_planning_data_analyzer, following the NAVSIM metric definition and reference implementation.

This PR specifically adds LK (Lane Keeping) as the next standalone subscore.

How was this PR tested?

Successfully built autoware_planning_data_analyzer and passed:

  • test_metrics
  • test_offline_evaluation

Successfully created output rosbag and JSON results that contain the lane_keeping metric.

input and output link:

Notes for reviewers

The current LK implementation is a package-level approximation based on:

  • ego center-point lateral distance to the lane centerline
  • route-scoped local lane lookup at each trajectory pose
  • intersection masking
  • continuous over-threshold duration logic

Effects on system behavior

None.

@github-actions
Copy link
Copy Markdown

github-actions Bot commented Mar 31, 2026

Thank you for contributing to the Autoware project!

🚧 If your pull request is in progress, switch it to draft mode.

Please ensure:

Copy link
Copy Markdown

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

Adds the LK (Lane Keeping) open-loop subscore to autoware_planning_data_analyzer, wiring it through trajectory metric computation, bag/JSON outputs, configuration parameters, and unit/integration tests (aligned with the NAVSIM metric direction described in the PR).

Changes:

  • Implement lane-keeping scoring (LK) with intersection masking and continuous-violation window logic.
  • Compute LK from per-pose route-local lane centerline deviation and export it via open-loop bag topics + JSON summary/full results.
  • Add config parameters + tests to validate LK behavior and presence in outputs.

Reviewed changes

Copilot reviewed 13 out of 13 changed files in this pull request and generated 2 comments.

Show a summary per file
File Description
planning/autoware_planning_data_analyzer/src/metrics/lane_keeping.hpp Declares LK parameters, sample type, and score API
planning/autoware_planning_data_analyzer/src/metrics/lane_keeping.cpp Implements LK scoring logic (binary pass/fail)
planning/autoware_planning_data_analyzer/src/metrics/trajectory_metrics.hpp Extends trajectory point metrics with LK field + params
planning/autoware_planning_data_analyzer/src/metrics/trajectory_metrics.cpp Computes lane-local lateral deviation + LK score per trajectory
planning/autoware_planning_data_analyzer/src/open_loop_evaluator.hpp Threads LK params and LK result through evaluator data structures
planning/autoware_planning_data_analyzer/src/open_loop_evaluator.cpp Saves LK to bag, summary JSON, and full results JSON; registers topic
planning/autoware_planning_data_analyzer/src/autoware_planning_data_analyzer_node.hpp Stores LK parameters in node state
planning/autoware_planning_data_analyzer/src/autoware_planning_data_analyzer_node.cpp Declares/reads LK params and passes them into OpenLoopEvaluator
planning/autoware_planning_data_analyzer/config/planning_data_analyzer.param.yaml Adds default open_loop.lk.* parameter values
planning/autoware_planning_data_analyzer/package.xml Adds dependency needed for intersection utilities
planning/autoware_planning_data_analyzer/CMakeLists.txt Builds LK metric source + adds LK unit test
planning/autoware_planning_data_analyzer/test/metrics/test_lane_keeping.cpp New LK unit tests covering threshold/window/intersection behavior
planning/autoware_planning_data_analyzer/test/test_open_loop_gt_source_mode.cpp Extends integration test to assert LK topic + summary output presence

💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.

const auto & point = trajectory.points[i];
const auto reference_lanelet = find_reference_lanelet(point.pose, route_handler);
if (!reference_lanelet.has_value()) {
metrics.lateral_deviations[i] = std::numeric_limits<double>::quiet_NaN();
Copy link

Copilot AI Mar 31, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

When find_reference_lanelet() returns nullopt you set metrics.lateral_deviations[i] to NaN and continue, but you don’t append a corresponding LaneKeepingSample. Since calculate_lane_keeping_score() resets the violation window on non-finite deviations, skipping the sample can incorrectly treat a gap in lane association as continuous violation time (e.g., violation @t0, no lanelet @t1, violation @t2.1 => duration computed as 2.1s). Consider pushing a sample with the same timestamp and lateral_deviation = NaN (or explicitly resetting the LK state for that time) so missing lanelets break continuity as intended.

Suggested change
metrics.lateral_deviations[i] = std::numeric_limits<double>::quiet_NaN();
metrics.lateral_deviations[i] = std::numeric_limits<double>::quiet_NaN();
lane_keeping_samples.push_back(LaneKeepingSample{
point.time_from_start, metrics.lateral_deviations[i], false});

Copilot uses AI. Check for mistakes.
Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Applied in 1cb4555e. I now append a same-timestamp non-finite LK evaluation point when no reference lanelet is found, so missing-lanelet gaps break the continuous-violation window.

Comment on lines +1063 to +1068
for (const auto & m : metrics_list_) {
lane_keeping_values.push_back(m.lane_keeping);
}
emit_metric(
"aggregate", "lane_keeping", "Binary lane keeping subscore across trajectories [-]",
lane_keeping_values);
Copy link

Copilot AI Mar 31, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

lane_keeping_values is aggregated across all trajectories unconditionally, but LK currently evaluates to 0.0 when there are no valid lane-keeping samples (e.g., route handler missing/not ready, or no lanelet found for poses). This makes “unavailable” indistinguishable from a true failing score and will bias the aggregate stats. Consider adding an availability flag/reason for lane keeping (similar to drivable_area_compliance_available), and only aggregating available LK values while also reporting available/unavailable counts.

Suggested change
for (const auto & m : metrics_list_) {
lane_keeping_values.push_back(m.lane_keeping);
}
emit_metric(
"aggregate", "lane_keeping", "Binary lane keeping subscore across trajectories [-]",
lane_keeping_values);
std::size_t lane_keeping_available_count = 0;
std::map<std::string, std::size_t> lane_keeping_reason_counts;
for (const auto & m : metrics_list_) {
++lane_keeping_reason_counts[m.lane_keeping_reason];
if (m.lane_keeping_available) {
lane_keeping_values.push_back(m.lane_keeping);
++lane_keeping_available_count;
}
}
emit_metric(
"aggregate", "lane_keeping", "Binary lane keeping subscore across trajectories [-]",
lane_keeping_values);
j["aggregate/lane_keeping_available_count"] = lane_keeping_available_count;
j["aggregate/lane_keeping_unavailable_count"] =
metrics_list_.size() - lane_keeping_available_count;

Copilot uses AI. Check for mistakes.
Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Applied in 1cb4555e. LK now reports lane_keeping_available and lane_keeping_reason, and the aggregate summary only uses available LK values while also reporting available/unavailable counts and reason counts.

Comment thread planning/autoware_planning_data_analyzer/config/planning_data_analyzer.param.yaml Outdated
gt_source_mode: "kinematic_state"
gt_trajectory_topic: "/planning/ground_truth_trajectory"
gt_sync_tolerance_ms: 200.0
hc:
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This abbreviation is not general neither

Comment thread planning/autoware_planning_data_analyzer/src/metrics/trajectory_metrics.cpp Outdated
const std::shared_ptr<SynchronizedData> & sync_data,
const std::shared_ptr<autoware::route_handler::RouteHandler> & route_handler,
const HistoryComfortParameters & history_comfort_params,
const LaneKeepingParameters & lane_keeping_params,
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think adding arguments to this function is not a good idea, since each parameter is used only to calculate each parameters. Should be fixed in another PR

Comment thread planning/autoware_planning_data_analyzer/src/metrics/lane_keeping.hpp Outdated
Comment thread planning/autoware_planning_data_analyzer/src/metrics/trajectory_metrics.cpp Outdated
Comment thread planning/autoware_planning_data_analyzer/src/metrics/lane_keeping.cpp Outdated
@beomseok-kimm
Copy link
Copy Markdown
Contributor Author

beomseok-kimm commented Mar 31, 2026

Addressed in 1cb4555e.

TL;DR by review theme:

  • Config naming: renamed open_loop.lk.* to open_loop.lane_keep.*.
  • LK naming clarity: renamed LaneKeepingSample to LaneKeepingEvaluationPoint, renamed the scorer argument to evaluation_points, and added a short function header.
  • Missing-lanelet continuity bug: fixed by appending a same-timestamp non-finite LK evaluation point when no reference lanelet is found, so gaps break the continuous-violation window.
  • LK unavailable vs fail: added lane_keeping_available and lane_keeping_reason, and aggregate LK now uses only available values while also reporting counts and reason counts.
  • RouteHandler check: I verified getClosestLaneletWithinRoute() only returns false when route_lanelets_ is empty or the output pointer is null, and isRouteLanelet() is just membership in route_lanelets_, so the previous fallback branch was effectively redundant. I removed it.
  • Broader API / output refactors: I kept the PR scoped and did not do a larger metric-plumbing or output/topic rename refactor here. The broader lateral_deviations naming and further GT longitudinal/lateral deviation work should be follow-up items.

@beomseok-kimm beomseok-kimm merged commit 38fc640 into autowarefoundation:main Mar 31, 2026
30 of 31 checks passed
@beomseok-kimm beomseok-kimm deleted the feat/epdms-lk branch March 31, 2026 07:02
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants