Skip to content

Commit

Permalink
fix(avoidance): check intersection location
Browse files Browse the repository at this point in the history
Signed-off-by: satoshi-ota <[email protected]>
  • Loading branch information
satoshi-ota committed May 23, 2024
1 parent 16a1e85 commit 9d3e6a9
Showing 1 changed file with 9 additions and 3 deletions.
12 changes: 9 additions & 3 deletions planning/behavior_path_avoidance_module/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -318,14 +318,20 @@ bool isWithinCrosswalk(
bool isWithinIntersection(
const ObjectData & object, const std::shared_ptr<RouteHandler> & route_handler)
{
const std::string id = object.overhang_lanelet.attributeOr("intersection_area", "else");
if (id == "else") {
const std::string area_id = object.overhang_lanelet.attributeOr("intersection_area", "else");
if (area_id == "else") {
return false;
}

const std::string location = object.overhang_lanelet.attributeOr("location", "else");
if (location == "private") {
return false;
}

const auto object_polygon = tier4_autoware_utils::toPolygon2d(object.object);

const auto polygon = route_handler->getLaneletMapPtr()->polygonLayer.get(std::atoi(id.c_str()));
const auto polygon =
route_handler->getLaneletMapPtr()->polygonLayer.get(std::atoi(area_id.c_str()));

return boost::geometry::within(
object_polygon, utils::toPolygon2d(lanelet::utils::to2D(polygon.basicPolygon())));
Expand Down

0 comments on commit 9d3e6a9

Please sign in to comment.