Skip to content

Commit

Permalink
Merge pull request #12 from garaemon/max-queue-size
Browse files Browse the repository at this point in the history
Add ~max_queue_size parameter for subscription queue size
  • Loading branch information
UltronDestroyer committed Jan 27, 2016
2 parents 6dc298a + f1ce314 commit 1aa6f4b
Showing 1 changed file with 4 additions and 3 deletions.
7 changes: 4 additions & 3 deletions src/self_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ class SelfFilter
{
nh_.param<std::string>("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<pcl::PointXYZRGB>(nh_);
Expand Down Expand Up @@ -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<sensor_msgs::PointCloud2>(sub_, tf_, "", 1));
sub_.subscribe(root_handle_, "cloud_in", max_queue_size_);
mn_.reset(new tf::MessageFilter<sensor_msgs::PointCloud2>(sub_, tf_, "", max_queue_size_));
mn_->setTargetFrames(frames_);
mn_->registerCallback(boost::bind(&SelfFilter::cloudCallback, this, _1));
}
Expand Down Expand Up @@ -188,7 +189,7 @@ class SelfFilter

ros::Publisher pointCloudPublisher_;
ros::Subscriber no_filter_sub_;

int max_queue_size_;
};
}

Expand Down

0 comments on commit 1aa6f4b

Please sign in to comment.