@@ -321,33 +321,39 @@ std::vector<std::pair<double, lanelet::Lanelet>> LaneDepartureChecker::getLanele
321
321
lanelet_map_ptr->laneletLayer , footprint_hull_basic_polygon, 0.0 );
322
322
}
323
323
324
- std::optional<lanelet::BasicPolygon2d > LaneDepartureChecker::getFusedLaneletPolygonForPath (
324
+ std::optional<tier4_autoware_utils::Polygon2d > LaneDepartureChecker::getFusedLaneletPolygonForPath (
325
325
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const
326
326
{
327
327
const auto lanelets_distance_pair = getLaneletsFromPath (lanelet_map_ptr, path);
328
+ auto to_polygon2d = [](const lanelet::BasicPolygon2d & poly) -> tier4_autoware_utils::Polygon2d {
329
+ tier4_autoware_utils::Polygon2d p;
330
+ auto & outer = p.outer ();
331
+
332
+ for (const auto & p : poly) {
333
+ tier4_autoware_utils::Point2d p2d (p.x (), p.y ());
334
+ outer.push_back (p2d);
335
+ }
336
+ boost::geometry::correct (p);
337
+ return p;
338
+ };
339
+
328
340
// Fuse lanelets into a single BasicPolygon2d
329
- auto fused_lanelets = [&lanelets_distance_pair ]() -> std::optional<lanelet::BasicPolygon2d > {
341
+ auto fused_lanelets = [&]() -> std::optional<tier4_autoware_utils::Polygon2d > {
330
342
if (lanelets_distance_pair.empty ()) return std::nullopt;
331
- if (lanelets_distance_pair. size () == 1 )
332
- return lanelets_distance_pair. at ( 0 ). second . polygon2d (). basicPolygon () ;
343
+ tier4_autoware_utils::MultiPolygon2d lanelet_unions;
344
+ tier4_autoware_utils::MultiPolygon2d result ;
333
345
334
- lanelet::BasicPolygon2d merged_polygon =
335
- lanelets_distance_pair.at (0 ).second .polygon2d ().basicPolygon ();
336
- for (size_t i = 1 ; i < lanelets_distance_pair.size (); ++i) {
346
+ for (size_t i = 0 ; i < lanelets_distance_pair.size (); ++i) {
337
347
const auto & route_lanelet = lanelets_distance_pair.at (i).second ;
338
- const auto & poly = route_lanelet.polygon2d ().basicPolygon ();
339
-
340
- std::vector<lanelet::BasicPolygon2d> lanelet_union_temp;
341
- boost::geometry::union_ (poly, merged_polygon, 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
+ const auto & p = route_lanelet.polygon2d ().basicPolygon ();
349
+ tier4_autoware_utils::Polygon2d poly = to_polygon2d (p);
350
+ boost::geometry::union_ (lanelet_unions, poly, result);
351
+ lanelet_unions = result;
352
+ result.clear ();
348
353
}
349
- if (merged_polygon.empty ()) return std::nullopt;
350
- return merged_polygon;
354
+
355
+ if (lanelet_unions.empty ()) return std::nullopt;
356
+ return lanelet_unions.front ();
351
357
}();
352
358
353
359
return fused_lanelets;
0 commit comments