Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(log-messages): reduce excessive log messages in velodyne decoder #118

Merged
merged 2 commits into from
Mar 29, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
*
* License: Modified BSD License
*
* $ Id: 02/14/2012 11:25:34 AM piyushk $

Check warning on line 9 in nebula_common/include/nebula_common/velodyne/velodyne_calibration_decoder.hpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (piyushk)
*/

#ifndef NEBULA_VELODYNE_CALIBRATION_DECODER_H
Expand Down Expand Up @@ -59,15 +59,14 @@
std::vector<VelodyneLaserCorrection> 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);
}
Expand Down
4 changes: 0 additions & 4 deletions nebula_common/src/velodyne/velodyne_calibration_decoder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -162,10 +162,6 @@
// 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;
}
}
}
}
Expand Down Expand Up @@ -237,11 +233,11 @@

void VelodyneCalibration::write(const std::string & calibration_file)
{
std::ofstream fout(calibration_file.c_str());

Check warning on line 236 in nebula_common/src/velodyne/velodyne_calibration_decoder.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (fout)
YAML::Emitter out;
out << *this;
fout << out.c_str();

Check warning on line 239 in nebula_common/src/velodyne/velodyne_calibration_decoder.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (fout)
fout.close();

Check warning on line 240 in nebula_common/src/velodyne/velodyne_calibration_decoder.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (fout)
}

} // namespace drivers
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
6 changes: 3 additions & 3 deletions nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<drivers::VelodyneCalibrationConfiguration>(calibration_configuration);

sensor_cfg_ptr_ = std::make_shared<drivers::VelodyneSensorConfiguration>(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<drivers::SensorConfigurationBase>(sensor_cfg_ptr_),
std::static_pointer_cast<drivers::CalibrationConfigurationBase>(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_msgs::msg::VelodyneScan>(
"velodyne_packets", rclcpp::SensorDataQoS(),
Expand Down
Loading