Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(goal_planner): fix parking_path curvature and DecidingState transition #9022

Conversation

soblin
Copy link
Contributor

@soblin soblin commented Oct 3, 2024

Description

  • due to a mistake, the curvature of parking_path was calculated from full_path, which caused massive "[WARN 1727950663.638648154] [goal_planner_util]: path.points.size() != curvatures.size() in checkObjectsCollision(). judge as non collision" error
  • the time DecidingState started was not properly updated
  • transition from NOT_DECIDED to DECIDING was inactivated by mistake

Related links

Parent Issue:

How was this PR tested?

Notes for reviewers

None.

Interface changes

None.

Effects on system behavior

None.

@github-actions github-actions bot added the component:planning Route planning, decision-making, and navigation. (auto-assigned) label Oct 3, 2024
Copy link

github-actions bot commented Oct 3, 2024

Thank you for contributing to the Autoware project!

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

Please ensure:

@@ -73,7 +73,7 @@ std::optional<PullOverPath> PullOverPath::create(
double parking_path_max_curvature{};
std::tie(full_path_curvatures, full_path_max_curvature) = calculateCurvaturesAndMax(full_path);
std::tie(parking_path_curvatures, parking_path_max_curvature) =
calculateCurvaturesAndMax(full_path);
calculateCurvaturesAndMax(parking_path);

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I was using full_path for calculating the curvature of parking_path by mistake

PathDecisionState current_state_{};
PathDecisionState prev_state_{};

/**
* @brief update current state and save old current state to prev state
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Only prev_state_.stamp was used for saving the time when DECIDING state started.
So I deleted prev_state_ and save deciding_start_time instead.

@@ -2766,10 +2779,15 @@ PathDecisionState PathDecisionStateController::get_next_state(
// if object recognition for path collision check is enabled, transition to DECIDING to check
// collision for a certain period of time. Otherwise, transition to DECIDED directly.
if (parameters.use_object_recognition) {
next_state.state = PathDecisionState::DecisionKind::DECIDED;
Copy link
Contributor Author

Choose a reason for hiding this comment

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

In prior PR, I mistakenly changed the next state to DECIDED. DECIDING is correct for this case.

"[DecidingPathStatus]: NOT_DECIDED->DECIDING. start checking collision for certain "
"period of time");
next_state.state = PathDecisionState::DecisionKind::DECIDING;
next_state.deciding_start_time = now;
Copy link
Contributor Author

Choose a reason for hiding this comment

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

fixedto return DECIDING as the next state.

@soblin soblin marked this pull request as ready for review October 4, 2024 04:10
@soblin soblin added the tag:run-build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci) label Oct 4, 2024
Copy link

codecov bot commented Oct 4, 2024

Codecov Report

Attention: Patch coverage is 0% with 15 lines in your changes missing coverage. Please review.

Project coverage is 26.17%. Comparing base (b401eba) to head (8823c0a).
Report is 5 commits behind head on main.

Files with missing lines Patch % Lines
...th_goal_planner_module/src/goal_planner_module.cpp 0.00% 13 Missing ⚠️
...havior_path_goal_planner_module/decision_state.hpp 0.00% 1 Missing ⚠️
...e/src/pull_over_planner/pull_over_planner_base.cpp 0.00% 1 Missing ⚠️
Additional details and impacted files
@@            Coverage Diff             @@
##             main    #9022      +/-   ##
==========================================
- Coverage   26.19%   26.17%   -0.02%     
==========================================
  Files        1302     1306       +4     
  Lines       96917    96980      +63     
  Branches    39174    39185      +11     
==========================================
  Hits        25388    25388              
- Misses      68959    69018      +59     
- Partials     2570     2574       +4     
Flag Coverage Δ *Carryforward flag
differential 1.22% <0.00%> (?)
total 26.19% <ø> (+<0.01%) ⬆️ Carriedforward from b401eba

*This pull request uses carry forward flags. Click here to find out more.

☔ View full report in Codecov by Sentry.
📢 Have feedback on the report? Share it here.

@soblin soblin merged commit 3a75e98 into autowarefoundation:main Oct 4, 2024
46 of 48 checks passed
@soblin soblin deleted the chore/goal-planner/deciding-status-transition branch October 4, 2024 04:25
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
component:planning Route planning, decision-making, and navigation. (auto-assigned) tag:run-build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci)
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants