Skip to content

Commit

Permalink
add queue_size parameter to all nodes, see #83
Browse files Browse the repository at this point in the history
  • Loading branch information
k-okada committed Apr 20, 2019
1 parent 350011e commit edbc0ab
Show file tree
Hide file tree
Showing 25 changed files with 100 additions and 50 deletions.
10 changes: 6 additions & 4 deletions src/nodelet/adding_images_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ namespace opencv_apps {
Config config_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

int queue_size_;
bool debug_view_;
ros::Time prev_stamp_;

Expand Down Expand Up @@ -116,27 +117,27 @@ namespace opencv_apps {
if (config_.use_camera_info) {
if (approximate_sync_) {
async_with_info_ = boost::make_shared<
message_filters::Synchronizer<ApproxSyncPolicyWithCameraInfo> >(100);
message_filters::Synchronizer<ApproxSyncPolicyWithCameraInfo> >(queue_size_);
async_with_info_->connectInput(sub_image1_, sub_image2_, sub_camera_info_);
async_with_info_->registerCallback(boost::bind(
&AddingImagesNodelet::imageCallbackWithInfo, this, _1, _2, _3));
} else {
sync_with_info_ =
boost::make_shared<message_filters::Synchronizer<SyncPolicyWithCameraInfo> >(100);
boost::make_shared<message_filters::Synchronizer<SyncPolicyWithCameraInfo> >(queue_size_);
sync_with_info_->connectInput(sub_image1_, sub_image2_, sub_camera_info_);
sync_with_info_->registerCallback(boost::bind(
&AddingImagesNodelet::imageCallbackWithInfo, this, _1, _2, _3));
}
} else {
if (approximate_sync_) {
async_ = boost::make_shared<
message_filters::Synchronizer<ApproxSyncPolicy> >(100);
message_filters::Synchronizer<ApproxSyncPolicy> >(queue_size_);
async_->connectInput(sub_image1_, sub_image2_);
async_->registerCallback(
boost::bind(&AddingImagesNodelet::imageCallback, this, _1, _2));
} else {
sync_ =
boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
sync_->connectInput(sub_image1_, sub_image2_);
sync_->registerCallback(
boost::bind(&AddingImagesNodelet::imageCallback, this, _1, _2));
Expand Down Expand Up @@ -251,6 +252,7 @@ namespace opencv_apps {
reconfigure_server_->setCallback(f);

pnh_->param("approximate_sync", approximate_sync_, true);
pnh_->param("queue_size", queue_size_, 100);
img_pub_ = advertiseImage(*pnh_, "image", 1);
onInitPostProcess();
}
Expand Down
6 changes: 4 additions & 2 deletions src/nodelet/camshift_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,7 @@ class CamShiftNodelet : public opencv_apps::Nodelet
Config config_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

int queue_size_;
bool debug_view_;
ros::Time prev_stamp_;

Expand Down Expand Up @@ -337,9 +338,9 @@ class CamShiftNodelet : public opencv_apps::Nodelet
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
cam_sub_ = it_->subscribeCamera("image", 3, &CamShiftNodelet::imageCallbackWithInfo, this);
cam_sub_ = it_->subscribeCamera("image", queue_size_, &CamShiftNodelet::imageCallbackWithInfo, this);
else
img_sub_ = it_->subscribe("image", 3, &CamShiftNodelet::imageCallback, this);
img_sub_ = it_->subscribe("image", queue_size_, &CamShiftNodelet::imageCallback, this);
}

void unsubscribe()
Expand All @@ -355,6 +356,7 @@ class CamShiftNodelet : public opencv_apps::Nodelet
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));

pnh_->param("queue_size", queue_size_, 3);
pnh_->param("debug_view", debug_view_, false);
if (debug_view_) {
always_subscribe_ = true;
Expand Down
6 changes: 4 additions & 2 deletions src/nodelet/color_filter_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,7 @@ class ColorFilterNodelet : public opencv_apps::Nodelet
Config config_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

int queue_size_;
bool debug_view_;

std::string window_name_;
Expand Down Expand Up @@ -145,9 +146,9 @@ class ColorFilterNodelet : public opencv_apps::Nodelet
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
cam_sub_ = it_->subscribeCamera("image", 3, &ColorFilterNodelet::imageCallbackWithInfo, this);
cam_sub_ = it_->subscribeCamera("image", queue_size_, &ColorFilterNodelet::imageCallbackWithInfo, this);
else
img_sub_ = it_->subscribe("image", 3, &ColorFilterNodelet::imageCallback, this);
img_sub_ = it_->subscribe("image", queue_size_, &ColorFilterNodelet::imageCallback, this);
}

void unsubscribe()
Expand All @@ -163,6 +164,7 @@ class ColorFilterNodelet : public opencv_apps::Nodelet
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));

pnh_->param("queue_size", queue_size_, 3);
pnh_->param("debug_view", debug_view_, false);

if (debug_view_) {
Expand Down
6 changes: 4 additions & 2 deletions src/nodelet/contour_moments_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,7 @@ class ContourMomentsNodelet : public opencv_apps::Nodelet
Config config_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

int queue_size_;
bool debug_view_;
ros::Time prev_stamp_;

Expand Down Expand Up @@ -238,9 +239,9 @@ class ContourMomentsNodelet : public opencv_apps::Nodelet
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
cam_sub_ = it_->subscribeCamera("image", 3, &ContourMomentsNodelet::imageCallbackWithInfo, this);
cam_sub_ = it_->subscribeCamera("image", queue_size_, &ContourMomentsNodelet::imageCallbackWithInfo, this);
else
img_sub_ = it_->subscribe("image", 3, &ContourMomentsNodelet::imageCallback, this);
img_sub_ = it_->subscribe("image", queue_size_, &ContourMomentsNodelet::imageCallback, this);
}

void unsubscribe()
Expand All @@ -256,6 +257,7 @@ class ContourMomentsNodelet : public opencv_apps::Nodelet
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));

pnh_->param("queue_size", queue_size_, 3);
pnh_->param("debug_view", debug_view_, false);
if (debug_view_) {
always_subscribe_ = true;
Expand Down
6 changes: 4 additions & 2 deletions src/nodelet/convex_hull_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ class ConvexHullNodelet : public opencv_apps::Nodelet
Config config_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

int queue_size_;
bool debug_view_;
ros::Time prev_stamp_;

Expand Down Expand Up @@ -199,9 +200,9 @@ class ConvexHullNodelet : public opencv_apps::Nodelet
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
cam_sub_ = it_->subscribeCamera("image", 3, &ConvexHullNodelet::imageCallbackWithInfo, this);
cam_sub_ = it_->subscribeCamera("image", queue_size_, &ConvexHullNodelet::imageCallbackWithInfo, this);
else
img_sub_ = it_->subscribe("image", 3, &ConvexHullNodelet::imageCallback, this);
img_sub_ = it_->subscribe("image", queue_size_, &ConvexHullNodelet::imageCallback, this);
}

void unsubscribe()
Expand All @@ -218,6 +219,7 @@ class ConvexHullNodelet : public opencv_apps::Nodelet
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));

pnh_->param("queue_size", queue_size_, 3);
pnh_->param("debug_view", debug_view_, false);
if (debug_view_) {
always_subscribe_ = true;
Expand Down
6 changes: 4 additions & 2 deletions src/nodelet/corner_harris_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,7 @@ class CornerHarrisNodelet : public opencv_apps::Nodelet
Config config_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

int queue_size_;
bool debug_view_;

std::string window_name_;
Expand Down Expand Up @@ -174,9 +175,9 @@ class CornerHarrisNodelet : public opencv_apps::Nodelet
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
cam_sub_ = it_->subscribeCamera("image", 3, &CornerHarrisNodelet::imageCallbackWithInfo, this);
cam_sub_ = it_->subscribeCamera("image", queue_size_, &CornerHarrisNodelet::imageCallbackWithInfo, this);
else
img_sub_ = it_->subscribe("image", 3, &CornerHarrisNodelet::imageCallback, this);
img_sub_ = it_->subscribe("image", queue_size_, &CornerHarrisNodelet::imageCallback, this);
}

void unsubscribe()
Expand All @@ -192,6 +193,7 @@ class CornerHarrisNodelet : public opencv_apps::Nodelet
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));

pnh_->param("queue_size", queue_size_, 3);
pnh_->param("debug_view", debug_view_, false);

