diff --git a/cfg/ImageLocalBinarization.cfg b/cfg/ImageLocalBinarization.cfg
index 8f3f5771dd67a0326f064e9e5cd0941598f37ffb..0851b6c695a03e734209b78b70d962375e8d7248 100755
--- a/cfg/ImageLocalBinarization.cfg
+++ b/cfg/ImageLocalBinarization.cfg
@@ -41,5 +41,7 @@ gen = ParameterGenerator()
 #gen.add("velocity_scale_factor",  double_t,  0,                               "Maximum velocity scale factor",  0.5,      0.0,  1.0)
 gen.add(           "window_size",     int_t,  0,                                  "Local threshold window size",   15,       3,  500)
 gen.add(                     "k",  double_t,  0,                 "Multiplicative constant for local deviation",   0.06,      0,  0.5)
+#not reconfigurable
+#gen.add(           "queue size",     int_t,  0,                                  "subscriber queue size for image_transport",   10,       1,  100)
 
 exit(gen.generate(PACKAGE, "ImageLocalBinarizationAlgorithm", "ImageLocalBinarization"))
diff --git a/src/image_local_binarization_alg_node.cpp b/src/image_local_binarization_alg_node.cpp
index b05eca5c7cb9108fa17d3dbb2f342fdfa6b05d9d..56c22bfb3c2c11196b86b5b40896da204ff95c1c 100644
--- a/src/image_local_binarization_alg_node.cpp
+++ b/src/image_local_binarization_alg_node.cpp
@@ -9,8 +9,10 @@ ImageLocalBinarizationAlgNode::ImageLocalBinarizationAlgNode(void) :
   // [init publishers]
   this->image_out_publisher_ = this->it.advertiseCamera("image_out/image_raw", 1);
   
+  int queue_size=10;
+  this->private_node_handle_.getParam("queue_size", queue_size);
   // [init subscribers]
-  this->image_in_subscriber_ = this->it.subscribeCamera("image_in/image_raw", 1, &ImageLocalBinarizationAlgNode::image_in_callback,this);
+  this->image_in_subscriber_ = this->it.subscribeCamera("image_in/image_raw", queue_size, &ImageLocalBinarizationAlgNode::image_in_callback,this);
   pthread_mutex_init(&this->image_in_mutex_,NULL);