From 25887c463024b645efb6d805da6c8a676a6d81be Mon Sep 17 00:00:00 2001 From: Furushchev Date: Mon, 24 Dec 2018 14:28:48 +0900 Subject: [PATCH] camera_subscriber: force queue_size to 1 for each subscriber --- image_transport/src/camera_subscriber.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/image_transport/src/camera_subscriber.cpp b/image_transport/src/camera_subscriber.cpp index a91a14ea..486c98bd 100644 --- a/image_transport/src/camera_subscriber.cpp +++ b/image_transport/src/camera_subscriber.cpp @@ -107,8 +107,8 @@ CameraSubscriber::CameraSubscriber(ImageTransport& image_it, ros::NodeHandle& in // to figure out the sibling camera_info topic. std::string image_topic = info_nh.resolveName(base_topic); std::string info_topic = getCameraInfoTopic(image_topic); - impl_->image_sub_.subscribe(image_it, image_topic, queue_size, transport_hints); - impl_->info_sub_ .subscribe(info_nh, info_topic, queue_size, transport_hints.getRosHints()); + impl_->image_sub_.subscribe(image_it, image_topic, 1, transport_hints); + impl_->info_sub_ .subscribe(info_nh, info_topic, 1, transport_hints.getRosHints()); impl_->sync_.connectInput(impl_->image_sub_, impl_->info_sub_); // need for Boost.Bind here is kind of broken impl_->sync_.registerCallback(boost::bind(callback, _1, _2));