diff --git a/README.md b/README.md
index ec729e820a55027329a8a8d9d2fbfe41aa03bdf7..a03709de9d8399073ab2988ad980de4704bc9b6e 100644
--- a/README.md
+++ b/README.md
@@ -1,4 +1,4 @@
-WOLF - Windowed Localization Frames | Laser Plugin
-===================================
+WOLF Laser Plugin
+=================
 
-For installation guide and code documentation, please visit the [documentation website](http://mobile_robotics.pages.iri.upc-csic.es/wolf_projects/wolf_lib/wolf-doc-sphinx/).
+For installation guide and code documentation, please visit the [documentation website](http://www.iri.upc.edu/wolf).
diff --git a/include/laser/processor/params_icp.h b/include/laser/processor/params_icp.h
index bfafa5dc03a2a341bbca112289316834bb95b8d0..9c57708c337730b005b57cf4bcd3c94df75edc19 100644
--- a/include/laser/processor/params_icp.h
+++ b/include/laser/processor/params_icp.h
@@ -77,6 +77,7 @@ struct ParamsIcp
 
         icp_params.do_compute_covariance        = _server.getParam<bool>   (_prefix_and_unique_name + "/icp/do_compute_covariance");
         icp_params.cov_factor                   = _server.getParam<double> (_prefix_and_unique_name + "/icp/cov_factor");
+        icp_params.cov_max_eigv_factor          = _server.getParam<double> (_prefix_and_unique_name + "/icp/cov_max_eigv_factor");
     }
 
     std::string print() const
@@ -110,7 +111,8 @@ struct ParamsIcp
               + "/icp/use_sigma_weights"            + std::to_string(icp_params.use_sigma_weights)              + "\n"
               + "/icp/sigma"                        + std::to_string(icp_params.sigma)                          + "\n"
               + "/icp/do_compute_covariance"        + std::to_string(icp_params.do_compute_covariance)          + "\n"
-              + "/icp/cov_factor"                   + std::to_string(icp_params.cov_factor)                     + "\n";
+              + "/icp/cov_factor"                   + std::to_string(icp_params.cov_factor)                     + "\n"
+              + "/icp/cov_max_eigv_factor"          + std::to_string(icp_params.cov_max_eigv_factor)            + "\n";
     }
 };
 
diff --git a/test/gtest_processor_loop_closure_icp.cpp b/test/gtest_processor_loop_closure_icp.cpp
index 491e22aafa5e22ebab10eaf7d436fc615a366889..a2d911e224c7414b8f051a9c2e06501b34ed4cbe 100644
--- a/test/gtest_processor_loop_closure_icp.cpp
+++ b/test/gtest_processor_loop_closure_icp.cpp
@@ -66,6 +66,7 @@ class ProcessorLoopClosureIcp_Test : public testing::Test
             params->icp_params.outliers_adaptive_mult       = 2;
             params->icp_params.do_compute_covariance        = true;
             params->icp_params.cov_factor                   = 1;
+            params->icp_params.cov_max_eigv_factor          = 1;
             params->icp_params.max_angular_correction_deg   = 1.5;
             params->icp_params.max_linear_correction        = 10;
             params->icp_params.epsilon_xy                   = 0.01;
diff --git a/test/yaml/params_processor_loop_closure_falko.yaml b/test/yaml/params_processor_loop_closure_falko.yaml
index a936e3029a9681df069492f873091f53385c097b..27f8284dccabb10938ae35ce92beb0253c950f7d 100644
--- a/test/yaml/params_processor_loop_closure_falko.yaml
+++ b/test/yaml/params_processor_loop_closure_falko.yaml
@@ -58,6 +58,7 @@
           outliers_adaptive_mult:              1.5
           do_compute_covariance:               true
           cov_factor:                          1
+          cov_max_eigv_factor:                 5
 
           max_angular_correction_deg:          4
           max_linear_correction:               10