@@ -553,15 +553,20 @@ bool NormalLaneChange::isNearEndOfCurrentLanes(
553
553
const auto lane_change_buffer =
554
554
utils::lane_change::calcMinimumLaneChangeLength (*lane_change_parameters_, shift_intervals);
555
555
556
- auto distance_to_end = utils::getDistanceToEndOfLane (current_pose, current_lanes);
556
+ const auto distance_to_lane_change_end = std::invoke ([&]() {
557
+ auto distance_to_end = utils::getDistanceToEndOfLane (current_pose, current_lanes);
557
558
558
- if (!target_lanes.empty () && route_handler->isInGoalRouteSection (target_lanes.back ())) {
559
- distance_to_end = std::min (
560
- distance_to_end,
561
- utils::getSignedDistance (current_pose, route_handler->getGoalPose (), current_lanes));
562
- }
559
+ if (!target_lanes.empty () && route_handler->isInGoalRouteSection (target_lanes.back ())) {
560
+ distance_to_end = std::min (
561
+ distance_to_end,
562
+ utils::getSignedDistance (current_pose, route_handler->getGoalPose (), current_lanes));
563
+ }
564
+
565
+ return std::max (0.0 , distance_to_end) - lane_change_buffer;
566
+ });
563
567
564
- return (std::max (0.0 , distance_to_end) - lane_change_buffer) < threshold;
568
+ lane_change_debug_.distance_to_end_of_current_lane = distance_to_lane_change_end;
569
+ return distance_to_lane_change_end < threshold;
565
570
}
566
571
567
572
bool NormalLaneChange::hasFinishedLaneChange () const
@@ -579,29 +584,34 @@ bool NormalLaneChange::hasFinishedLaneChange() const
579
584
}
580
585
581
586
const auto reach_lane_change_end = dist_to_lane_change_end + finish_judge_buffer < 0.0 ;
587
+
588
+ lane_change_debug_.distance_to_lane_change_finished =
589
+ dist_to_lane_change_end + finish_judge_buffer;
590
+
582
591
if (!reach_lane_change_end) {
583
592
return false ;
584
593
}
585
594
586
595
const auto arc_length = lanelet::utils::getArcCoordinates (status_.target_lanes , current_pose);
587
596
const auto reach_target_lane =
588
597
std::abs (arc_length.distance ) < lane_change_parameters_->finish_judge_lateral_threshold ;
589
- if (!reach_target_lane) {
590
- return false ;
591
- }
592
598
593
- return true ;
599
+ lane_change_debug_.distance_to_lane_change_finished = arc_length.distance ;
600
+
601
+ return reach_target_lane;
594
602
}
595
603
596
604
bool NormalLaneChange::isAbleToReturnCurrentLane () const
597
605
{
598
606
if (status_.lane_change_path .path .points .size () < 2 ) {
607
+ lane_change_debug_.is_able_to_return_to_current_lane = false ;
599
608
return false ;
600
609
}
601
610
602
611
if (!utils::isEgoWithinOriginalLane (
603
612
status_.current_lanes , getEgoPose (), planner_data_->parameters ,
604
613
lane_change_parameters_->cancel .overhang_tolerance )) {
614
+ lane_change_debug_.is_able_to_return_to_current_lane = false ;
605
615
return false ;
606
616
}
607
617
@@ -619,12 +629,15 @@ bool NormalLaneChange::isAbleToReturnCurrentLane() const
619
629
dist += calcSignedArcLength (status_.lane_change_path .path .points , idx, idx + 1 );
620
630
if (dist > estimated_travel_dist) {
621
631
const auto & estimated_pose = status_.lane_change_path .path .points .at (idx + 1 ).point .pose ;
622
- return utils::isEgoWithinOriginalLane (
632
+ auto is_ego_within_original_lane = utils::isEgoWithinOriginalLane (
623
633
status_.current_lanes , estimated_pose, planner_data_->parameters ,
624
634
lane_change_parameters_->cancel .overhang_tolerance );
635
+ lane_change_debug_.is_able_to_return_to_current_lane = is_ego_within_original_lane;
636
+ return is_ego_within_original_lane;
625
637
}
626
638
}
627
639
640
+ lane_change_debug_.is_able_to_return_to_current_lane = true ;
628
641
return true ;
629
642
}
630
643
@@ -665,17 +678,18 @@ bool NormalLaneChange::isAbleToStopSafely() const
665
678
bool NormalLaneChange::hasFinishedAbort () const
666
679
{
667
680
if (!abort_path_) {
681
+ lane_change_debug_.is_abort = true ;
668
682
return true ;
669
683
}
670
684
671
685
const auto distance_to_finish = calcSignedArcLength (
672
686
abort_path_->path .points , getEgoPosition (), abort_path_->info .shift_line .end .position );
687
+ lane_change_debug_.distance_to_abort_finished = distance_to_finish;
673
688
674
- if (distance_to_finish < 0.0 ) {
675
- return true ;
676
- }
689
+ const auto has_finished_abort = distance_to_finish < 0.0 ;
690
+ lane_change_debug_.is_abort = has_finished_abort;
677
691
678
- return false ;
692
+ return has_finished_abort ;
679
693
}
680
694
681
695
bool NormalLaneChange::isAbortState () const
@@ -692,6 +706,7 @@ bool NormalLaneChange::isAbortState() const
692
706
return false ;
693
707
}
694
708
709
+ lane_change_debug_.is_abort = true ;
695
710
return true ;
696
711
}
697
712
int NormalLaneChange::getNumToPreferredLane (const lanelet::ConstLanelet & lane) const
@@ -846,6 +861,10 @@ LaneChangeTargetObjects NormalLaneChange::getTargetObjects(
846
861
const auto target_backward_lanes = utils::lane_change::getBackwardLanelets (
847
862
route_handler, target_lanes, current_pose, backward_length);
848
863
864
+ lane_change_debug_.current_lanes = current_lanes;
865
+ lane_change_debug_.target_lanes = target_lanes;
866
+ lane_change_debug_.target_backward_lanes = target_backward_lanes;
867
+
849
868
// filter objects to get target object index
850
869
const auto target_obj_index =
851
870
filterObject (objects, current_lanes, target_lanes, target_backward_lanes);
@@ -2081,6 +2100,7 @@ bool NormalLaneChange::isVehicleStuck(
2081
2100
bool NormalLaneChange::isVehicleStuck (const lanelet::ConstLanelets & current_lanes) const
2082
2101
{
2083
2102
if (current_lanes.empty ()) {
2103
+ lane_change_debug_.is_stuck = false ;
2084
2104
return false ; // can not check
2085
2105
}
2086
2106
@@ -2100,7 +2120,10 @@ bool NormalLaneChange::isVehicleStuck(const lanelet::ConstLanelets & current_lan
2100
2120
getCommonParam ().base_link2front + DETECTION_DISTANCE_MARGIN;
2101
2121
RCLCPP_DEBUG (logger_, " max_lane_change_length: %f, max_acc: %f" , max_lane_change_length, max_acc);
2102
2122
2103
- return isVehicleStuck (current_lanes, detection_distance);
2123
+ auto is_vehicle_stuck = isVehicleStuck (current_lanes, detection_distance);
2124
+
2125
+ lane_change_debug_.is_stuck = is_vehicle_stuck;
2126
+ return is_vehicle_stuck;
2104
2127
}
2105
2128
2106
2129
void NormalLaneChange::setStopPose (const Pose & stop_pose)
0 commit comments