Skip to content

Commit

Permalink
chore(lane_change): don't exit for danger param (autowarefoundation#4092
Browse files Browse the repository at this point in the history
)

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>
  • Loading branch information
TakaHoribe authored and rej55 committed Jun 29, 2023
1 parent 3139472 commit e66196c
Showing 1 changed file with 3 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -829,10 +829,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;
Expand Down

0 comments on commit e66196c

Please sign in to comment.