-
Notifications
You must be signed in to change notification settings - Fork 690
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
base: main
Are you sure you want to change the base?
fix(autoware_behavior_path_planner_common): modify geometric parallel parking path planning #9622
Conversation
Thank you for contributing to the Autoware project! 🚧 If your pull request is in progress, switch it to draft mode. Please ensure:
|
Signed-off-by: Takumi Ito <[email protected]>
755ac9d
to
71b9ad0
Compare
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); | ||
} |
There was a problem hiding this comment.
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)
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); | ||
} |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
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
There was a problem hiding this comment.
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.
There was a problem hiding this comment.
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]>
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

After

Related links
Parent Issue:
How was this PR tested?
Notes for reviewers
None.
Interface changes
None.
Effects on system behavior
None.