Skip to content

Commit

Permalink
fix(lane_change): skip parked object filtering (autowarefoundation#4868)
Browse files Browse the repository at this point in the history
Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com>
  • Loading branch information
rej55 committed Sep 27, 2023
1 parent bacf767 commit c6fc9e2
Showing 1 changed file with 2 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -649,7 +649,6 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject(
const lanelet::ConstLanelets & target_backward_lanes) const
{
const auto current_pose = getEgoPose();
const auto current_vel = getEgoVelocity();
const auto & route_handler = *getRouteHandler();
const auto & common_parameters = planner_data_->parameters;
const auto & objects = *planner_data_->dynamic_object;
Expand All @@ -672,12 +671,6 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject(
const auto target_backward_polygon = utils::lane_change::createPolygon(
target_backward_lanes, 0.0, std::numeric_limits<double>::max());

// minimum distance to lane changing start point
const double t_prepare = common_parameters.lane_change_prepare_duration;
const double a_min = lane_change_parameters_->min_longitudinal_acc;
const double min_dist_to_lane_changing_start = std::max(
current_vel * t_prepare, current_vel * t_prepare + 0.5 * a_min * t_prepare * t_prepare);

auto filtered_objects = objects;

utils::path_safety_checker::filterObjectsByClass(
Expand Down Expand Up @@ -712,12 +705,8 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject(

// check if the object intersects with target lanes
if (target_polygon && boost::geometry::intersects(target_polygon.value(), obj_polygon)) {
// ignore static parked object that are in front of the ego vehicle in target lanes
bool is_parked_object =
utils::lane_change::isParkedObject(target_path, route_handler, extended_object, 0.0, 0.0);
if (is_parked_object && min_dist_ego_to_obj > min_dist_to_lane_changing_start) {
continue;
}
// 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;
Expand Down

0 comments on commit c6fc9e2

Please sign in to comment.