@@ -567,15 +567,20 @@ bool NormalLaneChange::isNearEndOfCurrentLanes(
567
567
const auto lane_change_buffer =
568
568
utils::lane_change::calcMinimumLaneChangeLength (*lane_change_parameters_, shift_intervals);
569
569
570
- auto distance_to_end = utils::getDistanceToEndOfLane (current_pose, current_lanes);
570
+ const auto distance_to_lane_change_end = std::invoke ([&]() {
571
+ auto distance_to_end = utils::getDistanceToEndOfLane (current_pose, current_lanes);
571
572
572
- if (!target_lanes.empty () && route_handler->isInGoalRouteSection (target_lanes.back ())) {
573
- distance_to_end = std::min (
574
- distance_to_end,
575
- utils::getSignedDistance (current_pose, route_handler->getGoalPose (), current_lanes));
576
- }
573
+ if (!target_lanes.empty () && route_handler->isInGoalRouteSection (target_lanes.back ())) {
574
+ distance_to_end = std::min (
575
+ distance_to_end,
576
+ utils::getSignedDistance (current_pose, route_handler->getGoalPose (), current_lanes));
577
+ }
578
+
579
+ return std::max (0.0 , distance_to_end) - lane_change_buffer;
580
+ });
577
581
578
- return (std::max (0.0 , distance_to_end) - lane_change_buffer) < threshold;
582
+ lane_change_debug_.distance_to_end_of_current_lane = distance_to_lane_change_end;
583
+ return distance_to_lane_change_end < threshold;
579
584
}
580
585
581
586
bool NormalLaneChange::hasFinishedLaneChange () const
@@ -593,29 +598,34 @@ bool NormalLaneChange::hasFinishedLaneChange() const
593
598
}
594
599
595
600
const auto reach_lane_change_end = dist_to_lane_change_end + finish_judge_buffer < 0.0 ;
601
+
602
+ lane_change_debug_.distance_to_lane_change_finished =
603
+ dist_to_lane_change_end + finish_judge_buffer;
604
+
596
605
if (!reach_lane_change_end) {
597
606
return false ;
598
607
}
599
608
600
609
const auto arc_length = lanelet::utils::getArcCoordinates (status_.target_lanes , current_pose);
601
610
const auto reach_target_lane =
602
611
std::abs (arc_length.distance ) < lane_change_parameters_->finish_judge_lateral_threshold ;
603
- if (!reach_target_lane) {
604
- return false ;
605
- }
606
612
607
- return true ;
613
+ lane_change_debug_.distance_to_lane_change_finished = arc_length.distance ;
614
+
615
+ return reach_target_lane;
608
616
}
609
617
610
618
bool NormalLaneChange::isAbleToReturnCurrentLane () const
611
619
{
612
620
if (status_.lane_change_path .path .points .size () < 2 ) {
621
+ lane_change_debug_.is_able_to_return_to_current_lane = false ;
613
622
return false ;
614
623
}
615
624
616
625
if (!utils::isEgoWithinOriginalLane (
617
626
status_.current_lanes , getEgoPose (), planner_data_->parameters ,
618
627
lane_change_parameters_->cancel .overhang_tolerance )) {
628
+ lane_change_debug_.is_able_to_return_to_current_lane = false ;
619
629
return false ;
620
630
}
621
631
@@ -633,12 +643,15 @@ bool NormalLaneChange::isAbleToReturnCurrentLane() const
633
643
dist += calcSignedArcLength (status_.lane_change_path .path .points , idx, idx + 1 );
634
644
if (dist > estimated_travel_dist) {
635
645
const auto & estimated_pose = status_.lane_change_path .path .points .at (idx + 1 ).point .pose ;
636
- return utils::isEgoWithinOriginalLane (
646
+ auto is_ego_within_original_lane = utils::isEgoWithinOriginalLane (
637
647
status_.current_lanes , estimated_pose, planner_data_->parameters ,
638
648
lane_change_parameters_->cancel .overhang_tolerance );
649
+ lane_change_debug_.is_able_to_return_to_current_lane = is_ego_within_original_lane;
650
+ return is_ego_within_original_lane;
639
651
}
640
652
}
641
653
654
+ lane_change_debug_.is_able_to_return_to_current_lane = true ;
642
655
return true ;
643
656
}
644
657
@@ -679,17 +692,18 @@ bool NormalLaneChange::isAbleToStopSafely() const
679
692
bool NormalLaneChange::hasFinishedAbort () const
680
693
{
681
694
if (!abort_path_) {
695
+ lane_change_debug_.is_abort = true ;
682
696
return true ;
683
697
}
684
698
685
699
const auto distance_to_finish = calcSignedArcLength (
686
700
abort_path_->path .points , getEgoPosition (), abort_path_->info .shift_line .end .position );
701
+ lane_change_debug_.distance_to_abort_finished = distance_to_finish;
687
702
688
- if (distance_to_finish < 0.0 ) {
689
- return true ;
690
- }
703
+ const auto has_finished_abort = distance_to_finish < 0.0 ;
704
+ lane_change_debug_.is_abort = has_finished_abort;
691
705
692
- return false ;
706
+ return has_finished_abort ;
693
707
}
694
708
695
709
bool NormalLaneChange::isAbortState () const
@@ -706,6 +720,7 @@ bool NormalLaneChange::isAbortState() const
706
720
return false ;
707
721
}
708
722
723
+ lane_change_debug_.is_abort = true ;
709
724
return true ;
710
725
}
711
726
int NormalLaneChange::getNumToPreferredLane (const lanelet::ConstLanelet & lane) const
@@ -860,6 +875,10 @@ LaneChangeTargetObjects NormalLaneChange::getTargetObjects(
860
875
const auto target_backward_lanes = behavior_path_planner::utils::getBackwardLanelets (
861
876
route_handler, target_lanes, current_pose, backward_length);
862
877
878
+ lane_change_debug_.current_lanes = current_lanes;
879
+ lane_change_debug_.target_lanes = target_lanes;
880
+ lane_change_debug_.target_backward_lanes = target_backward_lanes;
881
+
863
882
// filter objects to get target object index
864
883
const auto target_obj_index =
865
884
filterObject (objects, current_lanes, target_lanes, target_backward_lanes);
@@ -2043,6 +2062,7 @@ bool NormalLaneChange::isVehicleStuck(
2043
2062
bool NormalLaneChange::isVehicleStuck (const lanelet::ConstLanelets & current_lanes) const
2044
2063
{
2045
2064
if (current_lanes.empty ()) {
2065
+ lane_change_debug_.is_stuck = false ;
2046
2066
return false ; // can not check
2047
2067
}
2048
2068
@@ -2062,7 +2082,10 @@ bool NormalLaneChange::isVehicleStuck(const lanelet::ConstLanelets & current_lan
2062
2082
getCommonParam ().base_link2front + DETECTION_DISTANCE_MARGIN;
2063
2083
RCLCPP_DEBUG (logger_, " max_lane_change_length: %f, max_acc: %f" , max_lane_change_length, max_acc);
2064
2084
2065
- return isVehicleStuck (current_lanes, detection_distance);
2085
+ auto is_vehicle_stuck = isVehicleStuck (current_lanes, detection_distance);
2086
+
2087
+ lane_change_debug_.is_stuck = is_vehicle_stuck;
2088
+ return is_vehicle_stuck;
2066
2089
}
2067
2090
2068
2091
void NormalLaneChange::setStopPose (const Pose & stop_pose)
0 commit comments