diff --git a/src/self_filter.cpp b/src/self_filter.cpp index f6e0d74..ac99b92 100644 --- a/src/self_filter.cpp +++ b/src/self_filter.cpp @@ -50,6 +50,7 @@ class SelfFilter { nh_.param("sensor_frame", sensor_frame_, std::string()); nh_.param("use_rgb", use_rgb_, false); + nh_.param("max_queue_size", max_queue_size_, 10); if (use_rgb_) { self_filter_rgb_ = new filters::SelfFilter(nh_); @@ -112,8 +113,8 @@ class SelfFilter else { ROS_DEBUG("Valid frames were passed in. We'll filter them."); - sub_.subscribe(root_handle_, "cloud_in", 1); - mn_.reset(new tf::MessageFilter(sub_, tf_, "", 1)); + sub_.subscribe(root_handle_, "cloud_in", max_queue_size_); + mn_.reset(new tf::MessageFilter(sub_, tf_, "", max_queue_size_)); mn_->setTargetFrames(frames_); mn_->registerCallback(boost::bind(&SelfFilter::cloudCallback, this, _1)); } @@ -188,7 +189,7 @@ class SelfFilter ros::Publisher pointCloudPublisher_; ros::Subscriber no_filter_sub_; - + int max_queue_size_; }; }