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 f0b04bacf26dd..a778855f30b46 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 @@ -142,10 +142,10 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro // Subscribers { - RCLCPP_INFO_STREAM( + RCLCPP_DEBUG_STREAM( get_logger(), "Subscribing to " << input_topics_.size() << " user given topics as inputs:"); for (auto & input_topic : input_topics_) { - RCLCPP_INFO_STREAM(get_logger(), " - " << input_topic); + RCLCPP_DEBUG_STREAM(get_logger(), " - " << input_topic); } // Subscribe to the filters diff --git a/sensing/pointcloud_preprocessor/src/filter.cpp b/sensing/pointcloud_preprocessor/src/filter.cpp index d5843be395adf..a561f355e7a28 100644 --- a/sensing/pointcloud_preprocessor/src/filter.cpp +++ b/sensing/pointcloud_preprocessor/src/filter.cpp @@ -77,7 +77,7 @@ pointcloud_preprocessor::Filter::Filter( latched_indices_ = static_cast(declare_parameter("latched_indices", false)); approximate_sync_ = static_cast(declare_parameter("approximate_sync", false)); - RCLCPP_INFO_STREAM( + RCLCPP_DEBUG_STREAM( this->get_logger(), "Filter (as Component) successfully created with the following parameters:" << std::endl