diff --git a/CMakeLists.txt b/CMakeLists.txt
index bb7f032125ec1c5d926b19e94928ee5e085aafa2..4aa56e351ef94fb74f64eb72a2e126eb29c53ac2 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -286,9 +286,6 @@ SET(HDRS_YAML
   include/core/yaml/parser_yaml.hpp
   include/core/yaml/yaml_conversion.h
   )
-SET(HDRS_DUMMY
-  test/dummy/factor_feature_dummy.h
-  )
 #SOURCES
 SET(SRCS_PROBLEM
   src/problem/problem.cpp
@@ -513,8 +510,6 @@ INSTALL(FILES ${HDRS_SERIALIZATION}
   DESTINATION include/iri-algorithms/wolf/plugin_core/core/serialization)
 INSTALL(FILES ${HDRS_YAML}
   DESTINATION include/iri-algorithms/wolf/plugin_core/core/yaml)
-INSTALL(FILES ${HDRS_DUMMY}
-  DESTINATION include/iri-algorithms/wolf/plugin_core/core/dummy)
 
 FILE(WRITE ${PROJECT_NAME}.found "")
 INSTALL(FILES ${PROJECT_NAME}.found
diff --git a/hello_wolf/hello_wolf_autoconf.cpp b/hello_wolf/hello_wolf_autoconf.cpp
index 3b353bde24833278c6972dd1dc68f323e3ebede0..502c38e2ac48ff2539ab95f8ca21c1b674973b1f 100644
--- a/hello_wolf/hello_wolf_autoconf.cpp
+++ b/hello_wolf/hello_wolf_autoconf.cpp
@@ -107,9 +107,9 @@ int main()
     std::string file = std::string(_WOLF_ROOT_DIR) + "/hello_wolf/hello_wolf_config.yaml";
 
     // parse file into params server: each param will be retrievable from this params server:
-    parserYAML parser = parserYAML(file);
+    ParserYAML parser = ParserYAML(file);
     parser.parse();
-    paramsServer server = paramsServer(parser.getParams(), parser.sensorsSerialization(), parser.processorsSerialization());
+    ParamsServer server = ParamsServer(parser.getParams(), parser.sensorsSerialization(), parser.processorsSerialization());
 
     // Wolf problem: automatically build the left branch of the wolf tree from the contents of the params server:
     ProblemPtr problem          = Problem::autoSetup(server);
diff --git a/hello_wolf/processor_range_bearing.cpp b/hello_wolf/processor_range_bearing.cpp
index c379db030ca56f907560bcbb695e297cd77e7cc9..54bbb3aec498cacc736321f77abc127a24414106 100644
--- a/hello_wolf/processor_range_bearing.cpp
+++ b/hello_wolf/processor_range_bearing.cpp
@@ -116,7 +116,7 @@ ProcessorBasePtr ProcessorRangeBearing::create(const std::string& _unique_name,
 }
 
 ProcessorBasePtr ProcessorRangeBearing::createAutoConf(const std::string& _unique_name,
-                                                       const paramsServer& _server,
+                                                       const ParamsServer& _server,
                                                        const SensorBasePtr _sensor_ptr)
 {
     SensorRangeBearingPtr       sensor_rb = std::static_pointer_cast<SensorRangeBearing>(_sensor_ptr);
diff --git a/hello_wolf/processor_range_bearing.h b/hello_wolf/processor_range_bearing.h
index 6cfdd7d8943f13b4fb757c071582d99e9b6c3ea5..2bc4767c14f0c9619534d3bd6f6ae1dc5d4f506b 100644
--- a/hello_wolf/processor_range_bearing.h
+++ b/hello_wolf/processor_range_bearing.h
@@ -26,7 +26,7 @@ struct ProcessorParamsRangeBearing : public ProcessorParamsBase
         {
             //DEFINED FOR COMPATIBILITY PURPOSES. TO BE REMOVED IN THE FUTURE.
         }
-        ProcessorParamsRangeBearing(std::string _unique_name, const paramsServer& _server) :
+        ProcessorParamsRangeBearing(std::string _unique_name, const ParamsServer& _server) :
                 ProcessorParamsBase(_unique_name, _server)
         {
             //
@@ -54,7 +54,7 @@ class ProcessorRangeBearing : public ProcessorBase
                                        const ProcessorParamsBasePtr _params,
                                        const SensorBasePtr sensor_ptr = nullptr);
         static ProcessorBasePtr createAutoConf(const std::string& _unique_name,
-                                          const paramsServer& _server,
+                                          const ParamsServer& _server,
                                           const SensorBasePtr _sensor_ptr = nullptr);
 
     protected:
diff --git a/hello_wolf/sensor_range_bearing.cpp b/hello_wolf/sensor_range_bearing.cpp
index 878f08078fc69a5e20c27c99d2b17744a39db096..964b909338dfd1062012c73e1aaf0a7b33999295 100644
--- a/hello_wolf/sensor_range_bearing.cpp
+++ b/hello_wolf/sensor_range_bearing.cpp
@@ -43,7 +43,7 @@ SensorBasePtr SensorRangeBearing::create(const std::string& _unique_name, //
 }
 
 SensorBasePtr SensorRangeBearing::createAutoConf(const std::string& _unique_name, //
-                                            const paramsServer& _server)
+                                            const ParamsServer& _server)
 {
     IntrinsicsRangeBearing intr(_unique_name, _server);
     Eigen::Vector2s noise_std(intr.noise_range_metres_std, intr.noise_bearing_degrees_std);
diff --git a/hello_wolf/sensor_range_bearing.h b/hello_wolf/sensor_range_bearing.h
index 0a46b466e5470fcd89cd6874bdfb73dab8f5fae6..161818df65a56f5b2df02d9a66327a71e80a63a0 100644
--- a/hello_wolf/sensor_range_bearing.h
+++ b/hello_wolf/sensor_range_bearing.h
@@ -23,7 +23,7 @@ struct IntrinsicsRangeBearing : public IntrinsicsBase
     {
         //DEFINED FOR COMPATIBILITY PURPOSES. TO BE REMOVED IN THE FUTURE.
     }
-    IntrinsicsRangeBearing(std::string _unique_name, const paramsServer& _server):
+    IntrinsicsRangeBearing(std::string _unique_name, const ParamsServer& _server):
         IntrinsicsBase(_unique_name, _server)
     {
         noise_range_metres_std = _server.getParam<Scalar>(_unique_name + "/noise range metres std", "0.05");
@@ -50,7 +50,7 @@ class SensorRangeBearing : public SensorBase
                                     const Eigen::VectorXs& _extrinsics, //
                                     const IntrinsicsBasePtr _intrinsics);
         static SensorBasePtr createAutoConf(const std::string& _unique_name, //
-                                       const paramsServer& _server);
+                                       const ParamsServer& _server);
 };
 
 } /* namespace wolf */
