@@ -764,7 +764,7 @@ void reactRTCApprovalByDecisionResult(
764
764
{
765
765
planning_factor_interface->add (
766
766
path->points , path->points .at (closest_idx).point .pose ,
767
- path->points .at (stopline_idx).point .pose , path-> points . at (stopline_idx). point . pose ,
767
+ path->points .at (stopline_idx).point .pose ,
768
768
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
769
769
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
770
770
0.0 /* shift distance*/ , " intersection(pure StuckStop)" );
@@ -779,7 +779,6 @@ void reactRTCApprovalByDecisionResult(
779
779
planning_factor_interface->add (
780
780
path->points , path->points .at (closest_idx).point .pose ,
781
781
path->points .at (occlusion_stopline_idx).point .pose ,
782
- path->points .at (occlusion_stopline_idx).point .pose ,
783
782
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
784
783
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
785
784
0.0 /* shift distance*/ , " intersection(StuckStop with occlusion)" );
@@ -811,7 +810,7 @@ void reactRTCApprovalByDecisionResult(
811
810
{
812
811
planning_factor_interface->add (
813
812
path->points , path->points .at (closest_idx).point .pose ,
814
- path->points .at (stopline_idx).point .pose , path-> points . at (stopline_idx). point . pose ,
813
+ path->points .at (stopline_idx).point .pose ,
815
814
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
816
815
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
817
816
0.0 /* shift distance*/ , " intersection(Yield Stuck)" );
@@ -841,7 +840,7 @@ void reactRTCApprovalByDecisionResult(
841
840
{
842
841
planning_factor_interface->add (
843
842
path->points , path->points .at (decision_result.closest_idx ).point .pose ,
844
- path->points .at (stopline_idx).point .pose , path-> points . at (stopline_idx). point . pose ,
843
+ path->points .at (stopline_idx).point .pose ,
845
844
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
846
845
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
847
846
0.0 /* shift distance*/ , " intersection(CollisionStop)" );
@@ -855,7 +854,7 @@ void reactRTCApprovalByDecisionResult(
855
854
{
856
855
planning_factor_interface->add (
857
856
path->points , path->points .at (decision_result.closest_idx ).point .pose ,
858
- path->points .at (stopline_idx).point .pose , path-> points . at (stopline_idx). point . pose ,
857
+ path->points .at (stopline_idx).point .pose ,
859
858
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
860
859
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
861
860
0.0 /* shift distance*/ , " intersection(CollisionStop with occlusion)" );
@@ -885,7 +884,7 @@ void reactRTCApprovalByDecisionResult(
885
884
{
886
885
planning_factor_interface->add (
887
886
path->points , path->points .at (decision_result.closest_idx ).point .pose ,
888
- path->points .at (stopline_idx).point .pose , path-> points . at (stopline_idx). point . pose ,
887
+ path->points .at (stopline_idx).point .pose ,
889
888
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
890
889
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
891
890
0.0 /* shift distance*/ , " intersection(FirstWaitBeforeOcclusion with collision)" );
@@ -907,7 +906,7 @@ void reactRTCApprovalByDecisionResult(
907
906
{
908
907
planning_factor_interface->add (
909
908
path->points , path->points .at (decision_result.closest_idx ).point .pose ,
910
- path->points .at (stopline_idx).point .pose , path-> points . at (stopline_idx). point . pose ,
909
+ path->points .at (stopline_idx).point .pose ,
911
910
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
912
911
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
913
912
0.0 /* shift distance*/ , " intersection(FirstWaitBeforeOcclusion with occlusion)" );
@@ -951,7 +950,6 @@ void reactRTCApprovalByDecisionResult(
951
950
planning_factor_interface->add (
952
951
path->points , path->points .at (decision_result.closest_idx ).point .pose ,
953
952
path->points .at (occlusion_peeking_stopline).point .pose ,
954
- path->points .at (occlusion_peeking_stopline).point .pose ,
955
953
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
956
954
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
957
955
0.0 /* shift distance*/ , " intersection(PeekingToOcclusion)" );
@@ -965,7 +963,7 @@ void reactRTCApprovalByDecisionResult(
965
963
{
966
964
planning_factor_interface->add (
967
965
path->points , path->points .at (decision_result.closest_idx ).point .pose ,
968
- path->points .at (stopline_idx).point .pose , path-> points . at (stopline_idx). point . pose ,
966
+ path->points .at (stopline_idx).point .pose ,
969
967
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
970
968
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
971
969
0.0 /* shift distance*/ , " intersection(PeekingToOcclusion while stopping for collision)" );
@@ -995,7 +993,7 @@ void reactRTCApprovalByDecisionResult(
995
993
{
996
994
planning_factor_interface->add (
997
995
path->points , path->points .at (decision_result.closest_idx ).point .pose ,
998
- path->points .at (stopline_idx).point .pose , path-> points . at (stopline_idx). point . pose ,
996
+ path->points .at (stopline_idx).point .pose ,
999
997
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
1000
998
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
1001
999
0.0 /* shift distance*/ , " intersection(CollisionStop with occlusion)" );
@@ -1013,7 +1011,7 @@ void reactRTCApprovalByDecisionResult(
1013
1011
{
1014
1012
planning_factor_interface->add (
1015
1013
path->points , path->points .at (decision_result.closest_idx ).point .pose ,
1016
- path->points .at (stopline_idx).point .pose , path-> points . at (stopline_idx). point . pose ,
1014
+ path->points .at (stopline_idx).point .pose ,
1017
1015
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
1018
1016
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
1019
1017
0.0 /* shift distance*/ , " intersection(CollisionStop with occlusion)" );
@@ -1043,7 +1041,7 @@ void reactRTCApprovalByDecisionResult(
1043
1041
{
1044
1042
planning_factor_interface->add (
1045
1043
path->points , path->points .at (decision_result.closest_idx ).point .pose ,
1046
- path->points .at (stopline_idx).point .pose , path-> points . at (stopline_idx). point . pose ,
1044
+ path->points .at (stopline_idx).point .pose ,
1047
1045
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
1048
1046
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
1049
1047
0.0 /* shift distance*/ ,
@@ -1058,7 +1056,7 @@ void reactRTCApprovalByDecisionResult(
1058
1056
{
1059
1057
planning_factor_interface->add (
1060
1058
path->points , path->points .at (decision_result.closest_idx ).point .pose ,
1061
- path->points .at (stopline_idx).point .pose , path-> points . at (stopline_idx). point . pose ,
1059
+ path->points .at (stopline_idx).point .pose ,
1062
1060
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
1063
1061
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
1064
1062
0.0 /* shift distance*/ , " intersection(Occlusion without traffic light)" );
@@ -1096,7 +1094,7 @@ void reactRTCApprovalByDecisionResult(
1096
1094
{
1097
1095
planning_factor_interface->add (
1098
1096
path->points , path->points .at (decision_result.closest_idx ).point .pose ,
1099
- path->points .at (stopline_idx).point .pose , path-> points . at (stopline_idx). point . pose ,
1097
+ path->points .at (stopline_idx).point .pose ,
1100
1098
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
1101
1099
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
1102
1100
0.0 /* shift distance*/ , " intersection(Safe, but RTC interrupted for collision)" );
@@ -1110,7 +1108,7 @@ void reactRTCApprovalByDecisionResult(
1110
1108
{
1111
1109
planning_factor_interface->add (
1112
1110
path->points , path->points .at (decision_result.closest_idx ).point .pose ,
1113
- path->points .at (stopline_idx).point .pose , path-> points . at (stopline_idx). point . pose ,
1111
+ path->points .at (stopline_idx).point .pose ,
1114
1112
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
1115
1113
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
1116
1114
0.0 /* shift distance*/ , " intersection(Safe, but RTC interrupted for occlusion)" );
@@ -1140,7 +1138,7 @@ void reactRTCApprovalByDecisionResult(
1140
1138
{
1141
1139
planning_factor_interface->add (
1142
1140
path->points , path->points .at (decision_result.closest_idx ).point .pose ,
1143
- path->points .at (stopline_idx).point .pose , path-> points . at (stopline_idx). point . pose ,
1141
+ path->points .at (stopline_idx).point .pose ,
1144
1142
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
1145
1143
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
1146
1144
0.0 /* shift distance*/ , " intersection(FullyPrioritized, collision detected)" );
@@ -1154,7 +1152,7 @@ void reactRTCApprovalByDecisionResult(
1154
1152
{
1155
1153
planning_factor_interface->add (
1156
1154
path->points , path->points .at (decision_result.closest_idx ).point .pose ,
1157
- path->points .at (stopline_idx).point .pose , path-> points . at (stopline_idx). point . pose ,
1155
+ path->points .at (stopline_idx).point .pose ,
1158
1156
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
1159
1157
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /* is_driving_forward*/ , 0.0 ,
1160
1158
0.0 /* shift distance*/ ,
0 commit comments