From 14f7ee1c8dd97ab794340c00d5007ae8f32c5de1 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Mon, 26 Aug 2024 12:05:19 +0900 Subject: [PATCH] chore(autoware_pointcloud_preprocessor): change unnecessary warning message to debug (#8525) --- .../src/concatenate_data/concatenate_and_time_sync_nodelet.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp index ff72e433e9602..1611558f90f5d 100644 --- a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp @@ -252,7 +252,7 @@ PointCloudConcatenateDataSynchronizerComponent::computeTransformToAdjustForOldTi // return identity if old_stamp is newer than new_stamp if (old_stamp > new_stamp) { - RCLCPP_WARN_STREAM_THROTTLE( + RCLCPP_DEBUG_STREAM_THROTTLE( get_logger(), *get_clock(), std::chrono::milliseconds(10000).count(), "old_stamp is newer than new_stamp,"); return Eigen::Matrix4f::Identity();