File tree 1 file changed +9
-5
lines changed
control/lane_departure_checker/src/lane_departure_checker_node
1 file changed +9
-5
lines changed Original file line number Diff line number Diff line change @@ -331,7 +331,6 @@ std::optional<lanelet::BasicPolygon2d> LaneDepartureChecker::getFusedLaneletPoly
331
331
if (lanelets_distance_pair.size () == 1 )
332
332
return lanelets_distance_pair.at (0 ).second .polygon2d ().basicPolygon ();
333
333
334
- std::vector<lanelet::BasicPolygon2d> lanelet_union;
335
334
lanelet::BasicPolygon2d merged_polygon =
336
335
lanelets_distance_pair.at (0 ).second .polygon2d ().basicPolygon ();
337
336
for (size_t i = 1 ; i < lanelets_distance_pair.size (); ++i) {
@@ -340,11 +339,16 @@ std::optional<lanelet::BasicPolygon2d> LaneDepartureChecker::getFusedLaneletPoly
340
339
341
340
std::vector<lanelet::BasicPolygon2d> lanelet_union_temp;
342
341
boost::geometry::union_ (poly, merged_polygon, lanelet_union_temp);
343
- merged_polygon = lanelet_union_temp.back ();
344
- lanelet_union = lanelet_union_temp;
342
+
343
+ // Update merged_polygon by accumulating all merged results
344
+ merged_polygon.clear ();
345
+ for (const auto & temp_poly : lanelet_union_temp) {
346
+ merged_polygon.insert (merged_polygon.end (), temp_poly.begin (), temp_poly.end ());
347
+ }
348
+
345
349
}
346
- if (lanelet_union .empty ()) return std::nullopt;
347
- return lanelet_union. back () ;
350
+ if (merged_polygon .empty ()) return std::nullopt;
351
+ return merged_polygon ;
348
352
}();
349
353
350
354
return fused_lanelets;
You can’t perform that action at this time.
0 commit comments