@@ -318,25 +318,55 @@ 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 ())));
332
338
}
333
339
334
- bool isOnEgoLane (const ObjectData & object)
340
+ bool isOnEgoLane (const ObjectData & object, const std::shared_ptr<RouteHandler> & route_handler )
335
341
{
336
342
const auto & object_pos = object.object .kinematics .initial_pose_with_covariance .pose .position ;
337
- return boost::geometry::within (
338
- lanelet::utils::to2D (lanelet::utils::conversion::toLaneletPoint (object_pos)).basicPoint (),
339
- object.overhang_lanelet .polygon2d ().basicPolygon ());
343
+ if (boost::geometry::within (
344
+ lanelet::utils::to2D (lanelet::utils::conversion::toLaneletPoint (object_pos)).basicPoint (),
345
+ object.overhang_lanelet .polygon2d ().basicPolygon ())) {
346
+ return true ;
347
+ }
348
+
349
+ // push previous lanelet
350
+ lanelet::ConstLanelets prev_lanelet;
351
+ if (route_handler->getPreviousLaneletsWithinRoute (object.overhang_lanelet , &prev_lanelet)) {
352
+ if (boost::geometry::within (
353
+ lanelet::utils::to2D (lanelet::utils::conversion::toLaneletPoint (object_pos)).basicPoint (),
354
+ prev_lanelet.front ().polygon2d ().basicPolygon ())) {
355
+ return true ;
356
+ }
357
+ }
358
+
359
+ // push next lanelet
360
+ lanelet::ConstLanelet next_lanelet;
361
+ if (route_handler->getNextLaneletWithinRoute (object.overhang_lanelet , &next_lanelet)) {
362
+ if (boost::geometry::within (
363
+ lanelet::utils::to2D (lanelet::utils::conversion::toLaneletPoint (object_pos)).basicPoint (),
364
+ next_lanelet.polygon2d ().basicPolygon ())) {
365
+ return true ;
366
+ }
367
+ }
368
+
369
+ return false ;
340
370
}
341
371
342
372
bool isParallelToEgoLane (const ObjectData & object, const double threshold)
@@ -604,14 +634,49 @@ bool isNeverAvoidanceTarget(
604
634
605
635
if (object.is_on_ego_lane ) {
606
636
const auto right_lane =
607
- planner_data->route_handler ->getRightLanelet (object.overhang_lanelet , true , false );
637
+ planner_data->route_handler ->getRightLanelet (object.overhang_lanelet , true , true );
638
+ if (right_lane.has_value () && isOnRight (object)) {
639
+ const lanelet::Attribute & right_lane_sub_type =
640
+ right_lane.value ().attribute (lanelet::AttributeName::Subtype);
641
+ if (right_lane_sub_type != " road_shoulder" ) {
642
+ object.info = ObjectInfo::IS_NOT_PARKING_OBJECT;
643
+ RCLCPP_DEBUG (
644
+ rclcpp::get_logger (logger_namespace), " object isn't on the edge lane. never avoid it." );
645
+ return true ;
646
+ }
647
+
648
+ const auto object_polygon = tier4_autoware_utils::toPolygon2d (object.object );
649
+ const auto is_disjoint_right_lane =
650
+ boost::geometry::disjoint (object_polygon, right_lane.value ().polygon2d ().basicPolygon ());
651
+ if (is_disjoint_right_lane) {
652
+ object.info = ObjectInfo::IS_NOT_PARKING_OBJECT;
653
+ RCLCPP_DEBUG (
654
+ rclcpp::get_logger (logger_namespace), " object isn't on the edge lane. never avoid it." );
655
+ return true ;
656
+ }
657
+ }
658
+
608
659
const auto left_lane =
609
- planner_data->route_handler ->getLeftLanelet (object.overhang_lanelet , true , false );
610
- if (right_lane.has_value () && left_lane.has_value ()) {
611
- object.info = ObjectInfo::IS_NOT_PARKING_OBJECT;
612
- RCLCPP_DEBUG (
613
- rclcpp::get_logger (logger_namespace), " object isn't on the edge lane. never avoid it." );
614
- return true ;
660
+ planner_data->route_handler ->getLeftLanelet (object.overhang_lanelet , true , true );
661
+ if (left_lane.has_value () && !isOnRight (object)) {
662
+ const lanelet::Attribute & left_lane_sub_type =
663
+ left_lane.value ().attribute (lanelet::AttributeName::Subtype);
664
+ if (left_lane_sub_type != " road_shoulder" ) {
665
+ object.info = ObjectInfo::IS_NOT_PARKING_OBJECT;
666
+ RCLCPP_DEBUG (
667
+ rclcpp::get_logger (logger_namespace), " object isn't on the edge lane. never avoid it." );
668
+ return true ;
669
+ }
670
+
671
+ const auto object_polygon = tier4_autoware_utils::toPolygon2d (object.object );
672
+ const auto is_disjoint_left_lane =
673
+ boost::geometry::disjoint (object_polygon, left_lane.value ().polygon2d ().basicPolygon ());
674
+ if (is_disjoint_left_lane) {
675
+ object.info = ObjectInfo::IS_NOT_PARKING_OBJECT;
676
+ RCLCPP_DEBUG (
677
+ rclcpp::get_logger (logger_namespace), " object isn't on the edge lane. never avoid it." );
678
+ return true ;
679
+ }
615
680
}
616
681
}
617
682
@@ -754,7 +819,7 @@ bool isSatisfiedWithVehicleCondition(
754
819
const std::shared_ptr<AvoidanceParameters> & parameters)
755
820
{
756
821
object.behavior = getObjectBehavior (object, parameters);
757
- object.is_on_ego_lane = isOnEgoLane (object);
822
+ object.is_on_ego_lane = isOnEgoLane (object, planner_data-> route_handler );
758
823
759
824
if (isNeverAvoidanceTarget (object, data, planner_data, parameters)) {
760
825
return false ;
0 commit comments