@@ -628,14 +628,49 @@ bool isNeverAvoidanceTarget(
628
628
629
629
if (object.is_on_ego_lane ) {
630
630
const auto right_lane =
631
- planner_data->route_handler ->getRightLanelet (object.overhang_lanelet , true , false );
631
+ planner_data->route_handler ->getRightLanelet (object.overhang_lanelet , true , true );
632
+ if (right_lane.has_value () && isOnRight (object)) {
633
+ const lanelet::Attribute & right_lane_sub_type =
634
+ right_lane.value ().attribute (lanelet::AttributeName::Subtype);
635
+ if (right_lane_sub_type != " road_shoulder" ) {
636
+ object.info = ObjectInfo::IS_NOT_PARKING_OBJECT;
637
+ RCLCPP_DEBUG (
638
+ rclcpp::get_logger (logger_namespace), " object isn't on the edge lane. never avoid it." );
639
+ return true ;
640
+ }
641
+
642
+ const auto object_polygon = tier4_autoware_utils::toPolygon2d (object.object );
643
+ const auto is_disjoint_right_lane =
644
+ boost::geometry::disjoint (object_polygon, right_lane.value ().polygon2d ().basicPolygon ());
645
+ if (is_disjoint_right_lane) {
646
+ object.info = ObjectInfo::IS_NOT_PARKING_OBJECT;
647
+ RCLCPP_DEBUG (
648
+ rclcpp::get_logger (logger_namespace), " object isn't on the edge lane. never avoid it." );
649
+ return true ;
650
+ }
651
+ }
652
+
632
653
const auto left_lane =
633
- planner_data->route_handler ->getLeftLanelet (object.overhang_lanelet , true , false );
634
- if (right_lane.has_value () && left_lane.has_value ()) {
635
- object.info = ObjectInfo::IS_NOT_PARKING_OBJECT;
636
- RCLCPP_DEBUG (
637
- rclcpp::get_logger (logger_namespace), " object isn't on the edge lane. never avoid it." );
638
- return true ;
654
+ planner_data->route_handler ->getLeftLanelet (object.overhang_lanelet , true , true );
655
+ if (left_lane.has_value () && !isOnRight (object)) {
656
+ const lanelet::Attribute & left_lane_sub_type =
657
+ left_lane.value ().attribute (lanelet::AttributeName::Subtype);
658
+ if (left_lane_sub_type != " road_shoulder" ) {
659
+ object.info = ObjectInfo::IS_NOT_PARKING_OBJECT;
660
+ RCLCPP_DEBUG (
661
+ rclcpp::get_logger (logger_namespace), " object isn't on the edge lane. never avoid it." );
662
+ return true ;
663
+ }
664
+
665
+ const auto object_polygon = tier4_autoware_utils::toPolygon2d (object.object );
666
+ const auto is_disjoint_left_lane =
667
+ boost::geometry::disjoint (object_polygon, left_lane.value ().polygon2d ().basicPolygon ());
668
+ if (is_disjoint_left_lane) {
669
+ object.info = ObjectInfo::IS_NOT_PARKING_OBJECT;
670
+ RCLCPP_DEBUG (
671
+ rclcpp::get_logger (logger_namespace), " object isn't on the edge lane. never avoid it." );
672
+ return true ;
673
+ }
639
674
}
640
675
}
641
676
0 commit comments