From 5eb8b9ffcb57b50d25e77646ad38c2c369aef92d Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 27 Jun 2023 20:07:20 +0900 Subject: [PATCH] chore(lane_change): don't exit for danger param Signed-off-by: Takamasa Horibe --- .../src/behavior_path_planner_node.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index c3191d5ab4a2c..4ed96ebe463ae 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -853,10 +853,9 @@ LaneChangeParameters BehaviorPathPlannerNode::getLaneChangeParam() } if (p.cancel.delta_time < 1.0) { - RCLCPP_FATAL_STREAM( - get_logger(), "cancel.delta_time: " << p.cancel.delta_time << ", is too short.\n" - << "Terminating the program..."); - exit(EXIT_FAILURE); + RCLCPP_WARN_STREAM( + get_logger(), "cancel.delta_time: " << p.cancel.delta_time + << ", is too short. This could cause a danger behavior."); } return p;