diff --git a/cfg/GroundSegmentation.cfg b/cfg/GroundSegmentation.cfg
index 2f415cf619eda97345483f5c8abda0f4829ee94b..fd7f6fa46f667981b26852839d2952f2669c2377 100644
--- a/cfg/GroundSegmentation.cfg
+++ b/cfg/GroundSegmentation.cfg
@@ -48,7 +48,7 @@ gen.add("robot_height", double_t, 0, "All obstacle points above this value (w.r.
 gen.add("ROI_delta_x_and_y", double_t, 0, "ROI area = ( 2 * ROI_delta_x_and_y ) ^ 2", 2.0, 0.0, 10.0);
 gen.add("ROI_shadow_area", double_t, 0, "ROI for root vertex in shadow area = ( 2 * ROI_delta_x_and_y ) ^ 2", 6.0, 0.0, 10.0);
 gen.add("ground_reference_search_resolution_deg", double_t, 0, "It is the angular resolution when generating new ground references (graph nodes) in degrees", 20.0, 1.0, 100.0);
-gen.add("elevation_grid_resolution", double_t, 0, "define the coarseness of the elevation points", 0.5, 0.01, 10.0);
+gen.add("elevation_grid_resolution", double_t, 0, "define the coarseness of the elevation points", 0.5, 0.2, 10.0);
  
 # Kalman filter noise parameters
 ## initial uncertainties
diff --git a/params/iri_ground_segmentation.yaml b/params/iri_ground_segmentation.yaml
index abee10aed70fcfef822c44427474ac526566c462..60a1b185b473e627824d0f9be87908903675e658 100644
--- a/params/iri_ground_segmentation.yaml
+++ b/params/iri_ground_segmentation.yaml
@@ -36,15 +36,15 @@ iri_ground_segmentation: {
                                     ## and a big value will increase the number of false ground points)
 
   # labeling parameters
-  number_of_references_used_for_labelling: 4,            ## used to evaluate each elevation point cloud from different POVs // NEW!! value of zero enables fast labelling mode!! \m/
+  number_of_references_used_for_labelling: 0,            ## used to evaluate each elevation point cloud from different POVs // NEW!! value of zero enables fast labelling mode!! \m/
   max_pred_std_dev_for_labelling: 0.5,                   ## to give up trying to label ground points if we don't have enough confidence in our predictions
-  classify_not_labeled_points_as_obstacles: false,        ## when a point has no reference satisfying the max_pred_std_dev_for_labelling threshold we can leave as unknown or label it as obstacle
-  ground_threshold_in_not_analyzed_areas: 0.00,           ## when it is not possible to make a local analysis of the data, we will use the lowest point (the one in elevation_cloud) as ground height, and
+  classify_not_labeled_points_as_obstacles: false,       ## when a point has no reference satisfying the max_pred_std_dev_for_labelling threshold we can leave as unknown or label it as obstacle
+  ground_threshold_in_not_analyzed_areas: 0.00,          ## when it is not possible to make a local analysis of the data, we will use the lowest point (the one in elevation_cloud) as ground height, and
                                                          ## all the points above it and below this threshold will be classified as ground 
   discard_not_connected_references_for_labelling: false, ## to exclude not connected vertices in the roadmap from the labelling step 
 
   # visualization and debug parameters
-  measure_performance: false,             ## (feature still not debugged) Flag to measure number of execution and execution times of the different functions of the algorithm 
+  measure_performance: false,            ## (feature still not debugged) Flag to measure number of execution and execution times of the different functions of the algorithm 
   show_dense_reconstruction: false,      ## To show a dense ground surface reconstruction using the predictions of the ground mode (colored using the std_dev of z coordinate)   
                                          ## or alternatively the "elevation point cloud" (useful for parameter tunning) 
 }