diff --git a/include/core/ceres_wrapper/ceres_manager.h b/include/core/ceres_wrapper/ceres_manager.h
index 413ecce13ebd2bb179134e255fe1d1af228efe13..a31f5347c2ebc0ca9ce349111d0207d1c5542458 100644
--- a/include/core/ceres_wrapper/ceres_manager.h
+++ b/include/core/ceres_wrapper/ceres_manager.h
@@ -46,7 +46,7 @@ class CeresManager : public SolverManager
 
         ~CeresManager();
 
-        static SolverManagerPtr create(const ProblemPtr& wolf_problem, const paramsServer& _server);
+        static SolverManagerPtr create(const ProblemPtr& wolf_problem, const ParamsServer& _server);
 
         ceres::Solver::Summary getSummary();
 
diff --git a/include/core/common/params_base.h b/include/core/common/params_base.h
index 66034e29fd3e91ad28c2a08fea6a93eb0557bd90..ac9175668b12497d09017387fe7e9c1f1240b13e 100644
--- a/include/core/common/params_base.h
+++ b/include/core/common/params_base.h
@@ -7,7 +7,7 @@ namespace wolf {
   struct ParamsBase
   {
     ParamsBase() = default;
-    ParamsBase(std::string _unique_name, const paramsServer&)
+    ParamsBase(std::string _unique_name, const ParamsServer&)
     {
       //
     }
diff --git a/include/core/problem/problem.h b/include/core/problem/problem.h
index 6aca54c5d7109822c26aede36da25ecbe58e5491..d1aaba40fa7ff48ee93c83b625f62a80ba52d382 100644
--- a/include/core/problem/problem.h
+++ b/include/core/problem/problem.h
@@ -63,7 +63,7 @@ class Problem : public std::enable_shared_from_this<Problem>
 
     public:
         static ProblemPtr create(const std::string& _frame_structure, SizeEigen _dim); // USE THIS AS A CONSTRUCTOR!
-        static ProblemPtr autoSetup(paramsServer &_server);
+        static ProblemPtr autoSetup(ParamsServer &_server);
         virtual ~Problem();
 
         // Properties -----------------------------------------
@@ -101,7 +101,7 @@ class Problem : public std::enable_shared_from_this<Problem>
         */
         SensorBasePtr installSensor(const std::string& _sen_type, //
                                     const std::string& _unique_sensor_name,
-                                    const paramsServer& _server);
+                                    const ParamsServer& _server);
         /** \brief get a sensor pointer by its name
          * \param _sensor_name The sensor name, as it was installed with installSensor()
          */
@@ -141,7 +141,7 @@ class Problem : public std::enable_shared_from_this<Problem>
         ProcessorBasePtr installProcessor(const std::string& _prc_type, //
                                           const std::string& _unique_processor_name, //
                                           const std::string& _corresponding_sensor_name, //
-                                          const paramsServer& _server);
+                                          const ParamsServer& _server);
     protected:
         /** \brief Set the processor motion
          *
diff --git a/include/core/processor/autoconf_processor_factory.h b/include/core/processor/autoconf_processor_factory.h
index 0fc1b5de4ac4722bf204959483ab35cc392a6ac5..051b8d8578544f0fb4c195e5e591064b6b6f116f 100644
--- a/include/core/processor/autoconf_processor_factory.h
+++ b/include/core/processor/autoconf_processor_factory.h
@@ -167,7 +167,7 @@ namespace wolf
 
 typedef Factory<ProcessorBase,
         const std::string&,
-        const paramsServer&,
+        const ParamsServer&,
         const SensorBasePtr> AutoConfProcessorFactory;
 template<>
 inline std::string AutoConfProcessorFactory::getClass()
diff --git a/include/core/processor/processor_base.h b/include/core/processor/processor_base.h
index b2027b3d3b07d41af584043e69ddf7abd9ecfa80..3e555eb2ee5dbb569f1fa613e4330d4803db0272 100644
--- a/include/core/processor/processor_base.h
+++ b/include/core/processor/processor_base.h
@@ -176,7 +176,7 @@ struct ProcessorParamsBase : public ParamsBase
     {
       //
     }
-    ProcessorParamsBase(std::string _unique_name, const paramsServer& _server):
+    ProcessorParamsBase(std::string _unique_name, const ParamsServer& _server):
         ParamsBase(_unique_name, _server)
     {
         voting_active = _server.getParam<bool>(_unique_name + "/voting_active", "false");
diff --git a/include/core/processor/processor_diff_drive.h b/include/core/processor/processor_diff_drive.h
index 78ef6ca50c80e653f7143ebe72e310b859d7a18f..831fec13696365facbee70749bc197d5d7c3f3cd 100644
--- a/include/core/processor/processor_diff_drive.h
+++ b/include/core/processor/processor_diff_drive.h
@@ -20,7 +20,7 @@ struct ProcessorParamsDiffDrive : public ProcessorParamsMotion
 {
   Scalar unmeasured_perturbation_std = 0.0001;
   ProcessorParamsDiffDrive() = default;
-  ProcessorParamsDiffDrive(std::string _unique_name, const paramsServer& _server):
+  ProcessorParamsDiffDrive(std::string _unique_name, const ParamsServer& _server):
     ProcessorParamsMotion(_unique_name, _server)
   {
     unmeasured_perturbation_std = _server.getParam<Scalar>(_unique_name + "/unmeasured_perturbation_std", "0.0001");
diff --git a/include/core/processor/processor_motion.h b/include/core/processor/processor_motion.h
index 15f0ca9004ffc8ca36efadf233eb9a0bfbca384d..c7fc1771fa68882ac8f05d8d139dec0c3cbbfcef 100644
--- a/include/core/processor/processor_motion.h
+++ b/include/core/processor/processor_motion.h
@@ -30,7 +30,7 @@ struct ProcessorParamsMotion : public ProcessorParamsBase
         Scalar angle_turned     = 0.5;
         Scalar unmeasured_perturbation_std  = 1e-4;
         ProcessorParamsMotion() = default;
-        ProcessorParamsMotion(std::string _unique_name, const paramsServer& _server):
+        ProcessorParamsMotion(std::string _unique_name, const ParamsServer& _server):
             ProcessorParamsBase(_unique_name, _server)
         {
           max_time_span   = _server.getParam<Scalar>(_unique_name + "/max_time_span", "0.5");
diff --git a/include/core/processor/processor_odom_2D.h b/include/core/processor/processor_odom_2D.h
index 8e6c9ee6b2a8debaa727ef8128c47e8c20b2d3c4..7c7c1cd0a431d4c4c0053598fa9567854cc09742 100644
--- a/include/core/processor/processor_odom_2D.h
+++ b/include/core/processor/processor_odom_2D.h
@@ -23,7 +23,7 @@ struct ProcessorParamsOdom2D : public ProcessorParamsMotion
 {
         Scalar cov_det = 1.0;      // 1 rad^2
         ProcessorParamsOdom2D() = default;
-        ProcessorParamsOdom2D(std::string _unique_name, const wolf::paramsServer & _server) :
+        ProcessorParamsOdom2D(std::string _unique_name, const wolf::ParamsServer & _server) :
                 ProcessorParamsMotion(_unique_name, _server)
         {
             cov_det = _server.getParam<Scalar>(_unique_name + "/cov_det", "1.0");
@@ -92,7 +92,7 @@ class ProcessorOdom2D : public ProcessorMotion
         // Factory method
     public:
         static ProcessorBasePtr create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, const SensorBasePtr sensor_ptr = nullptr);
-        static ProcessorBasePtr createAutoConf(const std::string& _unique_name, const paramsServer& _server, const SensorBasePtr sensor_ptr = nullptr);
+        static ProcessorBasePtr createAutoConf(const std::string& _unique_name, const ParamsServer& _server, const SensorBasePtr sensor_ptr = nullptr);
 };
 
 inline Eigen::VectorXs ProcessorOdom2D::deltaZero() const
diff --git a/include/core/processor/processor_odom_3D.h b/include/core/processor/processor_odom_3D.h
index 1c70a3b3385c82116609fa47d3897ca82d89f800..759912f27680d5947352d599a889985b0e81d2b3 100644
--- a/include/core/processor/processor_odom_3D.h
+++ b/include/core/processor/processor_odom_3D.h
@@ -22,7 +22,7 @@ WOLF_STRUCT_PTR_TYPEDEFS(ProcessorParamsOdom3D);
 struct ProcessorParamsOdom3D : public ProcessorParamsMotion
 {
   ProcessorParamsOdom3D() = default;
-  ProcessorParamsOdom3D(std::string _unique_name, const paramsServer& _server):
+  ProcessorParamsOdom3D(std::string _unique_name, const ParamsServer& _server):
     ProcessorParamsMotion(_unique_name, _server)
   {
     //
diff --git a/include/core/processor/processor_tracker.h b/include/core/processor/processor_tracker.h
index bab37b3a271f53731e8a2777112f115f10497ed8..3915ba33f8b9899deb99b6436b66a5b5c9ef9f4f 100644
--- a/include/core/processor/processor_tracker.h
+++ b/include/core/processor/processor_tracker.h
@@ -21,7 +21,7 @@ struct ProcessorParamsTracker : public ProcessorParamsBase
     int max_new_features;                   ///< maximum nbr. of new features to be processed when adding a keyframe (-1: unlimited. 0: none.)
 
     ProcessorParamsTracker() = default;
-    ProcessorParamsTracker(std::string _unique_name, const wolf::paramsServer & _server):
+    ProcessorParamsTracker(std::string _unique_name, const wolf::ParamsServer & _server):
         ProcessorParamsBase(_unique_name, _server)
     {
         min_features_for_keyframe = _server.getParam<unsigned int>(_unique_name + "/min_features_for_keyframe", "1");
diff --git a/include/core/sensor/autoconf_sensor_factory.h b/include/core/sensor/autoconf_sensor_factory.h
index e52366e334187e9f318bb9a514c1e7fdde6b3b21..2d36307874fddbe2836ea1f905719007934cf679 100644
--- a/include/core/sensor/autoconf_sensor_factory.h
+++ b/include/core/sensor/autoconf_sensor_factory.h
@@ -210,7 +210,7 @@ namespace wolf
 
 typedef Factory<SensorBase,
                 const std::string&,
-                const paramsServer&> AutoConfSensorFactory;
+                const ParamsServer&> AutoConfSensorFactory;
 
 template<>
 inline std::string AutoConfSensorFactory::getClass()
diff --git a/include/core/sensor/sensor_diff_drive.h b/include/core/sensor/sensor_diff_drive.h
index 114be0e4d3342ed4936be3d0d9a6938e0735f898..e6737438050dba3f7bff3b51130937572cc5ef23 100644
--- a/include/core/sensor/sensor_diff_drive.h
+++ b/include/core/sensor/sensor_diff_drive.h
@@ -38,7 +38,7 @@ struct IntrinsicsDiffDrive : public IntrinsicsBase
     {
         //DEFINED FOR COMPATIBILITY PURPOSES. TO BE REMOVED IN THE FUTURE.
     }
-    IntrinsicsDiffDrive(std::string _unique_name, const paramsServer& _server):
+    IntrinsicsDiffDrive(std::string _unique_name, const ParamsServer& _server):
         IntrinsicsBase(_unique_name, _server)
     {
 
diff --git a/include/core/sensor/sensor_odom_2D.h b/include/core/sensor/sensor_odom_2D.h
index 94bbd03d3778221d1a7a2a0d51935f993e9ddbb7..efe8d7e4daa8705ebe2e9ecb07be0f1d4a377d65 100644
--- a/include/core/sensor/sensor_odom_2D.h
+++ b/include/core/sensor/sensor_odom_2D.h
@@ -19,7 +19,7 @@ struct IntrinsicsOdom2D : public IntrinsicsBase
     {
         //DEFINED FOR COMPATIBILITY PURPOSES. TO BE REMOVED IN THE FUTURE.
     }
-    IntrinsicsOdom2D(std::string _unique_name, const paramsServer& _server):
+    IntrinsicsOdom2D(std::string _unique_name, const ParamsServer& _server):
         IntrinsicsBase(_unique_name, _server)
     {
         k_disp_to_disp = _server.getParam<Scalar>(_unique_name + "/k_disp_to_disp");
@@ -63,7 +63,7 @@ class SensorOdom2D : public SensorBase
 
 	public:
         static SensorBasePtr create(const std::string& _unique_name, const Eigen::VectorXs& _extrinsics_pq, const IntrinsicsBasePtr _intrinsics);
-        static SensorBasePtr createAutoConf(const std::string& _unique_name, const paramsServer& _server);
+        static SensorBasePtr createAutoConf(const std::string& _unique_name, const ParamsServer& _server);
 
 };
 
diff --git a/include/core/sensor/sensor_odom_3D.h b/include/core/sensor/sensor_odom_3D.h
index b5ec6717fe701acf3c8b4ca8c49b3bd81d892b7c..2fab5f065909452622a8760e5f9a976c63327e89 100644
--- a/include/core/sensor/sensor_odom_3D.h
+++ b/include/core/sensor/sensor_odom_3D.h
@@ -27,7 +27,7 @@ struct IntrinsicsOdom3D : public IntrinsicsBase
     {
         //DEFINED FOR COMPATIBILITY PURPOSES. TO BE REMOVED IN THE FUTURE.
     }
-    IntrinsicsOdom3D(std::string _unique_name, const paramsServer& _server):
+    IntrinsicsOdom3D(std::string _unique_name, const ParamsServer& _server):
         IntrinsicsBase(_unique_name, _server)
     {
         k_disp_to_disp = _server.getParam<Scalar>(_unique_name + "/k_disp_to_disp");
diff --git a/include/core/solver/solver_factory.h b/include/core/solver/solver_factory.h
index 36a551b668a1f4f1c595d98ea61b1534f54c670e..5205ad5c9e1ff18d545dcd43555ecb47b4d780f8 100644
--- a/include/core/solver/solver_factory.h
+++ b/include/core/solver/solver_factory.h
@@ -211,7 +211,7 @@ namespace wolf
 
 typedef Factory<SolverManager,
                 const ProblemPtr&,
-                const paramsServer&> SolverFactory;
+                const ParamsServer&> SolverFactory;
 
 template<>
 inline std::string SolverFactory::getClass()
diff --git a/include/core/utils/params_server.hpp b/include/core/utils/params_server.hpp
index 4a58b290b31d38b29cea102431e2335c2597f1ee..94e8f1a8468a89749685ad471ee9b234e392f84d 100644
--- a/include/core/utils/params_server.hpp
+++ b/include/core/utils/params_server.hpp
@@ -9,8 +9,7 @@
 #include <map>
 
 namespace wolf{
-
-class paramsServer{
+class ParamsServer{
     struct ParamsInitSensor{
         std::string _type;
         std::string _name;
@@ -25,16 +24,13 @@ class paramsServer{
     std::map<std::string, std::string> _params;
     std::map<std::string,ParamsInitSensor> _paramsSens;
     std::map<std::string,ParamsInitProcessor> _paramsProc;
-
-    public:
-
-    paramsServer(){
+public:
+    ParamsServer(){
         _params = std::map<std::string, std::string>();
         _paramsSens = std::map<std::string,ParamsInitSensor>();
         _paramsProc = std::map<std::string,ParamsInitProcessor>();
     }
-
-    paramsServer(std::map<std::string, std::string> params,
+    ParamsServer(std::map<std::string, std::string> params,
                  std::vector<std::array<std::string,2>> sensors,
                  std::vector<std::array<std::string,3>> procs){
         _params = params;
@@ -49,15 +45,7 @@ class paramsServer{
             _paramsProc.insert(std::pair<std::string,ParamsInitProcessor>(it.at(1), pProcs));
         }
     }
-
-//    paramsServer(std::string _file)
-//    {
-//        parserYAML parser = parserYAML(_file);
-//        parser.parse();
-//        paramsServer(parser.getParams(), parser.sensorsSerialization(), parser.processorsSerialization());
-//    }
-
-    ~paramsServer(){
+    ~ParamsServer(){
         //
     }
 
diff --git a/include/core/yaml/parser_yaml.hpp b/include/core/yaml/parser_yaml.hpp
index b81813b07a8370e0a42ffcb8a25ce04485927466..3af5c1630da3e1bbeba9ec0ec4c6cc8ab5c63cfb 100644
--- a/include/core/yaml/parser_yaml.hpp
+++ b/include/core/yaml/parser_yaml.hpp
@@ -78,7 +78,7 @@ namespace {
         return "[" + accumulated + "]";
     }
 }
-class parserYAML {
+class ParserYAML {
     struct ParamsInitSensor{
         std::string _type;
         std::string _name;
@@ -102,7 +102,7 @@ class parserYAML {
     YAML::Node problem;
     std::string generatePath(std::string);
 public:
-    parserYAML(){
+    ParserYAML(){
         _params = std::map<std::string, std::string>();
         _active_name = "";
         _paramsSens = std::vector<ParamsInitSensor>();
@@ -113,7 +113,7 @@ public:
         _relative_path = false;
         _callbacks = std::vector<std::array<std::string, 3>>();
     }
-    parserYAML(std::string file){
+    ParserYAML(std::string file){
         _params = std::map<std::string, std::string>();
         _active_name = "";
         _paramsSens = std::vector<ParamsInitSensor>();
@@ -124,7 +124,7 @@ public:
         _relative_path = false;
         _callbacks = std::vector<std::array<std::string, 3>>();
     }
-    parserYAML(std::string file, std::string path_root){
+    ParserYAML(std::string file, std::string path_root){
         _params = std::map<std::string, std::string>();
         _active_name = "";
         _paramsSens = std::vector<ParamsInitSensor>();
@@ -141,7 +141,7 @@ public:
         }
         _callbacks = std::vector<std::array<std::string, 3>>();
     }
-    ~parserYAML(){
+    ~ParserYAML(){
         //
     }
     void walkTree(std::string file);
@@ -160,7 +160,7 @@ public:
     void parse();
     std::map<std::string, std::string> fetchAsMap(YAML::Node);
 };
-std::string parserYAML::generatePath(std::string path){
+std::string ParserYAML::generatePath(std::string path){
     std::regex r("^/.*");
     if(std::regex_match(path, r)){
       std::cout << "Generating " + path << std::endl;
@@ -170,25 +170,25 @@ std::string parserYAML::generatePath(std::string path){
         return _path_root + path;
     }
 }
-std::string parserYAML::tagsToString(std::vector<std::string> &tags){
+std::string ParserYAML::tagsToString(std::vector<std::string> &tags){
     std::string hdr = "";
     for(auto it : tags){
         hdr = hdr + "/" + it;
     }
     return hdr;
 }
-void parserYAML::walkTree(std::string file){
+void ParserYAML::walkTree(std::string file){
     YAML::Node n;
     n = YAML::LoadFile(generatePath(file));
     std::vector<std::string> hdrs = std::vector<std::string>();
     walkTreeR(n, hdrs, "");
 }
-void parserYAML::walkTree(std::string file, std::vector<std::string>& tags){
+void ParserYAML::walkTree(std::string file, std::vector<std::string>& tags){
     YAML::Node n;
     n = YAML::LoadFile(generatePath(file));
     walkTreeR(n, tags, "");
 }
-void parserYAML::walkTree(std::string file, std::vector<std::string>& tags, std::string hdr){
+void ParserYAML::walkTree(std::string file, std::vector<std::string>& tags, std::string hdr){
     YAML::Node n;
     n = YAML::LoadFile(generatePath(file));
     walkTreeR(n, tags, hdr);
@@ -198,7 +198,7 @@ void parserYAML::walkTree(std::string file, std::vector<std::string>& tags, std:
 * @param tags represents the path from the root of the YAML tree to the current node
 * @param hdr is the name of the current YAML node
 */
