We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent c831fcf commit e81a61cCopy full SHA for e81a61c
planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp
@@ -813,7 +813,9 @@ void CrosswalkModule::applySafetySlowDownSpeed(
813
const auto & p_safety_slow =
814
calcLongitudinalOffsetPoint(ego_path.points, ego_pos, safety_slow_point_range);
815
816
- insertDecelPointWithDebugInfo(p_safety_slow.value(), safety_slow_down_speed, output);
+ if (p_safety_slow.has_value()) {
817
+ insertDecelPointWithDebugInfo(p_safety_slow.value(), safety_slow_down_speed, output);
818
+ }
819
820
if (safety_slow_point_range < 0.0) {
821
passed_safety_slow_point_ = true;
0 commit comments