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(crosswalk): stopping besides the stop line (#6015) #1221

Merged
merged 1 commit into from
Apr 3, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -393,7 +393,7 @@ std::optional<StopFactor> CrosswalkModule::checkStopForCrosswalkUsers(
return {};
}

// Check if the ego should stop beyond the stop line.
// Check if the ego should stop at the stop line or the other points.
const bool stop_at_stop_line =
dist_ego_to_stop < nearest_stop_info->second &&
nearest_stop_info->second < dist_ego_to_stop + planner_param_.far_object_threshold;
Expand All @@ -404,9 +404,9 @@ std::optional<StopFactor> CrosswalkModule::checkStopForCrosswalkUsers(
return createStopFactor(*default_stop_pose, stop_factor_points);
}
} else {
// Stop beyond the stop line
const auto stop_pose = calcLongitudinalOffsetPose(
ego_path.points, nearest_stop_info->first, planner_param_.stop_distance_from_object);
ego_path.points, nearest_stop_info->first,
-base_link2front - planner_param_.stop_distance_from_object);
if (stop_pose) {
return createStopFactor(*stop_pose, stop_factor_points);
}
Expand Down
Loading