Skip to content

Commit

Permalink
add warning log
Browse files Browse the repository at this point in the history
  • Loading branch information
Shigekazu Fukuta committed May 9, 2024
1 parent f0041d3 commit bacba67
Showing 1 changed file with 2 additions and 0 deletions.
2 changes: 2 additions & 0 deletions planning/obstacle_avoidance_planner/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -344,6 +344,7 @@ std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> interpolate2DTraj

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

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

0 comments on commit bacba67

Please sign in to comment.