35
35
#include < autoware_lanelet2_extension/utility/utilities.hpp>
36
36
#include < autoware_vehicle_info_utils/vehicle_info.hpp>
37
37
#include < range/v3/algorithm/any_of.hpp>
38
+ #include < range/v3/range/conversion.hpp>
39
+ #include < range/v3/view/transform.hpp>
38
40
#include < rclcpp/rclcpp.hpp>
39
41
40
42
#include < geometry_msgs/msg/detail/pose__struct.hpp>
@@ -1149,11 +1151,8 @@ std::vector<LineString2d> get_line_string_paths(const ExtendedPredictedObject &
1149
1151
return line_string;
1150
1152
};
1151
1153
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>();
1157
1156
}
1158
1157
1159
1158
bool has_overtaking_turn_lane_object (
@@ -1164,10 +1163,6 @@ bool has_overtaking_turn_lane_object(
1164
1163
return false ;
1165
1164
}
1166
1165
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
-
1171
1166
const auto is_object_overlap_with_target = [&](const auto & object) {
1172
1167
// to compensate for perception issue, or if object is from behind ego, and tries to overtake,
1173
1168
// but stop all of sudden
@@ -1176,8 +1171,7 @@ bool has_overtaking_turn_lane_object(
1176
1171
return true ;
1177
1172
}
1178
1173
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 );
1181
1175
};
1182
1176
1183
1177
return std::any_of (
@@ -1190,6 +1184,7 @@ bool filter_target_lane_objects(
1190
1184
const bool before_terminal, TargetLaneLeadingObjects & leading_objects,
1191
1185
ExtendedPredictedObjects & trailing_objects)
1192
1186
{
1187
+ using behavior_path_planner::utils::path_safety_checker::filter::is_vehicle;
1193
1188
using behavior_path_planner::utils::path_safety_checker::filter::velocity_filter;
1194
1189
const auto & current_lanes = common_data_ptr->lanes_ptr ->current ;
1195
1190
const auto & vehicle_width = common_data_ptr->bpp_param_ptr ->vehicle_info .vehicle_width_m ;
@@ -1206,9 +1201,12 @@ bool filter_target_lane_objects(
1206
1201
const auto is_stopped = velocity_filter (
1207
1202
object.initial_twist , -std::numeric_limits<double >::epsilon (), stopped_obj_vel_th);
1208
1203
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) {
1212
1210
if (!ahead_of_ego && !is_stopped) {
1213
1211
trailing_objects.push_back (object);
1214
1212
return true ;
@@ -1247,4 +1245,12 @@ bool filter_target_lane_objects(
1247
1245
1248
1246
return false ;
1249
1247
}
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
+ }
1250
1256
} // namespace autoware::behavior_path_planner::utils::lane_change
0 commit comments