Skip to content

Commit b830618

Browse files
fix(lane_change): skip generating path if longitudinal distance difference is less than threshold (autowarefoundation#8363)
* fix when prepare length is insufficient Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * add reason for comparing prev_prep_diff with eps for lc_length_diff Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> --------- Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent 2e4164c commit b830618

File tree

4 files changed

+37
-0
lines changed

4 files changed

+37
-0
lines changed

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml

+5
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,11 @@
2626
min_longitudinal_acc: -1.0
2727
max_longitudinal_acc: 1.0
2828

29+
skip_process:
30+
longitudinal_distance_diff_threshold:
31+
prepare: 0.5
32+
lane_changing: 0.5
33+
2934
# safety check
3035
safety_check:
3136
allow_loose_check_for_cancel: true

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -124,6 +124,9 @@ struct Parameters
124124
double min_longitudinal_acc{-1.0};
125125
double max_longitudinal_acc{1.0};
126126

127+
double skip_process_lon_diff_th_prepare{0.5};
128+
double skip_process_lon_diff_th_lane_changing{1.0};
129+
127130
// collision check
128131
bool enable_collision_check_for_prepare_phase_in_general_lanes{false};
129132
bool enable_collision_check_for_prepare_phase_in_intersection{true};

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp

+7
Original file line numberDiff line numberDiff line change
@@ -354,6 +354,13 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector<rclcpp::Param
354354
updateParam<double>(parameters, ns + "max_longitudinal_acc", p->max_longitudinal_acc);
355355
}
356356

357+
{
358+
const std::string ns = "lane_change.skip_process.longitudinal_distance_diff_threshold.";
359+
updateParam<double>(parameters, ns + "prepare", p->skip_process_lon_diff_th_prepare);
360+
updateParam<double>(
361+
parameters, ns + "lane_changing", p->skip_process_lon_diff_th_lane_changing);
362+
}
363+
357364
{
358365
const std::string ns = "lane_change.safety_check.lane_expansion.";
359366
updateParam<double>(parameters, ns + "left_offset", p->lane_expansion_left_offset);

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

+22
Original file line numberDiff line numberDiff line change
@@ -1417,6 +1417,13 @@ bool NormalLaneChange::getLaneChangePaths(
14171417
continue;
14181418
}
14191419

1420+
if (!candidate_paths->empty()) {
1421+
const auto prev_prep_diff = candidate_paths->back().info.length.prepare - prepare_length;
1422+
if (std::abs(prev_prep_diff) < lane_change_parameters_->skip_process_lon_diff_th_prepare) {
1423+
RCLCPP_DEBUG(logger_, "Skip: Change in prepare length is less than threshold.");
1424+
continue;
1425+
}
1426+
}
14201427
auto prepare_segment = getPrepareSegment(current_lanes, backward_path_length, prepare_length);
14211428

14221429
const auto debug_print = [&](const auto & s) {
@@ -1488,6 +1495,21 @@ bool NormalLaneChange::getLaneChangePaths(
14881495
lane_changing_time, sampled_longitudinal_acc, longitudinal_acc_on_lane_changing,
14891496
lane_changing_length);
14901497
};
1498+
if (!candidate_paths->empty()) {
1499+
const auto prev_prep_diff = candidate_paths->back().info.length.prepare - prepare_length;
1500+
const auto lc_length_diff =
1501+
candidate_paths->back().info.length.lane_changing - lane_changing_length;
1502+
1503+
// We only check lc_length_diff if and only if the current prepare_length is equal to the
1504+
// previous prepare_length.
1505+
if (
1506+
std::abs(prev_prep_diff) < eps &&
1507+
std::abs(lc_length_diff) <
1508+
lane_change_parameters_->skip_process_lon_diff_th_lane_changing) {
1509+
RCLCPP_DEBUG(logger_, "Skip: Change in lane changing length is less than threshold.");
1510+
continue;
1511+
}
1512+
}
14911513

14921514
if (lane_changing_length + prepare_length > dist_to_end_of_current_lanes) {
14931515
debug_print_lat("Reject: length of lane changing path is longer than length to goal!!");

0 commit comments

Comments
 (0)