diff --git a/demos/processor_visual_odometry.yaml b/demos/processor_visual_odometry.yaml
index 017dde68ca26e4dbb5826774101b45e075b7259a..4f19f6af07466e337b79a0bb27f77058ee139244 100644
--- a/demos/processor_visual_odometry.yaml
+++ b/demos/processor_visual_odometry.yaml
@@ -15,34 +15,37 @@ max_new_features: 100
 ####################################
 # ProcessorVisualOdometry parameters
 
-# CLAHE = Contrast Limited Adaptive Histogram Equalization  
-# -> more continuous lighting and higher contrast images, 1-1.5 ms overhead
-use_clahe: true
+# Image Equalization methods
+#   0: none
+#   1: average
+#   2: histogram_equalization
+#   3: CLAHE = Contrast Limited Adaptive Histogram Equalization, 1-1.5 ms overhead
+equalization:
+    method: 1
+    average:
+        median: 127 # half of 8 bits = 255/2 = 127.5 --> to integer <-- TODO we could maybe automate this
+    histogram:
+    clahe:
+        clip_limit: 2
+        tile_grid_size: [8,8]
 
 # FAST KeyPoint detection 
-fast_params:
+fast:
     # Threshold on the keypoint pixel intensity (in uchar [0-255]) 
     # the higher, the more selective the detector is
-    threshold_fast: 30
+    threshold: 30
     # Avoids getting multiple keypoints at the same place
     non_max_suppresion: true
-    # number of cells used by the active search grid data structure
-    active_search_grid_nb_h: 8  # horizontal
-    active_search_grid_nb_v: 8  # vertical
-    # minimum margin of the region of interest from the edges of the image 
-    active_search_margin: 10
-    # reduce the size of each region of interest by n pixels to prevent keypoints from being too close
-    active_search_separation: 10
-
+    
 # Lucas Kanade tracking parameters
-klt_params:
+klt:
     patch_width: 15
     patch_height: 15
     nlevels_pyramids: 3
-    klt_max_err: 0.3
+    max_err: 0.3
 
 # tesselation grid    
-grid_params:
+grid:
     # number of cells used by the active search grid data structure
     nbr_cells_h: 6  # horizontal
     nbr_cells_v: 5  # vertical
@@ -51,12 +54,12 @@ grid_params:
     # reduce the size of each region of interest by n pixels to prevent keypoints from being too close
     separation: 10
 
-ransac_params:
+ransac:
     # specifies a desirable level of confidence (probability) that the estimated matrix is correct
-    ransac_prob: 0.999
+    prob: 0.999
     # maximum distance from a point to an epipolar line in pixels, beyond which the point 
     # is considered an outlier and is not used for computing the final fundamental matrix
-    ransac_thresh: 1
+    thresh: 1
 
 # Keep the number of tracks below 
 max_nb_tracks: 100
diff --git a/include/vision/processor/processor_visual_odometry.h b/include/vision/processor/processor_visual_odometry.h
index 099f3e1450ce8abfe58bc27238928e43975d6abf..6d4221057c002211655558f3c64c0a97f2ac38b3 100644
--- a/include/vision/processor/processor_visual_odometry.h
+++ b/include/vision/processor/processor_visual_odometry.h
@@ -56,119 +56,119 @@ struct ParamsProcessorVisualOdometry : public ParamsProcessorTracker
 {
     struct RansacParams
     {
-        double ransac_prob_;
-        double ransac_thresh_;
+        double prob;
+        double thresh;
     };
 
     struct KltParams
     {
-        int patch_width_;
-        int patch_height_;
-        double klt_max_err_;
-        int nlevels_pyramids_;
-        cv::TermCriteria criteria_;
+        int patch_width;
+        int patch_height;
+        double max_err;
+        int nlevels_pyramids;
+        cv::TermCriteria criteria;
     };
 
     struct FastParams
     {
-        int threshold_fast_;
-        bool non_max_suppresion_;
+        int threshold;
+        bool non_max_suppresion;
     };
 
     struct GridParams
     {
-        unsigned int nbr_cells_h_;
-        unsigned int nbr_cells_v_;
-        unsigned int margin_;
-        unsigned int separation_;
+        unsigned int nbr_cells_h;
+        unsigned int nbr_cells_v;
+        unsigned int margin;
+        unsigned int separation;
     };
 
     struct EqualizationParams
     {
-            unsigned int method_; // 0: none; 1: average; 2: histogram; 3: CLAHE
+            unsigned int method; // 0: none; 1: average; 2: histogram; 3: CLAHE
             // note: cv::histogramEqualization() has no tuning params
             struct AverageParams
             {
-                    int median_;
-            } average_;
+                    int median;
+            } average;
             struct ClaheParams
             {
-                    double clip_limit_;
-                    cv::Size2i tile_grid_size_;
-            } clahe_;
+                    double clip_limit;
+                    cv::Size2i tile_grid_size;
+            } clahe;
     };
 
