File tree 1 file changed +9
-3
lines changed
planning/behavior_path_avoidance_module/src
1 file changed +9
-3
lines changed Original file line number Diff line number Diff line change @@ -318,14 +318,20 @@ bool isWithinCrosswalk(
318
318
bool isWithinIntersection (
319
319
const ObjectData & object, const std::shared_ptr<RouteHandler> & route_handler)
320
320
{
321
- const std::string id = object.overhang_lanelet .attributeOr (" intersection_area" , " else" );
322
- if (id == " else" ) {
321
+ const std::string area_id = object.overhang_lanelet .attributeOr (" intersection_area" , " else" );
322
+ if (area_id == " else" ) {
323
+ return false ;
324
+ }
325
+
326
+ const std::string location = object.overhang_lanelet .attributeOr (" location" , " else" );
327
+ if (location == " private" ) {
323
328
return false ;
324
329
}
325
330
326
331
const auto object_polygon = tier4_autoware_utils::toPolygon2d (object.object );
327
332
328
- const auto polygon = route_handler->getLaneletMapPtr ()->polygonLayer .get (std::atoi (id.c_str ()));
333
+ const auto polygon =
334
+ route_handler->getLaneletMapPtr ()->polygonLayer .get (std::atoi (area_id.c_str ()));
329
335
330
336
return boost::geometry::within (
331
337
object_polygon, utils::toPolygon2d (lanelet::utils::to2D (polygon.basicPolygon ())));
You can’t perform that action at this time.
0 commit comments