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(behavior_path_planner): pull over dies after curve #1963

Merged
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 @@ -24,7 +24,6 @@
#include <vector>

namespace behavior_path_planner

{
ShiftPullOver::ShiftPullOver(
rclcpp::Node & node, const PullOverParameters & parameters,
Expand Down Expand Up @@ -108,15 +107,21 @@ std::vector<PullOverPath> ShiftPullOver::generatePullOverPaths(
const double jerk_resolution =
std::abs(maximum_lateral_jerk - minimum_lateral_jerk) / pull_over_sampling_num;

const double distance_to_shoulder_lane_boundary =
util::getDistanceToShoulderBoundary(shoulder_lanes, current_pose);
const double offset_from_current_pose =
distance_to_shoulder_lane_boundary + common_parameters.vehicle_width / 2 + margin;
// calc lateral offset from road lane center line to shoulder target line.
lanelet::ConstLanelet goal_closest_road_lane;
lanelet::utils::query::getClosestLanelet(road_lanes, goal_pose, &goal_closest_road_lane);
const auto closest_center_pose =
lanelet::utils::getClosestCenterPose(goal_closest_road_lane, goal_pose.position);
const double distance_from_shoulder_left_bound =
util::getDistanceToShoulderBoundary(shoulder_lanes, closest_center_pose);
const double offset_from_road_line_center =
distance_from_shoulder_left_bound + common_parameters.vehicle_width / 2 + margin;

// shift end point in shoulder lane
const auto shift_end_point = std::invoke([&]() {
const auto arc_position_goal = lanelet::utils::getArcCoordinates(shoulder_lanes, goal_pose);
const double s_start = arc_position_goal.length - after_pull_over_straight_distance;
const double s_start =
std::max(arc_position_goal.length - after_pull_over_straight_distance, 0.0);
const double s_end = s_start + std::numeric_limits<double>::epsilon();
const auto path = route_handler->getCenterLinePath(shoulder_lanes, s_start, s_end, true);
return path.points.front();
Expand All @@ -130,7 +135,7 @@ std::vector<PullOverPath> ShiftPullOver::generatePullOverPaths(
PullOverPath candidate_path;

const double pull_over_distance = path_shifter.calcLongitudinalDistFromJerk(
abs(offset_from_current_pose), lateral_jerk, pull_over_velocity);
std::abs(offset_from_road_line_center), lateral_jerk, pull_over_velocity);

// calculate straight distance before pull over
const double straight_distance = std::invoke([&]() {
Expand Down