@@ -721,27 +721,36 @@ PathWithLaneId StartPlannerModule::extractCollisionCheckSection(
721
721
722
722
const double collision_check_distance_from_end = collision_check_distances.at (planner_type);
723
723
724
- PathWithLaneId combined_path ;
724
+ PathWithLaneId full_path ;
725
725
for (const auto & partial_path : path.partial_paths ) {
726
- combined_path .points .insert (
727
- combined_path .points .end (), partial_path.points .begin (), partial_path.points .end ());
726
+ full_path .points .insert (
727
+ full_path .points .end (), partial_path.points .begin (), partial_path.points .end ());
728
728
}
729
- // calculate collision check end idx
730
- const size_t collision_check_end_idx = std::invoke ([&]() {
731
- const auto collision_check_end_pose = motion_utils::calcLongitudinalOffsetPose (
732
- combined_path.points , path.end_pose .position , collision_check_distance_from_end);
733
729
734
- if (collision_check_end_pose) {
735
- return motion_utils::findNearestIndex (
736
- combined_path.points , collision_check_end_pose->position );
737
- } else {
738
- return combined_path.points .size () - 1 ;
739
- }
740
- });
741
- // remove the point behind of collision check end pose
742
- combined_path.points .erase (
743
- combined_path.points .begin () + collision_check_end_idx + 1 , combined_path.points .end ());
744
- return combined_path;
730
+ // Find the start index for collision check section based on the shift start pose
731
+ const auto shift_start_idx =
732
+ motion_utils::findNearestIndex (full_path.points , path.start_pose .position );
733
+
734
+ // Find the end index for collision check section based on the end pose and collision check
735
+ // distance
736
+ const auto collision_check_end_idx = [&]() -> size_t {
737
+ const auto end_pose_offset = motion_utils::calcLongitudinalOffsetPose (
738
+ full_path.points , path.end_pose .position , collision_check_distance_from_end);
739
+
740
+ return end_pose_offset
741
+ ? motion_utils::findNearestIndex (full_path.points , end_pose_offset->position )
742
+ : full_path.points .size () - 1 ; // Use the last point if offset pose is not calculable
743
+ }();
744
+
745
+ // Extract the collision check section from the full path
746
+ PathWithLaneId collision_check_section;
747
+ if (shift_start_idx < collision_check_end_idx) {
748
+ collision_check_section.points .assign (
749
+ full_path.points .begin () + shift_start_idx,
750
+ full_path.points .begin () + collision_check_end_idx + 1 );
751
+ }
752
+
753
+ return collision_check_section;
745
754
}
746
755
747
756
void StartPlannerModule::updateStatusWithCurrentPath (
0 commit comments