if (debug_view_) {
Expand Down
6 changes: 4 additions & 2 deletions src/nodelet/discrete_fourier_transform_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,7 @@ class DiscreteFourierTransformNodelet : public opencv_apps::Nodelet {
Config config_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

int queue_size_;
bool debug_view_;
ros::Time prev_stamp_;

Expand All @@ -84,10 +85,10 @@ class DiscreteFourierTransformNodelet : public opencv_apps::Nodelet {
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
cam_sub_ = it_->subscribeCamera(
"image", 1, &DiscreteFourierTransformNodelet::imageCallbackWithInfo, this);
"image", queue_size_, &DiscreteFourierTransformNodelet::imageCallbackWithInfo, this);
else
img_sub_ =
it_->subscribe("image", 1, &DiscreteFourierTransformNodelet::imageCallback, this);
it_->subscribe("image", queue_size_, &DiscreteFourierTransformNodelet::imageCallback, this);
}

void unsubscribe() {
Expand Down Expand Up @@ -178,6 +179,7 @@ class DiscreteFourierTransformNodelet : public opencv_apps::Nodelet {
virtual void onInit() {
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
pnh_->param("queue_size", queue_size_, 3);
pnh_->param("debug_view", debug_view_, false);

if (debug_view_) {
Expand Down
6 changes: 4 additions & 2 deletions src/nodelet/edge_detection_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ class EdgeDetectionNodelet : public opencv_apps::Nodelet
Config config_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

int queue_size_;
bool debug_view_;
ros::Time prev_stamp_;

Expand Down Expand Up @@ -261,9 +262,9 @@ class EdgeDetectionNodelet : public opencv_apps::Nodelet
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
cam_sub_ = it_->subscribeCamera("image", 3, &EdgeDetectionNodelet::imageCallbackWithInfo, this);
cam_sub_ = it_->subscribeCamera("image", queue_size_, &EdgeDetectionNodelet::imageCallbackWithInfo, this);
else
img_sub_ = it_->subscribe("image", 3, &EdgeDetectionNodelet::imageCallback, this);
img_sub_ = it_->subscribe("image", queue_size_, &EdgeDetectionNodelet::imageCallback, this);
}

void unsubscribe()
Expand All @@ -279,6 +280,7 @@ class EdgeDetectionNodelet : public opencv_apps::Nodelet
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));

pnh_->param("queue_size", queue_size_, 3);
pnh_->param("debug_view", debug_view_, false);

if (debug_view_) {
Expand Down
6 changes: 4 additions & 2 deletions src/nodelet/face_detection_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,7 @@ class FaceDetectionNodelet : public opencv_apps::Nodelet
Config config_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

int queue_size_;
bool debug_view_;
ros::Time prev_stamp_;

Expand Down Expand Up @@ -202,9 +203,9 @@ class FaceDetectionNodelet : public opencv_apps::Nodelet
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
cam_sub_ = it_->subscribeCamera("image", 3, &FaceDetectionNodelet::imageCallbackWithInfo, this);
cam_sub_ = it_->subscribeCamera("image", queue_size_, &FaceDetectionNodelet::imageCallbackWithInfo, this);
else
img_sub_ = it_->subscribe("image", 3, &FaceDetectionNodelet::imageCallback, this);
img_sub_ = it_->subscribe("image", queue_size_, &FaceDetectionNodelet::imageCallback, this);
}

void unsubscribe()
Expand All @@ -220,6 +221,7 @@ class FaceDetectionNodelet : public opencv_apps::Nodelet
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));

pnh_->param("queue_size", queue_size_, 3);
pnh_->param("debug_view", debug_view_, false);
if (debug_view_ ) {
always_subscribe_ = true;
Expand Down
6 changes: 4 additions & 2 deletions src/nodelet/find_contours_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ class FindContoursNodelet : public opencv_apps::Nodelet
Config config_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

int queue_size_;
bool debug_view_;
ros::Time prev_stamp_;

Expand Down Expand Up @@ -196,9 +197,9 @@ class FindContoursNodelet : public opencv_apps::Nodelet
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
cam_sub_ = it_->subscribeCamera("image", 3, &FindContoursNodelet::imageCallbackWithInfo, this);
cam_sub_ = it_->subscribeCamera("image", queue_size_, &FindContoursNodelet::imageCallbackWithInfo, this);
else
img_sub_ = it_->subscribe("image", 3, &FindContoursNodelet::imageCallback, this);
img_sub_ = it_->subscribe("image", queue_size_, &FindContoursNodelet::imageCallback, this);
}

