@@ -559,15 +559,20 @@ bool NormalLaneChange::isNearEndOfCurrentLanes(
559
559
const auto lane_change_buffer =
560
560
utils::lane_change::calcMinimumLaneChangeLength (*lane_change_parameters_, shift_intervals);
561
561
562
- auto distance_to_end = utils::getDistanceToEndOfLane (current_pose, current_lanes);
562
+ const auto distance_to_lane_change_end = std::invoke ([&]() {
563
+ auto distance_to_end = utils::getDistanceToEndOfLane (current_pose, current_lanes);
563
564
564
- if (!target_lanes.empty () && route_handler->isInGoalRouteSection (target_lanes.back ())) {
565
- distance_to_end = std::min (
566
- distance_to_end,
567
- utils::getSignedDistance (current_pose, route_handler->getGoalPose (), current_lanes));
568
- }
565
+ if (!target_lanes.empty () && route_handler->isInGoalRouteSection (target_lanes.back ())) {
566
+ distance_to_end = std::min (
567
+ distance_to_end,
568
+ utils::getSignedDistance (current_pose, route_handler->getGoalPose (), current_lanes));
569
+ }
570
+
571
+ return std::max (0.0 , distance_to_end) - lane_change_buffer;
572
+ });
569
573
570
- return (std::max (0.0 , distance_to_end) - lane_change_buffer) < threshold;
574
+ lane_change_debug_.distance_to_end_of_current_lane = distance_to_lane_change_end;
575
+ return distance_to_lane_change_end < threshold;
571
576
}
572
577
573
578
bool NormalLaneChange::hasFinishedLaneChange () const
@@ -585,29 +590,34 @@ bool NormalLaneChange::hasFinishedLaneChange() const
585
590
}
586
591
587
592
const auto reach_lane_change_end = dist_to_lane_change_end + finish_judge_buffer < 0.0 ;
593
+
594
+ lane_change_debug_.distance_to_lane_change_finished =
595
+ dist_to_lane_change_end + finish_judge_buffer;
596
+
588
597
if (!reach_lane_change_end) {
589
598
return false ;
590
599
}
591
600
592
601
const auto arc_length = lanelet::utils::getArcCoordinates (status_.target_lanes , current_pose);
593
602
const auto reach_target_lane =
594
603
std::abs (arc_length.distance ) < lane_change_parameters_->finish_judge_lateral_threshold ;
595
- if (!reach_target_lane) {
596
- return false ;
597
- }
598
604
599
- return true ;
605
+ lane_change_debug_.distance_to_lane_change_finished = arc_length.distance ;
606
+
607
+ return reach_target_lane;
600
608
}
601
609
602
610
bool NormalLaneChange::isAbleToReturnCurrentLane () const
603
611
{
604
612
if (status_.lane_change_path .path .points .size () < 2 ) {
613
+ lane_change_debug_.is_able_to_return_to_current_lane = false ;
605
614
return false ;
606
615
}
607
616
608
617
if (!utils::isEgoWithinOriginalLane (
609
618
status_.current_lanes , getEgoPose (), planner_data_->parameters ,
610
619
lane_change_parameters_->cancel .overhang_tolerance )) {
620
+ lane_change_debug_.is_able_to_return_to_current_lane = false ;
611
621
return false ;
612
622
}
613
623
@@ -625,12 +635,15 @@ bool NormalLaneChange::isAbleToReturnCurrentLane() const
625
635
dist += calcSignedArcLength (status_.lane_change_path .path .points , idx, idx + 1 );
626
636
if (dist > estimated_travel_dist) {
627
637
const auto & estimated_pose = status_.lane_change_path .path .points .at (idx + 1 ).point .pose ;
628
- return utils::isEgoWithinOriginalLane (
638
+ auto is_ego_within_original_lane = utils::isEgoWithinOriginalLane (
629
639
status_.current_lanes , estimated_pose, planner_data_->parameters ,
630
640
lane_change_parameters_->cancel .overhang_tolerance );
641
+ lane_change_debug_.is_able_to_return_to_current_lane = is_ego_within_original_lane;
642
+ return is_ego_within_original_lane;
631
643
}
632
644
}
633
645
646
+ lane_change_debug_.is_able_to_return_to_current_lane = true ;
634
647
return true ;
635
648
}
636
649
@@ -671,17 +684,18 @@ bool NormalLaneChange::isAbleToStopSafely() const
671
684
bool NormalLaneChange::hasFinishedAbort () const
672
685
{
673
686
if (!abort_path_) {
687
+ lane_change_debug_.is_abort = true ;
674
688
return true ;
675
689
}
676
690
677
691
const auto distance_to_finish = calcSignedArcLength (
678
692
abort_path_->path .points , getEgoPosition (), abort_path_->info .shift_line .end .position );
693
+ lane_change_debug_.distance_to_abort_finished = distance_to_finish;
679
694
680
- if (distance_to_finish < 0.0 ) {
681
- return true ;
682
- }
695
+ const auto has_finished_abort = distance_to_finish < 0.0 ;
696
+ lane_change_debug_.is_abort = has_finished_abort;
683
697
684
- return false ;
698
+ return has_finished_abort ;
685
699
}
686
700
687
701
bool NormalLaneChange::isAbortState () const
@@ -698,6 +712,7 @@ bool NormalLaneChange::isAbortState() const
698
712
return false ;
699
713
}
700
714
715
+ lane_change_debug_.is_abort = true ;
701
716
return true ;
702
717
}
703
718
int NormalLaneChange::getNumToPreferredLane (const lanelet::ConstLanelet & lane) const
@@ -852,6 +867,10 @@ LaneChangeTargetObjects NormalLaneChange::getTargetObjects(
852
867
const auto target_backward_lanes = behavior_path_planner::utils::getBackwardLanelets (
853
868
route_handler, target_lanes, current_pose, backward_length);
854
869
870
+ lane_change_debug_.current_lanes = current_lanes;
871
+ lane_change_debug_.target_lanes = target_lanes;
872
+ lane_change_debug_.target_backward_lanes = target_backward_lanes;
873
+
855
874
// filter objects to get target object index
856
875
const auto target_obj_index =
857
876
filterObject (objects, current_lanes, target_lanes, target_backward_lanes);
@@ -2035,6 +2054,7 @@ bool NormalLaneChange::isVehicleStuck(
2035
2054
bool NormalLaneChange::isVehicleStuck (const lanelet::ConstLanelets & current_lanes) const
2036
2055
{
2037
2056
if (current_lanes.empty ()) {
2057
+ lane_change_debug_.is_stuck = false ;
2038
2058
return false ; // can not check
2039
2059
}
2040
2060
@@ -2054,7 +2074,10 @@ bool NormalLaneChange::isVehicleStuck(const lanelet::ConstLanelets & current_lan
2054
2074
getCommonParam ().base_link2front + DETECTION_DISTANCE_MARGIN;
2055
2075
RCLCPP_DEBUG (logger_, " max_lane_change_length: %f, max_acc: %f" , max_lane_change_length, max_acc);
2056
2076
2057
- return isVehicleStuck (current_lanes, detection_distance);
2077
+ auto is_vehicle_stuck = isVehicleStuck (current_lanes, detection_distance);
2078
+
2079
+ lane_change_debug_.is_stuck = is_vehicle_stuck;
2080
+ return is_vehicle_stuck;
2058
2081
}
2059
2082
2060
2083
void NormalLaneChange::setStopPose (const Pose & stop_pose)
0 commit comments