Skip to content

Commit bacba67

Browse files
author
Shigekazu Fukuta
committed
add warning log
1 parent f0041d3 commit bacba67

File tree

1 file changed

+2
-0
lines changed
  • planning/obstacle_avoidance_planner/src

1 file changed

+2
-0
lines changed

planning/obstacle_avoidance_planner/src/utils.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -344,6 +344,7 @@ std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> interpolate2DTraj
344344

345345
// spline interpolation
346346
std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> interpolated_points;
347+
auto clock = rclcpp::Clock{RCL_ROS_TIME};
347348
try {
348349
const auto interpolated_x = interpolation::slerp(base_s, base_x, new_s);
349350
const auto interpolated_y = interpolation::slerp(base_s, base_y, new_s);
@@ -365,6 +366,7 @@ std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> interpolate2DTraj
365366
}
366367

367368
} catch (const std::invalid_argument & e) {
369+
RCLCPP_WARN_THROTTLE(rclcpp::get_logger("util"), clock, 1000, "%s", e.what());
368370
return std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint>{};
369371
}
370372
return interpolated_points;

0 commit comments

Comments
 (0)