Skip to content

Commit

Permalink
fix(behavior_path_planner): minimum distance for lane change (#2413)
Browse files Browse the repository at this point in the history
Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>

Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
  • Loading branch information
zulfaqar-azmi-t4 committed Dec 12, 2022
1 parent 469d892 commit 284548c
Show file tree
Hide file tree
Showing 9 changed files with 34 additions and 15 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
backward_length_buffer_for_end_of_pull_over: 5.0
backward_length_buffer_for_end_of_pull_out: 5.0
minimum_lane_change_length: 12.0
minimum_lane_change_prepare_distance: 2.0 # [m]
minimum_pull_over_length: 16.0

drivable_area_resolution: 0.1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@ struct BehaviorPathPlannerParameters
double backward_length_buffer_for_end_of_pull_over;
double backward_length_buffer_for_end_of_pull_out;
double minimum_lane_change_length;
double minimum_lane_change_prepare_distance;

double minimum_pull_over_length;
double minimum_pull_out_length;
double drivable_area_resolution;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@ struct LaneChangeParameters
{
double lane_change_prepare_duration{2.0};
double lane_changing_duration{4.0};
double minimum_lane_change_prepare_distance{4.0};
double lane_change_finish_judge_buffer{3.0};
double minimum_lane_change_velocity{5.6};
double prediction_time_resolution{0.5};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -485,6 +485,12 @@ bool isSafeInFreeSpaceCollisionCheck(
const double front_decel, const double rear_decel, CollisionCheckDebug & debug);

bool checkPathRelativeAngle(const PathWithLaneId & path, const double angle_threshold);

double calcTotalLaneChangeDistanceWithBuffer(const BehaviorPathPlannerParameters & common_param);

double calcLaneChangeBuffer(
const BehaviorPathPlannerParameters & common_param, const int num_lane_change,
const double length_to_intersection);
} // namespace behavior_path_planner::util

#endif // BEHAVIOR_PATH_PLANNER__UTILITIES_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -205,6 +205,9 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam()
p.backward_length_buffer_for_end_of_pull_out =
declare_parameter("backward_length_buffer_for_end_of_pull_out", 5.0);
p.minimum_lane_change_length = declare_parameter("minimum_lane_change_length", 8.0);
p.minimum_lane_change_prepare_distance =
declare_parameter("minimum_lane_change_prepare_distance", 2.0);

p.minimum_pull_over_length = declare_parameter("minimum_pull_over_length", 15.0);
p.drivable_area_resolution = declare_parameter<double>("drivable_area_resolution");
p.drivable_lane_forward_length = declare_parameter<double>("drivable_lane_forward_length");
Expand Down Expand Up @@ -359,7 +362,6 @@ LaneChangeParameters BehaviorPathPlannerNode::getLaneChangeParam()
LaneChangeParameters p{};
p.lane_change_prepare_duration = dp("lane_change_prepare_duration", 2.0);
p.lane_changing_duration = dp("lane_changing_duration", 4.0);
p.minimum_lane_change_prepare_distance = dp("minimum_lane_change_prepare_distance", 4.0);
p.lane_change_finish_judge_buffer = dp("lane_change_finish_judge_buffer", 3.0);
p.minimum_lane_change_velocity = dp("minimum_lane_change_velocity", 5.6);
p.prediction_time_resolution = dp("prediction_time_resolution", 0.5);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -264,10 +264,9 @@ PathWithLaneId LaneChangeModule::getReferencePath() const
*route_handler, current_lanes, current_pose, common_parameters.backward_path_length,
common_parameters.forward_path_length, common_parameters, optional_lengths);
}
const double & buffer =
common_parameters.backward_length_buffer_for_end_of_lane; // buffer for min_lane_change_length

const double lane_change_buffer =
num_lane_change * (common_parameters.minimum_lane_change_length + buffer) + optional_lengths;
util::calcLaneChangeBuffer(common_parameters, num_lane_change, optional_lengths);

