Skip to content

Commit 52e02e9

Browse files
author
Shigekazu Fukuta
committed
update rclcpp_debug
1 parent bacba67 commit 52e02e9

File tree

1 file changed

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

1 file changed

+1
-2
lines changed

planning/obstacle_avoidance_planner/src/utils.cpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -344,7 +344,6 @@ 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};
348347
try {
349348
const auto interpolated_x = interpolation::slerp(base_s, base_x, new_s);
350349
const auto interpolated_y = interpolation::slerp(base_s, base_y, new_s);
@@ -366,7 +365,7 @@ std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> interpolate2DTraj
366365
}
367366

368367
} catch (const std::invalid_argument & e) {
369-
RCLCPP_WARN_THROTTLE(rclcpp::get_logger("util"), clock, 1000, "%s", e.what());
368+
RCLCPP_DEBUG(rclcpp::get_logger("util"), clock, 1000, "%s", e.what());
370369
return std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint>{};
371370
}
372371
return interpolated_points;

0 commit comments

Comments
 (0)