-    double std_pix_;
-    RansacParams ransac_params_;
-    KltParams klt_params_;
-    FastParams fast_params_;
-    GridParams grid_params_;
-    EqualizationParams equalization_params_;
-    unsigned int max_nb_tracks_;
-    unsigned int min_track_length_for_landmark_;
+    double std_pix;
+    RansacParams ransac;
+    KltParams klt;
+    FastParams fast;
+    GridParams grid;
+    EqualizationParams equalization;
+    unsigned int max_nb_tracks;
+    unsigned int min_track_length_for_landmark;
 
     ParamsProcessorVisualOdometry() = default;
     ParamsProcessorVisualOdometry(std::string _unique_name, const ParamsServer& _server):
         ParamsProcessorTracker(_unique_name, _server)
     {
-        std_pix_ = _server.getParam<int>(prefix + _unique_name + "/std_pix");
+        std_pix = _server.getParam<double>(prefix + _unique_name + "/std_pix");
 
-        equalization_params_.method_ = _server.getParam<unsigned int>(prefix + _unique_name + "/equalization_params/method");
-        switch (equalization_params_.method_)
+        equalization.method = _server.getParam<unsigned int>(prefix + _unique_name + "/equalization/method");
+        switch (equalization.method)
         {
             case 0: break;
             case 1:
-                equalization_params_.average_.median_ = _server.getParam<unsigned int>(prefix + _unique_name + "/equalization_params/average/median");
+                equalization.average.median = _server.getParam<unsigned int>(prefix + _unique_name + "/equalization/average/median");
                 break;
             case 2:
                 // note: cv::histogramEqualization() has no tuning params
                 break;
             case 3:
-                equalization_params_.clahe_.clip_limit_ = _server.getParam<double>(prefix + _unique_name + "/equalization_params/clahe/clip_limit");
-                vector<int> grid_size = _server.getParam<vector<int>>(prefix + _unique_name + "/equalization_params/clahe/tile_grid_size");
-                equalization_params_.clahe_.tile_grid_size_.width  = grid_size[0];
-                equalization_params_.clahe_.tile_grid_size_.height = grid_size[1];
+                equalization.clahe.clip_limit = _server.getParam<double>(prefix + _unique_name + "/equalization/clahe/clip_limit");
+                vector<int> grid_size = _server.getParam<vector<int>>(prefix + _unique_name + "/equalization/clahe/tile_grid_size");
+                equalization.clahe.tile_grid_size.width  = grid_size[0];
+                equalization.clahe.tile_grid_size.height = grid_size[1];
                 break;
         }
 
-        ransac_params_.ransac_prob_   = _server.getParam<double>(prefix + _unique_name + "/ransac_params/ransac_prob");
-        ransac_params_.ransac_thresh_ = _server.getParam<double>(prefix + _unique_name + "/ransac_params/ransac_thresh");
+        ransac.prob   = _server.getParam<double>(prefix + _unique_name + "/ransac/prob");
+        ransac.thresh = _server.getParam<double>(prefix + _unique_name + "/ransac/thresh");
 
-        klt_params_.patch_width_        = _server.getParam<int>(prefix + _unique_name + "/klt_params/patch_width");
-        klt_params_.patch_height_       = _server.getParam<int>(prefix + _unique_name + "/klt_params/patch_height");
-        klt_params_.klt_max_err_        = _server.getParam<double>(prefix + _unique_name + "/klt_params/klt_max_err");
-        klt_params_.nlevels_pyramids_   = _server.getParam<int>(prefix + _unique_name + "/klt_params/nlevels_pyramids");
-        klt_params_.criteria_           = cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 30, 0.01);  // everybody uses this defaults...
+        klt.patch_width        = _server.getParam<int>    (prefix + _unique_name + "/klt/patch_width");
+        klt.patch_height       = _server.getParam<int>    (prefix + _unique_name + "/klt/patch_height");
+        klt.max_err            = _server.getParam<double> (prefix + _unique_name + "/klt/max_err");
+        klt.nlevels_pyramids   = _server.getParam<int>    (prefix + _unique_name + "/klt/nlevels_pyramids");
+        klt.criteria           = cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 30, 0.01);  // everybody uses this defaults...
 
