Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(lane_change): check obj predicted path when filtering #9385

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -382,5 +382,22 @@ bool filter_target_lane_objects(
const double dist_ego_to_current_lanes_center, const bool ahead_of_ego,
const bool before_terminal, TargetLaneLeadingObjects & leading_objects,
ExtendedPredictedObjects & trailing_objects);

/**
* @brief Determines if the object's predicted path overlaps with the given lane polygon.
*
* This function checks whether any of the line string paths derived from the object's predicted
* trajectories intersect or overlap with the specified polygon representing lanes.
*
* @param object The extended predicted object containing predicted trajectories and initial
* polygon.
* @param lanes_polygon A polygon representing the lanes to check for overlaps with the object's
* paths.
*
* @return true if any of the object's predicted paths overlap with the lanes polygon, false
* otherwise.
*/
bool object_path_overlaps_lanes(
const ExtendedPredictedObject & object, const lanelet::BasicPolygon2d & lanes_polygon);
} // namespace autoware::behavior_path_planner::utils::lane_change
#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

Check notice on line 1 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1610 to 1611, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -988,6 +988,7 @@

FilteredLanesObjects NormalLaneChange::filter_objects() const
{
universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);
auto objects = *planner_data_->dynamic_object;
utils::path_safety_checker::filterObjectsByClass(
objects, lane_change_parameters_->safety.target_object_types);
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Overall Code Complexity

The mean cyclomatic complexity decreases from 4.90 to 4.88, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -35,6 +35,8 @@
#include <autoware_lanelet2_extension/utility/utilities.hpp>
#include <autoware_vehicle_info_utils/vehicle_info.hpp>
#include <range/v3/algorithm/any_of.hpp>
#include <range/v3/range/conversion.hpp>
#include <range/v3/view/transform.hpp>
#include <rclcpp/rclcpp.hpp>

#include <geometry_msgs/msg/detail/pose__struct.hpp>
Expand Down Expand Up @@ -1149,11 +1151,8 @@
return line_string;
};

const auto paths = object.predicted_paths;
std::vector<LineString2d> line_strings;
std::transform(paths.begin(), paths.end(), std::back_inserter(line_strings), to_linestring_2d);

return line_strings;
return object.predicted_paths | ranges::views::transform(to_linestring_2d) |
ranges::to<std::vector>();

Check warning on line 1155 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp#L1154-L1155

Added lines #L1154 - L1155 were not covered by tests
}

bool has_overtaking_turn_lane_object(
Expand All @@ -1164,10 +1163,6 @@
return false;
}

const auto is_path_overlap_with_target = [&](const LineString2d & path) {
return !boost::geometry::disjoint(path, common_data_ptr->lanes_polygon_ptr->target);
};

const auto is_object_overlap_with_target = [&](const auto & object) {
// to compensate for perception issue, or if object is from behind ego, and tries to overtake,
// but stop all of sudden
Expand All @@ -1176,8 +1171,7 @@
return true;
}

const auto paths = get_line_string_paths(object);
return std::any_of(paths.begin(), paths.end(), is_path_overlap_with_target);
return object_path_overlaps_lanes(object, common_data_ptr->lanes_polygon_ptr->target);

Check warning on line 1174 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp#L1174

Added line #L1174 was not covered by tests
};

