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

feat(goal_planner): add bezier based pull over planner #9642

Merged
merged 16 commits into from
Dec 15, 2024

Conversation

soblin
Copy link
Contributor

@soblin soblin commented Dec 13, 2024

Description

ros2 run autoware_behavior_path_goal_planner plot_map{1, 2} gives following figures.

image

image

Related links

Parent Issue:

  • Link

How was this PR tested?

Notes for reviewers

None.

Interface changes

None.

Effects on system behavior

None.

@github-actions github-actions bot added component:planning Route planning, decision-making, and navigation. (auto-assigned) component:common Common packages from the autoware-common repository. (auto-assigned) labels Dec 13, 2024
Copy link

github-actions bot commented Dec 13, 2024

Thank you for contributing to the Autoware project!

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

Please ensure:

@soblin soblin force-pushed the dev/goal-candidate branch 2 times, most recently from 4b10c86 to 0767098 Compare December 13, 2024 06:42
Copy link
Contributor

@maxime-clem maxime-clem left a comment

Choose a reason for hiding this comment

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

Change to the autoware_bezier_sampler look good.

Comment on lines 65 to 76
double distance_initial_to_final = std::sqrt(
(initial.pose.x() - final.pose.x()) * (initial.pose.x() - final.pose.x()) +
(initial.pose.y() - final.pose.y()) * (initial.pose.y() - final.pose.y()));
// Tangent vectors
const Eigen::Vector2d initial_tangent_unit(std::cos(initial.heading), std::sin(initial.heading));
const Eigen::Vector2d final_tangent_unit(std::cos(final.heading), std::sin(final.heading));
// Unit vectors
const Eigen::Vector2d initial_normal_unit = initial_tangent_unit.unitOrthogonal();
const Eigen::Vector2d final_normal_unit = final_tangent_unit.unitOrthogonal();
double initial_tangent_length = initial_velocity * distance_initial_to_final;
double final_tangent_length = final_velocity * distance_initial_to_final;
double acceleration_length = acceleration * distance_initial_to_final;
Copy link
Contributor

Choose a reason for hiding this comment

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

Everything can be made const here.

Suggested change
double distance_initial_to_final = std::sqrt(
(initial.pose.x() - final.pose.x()) * (initial.pose.x() - final.pose.x()) +
(initial.pose.y() - final.pose.y()) * (initial.pose.y() - final.pose.y()));
// Tangent vectors
const Eigen::Vector2d initial_tangent_unit(std::cos(initial.heading), std::sin(initial.heading));
const Eigen::Vector2d final_tangent_unit(std::cos(final.heading), std::sin(final.heading));
// Unit vectors
const Eigen::Vector2d initial_normal_unit = initial_tangent_unit.unitOrthogonal();
const Eigen::Vector2d final_normal_unit = final_tangent_unit.unitOrthogonal();
double initial_tangent_length = initial_velocity * distance_initial_to_final;
double final_tangent_length = final_velocity * distance_initial_to_final;
double acceleration_length = acceleration * distance_initial_to_final;
const double distance_initial_to_final = std::sqrt(
(initial.pose.x() - final.pose.x()) * (initial.pose.x() - final.pose.x()) +
(initial.pose.y() - final.pose.y()) * (initial.pose.y() - final.pose.y()));
// Tangent vectors
const Eigen::Vector2d initial_tangent_unit(std::cos(initial.heading), std::sin(initial.heading));
const Eigen::Vector2d final_tangent_unit(std::cos(final.heading), std::sin(final.heading));
// Unit vectors
const Eigen::Vector2d initial_normal_unit = initial_tangent_unit.unitOrthogonal();
const Eigen::Vector2d final_normal_unit = final_tangent_unit.unitOrthogonal();
const double initial_tangent_length = initial_velocity * distance_initial_to_final;
const double final_tangent_length = final_velocity * distance_initial_to_final;
const double acceleration_length = acceleration * distance_initial_to_final;

@soblin soblin force-pushed the dev/goal-candidate branch 2 times, most recently from 4b8400f to 1548a30 Compare December 13, 2024 09:16
@kosuke55 kosuke55 added the tag:run-build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci) label Dec 15, 2024
Signed-off-by: Mamoru Sobue <[email protected]>
Signed-off-by: Mamoru Sobue <[email protected]>
Signed-off-by: Mamoru Sobue <[email protected]>
Signed-off-by: Mamoru Sobue <[email protected]>
Signed-off-by: Mamoru Sobue <[email protected]>
Signed-off-by: Mamoru Sobue <[email protected]>
Signed-off-by: Mamoru Sobue <[email protected]>
@soblin soblin force-pushed the dev/goal-candidate branch from 96f632d to 21346a5 Compare December 15, 2024 07:47
@soblin soblin enabled auto-merge (squash) December 15, 2024 07:47
Copy link

codecov bot commented Dec 15, 2024

Codecov Report

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

Project coverage is 29.84%. Comparing base (9ff1c38) to head (21346a5).
Report is 1 commits behind head on main.

Files with missing lines Patch % Lines
..._module/src/pull_over_planner/bezier_pull_over.cpp 0.00% 186 Missing ⚠️
...er/autoware_bezier_sampler/src/bezier_sampling.cpp 0.00% 12 Missing ⚠️
...nner_module/pull_over_planner/bezier_pull_over.hpp 0.00% 1 Missing ⚠️
Additional details and impacted files
@@            Coverage Diff             @@
##             main    #9642      +/-   ##
==========================================
- Coverage   29.90%   29.84%   -0.06%     
==========================================
  Files        1441     1448       +7     
  Lines      108349   108575     +226     
  Branches    42492    42584      +92     
==========================================
+ Hits        32403    32407       +4     
- Misses      72763    72977     +214     
- Partials     3183     3191       +8     
Flag Coverage Δ *Carryforward flag
differential 32.40% <0.00%> (?)
total 29.96% <ø> (+0.05%) ⬆️ Carriedforward from 9ff1c38

*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.

Signed-off-by: Mamoru Sobue <[email protected]>
@github-actions github-actions bot removed the component:common Common packages from the autoware-common repository. (auto-assigned) label Dec 15, 2024
@soblin soblin merged commit 5ced41e into autowarefoundation:main Dec 15, 2024
26 of 27 checks passed
@soblin soblin deleted the dev/goal-candidate branch December 15, 2024 15:32
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
Status: Done
Development

Successfully merging this pull request may close these issues.

4 participants