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): lane change intersection stop #1480

Merged
Show file tree
Hide file tree
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 @@ -277,7 +277,9 @@ PathWithLaneId setDecelerationVelocity(

bool checkLaneIsInIntersection(
const RouteHandler & route_handler, const PathWithLaneId & ref,
const lanelet::ConstLanelets & lanelet_sequence, double & additional_length_to_add);
const lanelet::ConstLanelets & lanelet_sequence, const BehaviorPathPlannerParameters & parameters,
double & additional_length_to_add);

PathWithLaneId setDecelerationVelocity(
const PathWithLaneId & input, const double target_velocity, const Pose target_pose,
const double buffer, const double deceleration_interval);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -271,7 +271,7 @@ PathWithLaneId LaneChangeModule::getReferencePath() const

double optional_lengths{0.0};
const auto isInIntersection = util::checkLaneIsInIntersection(
*route_handler, reference_path, current_lanes, optional_lengths);
*route_handler, reference_path, current_lanes, common_parameters, optional_lengths);
if (isInIntersection) {
reference_path = util::getCenterLinePath(
*route_handler, current_lanes, current_pose, common_parameters.backward_path_length,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ PathWithLaneId LaneFollowingModule::getReferencePath() const
{
double optional_lengths{0.0};
const auto isInIntersection = util::checkLaneIsInIntersection(
*route_handler, reference_path, current_lanes, optional_lengths);
*route_handler, reference_path, current_lanes, p, optional_lengths);

if (isInIntersection) {
reference_path = util::getCenterLinePath(
Expand Down
10 changes: 5 additions & 5 deletions planning/behavior_path_planner/src/utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1684,7 +1684,8 @@ PathWithLaneId getCenterLinePath(

bool checkLaneIsInIntersection(
const RouteHandler & route_handler, const PathWithLaneId & reference_path,
const lanelet::ConstLanelets & lanelet_sequence, double & additional_length_to_add)
const lanelet::ConstLanelets & lanelet_sequence, const BehaviorPathPlannerParameters & parameter,
double & additional_length_to_add)
{
if (lanelet_sequence.size() < 2 || reference_path.points.empty()) {
return false;
Expand Down Expand Up @@ -1752,10 +1753,9 @@ bool checkLaneIsInIntersection(
const auto prohibited_arc_coordinate =
lanelet::utils::getArcCoordinates(lane_change_prohibited_lanes, end_of_route_pose);

constexpr double small_earlier_stopping_buffer = 0.2;
additional_length_to_add =
prohibited_arc_coordinate.length +
small_earlier_stopping_buffer; // additional a slight "buffer so that vehicle stop earlier"
additional_length_to_add = prohibited_arc_coordinate.length +
parameter.minimum_lane_change_length +
parameter.backward_length_buffer_for_end_of_lane;

return true;
}
Expand Down