void unsubscribe()
Expand All @@ -214,6 +215,7 @@ class FindContoursNodelet : public opencv_apps::Nodelet
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));

pnh_->param("queue_size", queue_size_, 3);
pnh_->param("debug_view", debug_view_, false);
if (debug_view_) {
always_subscribe_ = true;
Expand Down
6 changes: 4 additions & 2 deletions src/nodelet/general_contours_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ class GeneralContoursNodelet : public opencv_apps::Nodelet
Config config_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

int queue_size_;
bool debug_view_;
ros::Time prev_stamp_;

Expand Down Expand Up @@ -227,9 +228,9 @@ class GeneralContoursNodelet : public opencv_apps::Nodelet
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
cam_sub_ = it_->subscribeCamera("image", 3, &GeneralContoursNodelet::imageCallbackWithInfo, this);
cam_sub_ = it_->subscribeCamera("image", queue_size_, &GeneralContoursNodelet::imageCallbackWithInfo, this);
else
img_sub_ = it_->subscribe("image", 3, &GeneralContoursNodelet::imageCallback, this);
img_sub_ = it_->subscribe("image", queue_size_, &GeneralContoursNodelet::imageCallback, this);
}

void unsubscribe()
Expand All @@ -245,6 +246,7 @@ class GeneralContoursNodelet : public opencv_apps::Nodelet
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));

pnh_->param("queue_size", queue_size_, 3);
pnh_->param("debug_view", debug_view_, false);
if (debug_view_) {
always_subscribe_ = true;
Expand Down
6 changes: 4 additions & 2 deletions src/nodelet/goodfeature_track_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ class GoodfeatureTrackNodelet : public opencv_apps::Nodelet
Config config_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

int queue_size_;
bool debug_view_;
ros::Time prev_stamp_;

Expand Down Expand Up @@ -199,9 +200,9 @@ class GoodfeatureTrackNodelet : public opencv_apps::Nodelet
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
cam_sub_ = it_->subscribeCamera("image", 3, &GoodfeatureTrackNodelet::imageCallbackWithInfo, this);
cam_sub_ = it_->subscribeCamera("image", queue_size_, &GoodfeatureTrackNodelet::imageCallbackWithInfo, this);
else
img_sub_ = it_->subscribe("image", 3, &GoodfeatureTrackNodelet::imageCallback, this);
img_sub_ = it_->subscribe("image", queue_size_, &GoodfeatureTrackNodelet::imageCallback, this);
}

void unsubscribe()
Expand All @@ -217,6 +218,7 @@ class GoodfeatureTrackNodelet : public opencv_apps::Nodelet
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));

pnh_->param("queue_size", queue_size_, 3);
pnh_->param("debug_view", debug_view_, false);
if (debug_view_) {
always_subscribe_ = true;
Expand Down
6 changes: 4 additions & 2 deletions src/nodelet/hough_circles_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ class HoughCirclesNodelet : public opencv_apps::Nodelet
Config config_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

int queue_size_;
bool debug_view_;
ros::Time prev_stamp_;

Expand Down Expand Up @@ -294,9 +295,9 @@ class HoughCirclesNodelet : public opencv_apps::Nodelet
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
cam_sub_ = it_->subscribeCamera("image", 3, &HoughCirclesNodelet::imageCallbackWithInfo, this);
cam_sub_ = it_->subscribeCamera("image", queue_size_, &HoughCirclesNodelet::imageCallbackWithInfo, this);
else
img_sub_ = it_->subscribe("image", 3, &HoughCirclesNodelet::imageCallback, this);
img_sub_ = it_->subscribe("image", queue_size_, &HoughCirclesNodelet::imageCallback, this);
}

void unsubscribe()
Expand All @@ -313,6 +314,7 @@ class HoughCirclesNodelet : public opencv_apps::Nodelet
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));

debug_image_type_ = 0;
pnh_->param("queue_size", queue_size_, 3);
pnh_->param("debug_view", debug_view_, false);
if (debug_view_) {
always_subscribe_ = debug_view_;
Expand Down
Loading

0 comments on commit edbc0ab

Please sign in to comment.