Skip to content

Commit 9c0877a

Browse files
authored
fix(behavior_velocity_planner): planning factor integration (#10292)
* fix: blind_spot Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix: crosswalk Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix: detection_area Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix: intersection Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix: no_drivable_lane Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix: no_stopping_area Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix: run_out Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix: stop_line Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix: traffic_light Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix: virtual_traffic_light Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix: walk_way Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> --------- Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 7686e5a commit 9c0877a

File tree

12 files changed

+32
-34
lines changed

12 files changed

+32
-34
lines changed

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -102,7 +102,7 @@ void BlindSpotModule::reactRTCApprovalByDecision(
102102

103103
const auto stop_pose = path->points.at(decision.stop_line_idx).point.pose;
104104
planning_factor_interface_->add(
105-
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
105+
path->points, planner_data_->current_odometry->pose, stop_pose,
106106
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
107107
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
108108
0.0 /*shift distance*/, "blind_spot(module is judging as UNSAFE)");
@@ -136,7 +136,7 @@ void BlindSpotModule::reactRTCApprovalByDecision(
136136

137137
const auto stop_pose = path->points.at(decision.stop_line_idx).point.pose;
138138
planning_factor_interface_->add(
139-
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
139+
path->points, planner_data_->current_odometry->pose, stop_pose,
140140
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
141141
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
142142
0.0 /*shift distance*/, "blind_spot(module is judging as SAFE and RTC is not approved)");

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -881,7 +881,7 @@ void CrosswalkModule::applySlowDown(
881881
}
882882
if (slowdown_pose)
883883
planning_factor_interface_->add(
884-
output.points, planner_data_->current_odometry->pose, *slowdown_pose, *slowdown_pose,
884+
output.points, planner_data_->current_odometry->pose, *slowdown_pose,
885885
autoware_internal_planning_msgs::msg::PlanningFactor::SLOW_DOWN,
886886
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/,
887887
safety_slow_down_speed, 0.0 /*shift distance*/, "crosswalk_safety_slowdown_for_approaching");
@@ -1365,7 +1365,7 @@ void CrosswalkModule::planStop(
13651365
insertDecelPointWithDebugInfo(stop_factor->stop_pose.position, 0.0, ego_path);
13661366
planning_factor_interface_->add(
13671367
ego_path.points, planner_data_->current_odometry->pose, stop_factor->stop_pose,
1368-
stop_factor->stop_pose, autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
1368+
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
13691369
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/,
13701370
0.0 /*velocity*/, 0.0 /*shift distance*/, "crosswalk_stop");
13711371
}

planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -181,7 +181,7 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path)
181181
// Create StopReason
182182
{
183183
planning_factor_interface_->add(
184-
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
184+
path->points, planner_data_->current_odometry->pose, stop_pose,
185185
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
186186
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
187187
0.0 /*shift distance*/, "");

planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp

+15-17
Original file line numberDiff line numberDiff line change
@@ -764,7 +764,7 @@ void reactRTCApprovalByDecisionResult(
764764
{
765765
planning_factor_interface->add(
766766
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,
768768
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
769769
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
770770
0.0 /*shift distance*/, "intersection(pure StuckStop)");
@@ -779,7 +779,6 @@ void reactRTCApprovalByDecisionResult(
779779
planning_factor_interface->add(
780780
path->points, path->points.at(closest_idx).point.pose,
781781
path->points.at(occlusion_stopline_idx).point.pose,
782-
path->points.at(occlusion_stopline_idx).point.pose,
783782
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
784783
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
785784
0.0 /*shift distance*/, "intersection(StuckStop with occlusion)");
@@ -811,7 +810,7 @@ void reactRTCApprovalByDecisionResult(
811810
{
812811
planning_factor_interface->add(
813812
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,
815814
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
816815
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
817816
0.0 /*shift distance*/, "intersection(Yield Stuck)");
@@ -841,7 +840,7 @@ void reactRTCApprovalByDecisionResult(
841840
{
842841
planning_factor_interface->add(
843842
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,
845844
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
846845
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
847846
0.0 /*shift distance*/, "intersection(CollisionStop)");
@@ -855,7 +854,7 @@ void reactRTCApprovalByDecisionResult(
855854
{
856855
planning_factor_interface->add(
857856
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,
859858
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
860859
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
861860
0.0 /*shift distance*/, "intersection(CollisionStop with occlusion)");
@@ -885,7 +884,7 @@ void reactRTCApprovalByDecisionResult(
885884
{
886885
planning_factor_interface->add(
887886
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,
889888
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
890889
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
891890
0.0 /*shift distance*/, "intersection(FirstWaitBeforeOcclusion with collision)");
@@ -907,7 +906,7 @@ void reactRTCApprovalByDecisionResult(
907906
{
908907
planning_factor_interface->add(
909908
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,
911910
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
912911
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
913912
0.0 /*shift distance*/, "intersection(FirstWaitBeforeOcclusion with occlusion)");
@@ -951,7 +950,6 @@ void reactRTCApprovalByDecisionResult(
951950
planning_factor_interface->add(
952951
path->points, path->points.at(decision_result.closest_idx).point.pose,
953952
path->points.at(occlusion_peeking_stopline).point.pose,
954-
path->points.at(occlusion_peeking_stopline).point.pose,
955953
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
956954
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
957955
0.0 /*shift distance*/, "intersection(PeekingToOcclusion)");
@@ -965,7 +963,7 @@ void reactRTCApprovalByDecisionResult(
965963
{
966964
planning_factor_interface->add(
967965
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,
969967
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
970968
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
971969
0.0 /*shift distance*/, "intersection(PeekingToOcclusion while stopping for collision)");
@@ -995,7 +993,7 @@ void reactRTCApprovalByDecisionResult(
995993
{
996994
planning_factor_interface->add(
997995
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,
999997
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
1000998
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
1001999
0.0 /*shift distance*/, "intersection(CollisionStop with occlusion)");
@@ -1013,7 +1011,7 @@ void reactRTCApprovalByDecisionResult(
10131011
{
10141012
planning_factor_interface->add(
10151013
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,
10171015
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
10181016
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
10191017
0.0 /*shift distance*/, "intersection(CollisionStop with occlusion)");
@@ -1043,7 +1041,7 @@ void reactRTCApprovalByDecisionResult(
10431041
{
10441042
planning_factor_interface->add(
10451043
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,
10471045
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
10481046
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
10491047
0.0 /*shift distance*/,
@@ -1058,7 +1056,7 @@ void reactRTCApprovalByDecisionResult(
10581056
{
10591057
planning_factor_interface->add(
10601058
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,
10621060
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
10631061
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
10641062
0.0 /*shift distance*/, "intersection(Occlusion without traffic light)");
@@ -1096,7 +1094,7 @@ void reactRTCApprovalByDecisionResult(
10961094
{
10971095
planning_factor_interface->add(
10981096
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,
11001098
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
11011099
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
11021100
0.0 /*shift distance*/, "intersection(Safe, but RTC interrupted for collision)");
@@ -1110,7 +1108,7 @@ void reactRTCApprovalByDecisionResult(
11101108
{
11111109
planning_factor_interface->add(
11121110
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,
11141112
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
11151113
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
11161114
0.0 /*shift distance*/, "intersection(Safe, but RTC interrupted for occlusion)");
@@ -1140,7 +1138,7 @@ void reactRTCApprovalByDecisionResult(
11401138
{
11411139
planning_factor_interface->add(
11421140
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,
11441142
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
11451143
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
11461144
0.0 /*shift distance*/, "intersection(FullyPrioritized, collision detected)");
@@ -1154,7 +1152,7 @@ void reactRTCApprovalByDecisionResult(
11541152
{
11551153
planning_factor_interface->add(
11561154
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,
11581156
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
11591157
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
11601158
0.0 /*shift distance*/,

planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -157,7 +157,7 @@ bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path)
157157
/* get stop point and stop factor */
158158
const auto & stop_pose = path->points.at(stopline_idx).point.pose;
159159
planning_factor_interface_->add(
160-
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
160+
path->points, planner_data_->current_odometry->pose, stop_pose,
161161
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
162162
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
163163
0.0 /*shift distance*/, "merge_from_private");

planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -167,7 +167,7 @@ void NoDrivableLaneModule::handle_approaching_state(PathWithLaneId * path)
167167
{
168168
const auto & stop_pose = op_stop_pose.value();
169169
planning_factor_interface_->add(
170-
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
170+
path->points, planner_data_->current_odometry->pose, stop_pose,
171171
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
172172
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
173173
0.0 /*shift distance*/, "");
@@ -218,7 +218,7 @@ void NoDrivableLaneModule::handle_inside_no_drivable_lane_state(PathWithLaneId *
218218
{
219219
const auto & stop_pose = autoware_utils::get_pose(path->points.at(0));
220220
planning_factor_interface_->add(
221-
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
221+
path->points, planner_data_->current_odometry->pose, stop_pose,
222222
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
223223
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
224224
0.0 /*shift distance*/, "");
@@ -259,7 +259,7 @@ void NoDrivableLaneModule::handle_stopped_state(PathWithLaneId * path)
259259
{
260260
const auto & stop_pose = ego_pos_on_path.pose;
261261
planning_factor_interface_->add(
262-
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
262+
path->points, planner_data_->current_odometry->pose, stop_pose,
263263
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
264264
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
265265
0.0 /*shift distance*/, "");

planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -145,7 +145,7 @@ bool NoStoppingAreaModule::modifyPathVelocity(PathWithLaneId * path)
145145
// Create StopReason
146146
{
147147
planning_factor_interface_->add(
148-
path->points, planner_data_->current_odometry->pose, stop_point->second, stop_point->second,
148+
path->points, planner_data_->current_odometry->pose, stop_point->second,
149149
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
150150
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
151151
0.0 /*shift distance*/, "");

planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -768,7 +768,7 @@ bool RunOutModule::insertStopPoint(
768768
planning_utils::insertVelocity(path, stop_point_with_lane_id, stop_point_velocity, insert_idx);
769769

770770
planning_factor_interface_->add(
771-
path.points, planner_data_->current_odometry->pose, stop_point.value(), stop_point.value(),
771+
path.points, planner_data_->current_odometry->pose, stop_point.value(),
772772
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
773773
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/,
774774
0.0 /*velocity*/, 0.0 /*shift_distance*/, "run_out_stop");
@@ -884,7 +884,7 @@ void RunOutModule::insertApproachingVelocity(
884884

885885
planning_factor_interface_->add(
886886
output_path.points, planner_data_->current_odometry->pose, stop_point.value(),
887-
stop_point.value(), autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
887+
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
888888
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/,
889889
0.0 /*velocity*/, 0.0 /*shift_distance*/, "run_out_approaching_velocity");
890890

planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ bool StopLineModule::modifyPathVelocity(PathWithLaneId * path)
6767
// TODO(soblin): PlanningFactorInterface use trajectory class
6868
planning_factor_interface_->add(
6969
path->points, planner_data_->current_odometry->pose,
70-
trajectory->compute(*stop_point).point.pose, trajectory->compute(*stop_point).point.pose,
70+
trajectory->compute(*stop_point).point.pose,
7171
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
7272
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
7373
0.0 /*shift distance*/, "stopline");

planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -296,7 +296,7 @@ autoware_internal_planning_msgs::msg::PathWithLaneId TrafficLightModule::insertS
296296

297297
planning_factor_interface_->add(
298298
modified_path.points, planner_data_->current_odometry->pose,
299-
target_point_with_lane_id.point.pose, target_point_with_lane_id.point.pose,
299+
target_point_with_lane_id.point.pose,
300300
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
301301
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
302302
0.0 /*shift distance*/, "traffic_light");

planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -420,7 +420,7 @@ void VirtualTrafficLightModule::insertStopVelocityAtStopLine(
420420

421421
// Set StopReason
422422
planning_factor_interface_->add(
423-
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
423+
path->points, planner_data_->current_odometry->pose, stop_pose,
424424
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
425425
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
426426
0.0 /*shift distance*/, "");
@@ -455,7 +455,7 @@ void VirtualTrafficLightModule::insertStopVelocityAtEndLine(
455455

456456
// Set StopReason
457457
planning_factor_interface_->add(
458-
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
458+
path->points, planner_data_->current_odometry->pose, stop_pose,
459459
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
460460
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
461461
0.0 /*shift distance*/, "");

planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -123,7 +123,7 @@ bool WalkwayModule::modifyPathVelocity(PathWithLaneId * path)
123123

124124
/* get stop point and stop factor */
125125
planning_factor_interface_->add(
126-
path->points, planner_data_->current_odometry->pose, stop_pose.value(), stop_pose.value(),
126+
path->points, planner_data_->current_odometry->pose, stop_pose.value(),
127127
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
128128
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/,
129129
0.0 /*velocity*/, 0.0 /*shift distance*/, "walkway_stop");

0 commit comments

Comments
 (0)