Skip to content

Commit

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

* fix(log-messages): lower log level from info to debug in concatenate_and_time_sync_nodelet for info about subscribing to topics and their names

Signed-off-by: AhmedEbrahim <ahmed.a.d.ebrahim@gmail.com>

* fix(log-messages): adding info print in smart_pose_buffer indicating that there is a mismatch in timestamp

Signed-off-by: AhmedEbrahim <ahmed.a.d.ebrahim@gmail.com>

* fix(log-messages): removing info msg that is redundant with error msg

Signed-off-by: AhmedEbrahim <ahmed.a.d.ebrahim@gmail.com>

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

Signed-off-by: AhmedEbrahim <ahmed.a.d.ebrahim@gmail.com>

---------

Signed-off-by: AhmedEbrahim <ahmed.a.d.ebrahim@gmail.com>
  • Loading branch information
ahmeddesokyebrahim authored and karishma1911 committed Jun 3, 2024
1 parent 2329708 commit 85f241c
Show file tree
Hide file tree
Showing 7 changed files with 7 additions and 7 deletions.
1 change: 1 addition & 0 deletions localization/localization_util/src/smart_pose_buffer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ std::optional<SmartPoseBuffer::InterpolateResult> SmartPoseBuffer::interpolate(
const rclcpp::Time time_last = pose_buffer_.back()->header.stamp;

if (target_ros_time < time_first) {
RCLCPP_INFO(logger_, "Mismatch between pose timestamp and current timestamp");
return std::nullopt;
}

Expand Down
2 changes: 1 addition & 1 deletion localization/localization_util/src/util_func.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -241,7 +241,7 @@ void output_pose_with_cov_to_log(
rpy.y = rpy.y * 180.0 / M_PI;
rpy.z = rpy.z * 180.0 / M_PI;

RCLCPP_INFO_STREAM(
RCLCPP_DEBUG_STREAM(
logger, std::fixed << prefix << "," << pose.position.x << "," << pose.position.y << ","
<< pose.position.z << "," << pose.orientation.x << "," << pose.orientation.y
<< "," << pose.orientation.z << "," << pose.orientation.w << "," << rpy.x
Expand Down
2 changes: 1 addition & 1 deletion localization/ndt_scan_matcher/src/map_update_module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt
const auto duration_micro_sec =
std::chrono::duration_cast<std::chrono::microseconds>(exe_end_time - exe_start_time).count();
const auto exe_time = static_cast<double>(duration_micro_sec) / 1000.0;
RCLCPP_INFO(logger_, "Time duration for creating new ndt_ptr: %lf [ms]", exe_time);
RCLCPP_DEBUG(logger_, "Time duration for creating new ndt_ptr: %lf [ms]", exe_time);
return true; // Updated
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -992,7 +992,7 @@ geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_pose(
result_pose_with_cov_msg.pose.pose = best_particle_ptr->result_pose;

output_pose_with_cov_to_log(get_logger(), "align_pose_output", result_pose_with_cov_msg);
RCLCPP_INFO_STREAM(get_logger(), "best_score," << best_particle_ptr->score);
RCLCPP_DEBUG_STREAM(get_logger(), "best_score," << best_particle_ptr->score);

return result_pose_with_cov_msg;
}
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@ PoseWithCovarianceStamped NdtModule::align_pose(const PoseWithCovarianceStamped
RCLCPP_INFO(logger_, "Call NDT align server.");
const auto res = cli_align_->async_send_request(req).get();
if (!res->success) {
RCLCPP_INFO(logger_, "NDT align server failed.");
throw ServiceException(
Initialize::Service::Response::ERROR_ESTIMATION, "NDT align server failed.");
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -145,10 +145,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
Expand Down
2 changes: 1 addition & 1 deletion sensing/pointcloud_preprocessor/src/filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ pointcloud_preprocessor::Filter::Filter(
latched_indices_ = static_cast<bool>(declare_parameter("latched_indices", false));
approximate_sync_ = static_cast<bool>(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
Expand Down

0 comments on commit 85f241c

Please sign in to comment.