return std::any_of(
Expand All @@ -1190,25 +1184,29 @@
const bool before_terminal, TargetLaneLeadingObjects & leading_objects,
ExtendedPredictedObjects & trailing_objects)
{
using behavior_path_planner::utils::path_safety_checker::filter::is_vehicle;
using behavior_path_planner::utils::path_safety_checker::filter::velocity_filter;
const auto & current_lanes = common_data_ptr->lanes_ptr->current;
const auto & vehicle_width = common_data_ptr->bpp_param_ptr->vehicle_info.vehicle_width_m;
const auto & lanes_polygon = *common_data_ptr->lanes_polygon_ptr;
const auto stopped_obj_vel_th = common_data_ptr->lc_param_ptr->safety.th_stopped_object_velocity;

const auto is_lateral_far = std::invoke([&]() -> bool {
const auto dist_object_to_current_lanes_center =
lanelet::utils::getLateralDistanceToClosestLanelet(current_lanes, object.initial_pose);
const auto lateral = dist_object_to_current_lanes_center - dist_ego_to_current_lanes_center;
return std::abs(lateral) > (vehicle_width / 2);
});

const auto is_stopped = velocity_filter(
object.initial_twist, -std::numeric_limits<double>::epsilon(), stopped_obj_vel_th);
if (is_lateral_far && before_terminal) {
const auto in_target_lanes =
!boost::geometry::disjoint(object.initial_polygon, lanes_polygon.target);
if (in_target_lanes) {
const auto overlapping_with_target_lanes =
!boost::geometry::disjoint(object.initial_polygon, lanes_polygon.target) ||
(!is_stopped && is_vehicle(object.classification) &&
object_path_overlaps_lanes(object, lanes_polygon.target));

Check warning on line 1207 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp#L1207

Added line #L1207 was not covered by tests

if (overlapping_with_target_lanes) {

Check warning on line 1209 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

filter_target_lane_objects increases in cyclomatic complexity from 13 to 16, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
if (!ahead_of_ego && !is_stopped) {
trailing_objects.push_back(object);
return true;
Expand Down Expand Up @@ -1247,4 +1245,12 @@

return false;
}

bool object_path_overlaps_lanes(

Check warning on line 1249 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp#L1249

Added line #L1249 was not covered by tests
const ExtendedPredictedObject & object, const lanelet::BasicPolygon2d & lanes_polygon)
{
return ranges::any_of(get_line_string_paths(object), [&](const auto & path) {

Check warning on line 1252 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp#L1252

Added line #L1252 was not covered by tests
return !boost::geometry::disjoint(path, lanes_polygon);
});

Check warning on line 1254 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp#L1254

Added line #L1254 was not covered by tests
}
} // namespace autoware::behavior_path_planner::utils::lane_change
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,16 @@ bool is_within_circle(
const geometry_msgs::msg::Point & object_pos, const geometry_msgs::msg::Point & reference_point,
const double search_radius);

/**
* @brief Checks if the object classification represents a vehicle (CAR, TRUCK, BUS, TRAILER,
* MOTORCYCLE).
*
* @param classification The object classification to check.
* @return true If the classification is a vehicle type.
* @return false Otherwise.
*/
bool is_vehicle(const ObjectClassification & classification);

} // namespace autoware::behavior_path_planner::utils::path_safety_checker::filter

namespace autoware::behavior_path_planner::utils::path_safety_checker
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

Check notice on line 1 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Primitive Obsession

The ratio of primitive types in function arguments decreases from 31.43% to 30.99%, threshold = 30.0%. The functions in this file have too many primitive types (e.g. int, double, float) in their function argument lists. Using many primitive types lead to the code smell Primitive Obsession. Avoid adding more primitive arguments.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -57,6 +57,20 @@
std::hypot(reference_point.x - object_pos.x, reference_point.y - object_pos.y);
return dist < search_radius;
}

bool is_vehicle(const ObjectClassification & classification)

Check warning on line 61 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp#L61

Added line #L61 was not covered by tests
{
switch (classification.label) {
case ObjectClassification::CAR:
case ObjectClassification::TRUCK:
case ObjectClassification::BUS:
case ObjectClassification::TRAILER:
case ObjectClassification::MOTORCYCLE:
return true;
default:
return false;

Check warning on line 71 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp#L70-L71

Added lines #L70 - L71 were not covered by tests
}
}
} // namespace autoware::behavior_path_planner::utils::path_safety_checker::filter

namespace autoware::behavior_path_planner::utils::path_safety_checker
Expand Down
Loading