From 2154bbce574d0ca5556440b8335642968a8e8bb0 Mon Sep 17 00:00:00 2001 From: fherrero <fherrero@iri.upc.edu> Date: Mon, 17 Jul 2023 13:42:26 +0200 Subject: [PATCH] Set time stamp to camera publisher --- src/image_local_binarization_alg_node.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/image_local_binarization_alg_node.cpp b/src/image_local_binarization_alg_node.cpp index af729c2..52de7b0 100644 --- a/src/image_local_binarization_alg_node.cpp +++ b/src/image_local_binarization_alg_node.cpp @@ -86,7 +86,8 @@ void ImageLocalBinarizationAlgNode::image_callback(const sensor_msgs::Image::Con this->alg_.localThreshold(this->image_->image, this->image_->image, this->k_,(this->window_size_ % 2 == 0 ? this->window_size_ + 1: this->window_size_)); my_img = this->image_->toImageMsg(); my_img->header.stamp = msg->header.stamp; - this->image_out_publisher_.publish(*my_img,this->cam_info); + this->cam_info.header.stamp = msg->header.stamp; + this->image_out_publisher_.publish(*my_img,this->cam_info, msg->header.stamp); } catch(cv_bridge::Exception& e) { -- GitLab