From c2c3b5863a115eac86813234f019714a4a5c2b87 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Mon, 19 Feb 2024 06:35:00 +0200 Subject: [PATCH] fix(log-messages): lower some info message to debug --- nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp b/nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp index 26ca559b8..df484a27a 100644 --- a/nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp +++ b/nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp @@ -15,19 +15,19 @@ VelodyneDriverRosWrapper::VelodyneDriverRosWrapper(const rclcpp::NodeOptions & o RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); return; } - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); + RCLCPP_DEBUG_STREAM(this->get_logger(), this->get_name() << ". Starting..."); calibration_cfg_ptr_ = std::make_shared(calibration_configuration); sensor_cfg_ptr_ = std::make_shared(sensor_configuration); - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); + RCLCPP_DEBUG_STREAM(this->get_logger(), this->get_name() << ". Driver "); wrapper_status_ = InitializeDriver( std::const_pointer_cast(sensor_cfg_ptr_), std::static_pointer_cast(calibration_cfg_ptr_)); - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); + RCLCPP_DEBUG_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); velodyne_scan_sub_ = create_subscription( "velodyne_packets", rclcpp::SensorDataQoS(),