-        fast_params_.threshold_fast_     = _server.getParam<int>( prefix + _unique_name + "/fast_params/threshold_fast");
-        fast_params_.non_max_suppresion_ = _server.getParam<bool>(prefix + _unique_name + "/fast_params/non_max_suppresion");
+        fast.threshold         = _server.getParam<int>    ( prefix + _unique_name + "/fast/threshold");
+        fast.non_max_suppresion = _server.getParam<bool>  (prefix + _unique_name + "/fast/non_max_suppresion");
 
-        grid_params_.nbr_cells_h_   = _server.getParam<unsigned int>(prefix + _unique_name + "/grid_params/nbr_cells_h");
-        grid_params_.nbr_cells_v_   = _server.getParam<unsigned int>(prefix + _unique_name + "/grid_params/nbr_cells_v");
-        grid_params_.margin_        = _server.getParam<unsigned int>(prefix + _unique_name + "/grid_params/margin");
-        grid_params_.separation_    = _server.getParam<unsigned int>(prefix + _unique_name + "/grid_params/separation");
+        grid.nbr_cells_h   = _server.getParam<unsigned int>(prefix + _unique_name + "/grid/nbr_cells_h");
+        grid.nbr_cells_v   = _server.getParam<unsigned int>(prefix + _unique_name + "/grid/nbr_cells_v");
+        grid.margin        = _server.getParam<unsigned int>(prefix + _unique_name + "/grid/margin");
+        grid.separation    = _server.getParam<unsigned int>(prefix + _unique_name + "/grid/separation");
 
-        max_nb_tracks_ = _server.getParam<unsigned int>(prefix + _unique_name + "/max_nb_tracks");
-        min_track_length_for_landmark_ = _server.getParam<unsigned int>(prefix + _unique_name + "/min_track_length_for_landmark");
+        max_nb_tracks = _server.getParam<unsigned int>(prefix + _unique_name + "/max_nb_tracks");
+        min_track_length_for_landmark = _server.getParam<unsigned int>(prefix + _unique_name + "/min_track_length_for_landmark");
 
     }
     std::string print() const override
     {
         return ParamsProcessorTracker::print()                                                                   + "\n"
-            + "ransac_params_.ransac_prob_:      " + std::to_string(ransac_params_.ransac_prob_)                 + "\n"
-            + "ransac_params_.ransac_thresh_:    " + std::to_string(ransac_params_.ransac_thresh_)               + "\n"
-            + "klt_params_.tracker_width_:       " + std::to_string(klt_params_.patch_width_)                    + "\n"
-            + "klt_params_.tracker_height_:      " + std::to_string(klt_params_.patch_height_)                   + "\n"
-            + "klt_params_.klt_max_err_:         " + std::to_string(klt_params_.klt_max_err_)                    + "\n"
-            + "klt_params_.nlevels_pyramids_:    " + std::to_string(klt_params_.nlevels_pyramids_)               + "\n"
-            + "fast_params_.threshold_fast_:     " + std::to_string(fast_params_.threshold_fast_)                + "\n"
-            + "fast_params_.non_max_suppresion_: " + std::to_string(fast_params_.non_max_suppresion_)            + "\n"
-            + "grid_params_.nbr_cells_h_:        " + std::to_string(grid_params_.nbr_cells_h_)                   + "\n"
-            + "grid_params_.nbr_cells_v_:        " + std::to_string(grid_params_.nbr_cells_v_)                   + "\n"
-            + "grid_params_.margin_:             " + std::to_string(grid_params_.margin_)                        + "\n"
-            + "grid_params_.separation_:         " + std::to_string(grid_params_.separation_)                    + "\n"
-            + "max_nb_tracks_:                   " + std::to_string(max_nb_tracks_)                              + "\n"
-            + "min_track_length_for_landmark_:   " + std::to_string(min_track_length_for_landmark_)              + "\n";
+            + "ransac.prob:               " + std::to_string(ransac.prob)                 + "\n"
+            + "ransac.thresh:             " + std::to_string(ransac.thresh)               + "\n"
+            + "klt.patch_width:           " + std::to_string(klt.patch_width)                    + "\n"
+            + "klt.patch_height:          " + std::to_string(klt.patch_height)                   + "\n"
+            + "klt.max_err:               " + std::to_string(klt.max_err)                    + "\n"
+            + "klt.nlevels_pyramids:      " + std::to_string(klt.nlevels_pyramids)               + "\n"
+            + "fast.threshold:            " + std::to_string(fast.threshold)                + "\n"
+            + "fast.non_max_suppresion:   " + std::to_string(fast.non_max_suppresion)            + "\n"
+            + "grid.nbr_cells_h:          " + std::to_string(grid.nbr_cells_h)                   + "\n"
+            + "grid.nbr_cells_v:          " + std::to_string(grid.nbr_cells_v)                   + "\n"
+            + "grid.margin:               " + std::to_string(grid.margin)                        + "\n"
+            + "grid.separation:           " + std::to_string(grid.separation)                    + "\n"
+            + "max_nb_tracks:                   " + std::to_string(max_nb_tracks)                              + "\n"
+            + "min_track_length_for_landmark:   " + std::to_string(min_track_length_for_landmark)              + "\n";
     }
 };
 
