diff --git a/nebula_common/include/nebula_common/velodyne/velodyne_calibration_decoder.hpp b/nebula_common/include/nebula_common/velodyne/velodyne_calibration_decoder.hpp index d676ca9ee..9cbbb53ea 100644 --- a/nebula_common/include/nebula_common/velodyne/velodyne_calibration_decoder.hpp +++ b/nebula_common/include/nebula_common/velodyne/velodyne_calibration_decoder.hpp @@ -59,15 +59,14 @@ class VelodyneCalibration std::vector laser_corrections; int num_lasers{}; bool initialized; - bool ros_info; public: - explicit VelodyneCalibration(bool info = true) - : distance_resolution_m(0.002f), initialized(false), ros_info(info) + explicit VelodyneCalibration() + : distance_resolution_m(0.002f), initialized(false) { } - explicit VelodyneCalibration(const std::string & calibration_file, bool info = true) - : distance_resolution_m(0.002f), ros_info(info) + explicit VelodyneCalibration(const std::string & calibration_file) + : distance_resolution_m(0.002f) { read(calibration_file); } diff --git a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp index d620f8295..0c03c3c9e 100644 --- a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp +++ b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp @@ -162,10 +162,6 @@ void operator>>(const YAML::Node & node, VelodyneCalibration & calibration) // store this ring number with its corresponding laser number calibration.laser_corrections[next_index].laser_ring = ring; next_angle = min_seen; - if (calibration.ros_info) { - std::cout << "laser_ring[" << next_index << "] =" << ring << ", angle = " << next_angle - << std::endl; - } } } } diff --git a/nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp b/nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp index 78383d569..b0f664c8c 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp @@ -14,8 +14,6 @@ VelodyneDriver::VelodyneDriver( { // initialize proper parser from cloud config's model and echo mode driver_status_ = nebula::Status::OK; - std::cout << "sensor_configuration->sensor_model=" << sensor_configuration->sensor_model - << std::endl; switch (sensor_configuration->sensor_model) { case SensorModel::UNKNOWN: driver_status_ = nebula::Status::INVALID_SENSOR_MODEL; 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(),