From c64402f1c06ae74434f834638f5af10333a64e1b Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi Date: Mon, 16 Oct 2023 13:21:06 +0900 Subject: [PATCH] fix(lane_change): change logger level in isVehicleStuckByObstacle Signed-off-by: Zulfaqar Azmi --- .../src/scene_module/lane_change/normal.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index fadc63dd8834e..12b6d53a83220 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -1725,7 +1725,7 @@ bool NormalLaneChange::isVehicleStuckByObstacle(const lanelet::ConstLanelets & c constexpr double DETECTION_DISTANCE_MARGIN = 10.0; const auto detection_distance = max_lane_change_length + rss_dist + getCommonParam().base_link2front + DETECTION_DISTANCE_MARGIN; - RCLCPP_INFO(logger_, "max_lane_change_length: %f, max_acc: %f", max_lane_change_length, max_acc); + RCLCPP_DEBUG(logger_, "max_lane_change_length: %f, max_acc: %f", max_lane_change_length, max_acc); return isVehicleStuckByObstacle(current_lanes, detection_distance); }