-void parserYAML::walkTreeR(YAML::Node n, std::vector<std::string>& tags, std::string hdr){
+void ParserYAML::walkTreeR(YAML::Node n, std::vector<std::string>& tags, std::string hdr){
     switch (n.Type()) {
     case YAML::NodeType::Scalar : {
         std::regex r("^@.*");
@@ -279,13 +279,13 @@ void parserYAML::walkTreeR(YAML::Node n, std::vector<std::string>& tags, std::st
         break;
     }
 }
-void parserYAML::updateActiveName(std::string tag){
+void ParserYAML::updateActiveName(std::string tag){
     this->_active_name = tag;
 }
 /** @Brief Parse the sensors, processors, callbacks and files elements of the YAML file. We assume that these elements
     are defined at the top level of the YAML file.
  * @param file is the path to the YAML file */
-void parserYAML::parseFirstLevel(std::string file){
+void ParserYAML::parseFirstLevel(std::string file){
     YAML::Node n;
     n = YAML::LoadFile(generatePath(file));
 
@@ -309,32 +309,32 @@ void parserYAML::parseFirstLevel(std::string file){
     }
     _params.insert(std::pair<std::string,std::string>("files", wolf::converter<std::string>::convert(_files)));
 }
-std::vector<std::array<std::string, 2>> parserYAML::sensorsSerialization(){
+std::vector<std::array<std::string, 2>> ParserYAML::sensorsSerialization(){
     std::vector<std::array<std::string, 2>> aux = std::vector<std::array<std::string, 2>>();
     for(auto it : this->_paramsSens)
         aux.push_back({{it._type,it._name}});
     return aux;
 }
-std::vector<std::array<std::string, 3>> parserYAML::processorsSerialization(){
+std::vector<std::array<std::string, 3>> ParserYAML::processorsSerialization(){
     std::vector<std::array<std::string, 3>> aux = std::vector<std::array<std::string, 3>>();
     for(auto it : this->_paramsProc)
         aux.push_back({{it._type,it._name,it._name_assoc_sensor}});
     return aux;
 }
-std::vector<std::string> parserYAML::getFiles(){
+std::vector<std::string> ParserYAML::getFiles(){
     return this->_files;
 }
-std::vector<std::array<std::string, 3>> parserYAML::getCallbacks(){
+std::vector<std::array<std::string, 3>> ParserYAML::getCallbacks(){
     return this->_callbacks;
 }
-std::vector<std::array<std::string, 2>> parserYAML::getProblem(){
+std::vector<std::array<std::string, 2>> ParserYAML::getProblem(){
     return std::vector<std::array<std::string, 2>>();
 }
-std::map<std::string,std::string> parserYAML::getParams(){
+std::map<std::string,std::string> ParserYAML::getParams(){
     std::map<std::string,std::string> rtn = _params;
     return rtn;
 }
-void parserYAML::parse(){
+void ParserYAML::parse(){
     this->parseFirstLevel(this->_file);
 
     if(this->problem.Type() != YAML::NodeType::Undefined){
@@ -376,7 +376,7 @@ std::string fetchMapEntry(YAML::Node n){
  *  @param n the node representing a map
  *  @return std::map<std::string, std::string> populated with the key,value pairs in n
  */
-std::map<std::string, std::string> parserYAML::fetchAsMap(YAML::Node n){
+std::map<std::string, std::string> ParserYAML::fetchAsMap(YAML::Node n){
     assert(n.Type() == YAML::NodeType::Map && "trying to fetch as Map a non-Map node");
     auto m = std::map<std::string, std::string>();
     for(const auto& kv : n){
diff --git a/src/ceres_wrapper/ceres_manager.cpp b/src/ceres_wrapper/ceres_manager.cpp
index 681f3d59ee5e3f674d277182790d9247ac41aa4c..1528c15e708d61f13ed8a5d1084207287722ba6b 100644
--- a/src/ceres_wrapper/ceres_manager.cpp
+++ b/src/ceres_wrapper/ceres_manager.cpp
@@ -40,7 +40,7 @@ CeresManager::~CeresManager()
         removeFactor(fac_2_residual_idx_.begin()->first);
 }
 
-SolverManagerPtr CeresManager::create(const ProblemPtr &wolf_problem, const paramsServer &_server)
+SolverManagerPtr CeresManager::create(const ProblemPtr &wolf_problem, const ParamsServer &_server)
 {
     ceres::Solver::Options opt;
     opt.max_num_iterations = _server.getParam<int>("max_num_iterations","1000");
diff --git a/src/problem/problem.cpp b/src/problem/problem.cpp
index 0e59e89a53e1c85bea2bb0a370bd30b20fcdc0c4..eab55cc02cf4d12045fddf7813c4d7cdf87f35b4 100644
--- a/src/problem/problem.cpp
+++ b/src/problem/problem.cpp
@@ -74,7 +74,7 @@ ProblemPtr Problem::create(const std::string& _frame_structure, SizeEigen _dim)
     return p->shared_from_this();
 }
 
-ProblemPtr Problem::autoSetup(paramsServer &_server)
+ProblemPtr Problem::autoSetup(ParamsServer &_server)
 {
     // Problem structure and dimension
     std::string frame_structure = _server.getParam<std::string> ("problem/frame structure", "PO");
@@ -158,7 +158,7 @@ SensorBasePtr Problem::installSensor(const std::string& _sen_type, //
 
 SensorBasePtr Problem::installSensor(const std::string& _sen_type, //
                                      const std::string& _unique_sensor_name, //
-                                     const paramsServer& _server)
+                                     const ParamsServer& _server)
 {
     SensorBasePtr sen_ptr = AutoConfSensorFactory::get().create(uppercase(_sen_type), _unique_sensor_name, _server);
     sen_ptr->link(getHardware());
@@ -213,7 +213,7 @@ ProcessorBasePtr Problem::installProcessor(const std::string& _prc_type, //
 ProcessorBasePtr Problem::installProcessor(const std::string& _prc_type, //
                                            const std::string& _unique_processor_name, //
                                            const std::string& _corresponding_sensor_name, //
-                                           const paramsServer& _server)
+                                           const ParamsServer& _server)
 {
     SensorBasePtr sen_ptr = getSensor(_corresponding_sensor_name);
     if (sen_ptr == nullptr)
diff --git a/src/processor/processor_odom_2D.cpp b/src/processor/processor_odom_2D.cpp
index 38dccacd9bf4d2d1512de442f79734b30d4c02a6..48a2747789e943fc76a171c894c5802635bc0093 100644
--- a/src/processor/processor_odom_2D.cpp
+++ b/src/processor/processor_odom_2D.cpp
@@ -195,7 +195,7 @@ ProcessorBasePtr ProcessorOdom2D::create(const std::string& _unique_name, const
 
     return prc_ptr;
 }
-ProcessorBasePtr ProcessorOdom2D::createAutoConf(const std::string& _unique_name, const paramsServer& _server, const SensorBasePtr sensor_ptr)
+ProcessorBasePtr ProcessorOdom2D::createAutoConf(const std::string& _unique_name, const ParamsServer& _server, const SensorBasePtr sensor_ptr)
 {
 
     ProcessorOdom2DPtr prc_ptr;
diff --git a/src/sensor/sensor_odom_2D.cpp b/src/sensor/sensor_odom_2D.cpp
index f6b408c7ec9bb68544e5b5f24019bde710954c93..fd4427abec8211ddebf95b2172409692f807e72d 100644
--- a/src/sensor/sensor_odom_2D.cpp
+++ b/src/sensor/sensor_odom_2D.cpp
@@ -58,7 +58,7 @@ SensorBasePtr SensorOdom2D::create(const std::string& _unique_name, const Eigen:
     return odo;
 }
 
-SensorBasePtr SensorOdom2D::createAutoConf(const std::string& _unique_name, const paramsServer& _server)
+SensorBasePtr SensorOdom2D::createAutoConf(const std::string& _unique_name, const ParamsServer& _server)
 {
     // Eigen::VectorXs _extrinsics_po = Eigen::Vector3s(0,0,0);
     Eigen::VectorXs _extrinsics_po = _server.getParam<Eigen::VectorXs>(_unique_name + "/extrinsic/pos", "[0,0,0]");
diff --git a/test/dummy/processor_tracker_feature_dummy.h b/test/dummy/processor_tracker_feature_dummy.h
index 3621ce3017d8a362c999f9376908ab4e0445b910..217196b7e26542f39d60fbfb1f53f01214e20ff9 100644
--- a/test/dummy/processor_tracker_feature_dummy.h
+++ b/test/dummy/processor_tracker_feature_dummy.h
@@ -22,7 +22,7 @@ struct ProcessorParamsTrackerFeatureDummy : public ProcessorParamsTrackerFeature
     unsigned int n_tracks_lost; ///< number of tracks lost each time track is called (the first ones)
 
     ProcessorParamsTrackerFeatureDummy() = default;
-    ProcessorParamsTrackerFeatureDummy(std::string _unique_name, const wolf::paramsServer & _server):
+    ProcessorParamsTrackerFeatureDummy(std::string _unique_name, const wolf::ParamsServer & _server):
         ProcessorParamsTrackerFeature(_unique_name, _server)
     {
         n_tracks_lost = _server.getParam<unsigned int>(_unique_name + "/n_tracks_lost", "1");
diff --git a/test/dummy/processor_tracker_landmark_dummy.h b/test/dummy/processor_tracker_landmark_dummy.h
index 7dce7d14e23e77df062ff2774630767d1d2d6b48..f79b2da401c1f925d7f8629f1e4b9f1cc4c14b3b 100644
--- a/test/dummy/processor_tracker_landmark_dummy.h
+++ b/test/dummy/processor_tracker_landmark_dummy.h
@@ -20,7 +20,7 @@ struct ProcessorParamsTrackerLandmarkDummy : public ProcessorParamsTrackerLandma
     unsigned int n_landmarks_lost; ///< number of landmarks lost each time findLandmarks is called (the last ones)
 
     ProcessorParamsTrackerLandmarkDummy() = default;
-    ProcessorParamsTrackerLandmarkDummy(std::string _unique_name, const wolf::paramsServer & _server):
+    ProcessorParamsTrackerLandmarkDummy(std::string _unique_name, const wolf::ParamsServer & _server):
         ProcessorParamsTrackerLandmark(_unique_name, _server)
     {
         n_landmarks_lost = _server.getParam<unsigned int>(_unique_name + "/n_landmarks_lost", "1");
diff --git a/test/gtest_param_server.cpp b/test/gtest_param_server.cpp
index dc5f5a5aa40962abba31b3e21ccdaa3aeb2d928a..00c6c099f6542e6e1f08dc9e2e451d8d2d055e81 100644
--- a/test/gtest_param_server.cpp
+++ b/test/gtest_param_server.cpp
@@ -9,9 +9,9 @@ using namespace wolf;
 
 std::string wolf_root = _WOLF_ROOT_DIR;
 
-parserYAML parse(string _file, string _path_root)
+ParserYAML parse(string _file, string _path_root)
 {
-  parserYAML parser = parserYAML(_file, _path_root);
+  ParserYAML parser = ParserYAML(_file, _path_root);
   parser.parse();
   return parser;
 }
@@ -20,7 +20,7 @@ TEST(ParamsServer, Default)
 {
   auto parser = parse("test/yaml/params1.yaml", wolf_root);
   auto params = parser.getParams();
-  paramsServer server = paramsServer(params, parser.sensorsSerialization(), parser.processorsSerialization());
+  ParamsServer server = ParamsServer(params, parser.sensorsSerialization(), parser.processorsSerialization());
   EXPECT_EQ(server.getParam<double>("should_not_exist", "2.6"), 2.6);
   EXPECT_EQ(server.getParam<bool>("my_proc_test/voting_active", "true"), false);
   EXPECT_NE(server.getParam<unsigned int>("my_proc_test/time_tolerance", "23"), 23);
diff --git a/test/gtest_parser_yaml.cpp b/test/gtest_parser_yaml.cpp
index d3ba3a40587e1e732cccf4d1a6c0d39e58a0207f..5102157d05185f93874e9ec0e89e9141feaf230e 100644
--- a/test/gtest_parser_yaml.cpp
+++ b/test/gtest_parser_yaml.cpp
@@ -8,9 +8,9 @@ using namespace wolf;
 
 std::string wolf_root = _WOLF_ROOT_DIR;
 
-parserYAML parse(string _file, string _path_root)
+ParserYAML parse(string _file, string _path_root)
 {
-  parserYAML parser = parserYAML(_file, _path_root);
+  ParserYAML parser = ParserYAML(_file, _path_root);
   parser.parse();
   return parser;
 }