Skip to content

Commit

Permalink
fix(autoware_behavior_path_lane_change_module): fix shadowVariable (a…
Browse files Browse the repository at this point in the history
…utowarefoundation#7964)

fix:shadowVariable

Signed-off-by: kobayu858 <[email protected]>
  • Loading branch information
kobayu858 authored and zulfaqar-azmi-t4 committed Aug 1, 2024
1 parent d3a38a9 commit a20a3f0
Show file tree
Hide file tree
Showing 2 changed files with 20 additions and 20 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -1454,7 +1454,7 @@ bool NormalLaneChange::getLaneChangePaths(
RCLCPP_DEBUG(logger_, " - sampling num for lat_acc: %lu", sample_lat_acc.size());

for (const auto & lateral_acc : sample_lat_acc) {
const auto debug_print = [&](const auto & s) {
const auto debug_print_lat = [&](const auto & s) {
RCLCPP_DEBUG_STREAM(
logger_, " - " << s << " : prep_time = " << prepare_duration << ", lon_acc = "
<< sampled_longitudinal_acc << ", lat_acc = " << lateral_acc);
Expand All @@ -1476,7 +1476,7 @@ bool NormalLaneChange::getLaneChangePaths(
prepare_segment, current_velocity, terminal_lane_changing_velocity);

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

Expand All @@ -1495,7 +1495,7 @@ bool NormalLaneChange::getLaneChangePaths(
s_start + lane_changing_length + finish_judge_buffer + backward_buffer +
next_lane_change_buffer >
s_goal) {
debug_print("Reject: length of lane changing path is longer than length to goal!!");
debug_print_lat("Reject: length of lane changing path is longer than length to goal!!");
continue;
}
}
Expand All @@ -1505,7 +1505,7 @@ bool NormalLaneChange::getLaneChangePaths(
initial_lane_changing_velocity, next_lane_change_buffer);

if (target_segment.points.empty()) {
debug_print("Reject: target segment is empty!! something wrong...");
debug_print_lat("Reject: target segment is empty!! something wrong...");
continue;
}

Expand Down Expand Up @@ -1536,7 +1536,7 @@ bool NormalLaneChange::getLaneChangePaths(
lane_change_info.terminal_lane_changing_velocity = terminal_lane_changing_velocity;

if (!is_valid_start_point) {
debug_print(
debug_print_lat(
"Reject: lane changing points are not inside of the target preferred lanes or its "
"neighbors");
continue;
Expand All @@ -1550,7 +1550,7 @@ bool NormalLaneChange::getLaneChangePaths(
next_lane_change_buffer);

if (target_lane_reference_path.points.empty()) {
debug_print("Reject: target_lane_reference_path is empty!!");
debug_print_lat("Reject: target_lane_reference_path is empty!!");
continue;
}

Expand All @@ -1562,20 +1562,20 @@ bool NormalLaneChange::getLaneChangePaths(
sorted_lane_ids);

if (!candidate_path) {
debug_print("Reject: failed to generate candidate path!!");
debug_print_lat("Reject: failed to generate candidate path!!");
continue;
}

if (!hasEnoughLength(*candidate_path, current_lanes, target_lanes, direction)) {
debug_print("Reject: invalid candidate path!!");
debug_print_lat("Reject: invalid candidate path!!");
continue;
}

if (
lane_change_parameters_->regulate_on_crosswalk &&
!hasEnoughLengthToCrosswalk(*candidate_path, current_lanes)) {
if (getStopTime() < lane_change_parameters_->stop_time_threshold) {
debug_print("Reject: including crosswalk!!");
debug_print_lat("Reject: including crosswalk!!");
continue;
}
RCLCPP_INFO_THROTTLE(
Expand All @@ -1586,7 +1586,7 @@ bool NormalLaneChange::getLaneChangePaths(
lane_change_parameters_->regulate_on_intersection &&
!hasEnoughLengthToIntersection(*candidate_path, current_lanes)) {
if (getStopTime() < lane_change_parameters_->stop_time_threshold) {
debug_print("Reject: including intersection!!");
debug_print_lat("Reject: including intersection!!");
continue;
}
RCLCPP_WARN_STREAM(
Expand All @@ -1596,14 +1596,14 @@ bool NormalLaneChange::getLaneChangePaths(
if (
lane_change_parameters_->regulate_on_traffic_light &&
!hasEnoughLengthToTrafficLight(*candidate_path, current_lanes)) {
debug_print("Reject: regulate on traffic light!!");
debug_print_lat("Reject: regulate on traffic light!!");
continue;
}

if (utils::traffic_light::isStoppedAtRedTrafficLightWithinDistance(
lane_change_info.current_lanes, candidate_path.value().path, planner_data_,
lane_change_info.length.sum())) {
debug_print("Ego is stopping near traffic light. Do not allow lane change");
debug_print_lat("Ego is stopping near traffic light. Do not allow lane change");
continue;
}
candidate_paths->push_back(*candidate_path);
Expand All @@ -1613,26 +1613,26 @@ bool NormalLaneChange::getLaneChangePaths(
route_handler, *candidate_path, filtered_objects.target_lane,
lane_change_buffer, is_goal_in_route, *lane_change_parameters_,
lane_change_debug_.collision_check_objects)) {
debug_print(
debug_print_lat(
"Reject: parking vehicle exists in the target lane, and the ego is not in stuck. Skip "
"lane change.");
return false;
}

if (!check_safety) {
debug_print("ACCEPT!!!: it is valid (and safety check is skipped).");
debug_print_lat("ACCEPT!!!: it is valid (and safety check is skipped).");
return false;
}

const auto [is_safe, is_object_coming_from_rear] = isLaneChangePathSafe(
*candidate_path, target_objects, rss_params, lane_change_debug_.collision_check_objects);

if (is_safe) {
debug_print("ACCEPT!!!: it is valid and safe!");
debug_print_lat("ACCEPT!!!: it is valid and safe!");
return true;
}

debug_print("Reject: sampled path is not safe.");
debug_print_lat("Reject: sampled path is not safe.");
}
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -888,7 +888,7 @@ bool isParkedObject(
const auto most_left_lanelet_candidates =
route_handler.getLaneletMapPtr()->laneletLayer.findUsages(most_left_road_lanelet.leftBound());
lanelet::ConstLanelet most_left_lanelet = most_left_road_lanelet;
const lanelet::Attribute sub_type =
const lanelet::Attribute most_left_sub_type =
most_left_lanelet.attribute(lanelet::AttributeName::Subtype);

for (const auto & ll : most_left_lanelet_candidates) {
Expand All @@ -898,7 +898,7 @@ bool isParkedObject(
}
}
bound = most_left_lanelet.leftBound2d().basicLineString();
if (sub_type.value() != "road_shoulder") {
if (most_left_sub_type.value() != "road_shoulder") {
center_to_bound_buffer = object_check_min_road_shoulder_width;
}
} else {
Expand All @@ -909,7 +909,7 @@ bool isParkedObject(
most_right_road_lanelet.rightBound());

lanelet::ConstLanelet most_right_lanelet = most_right_road_lanelet;
const lanelet::Attribute sub_type =
const lanelet::Attribute most_right_sub_type =
most_right_lanelet.attribute(lanelet::AttributeName::Subtype);

for (const auto & ll : most_right_lanelet_candidates) {
Expand All @@ -919,7 +919,7 @@ bool isParkedObject(
}
}
bound = most_right_lanelet.rightBound2d().basicLineString();
if (sub_type.value() != "road_shoulder") {
if (most_right_sub_type.value() != "road_shoulder") {
center_to_bound_buffer = object_check_min_road_shoulder_width;
}
}
Expand Down

0 comments on commit a20a3f0

Please sign in to comment.