Skip to content

Commit 9fee884

Browse files
fix(lane_departure_checker): empty lanelet polygon (autowarefoundation#6588)
* fix union sometimes returning empty polygon Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * fix union of polygons Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * fix back launcher Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> --------- Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com>
1 parent ecdc576 commit 9fee884

File tree

3 files changed

+27
-21
lines changed

3 files changed

+27
-21
lines changed

control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -121,7 +121,7 @@ class LaneDepartureChecker
121121
std::vector<std::pair<double, lanelet::Lanelet>> getLaneletsFromPath(
122122
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const;
123123

124-
std::optional<lanelet::BasicPolygon2d> getFusedLaneletPolygonForPath(
124+
std::optional<tier4_autoware_utils::Polygon2d> getFusedLaneletPolygonForPath(
125125
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const;
126126

127127
bool checkPathWillLeaveLane(

control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp

+25-19
Original file line numberDiff line numberDiff line change
@@ -321,33 +321,39 @@ std::vector<std::pair<double, lanelet::Lanelet>> LaneDepartureChecker::getLanele
321321
lanelet_map_ptr->laneletLayer, footprint_hull_basic_polygon, 0.0);
322322
}
323323

324-
std::optional<lanelet::BasicPolygon2d> LaneDepartureChecker::getFusedLaneletPolygonForPath(
324+
std::optional<tier4_autoware_utils::Polygon2d> LaneDepartureChecker::getFusedLaneletPolygonForPath(
325325
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const
326326
{
327327
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+
328340
// 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> {
330342
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;
333345

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) {
337347
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();
348353
}
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();
351357
}();
352358

353359
return fused_lanelets;

planning/behavior_path_start_planner_module/src/shift_pull_out.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -115,7 +115,7 @@ std::optional<PullOutPath> ShiftPullOut::plan(const Pose & start_pose, const Pos
115115

116116
const auto cropped_path = lane_departure_checker_->cropPointsOutsideOfLanes(
117117
lanelet_map_ptr, shift_path, start_segment_idx);
118-
118+
if (cropped_path.points.empty()) continue;
119119
shift_path.points = cropped_path.points;
120120
shift_path.header = planner_data_->route_handler->getRouteHeader();
121121

0 commit comments

Comments
 (0)