Skip to content

Commit 061404b

Browse files
authored
fix(behavior_velocity_planner): fix distance for traffic light module (autowarefoundation#1455)
Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com>
1 parent 2a19f3b commit 061404b

File tree

1 file changed

+2
-0
lines changed
  • planning/behavior_velocity_planner/src/scene_module/traffic_light

1 file changed

+2
-0
lines changed

planning/behavior_velocity_planner/src/scene_module/traffic_light/scene.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -228,6 +228,8 @@ bool TrafficLightModule::modifyPathVelocity(
228228
planner_param_.stop_margin + planner_data_->vehicle_info_.max_longitudinal_offset_m,
229229
planner_data_->stop_line_extend_length, stop_line_point, stop_line_point_idx)) {
230230
RCLCPP_WARN_THROTTLE(logger_, *clock_, 5000, "Failed to calculate stop point and insert index");
231+
setSafe(true);
232+
setDistance(std::numeric_limits<double>::lowest());
231233
return false;
232234
}
233235

0 commit comments

Comments
 (0)