diff --git a/src/processor/processor_visual_odometry.cpp b/src/processor/processor_visual_odometry.cpp
index 947807475ed09c8abe899c2d4ed836ebf82cb56e..b52a01825caf8d047e1dcc23747f5feaa471ccce 100644
--- a/src/processor/processor_visual_odometry.cpp
+++ b/src/processor/processor_visual_odometry.cpp
@@ -37,13 +37,13 @@ ProcessorVisualOdometry::ProcessorVisualOdometry(ParamsProcessorVisualOdometryPt
                 frame_count_(0)
 {
     // Preprocessor stuff
-    detector_ = cv::FastFeatureDetector::create(_params_vo->fast_params_.threshold_fast_, 
-                                                _params_vo->fast_params_.non_max_suppresion_,
+    detector_ = cv::FastFeatureDetector::create(_params_vo->fast.threshold,
+                                                _params_vo->fast.non_max_suppresion,
                                                 cv::FastFeatureDetector::TYPE_9_16); // TYPE_5_8, TYPE_7_12, TYPE_9_16
     
     // Processor stuff
     // Set pixel noise covariance
-    Eigen::Vector2d std_pix; std_pix << params_visual_odometry_->std_pix_, params_visual_odometry_->std_pix_;
+    Eigen::Vector2d std_pix; std_pix << params_visual_odometry_->std_pix, params_visual_odometry_->std_pix;
     pixel_cov_ = std_pix.array().square().matrix().asDiagonal();
 
 }
@@ -61,10 +61,10 @@ void ProcessorVisualOdometry::configure(SensorBasePtr _sensor)
     
     // Tessalation of the image
     cell_grid_ = ActiveSearchGrid(sen_cam_->getImgWidth(), sen_cam_->getImgHeight(),
-                                  params_visual_odometry_->grid_params_.nbr_cells_h_,
-                                  params_visual_odometry_->grid_params_.nbr_cells_v_,
-                                  params_visual_odometry_->grid_params_.margin_,
-                                  params_visual_odometry_->grid_params_.separation_);
+                                  params_visual_odometry_->grid.nbr_cells_h,
+                                  params_visual_odometry_->grid.nbr_cells_v,
+                                  params_visual_odometry_->grid.margin,
+                                  params_visual_odometry_->grid.separation);
 }
 
 TracksMap ProcessorVisualOdometry::mergeTracks(const TracksMap& tracks_prev_curr, const TracksMap& tracks_curr_next){
@@ -96,7 +96,7 @@ void ProcessorVisualOdometry::preProcess()
      *      2. opencv: histogram_equalization
      *      3. opencv: CLAHE
      */
-    switch (params_visual_odometry_->equalization_params_.method_)
+    switch (params_visual_odometry_->equalization.method)
     {
         case 0:
             break;
@@ -104,7 +104,7 @@ void ProcessorVisualOdometry::preProcess()
         {
             // average to central brightness
             auto img_avg = (cv::mean(img_incoming)).val[0];
-            img_incoming += cv::Scalar(round(params_visual_odometry_->equalization_params_.average_.median_ - img_avg) );
+            img_incoming += cv::Scalar(round(params_visual_odometry_->equalization.average.median - img_avg) );
             break;
         }
         case 2:
@@ -116,8 +116,8 @@ void ProcessorVisualOdometry::preProcess()
         {
             // Contrast Limited Adaptive Histogram Equalization  CLAHE
             // -> more continuous lighting and higher contrast images
-            cv::Ptr<cv::CLAHE> clahe = cv::createCLAHE(params_visual_odometry_->equalization_params_.clahe_.clip_limit_,
-                                                       params_visual_odometry_->equalization_params_.clahe_.tile_grid_size_);
+            cv::Ptr<cv::CLAHE> clahe = cv::createCLAHE(params_visual_odometry_->equalization.clahe.clip_limit,
+                                                       params_visual_odometry_->equalization.clahe.tile_grid_size);
             clahe->apply(img_incoming, img_incoming);
             break;
         }
@@ -134,8 +134,8 @@ void ProcessorVisualOdometry::preProcess()
         cv::Rect rect_roi;
         Eigen::Vector2i cell_index;
         std::vector<cv::KeyPoint> kps_roi;
-        for (int i=1; i < params_visual_odometry_->grid_params_.nbr_cells_h_-1; i++){
-            for (int j=1; j < params_visual_odometry_->grid_params_.nbr_cells_v_-1; j++){
+        for (int i=1; i < params_visual_odometry_->grid.nbr_cells_h-1; i++){
+            for (int j=1; j < params_visual_odometry_->grid.nbr_cells_v-1; j++){
                 cell_index << i,j;
                 cell_grid_.cell2roi(cell_index, rect_roi);
 
@@ -469,7 +469,7 @@ void ProcessorVisualOdometry::establishFactors()
         }
 
         // 2) create landmark if track is not associated with one and has enough length
-        else if(track_matrix_.trackSize(feat->trackId()) >= params_visual_odometry_->min_track_length_for_landmark_)
+        else if(track_matrix_.trackSize(feat->trackId()) >= params_visual_odometry_->min_track_length_for_landmark)
         {
             // std::cout << "NEW valid track \\o/" << std::endl;
             LandmarkBasePtr lmk = emplaceLandmark(feat_pi);
@@ -626,16 +626,16 @@ TracksMap ProcessorVisualOdometry::kltTrack(const cv::Mat _img_prev, const cv::M
 
 
     // Process one way: previous->current with current init with previous
-    ParamsProcessorVisualOdometry::KltParams prms = params_visual_odometry_->klt_params_;
+    ParamsProcessorVisualOdometry::KltParams prms = params_visual_odometry_->klt;
     cv::calcOpticalFlowPyrLK(
             _img_prev,
             _img_curr, 
             p2f_prev,
             p2f_curr,
             status, err,
-            {prms.patch_width_, prms.patch_height_}, 
-            prms.nlevels_pyramids_,
-            prms.criteria_,
+            {prms.patch_width, prms.patch_height},
+            prms.nlevels_pyramids,
+            prms.criteria,
             (cv::OPTFLOW_USE_INITIAL_FLOW + cv::OPTFLOW_LK_GET_MIN_EIGENVALS));
     
     // Process the other way: current->previous
@@ -647,16 +647,16 @@ TracksMap ProcessorVisualOdometry::kltTrack(const cv::Mat _img_prev, const cv::M
             p2f_curr,
             p2f_prev,
             status_back, err_back,
-            {prms.patch_width_, prms.patch_height_},
-            prms.nlevels_pyramids_,
-            prms.criteria_,
+            {prms.patch_width, prms.patch_height},
+            prms.nlevels_pyramids,
+            prms.criteria,
             (cv::OPTFLOW_USE_INITIAL_FLOW + cv::OPTFLOW_LK_GET_MIN_EIGENVALS));
 
     // Delete point if KLT failed
     for (size_t j = 0; j < status.size(); j++) {
 
-        if(!status_back.at(j)  ||  (err_back.at(j) > prms.klt_max_err_) ||
-           !status.at(j)  ||  (err.at(j) > prms.klt_max_err_)) {
+        if(!status_back.at(j)  ||  (err_back.at(j) > prms.max_err) ||
+           !status.at(j)  ||  (err.at(j) > prms.max_err)) {
             continue;
         }
 
@@ -675,7 +675,7 @@ TracksMap ProcessorVisualOdometry::kltTrack(const cv::Mat _img_prev, const cv::M
 
 bool ProcessorVisualOdometry::filterWithEssential(const KeyPointsMap _mwkps_prev, const KeyPointsMap _mwkps_curr, TracksMap &_tracks_prev_curr, cv::Mat &_E)
 {
-    ParamsProcessorVisualOdometry::RansacParams prms = params_visual_odometry_->ransac_params_;
+    ParamsProcessorVisualOdometry::RansacParams prms = params_visual_odometry_->ransac;
 
     // We need to build lists of pt2d for openCV function
     std::vector<cv::Point2d> p2d_prev, p2d_curr;
@@ -700,8 +700,8 @@ bool ProcessorVisualOdometry::filterWithEssential(const KeyPointsMap _mwkps_prev
                               p2d_curr, 
                               Kcv_, 
                               cv::RANSAC,
-                              prms.ransac_prob_,
-                              prms.ransac_thresh_ / focal,
+                              prms.prob,
+                              prms.thresh / focal,
                               cvMask);
     
     // Let's remove outliers from tracksMap
diff --git a/test/gtest_processor_visual_odometry.cpp b/test/gtest_processor_visual_odometry.cpp
index 76c2713c056fe96d5dc465517d9ddf39f57e384c..f95bd8086984d2f631006e693182550962dbe397 100644
--- a/test/gtest_processor_visual_odometry.cpp
+++ b/test/gtest_processor_visual_odometry.cpp
@@ -101,13 +101,13 @@ TEST(ProcessorVisualOdometry, kltTrack)
 
     // Create a processor
     ParamsProcessorVisualOdometryPtr params = std::make_shared<ParamsProcessorVisualOdometry>();
-    params->klt_params_.patch_height_ = 21;
-    params->klt_params_.patch_width_ = 21;
-    params->klt_params_.nlevels_pyramids_ = 3;
-    params->klt_params_.klt_max_err_ = 1.0;
-    params->klt_params_.criteria_ = cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 30, 0.01);
-    params->fast_params_.threshold_fast_ = 30;
-    params->fast_params_.non_max_suppresion_ = true;
+    params->klt.patch_height = 21;
+    params->klt.patch_width = 21;
+    params->klt.nlevels_pyramids = 3;
+    params->klt.max_err = 1.0;
+    params->klt.criteria = cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 30, 0.01);
+    params->fast.threshold = 30;
+    params->fast.non_max_suppresion = true;
 
     ProcessorVisualOdometryTest processor(params);
     cv::Ptr<cv::FeatureDetector> detector = processor.getDetector();
@@ -141,16 +141,16 @@ TEST(ProcessorVisualOdometry, kltTrack)
 //
 //    // Create a processor
 //    ParamsProcessorVisualOdometryPtr params = std::make_shared<ParamsProcessorVisualOdometry>();
-//    params->klt_params_.patch_height_ = 21;
-//    params->klt_params_.patch_width_ = 21;
-//    params->klt_params_.nlevels_pyramids_ = 3;
-//    params->klt_params_.klt_max_err_ = 0.2;
-//    params->klt_params_.criteria_ = cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 30, 0.01);
-//    params->fast_params_.threshold_fast_ = 20;
-//    params->fast_params_.non_max_suppresion_ = true;
+//    params->klt_params.patch_height = 21;
+//    params->klt_params.patch_width = 21;
+//    params->klt_params.nlevels_pyramids = 3;
+//    params->klt_params.klt_max_err = 0.2;
+//    params->klt_params.criteria = cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 30, 0.01);
+//    params->fast_params.threshold_fast = 20;
+//    params->fast_params.non_max_suppresion = true;
 //    params->min_features_for_keyframe = 50;
-//    params->max_nb_tracks_ = 400;
-//    params->min_track_length_for_landmark_ = 4;
+//    params->max_nb_tracks = 400;
+//    params->min_track_length_for_landmark = 4;
 //    ProcessorVisualOdometryTest processor(params);
 //
 //
@@ -340,12 +340,12 @@ TEST(ProcessorVisualOdometry, filterWithEssential)
     
     // Create a processor
     ParamsProcessorVisualOdometryPtr params = std::make_shared<ParamsProcessorVisualOdometry>();
-    params->grid_params_.margin_ = 10;
-    params->grid_params_.nbr_cells_h_ = 8;
-    params->grid_params_.nbr_cells_v_ = 8;
-    params->grid_params_.separation_ = 10;
-    params->ransac_params_.ransac_prob_ = 0.999;  // 0.99 makes the gtest fail -> missing one point
-    params->ransac_params_.ransac_thresh_ = 1.0;
+    params->grid.margin = 10;
+    params->grid.nbr_cells_h = 8;
+    params->grid.nbr_cells_v = 8;
+    params->grid.separation = 10;
+    params->ransac.prob = 0.999;  // 0.99 makes the gtest fail -> missing one point
+    params->ransac.thresh = 1.0;
     ProcessorVisualOdometryTest processor(params);
 
     // Install camera