Skip to content

Commit e5fdea8

Browse files
maxime-clemkarishma1911
authored andcommitted
feat(dynamic_obstacle_stop): set velocity factor to ROUTE_OBSTACLE (autowarefoundation#6669)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 0741449 commit e5fdea8

File tree

1 file changed

+5
-1
lines changed

1 file changed

+5
-1
lines changed

planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -116,7 +116,11 @@ bool DynamicObstacleStopModule::modifyPathVelocity(PathWithLaneId * path, StopRe
116116
}
117117
}
118118

119-
if (current_stop_pose_) motion_utils::insertStopPoint(*current_stop_pose_, 0.0, path->points);
119+
if (current_stop_pose_) {
120+
motion_utils::insertStopPoint(*current_stop_pose_, 0.0, path->points);
121+
velocity_factor_.set(
122+
path->points, ego_data.pose, *current_stop_pose_, VelocityFactor::ROUTE_OBSTACLE);
123+
}
120124

121125
const auto total_time_us = stopwatch.toc();
122126
RCLCPP_DEBUG(

0 commit comments

Comments
 (0)