Skip to content

Commit dbdf9a1

Browse files
fix(lane_change): check obj predicted path when filtering (#9385)
* RT1-8537 check object's predicted path when filtering Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * use ranges view in get_line_string_paths Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * check only vehicle type predicted path Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Refactor naming Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix grammatical Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> * precommit and grammar fix Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> --------- Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com>
1 parent 9553414 commit dbdf9a1

File tree

5 files changed

+62
-14
lines changed

5 files changed

+62
-14
lines changed

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp

+17
Original file line numberDiff line numberDiff line change
@@ -382,5 +382,22 @@ bool filter_target_lane_objects(
382382
const double dist_ego_to_current_lanes_center, const bool ahead_of_ego,
383383
const bool before_terminal, TargetLaneLeadingObjects & leading_objects,
384384
ExtendedPredictedObjects & trailing_objects);
385+
386+
/**
387+
* @brief Determines if the object's predicted path overlaps with the given lane polygon.
388+
*
389+
* This function checks whether any of the line string paths derived from the object's predicted
390+
* trajectories intersect or overlap with the specified polygon representing lanes.
391+
*
392+
* @param object The extended predicted object containing predicted trajectories and initial
393+
* polygon.
394+
* @param lanes_polygon A polygon representing the lanes to check for overlaps with the object's
395+
* paths.
396+
*
397+
* @return true if any of the object's predicted paths overlap with the lanes polygon, false
398+
* otherwise.
399+
*/
400+
bool object_path_overlaps_lanes(
401+
const ExtendedPredictedObject & object, const lanelet::BasicPolygon2d & lanes_polygon);
385402
} // namespace autoware::behavior_path_planner::utils::lane_change
386403
#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -988,6 +988,7 @@ lane_change::TargetObjects NormalLaneChange::get_target_objects(
988988

989989
FilteredLanesObjects NormalLaneChange::filter_objects() const
990990
{
991+
universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);
991992
auto objects = *planner_data_->dynamic_object;
992993
utils::path_safety_checker::filterObjectsByClass(
993994
objects, lane_change_parameters_->safety.target_object_types);

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

+20-14
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,8 @@
3535
#include <autoware_lanelet2_extension/utility/utilities.hpp>
3636
#include <autoware_vehicle_info_utils/vehicle_info.hpp>
3737
#include <range/v3/algorithm/any_of.hpp>
38+
#include <range/v3/range/conversion.hpp>
39+
#include <range/v3/view/transform.hpp>
3840
#include <rclcpp/rclcpp.hpp>
3941

4042
#include <geometry_msgs/msg/detail/pose__struct.hpp>
@@ -1149,11 +1151,8 @@ std::vector<LineString2d> get_line_string_paths(const ExtendedPredictedObject &
11491151
return line_string;
11501152
};
11511153

1152-
const auto paths = object.predicted_paths;
1153-
std::vector<LineString2d> line_strings;
1154-
std::transform(paths.begin(), paths.end(), std::back_inserter(line_strings), to_linestring_2d);
1155-
1156-
return line_strings;
1154+
return object.predicted_paths | ranges::views::transform(to_linestring_2d) |
1155+
ranges::to<std::vector>();
11571156
}
11581157

