@@ -492,7 +492,8 @@ bool isMergingToEgoLane(const ObjectData & object)
492
492
}
493
493
494
494
bool isParkedVehicle (
495
- ObjectData & object, const std::shared_ptr<RouteHandler> & route_handler,
495
+ ObjectData & object, const AvoidancePlanningData & data,
496
+ const std::shared_ptr<RouteHandler> & route_handler,
496
497
const std::shared_ptr<AvoidanceParameters> & parameters)
497
498
{
498
499
using lanelet::geometry::distance2d;
@@ -589,57 +590,36 @@ bool isParkedVehicle(
589
590
object.shiftable_ratio > parameters->object_check_shiftable_ratio ;
590
591
}
591
592
592
- return is_left_side_parked_vehicle || is_right_side_parked_vehicle;
593
- }
594
-
595
- bool isAmbiguousStoppedVehicle (
596
- ObjectData & object, const AvoidancePlanningData & data,
597
- const std::shared_ptr<const PlannerData> & planner_data,
598
- const std::shared_ptr<AvoidanceParameters> & parameters)
599
- {
600
- const auto stop_time_longer_than_threshold =
601
- object.stop_time > parameters->threshold_time_force_avoidance_for_stopped_vehicle ;
602
-
603
- if (!stop_time_longer_than_threshold) {
593
+ if (!is_left_side_parked_vehicle && !is_right_side_parked_vehicle) {
604
594
return false ;
605
595
}
606
596
607
597
const auto & object_pose = object.object .kinematics .initial_pose_with_covariance .pose ;
608
- const auto is_moving_distance_longer_than_threshold =
609
- tier4_autoware_utils::calcDistance2d (object.init_pose , object_pose) >
610
- parameters->force_avoidance_distance_threshold ;
611
-
612
- if (is_moving_distance_longer_than_threshold) {
613
- return false ;
614
- }
615
-
616
- if (object.is_within_intersection ) {
617
- RCLCPP_DEBUG (rclcpp::get_logger (__func__), " object is in the intersection area." );
618
- return false ;
619
- }
620
-
621
- const auto rh = planner_data->route_handler ;
622
-
623
- if (
624
- !!rh->getRoutingGraphPtr ()->right (object.overhang_lanelet ) &&
625
- !!rh->getRoutingGraphPtr ()->left (object.overhang_lanelet )) {
626
- RCLCPP_DEBUG (rclcpp::get_logger (__func__), " object isn't on the edge lane." );
598
+ object.to_centerline =
599
+ lanelet::utils::getArcCoordinates (data.current_lanelets , object_pose).distance ;
600
+ if (std::abs (object.to_centerline ) < parameters->threshold_distance_object_is_on_center ) {
627
601
return false ;
628
602
}
629
603
630
- if (!object.is_on_ego_lane ) {
631
- return true ;
632
- }
604
+ return true ;
605
+ }
633
606
607
+ bool isCloseToStopFactor (
608
+ ObjectData & object, const AvoidancePlanningData & data,
609
+ const std::shared_ptr<const PlannerData> & planner_data,
610
+ const std::shared_ptr<AvoidanceParameters> & parameters)
611
+ {
612
+ const auto & rh = planner_data->route_handler ;
634
613
const auto & ego_pose = planner_data->self_odometry ->pose .pose ;
614
+ const auto & object_pose = object.object .kinematics .initial_pose_with_covariance .pose ;
635
615
636
616
// force avoidance for stopped vehicle
637
- bool not_parked_object = true ;
617
+ bool is_close_to_stop_factor = false ;
638
618
639
619
// check traffic light
640
620
const auto to_traffic_light = getDistanceToNextTrafficLight (object_pose, data.extend_lanelets );
641
621
{
642
- not_parked_object =
622
+ is_close_to_stop_factor =
643
623
to_traffic_light < parameters->object_ignore_section_traffic_light_in_front_distance ;
644
624
}
645
625
@@ -651,12 +631,89 @@ bool isAmbiguousStoppedVehicle(
651
631
const auto stop_for_crosswalk =
652
632
to_crosswalk < parameters->object_ignore_section_crosswalk_in_front_distance &&
653
633
to_crosswalk > -1.0 * parameters->object_ignore_section_crosswalk_behind_distance ;
654
- not_parked_object = not_parked_object || stop_for_crosswalk;
634
+ is_close_to_stop_factor = is_close_to_stop_factor || stop_for_crosswalk;
655
635
}
656
636
657
637
object.to_stop_factor_distance = std::min (to_traffic_light, to_crosswalk);
658
638
659
- return !not_parked_object;
639
+ return is_close_to_stop_factor;
640
+ }
641
+
642
+ bool isNeverAvoidanceTarget (
643
+ ObjectData & object, const AvoidancePlanningData & data,
644
+ const std::shared_ptr<const PlannerData> & planner_data,
645
+ const std::shared_ptr<AvoidanceParameters> & parameters)
646
+ {
647
+ const auto & object_pose = object.object .kinematics .initial_pose_with_covariance .pose ;
648
+ const auto is_moving_distance_longer_than_threshold =
649
+ tier4_autoware_utils::calcDistance2d (object.init_pose , object_pose) >
650
+ parameters->distance_threshold_for_ambiguous_vehicle ;
651
+ if (is_moving_distance_longer_than_threshold) {
652
+ object.reason = AvoidanceDebugFactor::MOVING_OBJECT;
653
+ return true ;
654
+ }
655
+
656
+ if (object.is_within_intersection ) {
657
+ if (object.behavior == ObjectData::Behavior::NONE) {
658
+ object.reason = " ParallelToEgoLane" ;
659
+ RCLCPP_DEBUG (rclcpp::get_logger (__func__), " object belongs to ego lane. never avoid it." );
660
+ return true ;
661
+ }
662
+
663
+ if (object.behavior == ObjectData::Behavior::MERGING) {
664
+ object.reason = " MergingToEgoLane" ;
665
+ RCLCPP_DEBUG (rclcpp::get_logger (__func__), " object belongs to ego lane. never avoid it." );
666
+ return true ;
667
+ }
668
+ }
669
+
670
+ if (object.is_on_ego_lane ) {
671
+ if (
672
+ planner_data->route_handler ->getRightLanelet (object.overhang_lanelet ).has_value () &&
673
+ planner_data->route_handler ->getLeftLanelet (object.overhang_lanelet ).has_value ()) {
674
+ object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
675
+ RCLCPP_DEBUG (rclcpp::get_logger (__func__), " object isn't on the edge lane. never avoid it." );
676
+ return true ;
677
+ }
678
+ }
679
+
680
+ if (isCloseToStopFactor (object, data, planner_data, parameters)) {
681
+ if (object.is_on_ego_lane && !object.is_parked ) {
682
+ object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
683
+ RCLCPP_DEBUG (rclcpp::get_logger (__func__), " object is close to stop factor. never avoid it." );
684
+ return true ;
685
+ }
686
+ }
687
+
688
+ return false ;
689
+ }
690
+
691
+ bool isObviousAvoidanceTarget (
692
+ ObjectData & object, [[maybe_unused]] const AvoidancePlanningData & data,
693
+ [[maybe_unused]] const std::shared_ptr<const PlannerData> & planner_data,
694
+ [[maybe_unused]] const std::shared_ptr<AvoidanceParameters> & parameters)
695
+ {
696
+ if (!object.is_within_intersection ) {
697
+ if (object.is_parked && object.behavior == ObjectData::Behavior::NONE) {
698
+ RCLCPP_DEBUG (rclcpp::get_logger (__func__), " object is obvious parked vehicle." );
699
+ return true ;
700
+ }
701
+
702
+ if (!object.is_on_ego_lane && object.behavior == ObjectData::Behavior::NONE) {
703
+ RCLCPP_DEBUG (rclcpp::get_logger (__func__), " object is adjacent vehicle." );
704
+ return true ;
705
+ }
706
+ }
707
+
708
+ if (!object.is_parked ) {
709
+ object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
710
+ }
711
+
712
+ if (object.behavior == ObjectData::Behavior::MERGING) {
713
+ object.reason = " MergingToEgoLane" ;
714
+ }
715
+
716
+ return false ;
660
717
}
661
718
662
719
bool isSatisfiedWithCommonCondition (
@@ -759,50 +816,56 @@ bool isSatisfiedWithVehicleCondition(
759
816
{
760
817
object.behavior = getObjectBehavior (object, parameters);
761
818
object.is_on_ego_lane = isOnEgoLane (object);
762
- object.is_ambiguous = isAmbiguousStoppedVehicle (object, data, planner_data, parameters);
763
819
764
- // from here condition check for vehicle type objects.
765
- if (object.is_ambiguous && parameters->enable_force_avoidance_for_stopped_vehicle ) {
820
+ if (isNeverAvoidanceTarget (object, data, planner_data, parameters)) {
821
+ return false ;
822
+ }
823
+
824
+ if (isObviousAvoidanceTarget (object, data, planner_data, parameters)) {
766
825
return true ;
767
826
}
768
827
769
- // check vehicle shift ratio
770
- if (object.is_on_ego_lane ) {
771
- if (object.is_parked ) {
772
- return true ;
773
- } else {
774
- object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
775
- return false ;
776
- }
828
+ // from here, filtering for ambiguous vehicle.
829
+
830
+ if (!parameters->enable_avoidance_for_ambiguous_vehicle ) {
831
+ object.reason = " AmbiguousStoppedVehicle" ;
832
+ return false ;
777
833
}
778
834
779
- // Object is on center line -> ignore.
780
- const auto & object_pose = object.object .kinematics .initial_pose_with_covariance .pose ;
781
- object.to_centerline =
782
- lanelet::utils::getArcCoordinates (data.current_lanelets , object_pose).distance ;
783
- if (std::abs (object.to_centerline ) < parameters->threshold_distance_object_is_on_center ) {
784
- object.reason = AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE;
835
+ const auto stop_time_longer_than_threshold =
836
+ object.stop_time > parameters->time_threshold_for_ambiguous_vehicle ;
837
+ if (!stop_time_longer_than_threshold) {
838
+ object.reason = " AmbiguousStoppedVehicle(wait-and-see)" ;
785
839
return false ;
786
840
}
787
841
788
842
if (object.is_within_intersection ) {
789
- std::string turn_direction = object.overhang_lanelet .attributeOr (" turn_direction" , " else" );
790
- if (turn_direction == " straight" ) {
843
+ if (object.behavior == ObjectData::Behavior::DEVIATING) {
844
+ object.reason = " AmbiguousStoppedVehicle(wait-and-see)" ;
845
+ object.is_ambiguous = true ;
846
+ return true ;
847
+ }
848
+ } else {
849
+ if (object.behavior == ObjectData::Behavior::MERGING) {
850
+ object.reason = " AmbiguousStoppedVehicle(wait-and-see)" ;
851
+ object.is_ambiguous = true ;
791
852
return true ;
792
853
}
793
854
794
- if (object.behavior == ObjectData::Behavior::NONE) {
795
- object.reason = " ParallelToEgoLane" ;
796
- return false ;
855
+ if (object.behavior == ObjectData::Behavior::DEVIATING) {
856
+ object.reason = " AmbiguousStoppedVehicle(wait-and-see)" ;
857
+ object.is_ambiguous = true ;
858
+ return true ;
797
859
}
798
- }
799
860
800
- if (object.behavior == ObjectData::Behavior::MERGING) {
801
- object.reason = " MergingToEgoLane" ;
802
- return false ;
861
+ if (object.behavior == ObjectData::Behavior::NONE) {
862
+ object.is_ambiguous = false ;
863
+ return true ;
864
+ }
803
865
}
804
866
805
- return true ;
867
+ object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
868
+ return false ;
806
869
}
807
870
808
871
bool isNoNeedAvoidanceBehavior (
@@ -1729,7 +1792,8 @@ void filterTargetObjects(
1729
1792
if (filtering_utils::isVehicleTypeObject (o)) {
1730
1793
o.is_within_intersection =
1731
1794
filtering_utils::isWithinIntersection (o, planner_data->route_handler );
1732
- o.is_parked = filtering_utils::isParkedVehicle (o, planner_data->route_handler , parameters);
1795
+ o.is_parked =
1796
+ filtering_utils::isParkedVehicle (o, data, planner_data->route_handler , parameters);
1733
1797
o.avoid_margin = filtering_utils::getAvoidMargin (o, planner_data, parameters);
1734
1798
1735
1799
if (filtering_utils::isNoNeedAvoidanceBehavior (o, parameters)) {
0 commit comments