Skip to content

Commit

Permalink
fix(lane_change): skip generating path if longitudinal distance diffe…
Browse files Browse the repository at this point in the history
…rence 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>
  • Loading branch information
zulfaqar-azmi-t4 authored and mbharatheesha committed Aug 16, 2024
1 parent 3dadb65 commit f5c4065
Show file tree
Hide file tree
Showing 4 changed files with 37 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,11 @@
min_longitudinal_acc: -1.0
max_longitudinal_acc: 1.0

skip_process:
longitudinal_distance_diff_threshold:
prepare: 0.5
lane_changing: 0.5

# safety check
safety_check:
allow_loose_check_for_cancel: true
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,9 @@ struct Parameters
double min_longitudinal_acc{-1.0};
double max_longitudinal_acc{1.0};

double skip_process_lon_diff_th_prepare{0.5};
double skip_process_lon_diff_th_lane_changing{1.0};

// collision check
bool enable_collision_check_for_prepare_phase_in_general_lanes{false};
bool enable_collision_check_for_prepare_phase_in_intersection{true};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -354,6 +354,13 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector<rclcpp::Param
updateParam<double>(parameters, ns + "max_longitudinal_acc", p->max_longitudinal_acc);
}

{
const std::string ns = "lane_change.skip_process.longitudinal_distance_diff_threshold.";
updateParam<double>(parameters, ns + "prepare", p->skip_process_lon_diff_th_prepare);
updateParam<double>(
parameters, ns + "lane_changing", p->skip_process_lon_diff_th_lane_changing);
}

{
const std::string ns = "lane_change.safety_check.lane_expansion.";
updateParam<double>(parameters, ns + "left_offset", p->lane_expansion_left_offset);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1417,6 +1417,13 @@ bool NormalLaneChange::getLaneChangePaths(
continue;
}

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

const auto debug_print = [&](const auto & s) {
Expand Down Expand Up @@ -1488,6 +1495,21 @@ bool NormalLaneChange::getLaneChangePaths(
lane_changing_time, sampled_longitudinal_acc, longitudinal_acc_on_lane_changing,
lane_changing_length);
};
if (!candidate_paths->empty()) {
const auto prev_prep_diff = candidate_paths->back().info.length.prepare - prepare_length;
const auto lc_length_diff =
candidate_paths->back().info.length.lane_changing - lane_changing_length;

// We only check lc_length_diff if and only if the current prepare_length is equal to the
// previous prepare_length.
if (
std::abs(prev_prep_diff) < eps &&
std::abs(lc_length_diff) <
lane_change_parameters_->skip_process_lon_diff_th_lane_changing) {
RCLCPP_DEBUG(logger_, "Skip: Change in lane changing length is less than threshold.");
continue;
}
}

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

0 comments on commit f5c4065

Please sign in to comment.