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(autoware_behavior_path_planner_common): modify geometric parallel parking path planning #9622

Open
wants to merge 2 commits into
base: main
Choose a base branch
from

Conversation

TakumIto
Copy link
Contributor

@TakumIto TakumIto commented Dec 11, 2024

Description

Modify the weird path generation of geometric parallel parking. The alpha calculation was wrong and must be computed according to forward or backward parking.
Moreover, this PR includes modification of a useless boundary check (check for the opposite side of the shoulder).

Before
Screenshot from 2024-12-11 12-46-34

After
Screenshot from 2024-12-11 12-47-40

Related links

Parent Issue:

  • N/A

How was this PR tested?

Notes for reviewers

None.

Interface changes

None.

Effects on system behavior

None.

Copy link

github-actions bot commented Dec 11, 2024

Thank you for contributing to the Autoware project!

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

Please ensure:

@github-actions github-actions bot added the component:planning Route planning, decision-making, and navigation. (auto-assigned) label Dec 11, 2024
@TakumIto TakumIto marked this pull request as ready for review December 17, 2024 02:25
@kosuke55 kosuke55 force-pushed the fix/geometric_parallel_parking branch from 755ac9d to 71b9ad0 Compare December 17, 2024 03:59
@kosuke55 kosuke55 added the run:build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci) label Dec 17, 2024
@kosuke55 kosuke55 self-assigned this Dec 17, 2024
Comment on lines 403 to 416
double alpha;
if (is_forward) {
alpha =
left_side_parking
? M_PI_2 + psi + std::asin((self_point_goal_coords.y - C_far_goal_coords.y) / d_C_far_Einit)
: M_PI_2 - psi -
std::asin((self_point_goal_coords.y - C_far_goal_coords.y) / d_C_far_Einit);
} else {
alpha =
left_side_parking
? M_PI_2 - psi + std::asin((self_point_goal_coords.y - C_far_goal_coords.y) / d_C_far_Einit)
: M_PI_2 + psi -
std::asin((self_point_goal_coords.y - C_far_goal_coords.y) / d_C_far_Einit);
}
Copy link
Contributor

Choose a reason for hiding this comment

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

too many std::asin((self_point_goal_coords.y - C_far_goal_coords.y)

Comment on lines 403 to 416
double alpha;
if (is_forward) {
alpha =
left_side_parking
? M_PI_2 + psi + std::asin((self_point_goal_coords.y - C_far_goal_coords.y) / d_C_far_Einit)
: M_PI_2 - psi -
std::asin((self_point_goal_coords.y - C_far_goal_coords.y) / d_C_far_Einit);
} else {
alpha =
left_side_parking
? M_PI_2 - psi + std::asin((self_point_goal_coords.y - C_far_goal_coords.y) / d_C_far_Einit)
: M_PI_2 + psi -
std::asin((self_point_goal_coords.y - C_far_goal_coords.y) / d_C_far_Einit);
}
Copy link
Contributor

Choose a reason for hiding this comment

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

Suggested change
double alpha;
if (is_forward) {
alpha =
left_side_parking
? M_PI_2 + psi + std::asin((self_point_goal_coords.y - C_far_goal_coords.y) / d_C_far_Einit)
: M_PI_2 - psi -
std::asin((self_point_goal_coords.y - C_far_goal_coords.y) / d_C_far_Einit);
} else {
alpha =
left_side_parking
? M_PI_2 - psi + std::asin((self_point_goal_coords.y - C_far_goal_coords.y) / d_C_far_Einit)
: M_PI_2 + psi -
std::asin((self_point_goal_coords.y - C_far_goal_coords.y) / d_C_far_Einit);
}
const double angle_offset =
std::asin((self_point_goal_coords.y - C_far_goal_coords.y) / d_C_far_Einit);
const double alpha = M_PI_2 + (left_side_parking ? 1.0 : -1.0) *
(is_forward ? psi + angle_offset : -psi + angle_offset);

is this same?
I am not sure that angle_offset is appropriate name, so please replace

Copy link
Contributor Author

Choose a reason for hiding this comment

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

It's the same procedure, and the parameter name sounds good to me.

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 modified it.

Signed-off-by: Takumi Ito <[email protected]>
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) run:build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci)
Projects
Status: To Triage
Development

Successfully merging this pull request may close these issues.

2 participants