reference_path = util::setDecelerationVelocity(
*route_handler, reference_path, current_lanes, parameters_->lane_change_prepare_duration,
Expand Down Expand Up @@ -416,9 +415,7 @@ bool LaneChangeModule::isValidPath(const PathWithLaneId & path) const
bool LaneChangeModule::isNearEndOfLane() const
{
const auto & current_pose = getEgoPose();
const auto minimum_lane_change_length = planner_data_->parameters.minimum_lane_change_length;
const auto end_of_lane_buffer = planner_data_->parameters.backward_length_buffer_for_end_of_lane;
const double threshold = end_of_lane_buffer + minimum_lane_change_length;
const double threshold = util::calcTotalLaneChangeDistanceWithBuffer(planner_data_->parameters);

return std::max(0.0, util::getDistanceToEndOfLane(current_pose, status_.current_lanes)) <
threshold;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,7 @@ LaneChangePaths getLaneChangePaths(
const auto & lane_change_prepare_duration = parameter.lane_change_prepare_duration;
const auto & lane_changing_duration = parameter.lane_changing_duration;
const auto & minimum_lane_change_prepare_distance =
parameter.minimum_lane_change_prepare_distance;
common_parameter.minimum_lane_change_prepare_distance;
const auto & minimum_lane_change_length = common_parameter.minimum_lane_change_length;
const auto & minimum_lane_change_velocity = parameter.minimum_lane_change_velocity;
const auto & maximum_deceleration = parameter.maximum_deceleration;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -128,9 +128,8 @@ PathWithLaneId LaneFollowingModule::getReferencePath() const
p, optional_lengths);
}

const double buffer = p.backward_length_buffer_for_end_of_lane;
const double lane_change_buffer =
num_lane_change * (p.minimum_lane_change_length + buffer) + optional_lengths;
util::calcLaneChangeBuffer(p, num_lane_change, optional_lengths);

reference_path = util::setDecelerationVelocity(
*route_handler, reference_path, current_lanes, parameters_.lane_change_prepare_duration,
Expand Down
21 changes: 17 additions & 4 deletions planning/behavior_path_planner/src/utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2022,13 +2022,11 @@ PathWithLaneId getCenterLinePath(
const double s_backward = std::max(0., s - backward_path_length);
double s_forward = s + forward_path_length;

const double buffer =
parameter.backward_length_buffer_for_end_of_lane; // buffer for min_lane_change_length
const int num_lane_change =
std::abs(route_handler.getNumLaneToPreferredLane(lanelet_sequence.back()));
const double lane_length = lanelet::utils::getLaneletLength2d(lanelet_sequence);
const double lane_change_buffer =
std::fabs(num_lane_change * (parameter.minimum_lane_change_length + buffer) + optional_length);
calcLaneChangeBuffer(parameter, std::abs(num_lane_change), optional_length);

if (route_handler.isDeadEndLanelet(lanelet_sequence.back())) {
s_forward = std::min(s_forward, lane_length - lane_change_buffer);
Expand Down Expand Up @@ -2168,7 +2166,7 @@ PathWithLaneId setDecelerationVelocity(
const double lane_length = lanelet::utils::getLaneletLength2d(lanelet_sequence);
const auto arclength = lanelet::utils::getArcCoordinates(lanelet_sequence, point.point.pose);
const double distance_to_end =
std::max(0.0, lane_length - std::fabs(lane_change_buffer) - arclength.length);
std::max(0.0, lane_length - std::abs(lane_change_buffer) - arclength.length);
point.point.longitudinal_velocity_mps = std::min(
point.point.longitudinal_velocity_mps,
static_cast<float>(distance_to_end / lane_change_prepare_duration));
Expand Down Expand Up @@ -2776,4 +2774,19 @@ bool checkPathRelativeAngle(const PathWithLaneId & path, const double angle_thre
return true;
}

double calcTotalLaneChangeDistanceWithBuffer(const BehaviorPathPlannerParameters & common_param)
{
const double minimum_lane_change_distance =
common_param.minimum_lane_change_prepare_distance + common_param.minimum_lane_change_length;
const double end_of_lane_buffer = common_param.backward_length_buffer_for_end_of_lane;
return minimum_lane_change_distance + end_of_lane_buffer;
}

double calcLaneChangeBuffer(
const BehaviorPathPlannerParameters & common_param, const int num_lane_change,
const double length_to_intersection)
{
return num_lane_change * calcTotalLaneChangeDistanceWithBuffer(common_param) +
length_to_intersection;
}
} // namespace behavior_path_planner::util

0 comments on commit 284548c

Please sign in to comment.