11591158
bool has_overtaking_turn_lane_object(
@@ -1164,10 +1163,6 @@ bool has_overtaking_turn_lane_object(
11641163
return false;
11651164
}
11661165

1167-
const auto is_path_overlap_with_target = [&](const LineString2d & path) {
1168-
return !boost::geometry::disjoint(path, common_data_ptr->lanes_polygon_ptr->target);
1169-
};
1170-
11711166
const auto is_object_overlap_with_target = [&](const auto & object) {
11721167
// to compensate for perception issue, or if object is from behind ego, and tries to overtake,
11731168
// but stop all of sudden
@@ -1176,8 +1171,7 @@ bool has_overtaking_turn_lane_object(
11761171
return true;
11771172
}
11781173

1179-
const auto paths = get_line_string_paths(object);
1180-
return std::any_of(paths.begin(), paths.end(), is_path_overlap_with_target);
1174+
return object_path_overlaps_lanes(object, common_data_ptr->lanes_polygon_ptr->target);
11811175
};
11821176

11831177
return std::any_of(
@@ -1190,6 +1184,7 @@ bool filter_target_lane_objects(
11901184
const bool before_terminal, TargetLaneLeadingObjects & leading_objects,
11911185
ExtendedPredictedObjects & trailing_objects)
11921186
{
1187+
using behavior_path_planner::utils::path_safety_checker::filter::is_vehicle;
11931188
using behavior_path_planner::utils::path_safety_checker::filter::velocity_filter;
11941189
const auto & current_lanes = common_data_ptr->lanes_ptr->current;
11951190
const auto & vehicle_width = common_data_ptr->bpp_param_ptr->vehicle_info.vehicle_width_m;
@@ -1206,9 +1201,12 @@ bool filter_target_lane_objects(
12061201
const auto is_stopped = velocity_filter(
12071202
object.initial_twist, -std::numeric_limits<double>::epsilon(), stopped_obj_vel_th);
12081203
if (is_lateral_far && before_terminal) {
1209-
const auto in_target_lanes =
1210-
!boost::geometry::disjoint(object.initial_polygon, lanes_polygon.target);
1211-
if (in_target_lanes) {
1204+
const auto overlapping_with_target_lanes =
1205+
!boost::geometry::disjoint(object.initial_polygon, lanes_polygon.target) ||
1206+
(!is_stopped && is_vehicle(object.classification) &&
1207+
object_path_overlaps_lanes(object, lanes_polygon.target));
1208+
1209+
if (overlapping_with_target_lanes) {
12121210
if (!ahead_of_ego && !is_stopped) {
12131211
trailing_objects.push_back(object);
12141212
return true;
@@ -1247,4 +1245,12 @@ bool filter_target_lane_objects(
12471245

12481246
return false;
12491247
}
1248+
1249+
bool object_path_overlaps_lanes(
1250+
const ExtendedPredictedObject & object, const lanelet::BasicPolygon2d & lanes_polygon)
1251+
{
1252+
return ranges::any_of(get_line_string_paths(object), [&](const auto & path) {
1253+
return !boost::geometry::disjoint(path, lanes_polygon);
1254+
});
1255+
}
12501256
} // namespace autoware::behavior_path_planner::utils::lane_change

planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp

+10
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,16 @@ bool is_within_circle(
7171
const geometry_msgs::msg::Point & object_pos, const geometry_msgs::msg::Point & reference_point,
7272
const double search_radius);
7373

74+
/**
75+
* @brief Checks if the object classification represents a vehicle (CAR, TRUCK, BUS, TRAILER,
76+
* MOTORCYCLE).
77+
*
78+
* @param classification The object classification to check.
79+
* @return true If the classification is a vehicle type.
80+
* @return false Otherwise.
81+
*/
82+
bool is_vehicle(const ObjectClassification & classification);
83+
7484
} // namespace autoware::behavior_path_planner::utils::path_safety_checker::filter
7585

7686
namespace autoware::behavior_path_planner::utils::path_safety_checker

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

+14
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,20 @@ bool is_within_circle(
5757
std::hypot(reference_point.x - object_pos.x, reference_point.y - object_pos.y);
5858
return dist < search_radius;
5959
}
60+
61+
bool is_vehicle(const ObjectClassification & classification)
62+
{
63+
switch (classification.label) {
64+
case ObjectClassification::CAR:
65+
case ObjectClassification::TRUCK:
66+
case ObjectClassification::BUS:
67+
case ObjectClassification::TRAILER:
68+
case ObjectClassification::MOTORCYCLE:
69+
return true;
70+
default:
71+
return false;
72+
}
73+
}
6074
} // namespace autoware::behavior_path_planner::utils::path_safety_checker::filter
6175

6276
namespace autoware::behavior_path_planner::utils::path_safety_checker

0 commit comments

Comments
 (0)