Skip to content
This repository is currently being migrated. It's locked while the migration is in progress.

camera_subscriber: force queue_size to 1 for each subscriber #6

Merged
merged 2 commits into from
Dec 26, 2019
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions image_transport/src/camera_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand Down