Skip to content

Commit

Permalink
fix(lane_change): fix target object filter
Browse files Browse the repository at this point in the history
Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
  • Loading branch information
zulfaqar-azmi-t4 committed Sep 11, 2023
1 parent a25cbe0 commit a87d526
Showing 1 changed file with 10 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -694,6 +694,12 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject(
min_dist_ego_to_obj = std::min(dist_ego_to_obj, min_dist_ego_to_obj);
}

const auto is_lateral_far = [&]() {
const auto lateral = tier4_autoware_utils::calcLateralDeviation(
current_pose, object.kinematics.initial_pose_with_covariance.pose.position);
return std::abs(lateral) > common_parameters.vehicle_width;
};

// ignore static object that are behind the ego vehicle
if (obj_velocity_norm < 1.0 && max_dist_ego_to_obj < 0.0) {
continue;
Expand All @@ -704,8 +710,10 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject(
// TODO(watanabe): ignore static parked object that are in front of the ego vehicle in target
// lanes

filtered_obj_indices.target_lane.push_back(i);
continue;
if (is_lateral_far()) {
filtered_obj_indices.target_lane.push_back(i);
continue;
}
}

// check if the object intersects with target backward lanes
Expand Down

0 comments on commit a87d526

Please sign in to comment.