From 97ac113aa1c77b2ad1fb042136e6b7cc48f3af41 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Sun, 9 Jun 2024 21:15:59 +0900 Subject: [PATCH] Update planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp --- .../src/scene_no_stopping_area.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp b/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp index 75e3a9e55108f..35dcf721067c7 100644 --- a/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp +++ b/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp @@ -253,7 +253,7 @@ bool NoStoppingAreaModule::checkStopLinesInNoStoppingArea( const double stop_vel = std::numeric_limits::min(); // if the detected stop point is near goal, it's ignored. - const double close_to_goal_distance = 1.0; + static constexpr double close_to_goal_distance = 1.0; // stuck points by stop line for (size_t i = 0; i < path.points.size() - 1; ++i) {