diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index 656adaac252fc..b5ca4b8006552 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -164,7 +164,8 @@ void FusionNode::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; } @@ -269,7 +270,8 @@ void FusionNode::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; } diff --git a/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp b/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp index eb4a497e70495..0daed93c05b2d 100644 --- a/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp +++ b/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp @@ -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"); } } @@ -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"); } }