Skip to content

Commit

Permalink
Merge pull request #722 from mkuri/chore/fix-to-throttle-log
Browse files Browse the repository at this point in the history
chore: fix to throttle log
  • Loading branch information
0x126 authored Aug 10, 2023
2 parents e63f5b3 + 45f52d0 commit 5b37742
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 4 deletions.
6 changes: 4 additions & 2 deletions perception/image_projection_based_fusion/src/fusion_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,8 @@ void FusionNode<Msg, Obj>::subCallback(const typename Msg::ConstSharedPtr input_
// if matching rois exist, fuseOnSingle
for (std::size_t roi_i = 0; roi_i < rois_number_; ++roi_i) {
if (camera_info_map_.find(roi_i) == camera_info_map_.end()) {
RCLCPP_WARN(this->get_logger(), "no camera info. id is %zu", roi_i);
RCLCPP_WARN_THROTTLE(
this->get_logger(), *this->get_clock(), 5000, "no camera info. id is %zu", roi_i);
continue;
}

Expand Down Expand Up @@ -269,7 +270,8 @@ void FusionNode<Msg, Obj>::roiCallback(

if (interval < match_threshold_ms_ * (int64_t)1e6 && is_fused_.at(roi_i) == false) {
if (camera_info_map_.find(roi_i) == camera_info_map_.end()) {
RCLCPP_WARN(this->get_logger(), "no camera info. id is %zu", roi_i);
RCLCPP_WARN_THROTTLE(
this->get_logger(), *this->get_clock(), 5000, "no camera info. id is %zu", roi_i);
(roi_stdmap_.at(roi_i))[timestamp_nsec] = input_roi_msg;
return;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -216,7 +216,7 @@ DetectedObjects RadarTracksMsgsConverterNode::convertRadarTrackToDetectedObjects
kinematics.twist_with_covariance.twist.linear.y += odometry_data_->twist.twist.linear.y;
kinematics.twist_with_covariance.twist.linear.z += odometry_data_->twist.twist.linear.z;
} else {
RCLCPP_INFO(get_logger(), "Odometry data is not coming");
RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 5000, "Odometry data is not coming");
}
}

Expand Down Expand Up @@ -303,7 +303,7 @@ TrackedObjects RadarTracksMsgsConverterNode::convertRadarTrackToTrackedObjects()
kinematics.twist_with_covariance.twist.linear.y += odometry_data_->twist.twist.linear.y;
kinematics.twist_with_covariance.twist.linear.z += odometry_data_->twist.twist.linear.z;
} else {
RCLCPP_INFO(get_logger(), "Odometry data is not coming");
RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 5000, "Odometry data is not coming");
}
}

Expand Down

0 comments on commit 5b37742

Please sign in to comment.