File tree 1 file changed +1
-14
lines changed
planning/behavior_velocity_out_of_lane_module/src
1 file changed +1
-14
lines changed Original file line number Diff line number Diff line change @@ -69,25 +69,12 @@ lanelet::ConstLanelets calculate_other_lanelets(
69
69
const auto lanelets_within_range = lanelet::geometry::findWithin2d (
70
70
route_handler.getLaneletMapPtr ()->laneletLayer , ego_point,
71
71
std::max (params.slow_dist_threshold , params.stop_dist_threshold ));
72
- const auto is_overlapped_by_path_lanelets = [&](const auto & l) {
73
- for (const auto & path_ll : path_lanelets) {
74
- if (
75
- boost::geometry::overlaps (
76
- path_ll.polygon2d ().basicPolygon (), l.polygon2d ().basicPolygon ()) ||
77
- boost::geometry::within (path_ll.polygon2d ().basicPolygon (), l.polygon2d ().basicPolygon ()) ||
78
- boost::geometry::within (l.polygon2d ().basicPolygon (), path_ll.polygon2d ().basicPolygon ())) {
79
- return true ;
80
- }
81
- }
82
- return false ;
83
- };
84
72
for (const auto & ll : lanelets_within_range) {
85
73
if (std::string (ll.second .attributeOr (lanelet::AttributeName::Subtype, " none" )) != " road" )
86
74
continue ;
87
75
const auto is_path_lanelet = contains_lanelet (path_lanelets, ll.second .id ());
88
76
const auto is_ignored_lanelet = contains_lanelet (ignored_lanelets, ll.second .id ());
89
- if (!is_path_lanelet && !is_ignored_lanelet && !is_overlapped_by_path_lanelets (ll.second ))
90
- other_lanelets.push_back (ll.second );
77
+ if (!is_path_lanelet && !is_ignored_lanelet) other_lanelets.push_back (ll.second );
91
78
}
92
79
return other_lanelets;
93
80
}
You can’t perform that action at this time.
0 commit comments