diff --git a/cfg/HoleDetection.cfg b/cfg/HoleDetection.cfg
index 2ce0503b7b2848fbf2b32c3fb4cbe9a581aef400..a906897897bb04cdff6c696e3a9516026c86f3e6 100755
--- a/cfg/HoleDetection.cfg
+++ b/cfg/HoleDetection.cfg
@@ -40,11 +40,11 @@ gen = ParameterGenerator()
 #       Name                       Type       Reconfiguration level            Description                       Default   Min   Max
 #gen.add("velocity_scale_factor",  double_t,  0,                               "Maximum velocity scale factor",  0.5,      0.0,  1.0)
 gen.add(            "hole_min_p",  int_t,     0,             "No of Points to be hole (less points is a hole)",   30,       5,  200)
-gen.add(           "box_y",  double_t,  0,                              "Y distance hole detection zone",  0.6,        0,  1.5)
-gen.add(           "box_z_ini",  double_t,  0,                              "Z distance hole detection zone", 0,     -0.5,    0.5)
-gen.add(            "box_z_end",  double_t,  0,                               "Initial Z hole detection zone",    0.1,     -0.5,  0.5)
-gen.add(            "box_x_ini",  double_t,  0,                               "Initial X hole detection zone",    0.8,      0,    2)
-gen.add(           "box_x_end",  double_t,  0,                              "X distance hole detection zone",  0.9,        0.5,    2)
+gen.add(           "box_x",  double_t,  0,                              "X distance hole detection zone",  0.6,        0,  1.5)
+gen.add(           "box_y_ini",  double_t,  0,                              "Y distance hole detection zone", 0,     -0.5,    0.5)
+gen.add(            "box_y_end",  double_t,  0,                               "Initial Y hole detection zone",    0.1,     -0.5,  0.5)
+gen.add(            "box_z_ini",  double_t,  0,                               "Initial Z hole detection zone",    0.8,      0,    2)
+gen.add(           "box_z_end",  double_t,  0,                              "Z distance hole detection zone",  0.9,        0.5,    2)
 
 
 
diff --git a/cfg/OLD_HoleDetection.cfg b/cfg/OLD_HoleDetection.cfg
deleted file mode 100755
index a906897897bb04cdff6c696e3a9516026c86f3e6..0000000000000000000000000000000000000000
--- a/cfg/OLD_HoleDetection.cfg
+++ /dev/null
@@ -1,51 +0,0 @@
-#! /usr/bin/env python
-#*  All rights reserved.
-#*
-#*  Redistribution and use in source and binary forms, with or without
-#*  modification, are permitted provided that the following conditions
-#*  are met:
-#*
-#*   * Redistributions of source code must retain the above copyright
-#*     notice, this list of conditions and the following disclaimer.
-#*   * Redistributions in binary form must reproduce the above
-#*     copyright notice, this list of conditions and the following
-#*     disclaimer in the documentation and/or other materials provided
-#*     with the distribution.
-#*   * Neither the name of the Willow Garage nor the names of its
-#*     contributors may be used to endorse or promote products derived
-#*     from this software without specific prior written permission.
-#*
-#*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-#*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-#*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-#*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-#*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-#*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-#*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-#*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-#*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-#*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-#*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-#*  POSSIBILITY OF SUCH DAMAGE.
-#***********************************************************
-
-# Author: 
-
-PACKAGE='iri_hole_detection'
-
-from dynamic_reconfigure.parameter_generator_catkin import *
-
-gen = ParameterGenerator()
-
-#       Name                       Type       Reconfiguration level            Description                       Default   Min   Max
-#gen.add("velocity_scale_factor",  double_t,  0,                               "Maximum velocity scale factor",  0.5,      0.0,  1.0)
-gen.add(            "hole_min_p",  int_t,     0,             "No of Points to be hole (less points is a hole)",   30,       5,  200)
-gen.add(           "box_x",  double_t,  0,                              "X distance hole detection zone",  0.6,        0,  1.5)
-gen.add(           "box_y_ini",  double_t,  0,                              "Y distance hole detection zone", 0,     -0.5,    0.5)
-gen.add(            "box_y_end",  double_t,  0,                               "Initial Y hole detection zone",    0.1,     -0.5,  0.5)
-gen.add(            "box_z_ini",  double_t,  0,                               "Initial Z hole detection zone",    0.8,      0,    2)
-gen.add(           "box_z_end",  double_t,  0,                              "Z distance hole detection zone",  0.9,        0.5,    2)
-
-
-
-exit(gen.generate(PACKAGE, "HoleDetectionAlgorithm", "HoleDetection"))