Skip to content

Commit

Permalink
fix(log-messages): reduce excessive log messages in velodyne decoder (#…
Browse files Browse the repository at this point in the history
…118)

* fix(log-messages): lower some info message to debug

* fix(log-messages): removing leftover std::cout log from  from the original Velodyne implementation

Signed-off-by: AhmedEbrahim <[email protected]>

---------

Signed-off-by: AhmedEbrahim <[email protected]>
  • Loading branch information
ahmeddesokyebrahim authored Mar 29, 2024
1 parent cb3c56a commit dd31cc3
Show file tree
Hide file tree
Showing 4 changed files with 7 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -59,15 +59,14 @@ class VelodyneCalibration
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 @@ 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;
}
}
}
}
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

0 comments on commit dd31cc3

Please sign in to comment.