@@ -767,22 +767,11 @@ bool StartPlannerModule::findPullOutPath(
767
767
const Pose & start_pose_candidate, const std::shared_ptr<PullOutPlannerBase> & planner,
768
768
const Pose & refined_start_pose, const Pose & goal_pose, const double collision_check_margin)
769
769
{
770
- const auto & dynamic_objects = planner_data_->dynamic_object ;
771
- const auto pull_out_lanes = start_planner_utils::getPullOutLanes (
772
- planner_data_, planner_data_->parameters .backward_path_length + parameters_->max_back_distance );
773
- const auto & vehicle_footprint = vehicle_info_.createFootprint ();
774
- // extract stop objects in pull out lane for collision check
775
- const auto stop_objects = utils::path_safety_checker::filterObjectsByVelocity (
776
- *dynamic_objects, parameters_->th_moving_object_velocity );
777
- auto [pull_out_lane_stop_objects, others] = utils::path_safety_checker::separateObjectsByLanelets (
778
- stop_objects, pull_out_lanes, utils::path_safety_checker::isPolygonOverlapLanelet);
779
- utils::path_safety_checker::filterObjectsByClass (
780
- pull_out_lane_stop_objects, parameters_->object_types_to_check_for_path_generation );
781
-
782
770
// if start_pose_candidate is far from refined_start_pose, backward driving is necessary
783
771
const bool backward_is_unnecessary =
784
772
tier4_autoware_utils::calcDistance2d (start_pose_candidate, refined_start_pose) < 0.01 ;
785
773
774
+ planner->setCollisionCheckMargin (collision_check_margin);
786
775
planner->setPlannerData (planner_data_);
787
776
const auto pull_out_path = planner->plan (start_pose_candidate, goal_pose);
788
777
@@ -791,13 +780,6 @@ bool StartPlannerModule::findPullOutPath(
791
780
return false ;
792
781
}
793
782
794
- // check collision
795
- if (utils::checkCollisionBetweenPathFootprintsAndObjects (
796
- vehicle_footprint, extractCollisionCheckSection (*pull_out_path, planner->getPlannerType ()),
797
- pull_out_lane_stop_objects, collision_check_margin)) {
798
- return false ;
799
- }
800
-
801
783
if (backward_is_unnecessary) {
802
784
updateStatusWithCurrentPath (*pull_out_path, start_pose_candidate, planner->getPlannerType ());
803
785
return true ;
@@ -808,49 +790,6 @@ bool StartPlannerModule::findPullOutPath(
808
790
return true ;
809
791
}
810
792
811
- PathWithLaneId StartPlannerModule::extractCollisionCheckSection (
812
- const PullOutPath & path, const behavior_path_planner::PlannerType & planner_type)
813
- {
814
- const std::map<PlannerType, double > collision_check_distances = {
815
- {behavior_path_planner::PlannerType::SHIFT,
816
- parameters_->shift_collision_check_distance_from_end },
817
- {behavior_path_planner::PlannerType::GEOMETRIC,
818
- parameters_->geometric_collision_check_distance_from_end }};
819
-
820
- const double collision_check_distance_from_end = collision_check_distances.at (planner_type);
821
-
822
- PathWithLaneId full_path;
823
- for (const auto & partial_path : path.partial_paths ) {
824
- full_path.points .insert (
825
- full_path.points .end (), partial_path.points .begin (), partial_path.points .end ());
826
- }
827
-
828
- // Find the start index for collision check section based on the shift start pose
829
- const auto shift_start_idx =
830
- motion_utils::findNearestIndex (full_path.points , path.start_pose .position );
831
-
832
- // Find the end index for collision check section based on the end pose and collision check
833
- // distance
834
- const auto collision_check_end_idx = [&]() -> size_t {
835
- const auto end_pose_offset = motion_utils::calcLongitudinalOffsetPose (
836
- full_path.points , path.end_pose .position , collision_check_distance_from_end);
837
-
838
- return end_pose_offset
839
- ? motion_utils::findNearestIndex (full_path.points , end_pose_offset->position )
840
- : full_path.points .size () - 1 ; // Use the last point if offset pose is not calculable
841
- }();
842
-
843
- // Extract the collision check section from the full path
844
- PathWithLaneId collision_check_section;
845
- if (shift_start_idx < collision_check_end_idx) {
846
- collision_check_section.points .assign (
847
- full_path.points .begin () + shift_start_idx,
848
- full_path.points .begin () + collision_check_end_idx + 1 );
849
- }
850
-
851
- return collision_check_section;
852
- }
853
-
854
793
void StartPlannerModule::updateStatusWithCurrentPath (
855
794
const behavior_path_planner::PullOutPath & path, const Pose & start_pose,
856
795
const behavior_path_planner::PlannerType & planner_type)
0 commit comments