diff --git a/include/core/common/node_base.h b/include/core/common/node_base.h
index 59b5123c4971be28214e50021fe1fff0dc21d537..3902dd0f05827eb30ac8b06e909a9b5272933ff0 100644
--- a/include/core/common/node_base.h
+++ b/include/core/common/node_base.h
@@ -13,7 +13,7 @@ namespace wolf {
  *  - A unique ID. The class implements the ID factory.
  *
  *  - A unique category name, strictly within this range of possibilities:
- *    - "BASE" -- should not be used
+ *    - "NodeBase" -- should not be used
  *    - "PROBLEM"
  *    - "HARDWARE"
  *    - "SENSOR"
diff --git a/include/core/factor/factor_diff_drive.h b/include/core/factor/factor_diff_drive.h
index 274c226ed779ced623f5ae8c0eb76c0e5bc4d291..687a24728a081025a0f80f9780cb0df925109dd6 100644
--- a/include/core/factor/factor_diff_drive.h
+++ b/include/core/factor/factor_diff_drive.h
@@ -53,7 +53,7 @@ class FactorDiffDrive : public FactorAutodiff<FactorDiffDrive,
                         const ProcessorBasePtr& _processor_ptr = nullptr,
                         const bool _apply_loss_function = false,
                         const FactorStatus _status = FAC_ACTIVE) :
-                Base("DIFF DRIVE",
+                Base("FactorDiffDrive",
                      _capture_origin_ptr->getFrame(),
                      _capture_origin_ptr,
                      nullptr,
diff --git a/include/core/factor/factor_odom_2D.h b/include/core/factor/factor_odom_2D.h
index e5cfd57a69329ca9c82c9019f29d4ee591b27f77..ff322cf51790789313a289a3e49f5379fac6add0 100644
--- a/include/core/factor/factor_odom_2D.h
+++ b/include/core/factor/factor_odom_2D.h
@@ -19,7 +19,7 @@ class FactorOdom2D : public FactorAutodiff<FactorOdom2D, 3, 2, 1, 2, 1>
                          const FrameBasePtr& _frame_other_ptr,
                          const ProcessorBasePtr& _processor_ptr = nullptr,
                          bool _apply_loss_function = false, FactorStatus _status = FAC_ACTIVE) :
-             FactorAutodiff<FactorOdom2D, 3, 2, 1, 2, 1>("ODOM 2D",
+             FactorAutodiff<FactorOdom2D, 3, 2, 1, 2, 1>("FactorOdom2D",
                                                                  _frame_other_ptr, nullptr, nullptr, nullptr,
                                                                  _processor_ptr,
                                                                  _apply_loss_function, _status,
diff --git a/include/core/factor/factor_odom_3D.h b/include/core/factor/factor_odom_3D.h
index 587472541124f2d0d158b3d999c9b65bb1bc5dcb..25d751ca849a6b1ec7650bd01646846570a04680 100644
--- a/include/core/factor/factor_odom_3D.h
+++ b/include/core/factor/factor_odom_3D.h
@@ -75,7 +75,7 @@ inline FactorOdom3D::FactorOdom3D(const FeatureBasePtr& _ftr_current_ptr,
                                           const ProcessorBasePtr& _processor_ptr,
                                           bool _apply_loss_function,
                                           FactorStatus _status) :
-        FactorAutodiff<FactorOdom3D, 6, 3, 4, 3, 4>("ODOM 3D",        // type
+        FactorAutodiff<FactorOdom3D, 6, 3, 4, 3, 4>("FactorOdom3D",        // type
                                         _frame_past_ptr,    // frame other
                                         nullptr,            // capture other
                                         nullptr,            // feature other
diff --git a/include/core/factor/factor_pose_2D.h b/include/core/factor/factor_pose_2D.h
index e4caa3b2dbd2ed26ef8b23a83443b0662b1ec823..520e771471fcc2c7e8f309e8f539530ad6c30d77 100644
--- a/include/core/factor/factor_pose_2D.h
+++ b/include/core/factor/factor_pose_2D.h
@@ -18,7 +18,7 @@ class FactorPose2D: public FactorAutodiff<FactorPose2D,3,2,1>
 {
     public:
         FactorPose2D(FeatureBasePtr _ftr_ptr, bool _apply_loss_function = false, FactorStatus _status = FAC_ACTIVE) :
-                FactorAutodiff<FactorPose2D, 3, 2, 1>("POSE 2D", nullptr, nullptr, nullptr, nullptr, nullptr,_apply_loss_function, _status, _ftr_ptr->getFrame()->getP(), _ftr_ptr->getFrame()->getO())
+                FactorAutodiff<FactorPose2D, 3, 2, 1>("FactorPose2D", nullptr, nullptr, nullptr, nullptr, nullptr,_apply_loss_function, _status, _ftr_ptr->getFrame()->getP(), _ftr_ptr->getFrame()->getO())
         {
 //            std::cout << "created FactorPose2D " << std::endl;
         }
diff --git a/include/core/factor/factor_pose_3D.h b/include/core/factor/factor_pose_3D.h
index d36bcdb32a832695b29bbbe5a0610ded37746218..9f28b946136f75875a630388bb4674ebbf485651 100644
--- a/include/core/factor/factor_pose_3D.h
+++ b/include/core/factor/factor_pose_3D.h
@@ -17,7 +17,7 @@ class FactorPose3D: public FactorAutodiff<FactorPose3D,6,3,4>
     public:
 
         FactorPose3D(FeatureBasePtr _ftr_ptr, bool _apply_loss_function = false, FactorStatus _status = FAC_ACTIVE) :
-            FactorAutodiff<FactorPose3D,6,3,4>("POSE 3D", nullptr, nullptr, nullptr, nullptr, nullptr, _apply_loss_function, _status, _ftr_ptr->getFrame()->getP(), _ftr_ptr->getFrame()->getO())
+            FactorAutodiff<FactorPose3D,6,3,4>("FactorPose3D", nullptr, nullptr, nullptr, nullptr, nullptr, _apply_loss_function, _status, _ftr_ptr->getFrame()->getP(), _ftr_ptr->getFrame()->getO())
         {
             //
         }
diff --git a/include/core/processor/processor_factory.h b/include/core/processor/processor_factory.h
index 1f1d8606c449f9b57625bac9c12f8f9207322d0b..24f074902f56999949d83e9b7b8a412c14e3aa41 100644
--- a/include/core/processor/processor_factory.h
+++ b/include/core/processor/processor_factory.h
@@ -69,7 +69,7 @@ namespace wolf
  * that knows how to create your specific processor, e.g.:
  *
  *     \code
- *     ProcessorFactory::get().registerCreator("ODOM 2D", ProcessorOdom2D::create);
+ *     ProcessorFactory::get().registerCreator("ProcessorOdom2D", ProcessorOdom2D::create);
  *     \endcode
  *
  * The method ProcessorOdom2D::create() exists in the ProcessorOdom2D class as a static method.
@@ -96,7 +96,7 @@ namespace wolf
  * For example, in processor_odom_2D.cpp we find the line:
  *
  *     \code
- *     const bool registered_odom_2D = ProcessorFactory::get().registerCreator("ODOM 2D", ProcessorOdom2D::create);
+ *     const bool registered_odom_2D = ProcessorFactory::get().registerCreator("ProcessorOdom2D", ProcessorOdom2D::create);
  *     \endcode
  *
  * which is a static invocation (i.e., it is placed at global scope outside of the ProcessorOdom2D class).
@@ -107,7 +107,7 @@ namespace wolf
  * It only needs to be passed the string of the processor type.
  *
  *     \code
- *     ProcessorFactory::get().unregisterCreator("ODOM 2D");
+ *     ProcessorFactory::get().unregisterCreator("ProcessorOdom2D");
  *     \endcode
  *
  * #### Creating processors
@@ -117,7 +117,7 @@ namespace wolf
  * To create a ProcessorOdom2D, you type:
  *
  *     \code
- *     ProcessorFactory::get().create("ODOM 2D", "main odometry", params_ptr);
+ *     ProcessorFactory::get().create("ProcessorOdom2D", "main odometry", params_ptr);
  *     \endcode
  *
  * #### Example 1 : using the Factories alone
@@ -132,14 +132,14 @@ namespace wolf
  *     // Note: ProcessorOdom2D::create() is already registered, automatically.
  *
  *     // First create the sensor (See SensorFactory for details)
- *     SensorBasePtr sensor_ptr = SensorFactory::get().create ( "ODOM 2D" , "Main odometer" , extrinsics , &intrinsics );
+ *     SensorBasePtr sensor_ptr = SensorFactory::get().create ( "FactorOdom2D" , "Main odometer" , extrinsics , &intrinsics );
  *
  *     // To create a odometry integrator, provide a type="ODOM 2D", a name="main odometry", and a pointer to the parameters struct:
  *
  *     ProcessorParamsOdom2D  params({...});   // fill in the derived struct (note: ProcessorOdom2D actually has no input params)
  *
  *     ProcessorBasePtr processor_ptr =
- *         ProcessorFactory::get().create ( "ODOM 2D" , "main odometry" , &params );
+ *         ProcessorFactory::get().create ( "ProcessorOdom2D" , "main odometry" , &params );
  *
  *     // Bind processor to sensor
  *     sensor_ptr->addProcessor(processor_ptr);
@@ -158,8 +158,8 @@ namespace wolf
  *     #include "core/problem/problem.h"
  *
  *     Problem problem(FRM_PO_2D);
- *     problem.installSensor    ( "ODOM 2D" , "Main odometer" , extrinsics      , &intrinsics );
- *     problem.installProcessor ( "ODOM 2D" , "Odometry"      , "Main odometer" , &params     );
+ *     problem.installSensor    ( "SensorOdom2D" , "Main odometer" , extrinsics      , &intrinsics );
+ *     problem.installProcessor ( "ProcessorOdom2D" , "Odometry"      , "Main odometer" , &params     );
  *     \endcode
  *
  * You can also check the code in the example file ````src/examples/test_wolf_factories.cpp````.
diff --git a/src/capture/capture_diff_drive.cpp b/src/capture/capture_diff_drive.cpp
index cc81850c8447040d21f7e6cffa4f079c5884ca47..625007b36f72d69fa4f9a7535729dcc29fae9f4e 100644
--- a/src/capture/capture_diff_drive.cpp
+++ b/src/capture/capture_diff_drive.cpp
@@ -13,7 +13,7 @@ CaptureDiffDrive::CaptureDiffDrive(const TimeStamp& _ts,
                                    StateBlockPtr _p_ptr,
                                    StateBlockPtr _o_ptr,
                                    StateBlockPtr _intr_ptr) :
-  CaptureMotion("DIFF DRIVE",
+  CaptureMotion("CaptureDiffDrive",
                 _ts,
                 _sensor_ptr,
                 _data,
diff --git a/src/capture/capture_odom_2D.cpp b/src/capture/capture_odom_2D.cpp
index 36826540a27804e14c61102260bbec24a36df58f..ab9c39b639f55c6b98cc4fecd175fc02169223bb 100644
--- a/src/capture/capture_odom_2D.cpp
+++ b/src/capture/capture_odom_2D.cpp
@@ -14,7 +14,7 @@ CaptureOdom2D::CaptureOdom2D(const TimeStamp& _init_ts,
                              SensorBasePtr _sensor_ptr,
                              const Eigen::VectorXs& _data,
                              CaptureBasePtr _capture_origin_ptr):
-        CaptureMotion("ODOM 2D", _init_ts, _sensor_ptr, _data, 3, 3, _capture_origin_ptr)
+        CaptureMotion("CaptureOdom2D", _init_ts, _sensor_ptr, _data, 3, 3, _capture_origin_ptr)
 {
     //
 }
@@ -24,7 +24,7 @@ CaptureOdom2D::CaptureOdom2D(const TimeStamp& _init_ts,
                              const Eigen::VectorXs& _data,
                              const Eigen::MatrixXs& _data_cov,
                              CaptureBasePtr _capture_origin_ptr):
-        CaptureMotion("ODOM 2D", _init_ts, _sensor_ptr, _data, _data_cov, 3, 3, _capture_origin_ptr)
+        CaptureMotion("CaptureOdom2D", _init_ts, _sensor_ptr, _data, _data_cov, 3, 3, _capture_origin_ptr)
 {
     //
 }
diff --git a/src/capture/capture_odom_3D.cpp b/src/capture/capture_odom_3D.cpp
index 84f263d2cfbd6c97e647b8504322352696d4332d..bbb529ee925c68355717afc4462a0aae8444533a 100644
--- a/src/capture/capture_odom_3D.cpp
+++ b/src/capture/capture_odom_3D.cpp
@@ -14,7 +14,7 @@ CaptureOdom3D::CaptureOdom3D(const TimeStamp& _init_ts,
                              SensorBasePtr _sensor_ptr,
                              const Eigen::VectorXs& _data,
                              CaptureBasePtr _capture_origin_ptr):
-        CaptureMotion("ODOM 3D", _init_ts, _sensor_ptr, _data, 7, 6, _capture_origin_ptr)
+        CaptureMotion("CaptureOdom3D", _init_ts, _sensor_ptr, _data, 7, 6, _capture_origin_ptr)
 {
     //
 }
@@ -24,7 +24,7 @@ CaptureOdom3D::CaptureOdom3D(const TimeStamp& _init_ts,
                              const Eigen::VectorXs& _data,
                              const Eigen::MatrixXs& _data_cov,
                              CaptureBasePtr _capture_origin_ptr):
-        CaptureMotion("ODOM 3D", _init_ts, _sensor_ptr, _data, _data_cov, 7, 6, _capture_origin_ptr)
+        CaptureMotion("CaptureOdom3D", _init_ts, _sensor_ptr, _data, _data_cov, 7, 6, _capture_origin_ptr)
 {
     //
 }
diff --git a/src/capture/capture_pose.cpp b/src/capture/capture_pose.cpp
index 46177687a1cbaab1a507ba3ac4e091aec7d9b7fd..3771b44fbba116020c82456804960bff07f18808 100644
--- a/src/capture/capture_pose.cpp
+++ b/src/capture/capture_pose.cpp
@@ -3,7 +3,7 @@
 namespace wolf{
 
 CapturePose::CapturePose(const TimeStamp& _ts, SensorBasePtr _sensor_ptr, const Eigen::VectorXs& _data, const Eigen::MatrixXs& _data_covariance) :
-	CaptureBase("POSE", _ts, _sensor_ptr),
+	CaptureBase("CapturePose", _ts, _sensor_ptr),
 	data_(_data),
 	data_covariance_(_data_covariance)
 {
diff --git a/src/capture/capture_velocity.cpp b/src/capture/capture_velocity.cpp
index 00a6b796bbba9135ee8fbba1150ff353c29b72ec..14cb2626fa074450dc484b6c90c02aff647f909d 100644
--- a/src/capture/capture_velocity.cpp
+++ b/src/capture/capture_velocity.cpp
@@ -7,7 +7,7 @@ CaptureVelocity::CaptureVelocity(const TimeStamp& _ts,
                                  const Eigen::VectorXs& _velocity,
                                  SizeEigen _delta_size, SizeEigen _delta_cov_size,
                                  CaptureBasePtr _capture_origin_ptr) :
-  CaptureMotion("VELOCITY", _ts, _sensor_ptr, _velocity,
+  CaptureMotion("CaptureVelocity", _ts, _sensor_ptr, _velocity,
                 _delta_size, _delta_cov_size, _capture_origin_ptr)
 {
   //
@@ -22,7 +22,7 @@ CaptureVelocity::CaptureVelocity(const TimeStamp& _ts,
                                  StateBlockPtr _p_ptr,
                                  StateBlockPtr _o_ptr,
                                  StateBlockPtr _intr_ptr) :
-  CaptureMotion("VELOCITY", _ts, _sensor_ptr, _velocity, _velocity_cov,
+  CaptureMotion("CaptureVelocity", _ts, _sensor_ptr, _velocity, _velocity_cov,
                 _delta_size, _delta_cov_size, _capture_origin_ptr,
                 _p_ptr, _o_ptr, _intr_ptr)
 {
diff --git a/src/capture/capture_void.cpp b/src/capture/capture_void.cpp
index cdc8ce156ab6f7309a28cc3e5c8551dd7bea1d12..dcce03c9dc66e1dc38c62fa87dcdfdd4a25b528e 100644
--- a/src/capture/capture_void.cpp
+++ b/src/capture/capture_void.cpp
@@ -3,7 +3,7 @@
 namespace wolf {
 
 CaptureVoid::CaptureVoid(const TimeStamp& _ts, SensorBasePtr _sensor_ptr) :
-    CaptureBase("VOID", _ts, _sensor_ptr)
+    CaptureBase("CaptureVoid", _ts, _sensor_ptr)
 {
     //
 }
diff --git a/src/feature/feature_diff_drive.cpp b/src/feature/feature_diff_drive.cpp
index ecf92ab78148361f036d7df23cae237a998a98d4..452ade3585f54eaa436226838247ddbe067e69b7 100644
--- a/src/feature/feature_diff_drive.cpp
+++ b/src/feature/feature_diff_drive.cpp
@@ -7,7 +7,7 @@ FeatureDiffDrive::FeatureDiffDrive(const Eigen::VectorXs& _delta_preintegrated,
                                    const Eigen::MatrixXs& _delta_preintegrated_covariance,
                                    const Eigen::VectorXs& _diff_drive_params,
                                    const Eigen::MatrixXs& _jacobian_diff_drive_params) :
-        FeatureMotion("DIFF DRIVE",
+        FeatureMotion("FeatureDiffDrive",
                     _delta_preintegrated,
                     _delta_preintegrated_covariance,
                     _diff_drive_params,
diff --git a/src/feature/feature_odom_2D.cpp b/src/feature/feature_odom_2D.cpp
index ee6cd60ba38a16a161925d79512eaf9fa1e6212d..30bdb519152a1be4f849218fb9a88cbfd489da18 100644
--- a/src/feature/feature_odom_2D.cpp
+++ b/src/feature/feature_odom_2D.cpp
@@ -3,7 +3,7 @@
 namespace wolf {
 
 FeatureOdom2D::FeatureOdom2D(const Eigen::VectorXs& _measurement, const Eigen::MatrixXs& _meas_covariance) :
-    FeatureBase("ODOM 2D", _measurement, _meas_covariance)
+    FeatureBase("FeatureOdom2D", _measurement, _meas_covariance)
 {
     //std::cout << "New FeatureOdom2D: measurement " << _measurement.transpose() << std::endl << "covariance" << std::endl << _meas_covariance << std::endl;
 }
diff --git a/src/feature/feature_pose.cpp b/src/feature/feature_pose.cpp
index 344d230a7164d0c222567ae9ea7e1000be23cb84..7aba0e1bc02efdcad0d6f0a5115b036ea397bc80 100644
--- a/src/feature/feature_pose.cpp
+++ b/src/feature/feature_pose.cpp
@@ -3,7 +3,7 @@
 namespace wolf {
 
 FeaturePose::FeaturePose(const Eigen::VectorXs& _measurement, const Eigen::MatrixXs& _meas_covariance) :
-    FeatureBase("POSE", _measurement, _meas_covariance)
+    FeatureBase("FeaturePose", _measurement, _meas_covariance)
 {
     //
 }
diff --git a/src/landmark/landmark_base.cpp b/src/landmark/landmark_base.cpp
index 20e32da0a4e7d5d03a4475cb7ed37e54a7865311..a54bf42672a05a8eceb75f52d2ec829e22c2cc8d 100644
--- a/src/landmark/landmark_base.cpp
+++ b/src/landmark/landmark_base.cpp
@@ -221,7 +221,7 @@ LandmarkBasePtr LandmarkBase::create(const YAML::Node& _node)
             ori_sb = std::make_shared<StateAngle>(ori(0), ori_fixed);
     }
 
-    LandmarkBasePtr lmk = std::make_shared<LandmarkBase>("BASE", pos_sb, ori_sb);
+    LandmarkBasePtr lmk = std::make_shared<LandmarkBase>("LandmarkBase", pos_sb, ori_sb);
     lmk->setId(id);
 
     return lmk;
@@ -230,7 +230,7 @@ LandmarkBasePtr LandmarkBase::create(const YAML::Node& _node)
 // Register landmark creator
 namespace
 {
-const bool WOLF_UNUSED registered_lmk_base = LandmarkFactory::get().registerCreator("BASE", LandmarkBase::create);
+const bool WOLF_UNUSED registered_lmk_base = LandmarkFactory::get().registerCreator("LandmarkBase", LandmarkBase::create);
 }
 
 } // namespace wolf
diff --git a/src/problem/problem.cpp b/src/problem/problem.cpp
index d39042c0f60ef8a070541d786d1e71dc7e0a8000..2eacf6c8d8c4e2c05772a15d02b57cf94b058933 100644
--- a/src/problem/problem.cpp
+++ b/src/problem/problem.cpp
@@ -30,12 +30,6 @@
 namespace wolf
 {
 
-// unnamed namespace used for helper functions local to this file.
-namespace
-{
-std::string uppercase(std::string s) {for (auto & c: s) c = std::toupper(c); return s;}
-}
-
 Problem::Problem(const std::string& _frame_structure, SizeEigen _dim) :
         hardware_ptr_(std::make_shared<HardwareBase>()),
         trajectory_ptr_(std::make_shared<TrajectoryBase>(_frame_structure)),
@@ -181,7 +175,7 @@ SensorBasePtr Problem::installSensor(const std::string& _sen_type, //
                                      const Eigen::VectorXs& _extrinsics, //
                                      IntrinsicsBasePtr _intrinsics)
 {
-    SensorBasePtr sen_ptr = SensorFactory::get().create(uppercase(_sen_type), _unique_sensor_name, _extrinsics, _intrinsics);
+    SensorBasePtr sen_ptr = SensorFactory::get().create(_sen_type, _unique_sensor_name, _extrinsics, _intrinsics);
     sen_ptr->link(getHardware());
     return sen_ptr;
 }
@@ -207,7 +201,7 @@ SensorBasePtr Problem::installSensor(const std::string& _sen_type, //
                                      const std::string& _unique_sensor_name, //
                                      const ParamsServer& _server)
 {
-    SensorBasePtr sen_ptr = AutoConfSensorFactory::get().create(uppercase(_sen_type), _unique_sensor_name, _server);
+    SensorBasePtr sen_ptr = AutoConfSensorFactory::get().create(_sen_type, _unique_sensor_name, _server);
     sen_ptr->link(getHardware());
     return sen_ptr;
 }
@@ -224,7 +218,7 @@ ProcessorBasePtr Problem::installProcessor(const std::string& _prc_type, //
       return ProcessorBasePtr();
     }
 
-    ProcessorBasePtr prc_ptr = ProcessorFactory::get().create(uppercase(_prc_type), _unique_processor_name, _prc_params);
+    ProcessorBasePtr prc_ptr = ProcessorFactory::get().create(_prc_type, _unique_processor_name, _prc_params);
     prc_ptr->configure(_corresponding_sensor_ptr);
     prc_ptr->link(_corresponding_sensor_ptr);
 
@@ -266,7 +260,7 @@ ProcessorBasePtr Problem::installProcessor(const std::string& _prc_type, //
     if (sen_ptr == nullptr)
         throw std::runtime_error("Cannot bind processor. Reason: Sensor \"" + _corresponding_sensor_name + "\" not found. Check sensor name, it must match in sensor and processor!");
 
-    ProcessorBasePtr prc_ptr = AutoConfProcessorFactory::get().create(uppercase(_prc_type), _unique_processor_name, _server);
+    ProcessorBasePtr prc_ptr = AutoConfProcessorFactory::get().create(_prc_type, _unique_processor_name, _server);
     prc_ptr->configure(sen_ptr);
     prc_ptr->link(sen_ptr);
 
diff --git a/src/processor/processor_diff_drive.cpp b/src/processor/processor_diff_drive.cpp
index 79de4b220a5e3ea71233aed1a760936ba28f5042..da45cb6f62a7f0304061158e1f694e8232956400 100644
--- a/src/processor/processor_diff_drive.cpp
+++ b/src/processor/processor_diff_drive.cpp
@@ -21,7 +21,7 @@ ProcessorDiffDrive::ProcessorDiffDrive(const ProcessorParamsDiffDrivePtr _params
         params_prc_diff_drv_selfcal_(_params),
         radians_per_tick_(0.0) // This param needs further initialization. See this->configure(sensor).
 {
-    setType("DIFF DRIVE");  // overwrite odom2D setting
+    setType("ProcessorDiffDrive");  // overwrite odom2D setting
     calib_size_ = 3;        // overwrite odom2D setting
     unmeasured_perturbation_cov_ = Matrix1s(_params->unmeasured_perturbation_std * _params->unmeasured_perturbation_std); // overwrite odom2D setting
 }
@@ -147,7 +147,7 @@ CaptureMotionPtr ProcessorDiffDrive::emplaceCapture(const FrameBasePtr& _frame_o
 FeatureBasePtr ProcessorDiffDrive::emplaceFeature(CaptureMotionPtr _capture_motion)
 {
     auto key_feature_ptr = FeatureBase::emplace<FeatureMotion>(_capture_motion,
-                                                               "DIFF DRIVE",
+                                                               "ProcessorDiffDrive",
                                                                _capture_motion->getBuffer().get().back().delta_integr_,
                                                                _capture_motion->getBuffer().get().back().delta_integr_cov_,
                                                                _capture_motion->getCalibrationPreint(),
@@ -174,7 +174,7 @@ FactorBasePtr ProcessorDiffDrive::emplaceFactor(FeatureBasePtr _feature,
 // Register in the ProcessorFactory
 #include "core/processor/processor_factory.h"
 namespace wolf {
-WOLF_REGISTER_PROCESSOR("DIFF DRIVE", ProcessorDiffDrive);
-WOLF_REGISTER_PROCESSOR_AUTO("DIFF DRIVE", ProcessorDiffDrive);
+WOLF_REGISTER_PROCESSOR("ProcessorDiffDrive", ProcessorDiffDrive);
+WOLF_REGISTER_PROCESSOR_AUTO("ProcessorDiffDrive", ProcessorDiffDrive);
 } // namespace wolf
 
diff --git a/src/processor/processor_odom_2D.cpp b/src/processor/processor_odom_2D.cpp
index bf825c29f5f994bb09bfbe839ef56c98d37905f4..2edeaa5256310cf04c19a75aa04d14093a96b90c 100644
--- a/src/processor/processor_odom_2D.cpp
+++ b/src/processor/processor_odom_2D.cpp
@@ -3,7 +3,7 @@ namespace wolf
 {
 
 ProcessorOdom2D::ProcessorOdom2D(ProcessorParamsOdom2DPtr _params) :
-                ProcessorMotion("ODOM 2D", 3, 3, 3, 2, 0, _params),
+                ProcessorMotion("ProcessorOdom2D", 3, 3, 3, 2, 0, _params),
                 params_odom_2D_(_params)
 {
     unmeasured_perturbation_cov_ = _params->unmeasured_perturbation_std * _params->unmeasured_perturbation_std * Matrix3s::Identity();
@@ -151,7 +151,7 @@ FeatureBasePtr ProcessorOdom2D::emplaceFeature(CaptureMotionPtr _capture_motion)
     makePosDef(covariance);
 
     FeatureBasePtr key_feature_ptr = FeatureBase::emplace<FeatureBase>(_capture_motion,
-                                                                       "ODOM 2D",
+                                                                       "ProcessorOdom2D",
                                                                        _capture_motion->getBuffer().get().back().delta_integr_,
                                                                        covariance);
     return key_feature_ptr;
@@ -164,6 +164,6 @@ FeatureBasePtr ProcessorOdom2D::emplaceFeature(CaptureMotionPtr _capture_motion)
 // Register in the ProcessorFactory
 #include "core/processor/processor_factory.h"
 namespace wolf {
-WOLF_REGISTER_PROCESSOR("ODOM 2D", ProcessorOdom2D);
-WOLF_REGISTER_PROCESSOR_AUTO("ODOM 2D", ProcessorOdom2D);
+WOLF_REGISTER_PROCESSOR("ProcessorOdom2D", ProcessorOdom2D);
+WOLF_REGISTER_PROCESSOR_AUTO("ProcessorOdom2D", ProcessorOdom2D);
 } // namespace wolf
diff --git a/src/processor/processor_odom_3D.cpp b/src/processor/processor_odom_3D.cpp
index 180293e74f0c19689e7ca30919a4afb542ab8726..a840e0d733cfcd83d63311c3caaaa99393e287d7 100644
--- a/src/processor/processor_odom_3D.cpp
+++ b/src/processor/processor_odom_3D.cpp
@@ -3,7 +3,7 @@ namespace wolf
 {
 
 ProcessorOdom3D::ProcessorOdom3D(ProcessorParamsOdom3DPtr _params) :
-                        ProcessorMotion("ODOM 3D", 7, 7, 6, 6, 0, _params),
+                        ProcessorMotion("ProcessorOdom3D", 7, 7, 6, 6, 0, _params),
                         params_odom_3D_ (_params),
                         k_disp_to_disp_ (0),
                         k_disp_to_rot_  (0),
@@ -227,7 +227,7 @@ CaptureMotionPtr ProcessorOdom3D::emplaceCapture(const FrameBasePtr& _frame_own,
 FeatureBasePtr ProcessorOdom3D::emplaceFeature(CaptureMotionPtr _capture_motion)
 {
     FeatureBasePtr key_feature_ptr = FeatureBase::emplace<FeatureBase>(_capture_motion,
-                                                                       "ODOM 3D",
+                                                                       "ProcessorOdom3D",
                                                                        _capture_motion->getBuffer().get().back().delta_integr_,
                                                                        _capture_motion->getBuffer().get().back().delta_integr_cov_);
     return key_feature_ptr;
@@ -246,6 +246,6 @@ FactorBasePtr ProcessorOdom3D::emplaceFactor(FeatureBasePtr _feature_motion, Cap
 // Register in the SensorFactory
 #include "core/processor/processor_factory.h"
 namespace wolf {
-WOLF_REGISTER_PROCESSOR("ODOM 3D", ProcessorOdom3D);
-WOLF_REGISTER_PROCESSOR_AUTO("ODOM 3D", ProcessorOdom3D);
+WOLF_REGISTER_PROCESSOR("ProcessorOdom3D", ProcessorOdom3D);
+WOLF_REGISTER_PROCESSOR_AUTO("ProcessorOdom3D", ProcessorOdom3D);
 } // namespace wolf
diff --git a/src/sensor/sensor_diff_drive.cpp b/src/sensor/sensor_diff_drive.cpp
index d19ab8aa2e4d2ba5f9146bbdad2d45e5d855afc2..6e4446da2766cb670e23226fc1945d4f86af3f90 100644
--- a/src/sensor/sensor_diff_drive.cpp
+++ b/src/sensor/sensor_diff_drive.cpp
@@ -13,7 +13,7 @@ namespace wolf
 
 SensorDiffDrive::SensorDiffDrive(const Eigen::VectorXs& _extrinsics,
                                  const IntrinsicsDiffDrivePtr& _intrinsics) :
-                                                                   SensorBase("DIFF DRIVE",
+                                                                   SensorBase("SensorDiffDrive",
                                                                               std::make_shared<StateBlock>(_extrinsics.head(2), true),
                                                                               std::make_shared<StateAngle>(_extrinsics(2), true),
                                                                               std::make_shared<StateBlock>(3, false),
@@ -36,7 +36,7 @@ SensorDiffDrive::~SensorDiffDrive()
 // Register in the SensorFactory
 #include "core/sensor/sensor_factory.h"
 namespace wolf {
-WOLF_REGISTER_SENSOR("DIFF DRIVE", SensorDiffDrive);
-WOLF_REGISTER_SENSOR_AUTO("DIFF DRIVE", SensorDiffDrive);
+WOLF_REGISTER_SENSOR("SensorDiffDrive", SensorDiffDrive);
+WOLF_REGISTER_SENSOR_AUTO("SensorDiffDrive", SensorDiffDrive);
 } // namespace wolf
 
diff --git a/src/sensor/sensor_odom_2D.cpp b/src/sensor/sensor_odom_2D.cpp
index 44d69e34f81044c6706d952c2f1eeff1b9cdc533..8714478613edb4747ddab4285c4c1e16d7bba110 100644
--- a/src/sensor/sensor_odom_2D.cpp
+++ b/src/sensor/sensor_odom_2D.cpp
@@ -5,7 +5,7 @@
 namespace wolf {
 
 SensorOdom2D::SensorOdom2D(Eigen::VectorXs _extrinsics, const IntrinsicsOdom2D& _intrinsics) :
-        SensorBase("ODOM 2D", std::make_shared<StateBlock>(_extrinsics.head(2), true), std::make_shared<StateAngle>(_extrinsics(2), true), nullptr, 2),
+        SensorBase("SensorOdom2D", std::make_shared<StateBlock>(_extrinsics.head(2), true), std::make_shared<StateAngle>(_extrinsics(2), true), nullptr, 2),
         k_disp_to_disp_(_intrinsics.k_disp_to_disp),
         k_rot_to_rot_(_intrinsics.k_rot_to_rot)
 {
@@ -39,6 +39,6 @@ Scalar SensorOdom2D::getRotVarToRotNoiseFactor() const
 // Register in the SensorFactory
 #include "core/sensor/sensor_factory.h"
 namespace wolf {
-WOLF_REGISTER_SENSOR("ODOM 2D", SensorOdom2D);
-WOLF_REGISTER_SENSOR_AUTO("ODOM 2D", SensorOdom2D);
+WOLF_REGISTER_SENSOR("SensorOdom2D", SensorOdom2D);
+WOLF_REGISTER_SENSOR_AUTO("SensorOdom2D", SensorOdom2D);
 } // namespace wolf
diff --git a/src/sensor/sensor_odom_3D.cpp b/src/sensor/sensor_odom_3D.cpp
index 04de2bbd642491004a640971dba01c99032c6607..e3aba3760ee96f897e865dda5c78b32fa0867043 100644
--- a/src/sensor/sensor_odom_3D.cpp
+++ b/src/sensor/sensor_odom_3D.cpp
@@ -13,7 +13,7 @@
 namespace wolf {
 
 SensorOdom3D::SensorOdom3D(const Eigen::VectorXs& _extrinsics_pq, const IntrinsicsOdom3D& _intrinsics) :
-                        SensorBase("ODOM 3D", std::make_shared<StateBlock>(_extrinsics_pq.head(3), true), std::make_shared<StateQuaternion>(_extrinsics_pq.tail(4), true), nullptr, 6),
+                        SensorBase("SensorOdom3D", std::make_shared<StateBlock>(_extrinsics_pq.head(3), true), std::make_shared<StateQuaternion>(_extrinsics_pq.tail(4), true), nullptr, 6),
                         k_disp_to_disp_(_intrinsics.k_disp_to_disp),
                         k_disp_to_rot_(_intrinsics.k_disp_to_rot),
                         k_rot_to_rot_(_intrinsics.k_rot_to_rot),
@@ -42,6 +42,6 @@ SensorOdom3D::~SensorOdom3D()
 // Register in the SensorFactory
 #include "core/sensor/sensor_factory.h"
 namespace wolf {
-WOLF_REGISTER_SENSOR("ODOM 3D", SensorOdom3D);
-WOLF_REGISTER_SENSOR_AUTO("ODOM 3D", SensorOdom3D);
+WOLF_REGISTER_SENSOR("SensorOdom3D", SensorOdom3D);
+WOLF_REGISTER_SENSOR_AUTO("SensorOdom3D", SensorOdom3D);
 }
diff --git a/src/yaml/processor_odom_3D_yaml.cpp b/src/yaml/processor_odom_3D_yaml.cpp
index f9f939553af76223416385f11785fe2ee694e70d..99a3d6f2d9a80b34815075dff721aaafc77728e2 100644
--- a/src/yaml/processor_odom_3D_yaml.cpp
+++ b/src/yaml/processor_odom_3D_yaml.cpp
@@ -24,7 +24,7 @@ static ProcessorParamsBasePtr createProcessorOdom3DParams(const std::string & _f
 {
     YAML::Node config = YAML::LoadFile(_filename_dot_yaml);
 
-    if (config["type"].as<std::string>() == "ODOM 3D")
+    if (config["type"].as<std::string>() == "ProcessorOdom3D")
     {
         ProcessorParamsOdom3DPtr params = std::make_shared<ProcessorParamsOdom3D>();
 
@@ -48,7 +48,7 @@ static ProcessorParamsBasePtr createProcessorOdom3DParams(const std::string & _f
 }
 
 // Register in the SensorFactory
-const bool WOLF_UNUSED registered_prc_odom_3D = ProcessorParamsFactory::get().registerCreator("ODOM 3D", createProcessorOdom3DParams);
+const bool WOLF_UNUSED registered_prc_odom_3D = ProcessorParamsFactory::get().registerCreator("ProcessorOdom3D", createProcessorOdom3DParams);
 
 } // namespace [unnamed]
 
diff --git a/src/yaml/sensor_odom_2D_yaml.cpp b/src/yaml/sensor_odom_2D_yaml.cpp
index 99220af9bcb49ff574228c059cb09b8b6a8ee1a3..47bcea92a34c78ee2fd068beccdd5ecf7ac999c8 100644
--- a/src/yaml/sensor_odom_2D_yaml.cpp
+++ b/src/yaml/sensor_odom_2D_yaml.cpp
@@ -25,7 +25,7 @@ static IntrinsicsBasePtr createIntrinsicsOdom2D(const std::string & _filename_do
 {
     YAML::Node config = YAML::LoadFile(_filename_dot_yaml);
 
-    if (config["type"].as<std::string>() == "ODOM 2D")
+    if (config["type"].as<std::string>() == "SensorOdom2D")
     {
         auto params = std::make_shared<IntrinsicsOdom2D>();
 
@@ -40,7 +40,7 @@ static IntrinsicsBasePtr createIntrinsicsOdom2D(const std::string & _filename_do
 }
 
 // Register in the SensorFactory
-const bool WOLF_UNUSED registered_odom_2D_intr = IntrinsicsFactory::get().registerCreator("ODOM 2D", createIntrinsicsOdom2D);
+const bool WOLF_UNUSED registered_odom_2D_intr = IntrinsicsFactory::get().registerCreator("SensorOdom2D", createIntrinsicsOdom2D);
 
 } // namespace [unnamed]
 
diff --git a/src/yaml/sensor_odom_3D_yaml.cpp b/src/yaml/sensor_odom_3D_yaml.cpp
index 51ceb2f6344d440fec93bf3417654a9f47bf3333..3d364d9114d0f90bdbbb881abee6b410ada771a8 100644
--- a/src/yaml/sensor_odom_3D_yaml.cpp
+++ b/src/yaml/sensor_odom_3D_yaml.cpp
@@ -24,7 +24,7 @@ static IntrinsicsBasePtr createIntrinsicsOdom3D(const std::string & _filename_do
 {
     YAML::Node config = YAML::LoadFile(_filename_dot_yaml);
 
-    if (config["type"].as<std::string>() == "ODOM 3D")
+    if (config["type"].as<std::string>() == "SensorOdom3D")
     {
         IntrinsicsOdom3DPtr params = std::make_shared<IntrinsicsOdom3D>();
 
@@ -42,7 +42,7 @@ static IntrinsicsBasePtr createIntrinsicsOdom3D(const std::string & _filename_do
 }
 
 // Register in the SensorFactory
-const bool WOLF_UNUSED registered_odom_3D_intr = IntrinsicsFactory::get().registerCreator("ODOM 3D", createIntrinsicsOdom3D);
+const bool WOLF_UNUSED registered_odom_3D_intr = IntrinsicsFactory::get().registerCreator("SensorOdom3D", createIntrinsicsOdom3D);
 
 } // namespace [unnamed]
 
diff --git a/test/dummy/factor_feature_dummy.h b/test/dummy/factor_feature_dummy.h
index 83e07bb49060279665ba9002798989be5693440a..c95634eb09ffbea46dae309720c02f889458539d 100644
--- a/test/dummy/factor_feature_dummy.h
+++ b/test/dummy/factor_feature_dummy.h
@@ -52,7 +52,7 @@ class FactorFeatureDummy : public FactorBase
 inline FactorFeatureDummy::FactorFeatureDummy(const FeatureBasePtr& /*_feature_ptr*/, const FeatureBasePtr& _feature_other_ptr,
                                               const ProcessorBasePtr& _processor_ptr,
                                               bool _apply_loss_function, FactorStatus _status) :
-        FactorBase("FEATURE DUMMY", nullptr, nullptr, _feature_other_ptr, nullptr, _processor_ptr, _apply_loss_function, _status)
+        FactorBase("FactorFeatureDummy", nullptr, nullptr, _feature_other_ptr, nullptr, _processor_ptr, _apply_loss_function, _status)
 {
     //
 }
diff --git a/test/dummy/factor_landmark_dummy.h b/test/dummy/factor_landmark_dummy.h
index 95a5c483dc4dfd336880b64972f4ecad4fcb07bf..d46f6c645cd3d3bc626fc648a2107308022da96a 100644
--- a/test/dummy/factor_landmark_dummy.h
+++ b/test/dummy/factor_landmark_dummy.h
@@ -52,7 +52,7 @@ class FactorLandmarkDummy : public FactorBase
 inline FactorLandmarkDummy::FactorLandmarkDummy(const FeatureBasePtr& /*_feature_ptr*/, const LandmarkBasePtr& _landmark_other_ptr,
                                                 const ProcessorBasePtr& _processor_ptr,
                                                 bool _apply_loss_function, FactorStatus _status) :
-        FactorBase("FEATURE DUMMY", nullptr, nullptr, nullptr, _landmark_other_ptr, _processor_ptr, _apply_loss_function, _status)
+        FactorBase("FactorFeatureDummy", nullptr, nullptr, nullptr, _landmark_other_ptr, _processor_ptr, _apply_loss_function, _status)
 {
     //
 }
diff --git a/test/dummy/processor_tracker_feature_dummy.cpp b/test/dummy/processor_tracker_feature_dummy.cpp
index 05b2f34494472cfa9fde355b91d0b48a6609d25a..6a2626e76296f0616418762f3971e4c6f4c5d74a 100644
--- a/test/dummy/processor_tracker_feature_dummy.cpp
+++ b/test/dummy/processor_tracker_feature_dummy.cpp
@@ -113,5 +113,5 @@ ProcessorBasePtr ProcessorTrackerFeatureDummy::create(const std::string& _unique
 // Register in the ProcessorFactory
 #include "core/processor/processor_factory.h"
 namespace wolf {
-WOLF_REGISTER_PROCESSOR("TRACKER FEATURE DUMMY", ProcessorTrackerFeatureDummy)
+WOLF_REGISTER_PROCESSOR("ProcessorTrackerFeatureDummy", ProcessorTrackerFeatureDummy)
 } // namespace wolf
diff --git a/test/dummy/processor_tracker_feature_dummy.h b/test/dummy/processor_tracker_feature_dummy.h
index b4fdb44a79f6d5053e258379e1eadc8811cbfae7..4f5205d152ad4b0916d5c4968e754eb8da84c023 100644
--- a/test/dummy/processor_tracker_feature_dummy.h
+++ b/test/dummy/processor_tracker_feature_dummy.h
@@ -110,7 +110,7 @@ class ProcessorTrackerFeatureDummy : public ProcessorTrackerFeature
 };
 
 inline ProcessorTrackerFeatureDummy::ProcessorTrackerFeatureDummy(ProcessorParamsTrackerFeatureDummyPtr _params_tracker_feature_dummy) :
-        ProcessorTrackerFeature("TRACKER FEATURE DUMMY", _params_tracker_feature_dummy),
+        ProcessorTrackerFeature("ProcessorTrackerFeatureDummy", _params_tracker_feature_dummy),
         params_tracker_feature_dummy_(_params_tracker_feature_dummy)
 {
     //
diff --git a/test/dummy/processor_tracker_landmark_dummy.cpp b/test/dummy/processor_tracker_landmark_dummy.cpp
index 532906ac27f319486b619fd6f8e0f882d3676197..42da1408bd12e47ffcc4c10409087b38e7d3aa3c 100644
--- a/test/dummy/processor_tracker_landmark_dummy.cpp
+++ b/test/dummy/processor_tracker_landmark_dummy.cpp
@@ -13,7 +13,7 @@ namespace wolf
 {
 
 ProcessorTrackerLandmarkDummy::ProcessorTrackerLandmarkDummy(ProcessorParamsTrackerLandmarkDummyPtr _params_tracker_landmark_dummy) :
-        ProcessorTrackerLandmark("TRACKER LANDMARK DUMMY", _params_tracker_landmark_dummy),
+        ProcessorTrackerLandmark("ProcessorTrackerLandmarkDummy", _params_tracker_landmark_dummy),
         params_tracker_landmark_dummy_(_params_tracker_landmark_dummy)
 {
     //
@@ -101,7 +101,7 @@ unsigned int ProcessorTrackerLandmarkDummy::detectNewFeatures(const int& _max_fe
 LandmarkBasePtr ProcessorTrackerLandmarkDummy::emplaceLandmark(FeatureBasePtr _feature_ptr)
 {
     //std::cout << "ProcessorTrackerLandmarkDummy::emplaceLandmark" << std::endl;
-    return LandmarkBase::emplace<LandmarkBase>(getProblem()->getMap(), "BASE", std::make_shared<StateBlock>(2), std::make_shared<StateBlock>(1));
+    return LandmarkBase::emplace<LandmarkBase>(getProblem()->getMap(), "LandmarkBase", std::make_shared<StateBlock>(2), std::make_shared<StateBlock>(1));
 }
 
 FactorBasePtr ProcessorTrackerLandmarkDummy::emplaceFactor(FeatureBasePtr _feature_ptr, LandmarkBasePtr _landmark_ptr)
diff --git a/test/gtest_ceres_manager.cpp b/test/gtest_ceres_manager.cpp
index da5a01b80e98cf776957422d5bca8729b89ff038..e2047009e612990818bf877724804500464a8577 100644
--- a/test/gtest_ceres_manager.cpp
+++ b/test/gtest_ceres_manager.cpp
@@ -320,7 +320,7 @@ TEST(CeresManager, AddFactor)
     // Create (and add) factor point 2d
     FrameBasePtr        F = P->emplaceFrame(KEY, P->zeroState(), TimeStamp(0));
     auto C = CaptureBase::emplace<CaptureVoid>(F, 0, nullptr);
-    auto f = FeatureBase::emplace<FeatureBase>(C, "ODOM 2D", Vector3s::Zero(), Matrix3s::Identity());
+    auto f = FeatureBase::emplace<FeatureBase>(C, "FeatureOdom2D", Vector3s::Zero(), Matrix3s::Identity());
     FactorPose2DPtr c = FactorBase::emplace<FactorPose2D>(f,f);
 
     // update solver
@@ -342,7 +342,7 @@ TEST(CeresManager, DoubleAddFactor)
     // Create (and add) factor point 2d
     FrameBasePtr        F = P->emplaceFrame(KEY, P->zeroState(), TimeStamp(0));
     auto C = CaptureBase::emplace<CaptureVoid>(F, 0, nullptr);
-    auto f = FeatureBase::emplace<FeatureBase>(C, "ODOM 2D", Vector3s::Zero(), Matrix3s::Identity());
+    auto f = FeatureBase::emplace<FeatureBase>(C, "FeatureOdom2D", Vector3s::Zero(), Matrix3s::Identity());
     FactorPose2DPtr c = FactorBase::emplace<FactorPose2D>(f,f);
 
     // add factor again
@@ -367,7 +367,7 @@ TEST(CeresManager, RemoveFactor)
     // Create (and add) factor point 2d
     FrameBasePtr        F = P->emplaceFrame(KEY, P->zeroState(), TimeStamp(0));
     auto C = CaptureBase::emplace<CaptureVoid>(F, 0, nullptr);
-    auto f = FeatureBase::emplace<FeatureBase>(C, "ODOM 2D", Vector3s::Zero(), Matrix3s::Identity());
+    auto f = FeatureBase::emplace<FeatureBase>(C, "FeatureOdom2D", Vector3s::Zero(), Matrix3s::Identity());
     FactorPose2DPtr c = FactorBase::emplace<FactorPose2D>(f,f);
 
     // update solver
@@ -395,7 +395,7 @@ TEST(CeresManager, AddRemoveFactor)
     // Create (and add) factor point 2d
     FrameBasePtr        F = P->emplaceFrame(KEY, P->zeroState(), TimeStamp(0));
     auto C = CaptureBase::emplace<CaptureVoid>(F, 0, nullptr);
-    auto f = FeatureBase::emplace<FeatureBase>(C, "ODOM 2D", Vector3s::Zero(), Matrix3s::Identity());
+    auto f = FeatureBase::emplace<FeatureBase>(C, "FeatureOdom2D", Vector3s::Zero(), Matrix3s::Identity());
     FactorPose2DPtr c = FactorBase::emplace<FactorPose2D>(f,f);
 
     // remove factor
@@ -422,7 +422,7 @@ TEST(CeresManager, DoubleRemoveFactor)
     // Create (and add) factor point 2d
     FrameBasePtr        F = P->emplaceFrame(KEY, P->zeroState(), TimeStamp(0));
     auto C = CaptureBase::emplace<CaptureVoid>(F, 0, nullptr);
-    auto f = FeatureBase::emplace<FeatureBase>(C, "ODOM 2D", Vector3s::Zero(), Matrix3s::Identity());
+    auto f = FeatureBase::emplace<FeatureBase>(C, "FeatureOdom2D", Vector3s::Zero(), Matrix3s::Identity());
     FactorPose2DPtr c = FactorBase::emplace<FactorPose2D>(f,f);
 
     // update solver
@@ -549,7 +549,7 @@ TEST(CeresManager, FactorsRemoveLocalParam)
     // Create (and add) 2 factors quaternion
     FrameBasePtr                    F = P->emplaceFrame(KEY, P->zeroState(), TimeStamp(0));
     auto C = CaptureBase::emplace<CaptureVoid>(F, 0, nullptr);
-    auto f = FeatureBase::emplace<FeatureBase>(C, "ODOM 2D", Vector3s::Zero(), Matrix3s::Identity());
+    auto f = FeatureBase::emplace<FeatureBase>(C, "FeatureOdom2D", Vector3s::Zero(), Matrix3s::Identity());
     FactorQuaternionAbsolutePtr c1 = FactorBase::emplace<FactorQuaternionAbsolute>(f, F->getO());
     FactorQuaternionAbsolutePtr c2 = FactorBase::emplace<FactorQuaternionAbsolute>(f, F->getO());
 
@@ -591,7 +591,7 @@ TEST(CeresManager, FactorsUpdateLocalParam)
     // Create (and add) 2 factors quaternion
     FrameBasePtr                    F = P->emplaceFrame(KEY, P->zeroState(), TimeStamp(0));
     auto C = CaptureBase::emplace<CaptureVoid>(F, 0, nullptr);
-    auto f = FeatureBase::emplace<FeatureBase>(C, "ODOM 2D", Vector3s::Zero(), Matrix3s::Identity());
+    auto f = FeatureBase::emplace<FeatureBase>(C, "FeatureOdom2D", Vector3s::Zero(), Matrix3s::Identity());
     FactorQuaternionAbsolutePtr c1 = FactorBase::emplace<FactorQuaternionAbsolute>(f, F->getO());
     FactorQuaternionAbsolutePtr c2 = FactorBase::emplace<FactorQuaternionAbsolute>(f, F->getO());
 
diff --git a/test/gtest_factor_absolute.cpp b/test/gtest_factor_absolute.cpp
index 7213c1084cf13077a0413cbbea48af0676b330d8..f6705579818494debc790f7ed397c38a661bf154 100644
--- a/test/gtest_factor_absolute.cpp
+++ b/test/gtest_factor_absolute.cpp
@@ -82,7 +82,7 @@ TEST(FactorBlockAbs, fac_block_abs_p_tail2)
 
 TEST(FactorBlockAbs, fac_block_abs_v)
 {
-    auto fea0 = FeatureBase::emplace<FeatureBase>(cap0, "VELOCITY", pose10.tail<3>(), data_cov.bottomRightCorner<3,3>());
+    auto fea0 = FeatureBase::emplace<FeatureBase>(cap0, "FeatureVelocity", pose10.tail<3>(), data_cov.bottomRightCorner<3,3>());
     FactorBase::emplace<FactorBlockAbsolute>(fea0, fea0->getFrame()->getV());
 
     ASSERT_TRUE(problem_ptr->check(0));
@@ -100,7 +100,7 @@ TEST(FactorBlockAbs, fac_block_abs_v)
 
 TEST(FactorQuatAbs, fac_block_abs_o)
 {
-    auto fea0 = FeatureBase::emplace<FeatureBase>(cap0, "QUATERNION", pose10.segment<4>(3), data_cov.block<3,3>(3,3));
+    auto fea0 = FeatureBase::emplace<FeatureBase>(cap0, "FeatureQuaternion", pose10.segment<4>(3), data_cov.block<3,3>(3,3));
     FactorBase::emplace<FactorQuaternionAbsolute>(fea0, fea0->getFrame()->getO());
 
     ASSERT_TRUE(problem_ptr->check(0));
diff --git a/test/gtest_factor_diff_drive.cpp b/test/gtest_factor_diff_drive.cpp
index 6caa5f868adceb291690590455bea94520771b0f..7d3aeb5e822545d7ad20d2d76fb715813aae4eef 100644
--- a/test/gtest_factor_diff_drive.cpp
+++ b/test/gtest_factor_diff_drive.cpp
@@ -149,7 +149,7 @@ class FactorDiffDriveTest : public testing::Test
             intr->wheel_separation  = 1.0; // DO NOT MODIFY THESE VALUES !!!
             intr->ticks_per_wheel_revolution = 100; // DO NOT MODIFY THESE VALUES !!!
             Vector3s extr(0, 0, 0);
-            auto sen = problem->installSensor("DIFF DRIVE", "sensor", extr, intr);
+            auto sen = problem->installSensor("SensorDiffDrive", "sensor", extr, intr);
             sensor = std::static_pointer_cast<SensorDiffDrive>(sen);
             calib = sensor->getIntrinsic()->getState();
 
@@ -158,7 +158,7 @@ class FactorDiffDriveTest : public testing::Test
             params->angle_turned    = 1;
             params->dist_traveled   = 2;
             params->max_buff_length = 3;
-            auto prc = problem->installProcessor("DIFF DRIVE", "diff drive", sensor, params);
+            auto prc = problem->installProcessor("ProcessorDiffDrive", "diff drive", sensor, params);
             processor = std::static_pointer_cast<ProcessorDiffDrivePublic>(prc);
 
             // frames
@@ -198,7 +198,7 @@ class FactorDiffDriveTest : public testing::Test
 
             // feature
             f1 = FeatureBase::emplace<FeatureMotion>(C1,
-                                                     "DIFF DRIVE",
+                                                     "FeatureDiffDrive",
                                                      delta1,
                                                      delta1_cov,
                                                      C0->getCalibration(),
@@ -234,7 +234,7 @@ TEST_F(FactorDiffDriveTest, constructor)
 {
     // plain constructor
     auto c1_obj = FactorDiffDrive(f1, C0, processor);
-    ASSERT_EQ(c1_obj.getType(), "DIFF DRIVE");
+    ASSERT_EQ(c1_obj.getType(), "FactorDiffDrive");
 
     // std: make_shared
     c1 = std::make_shared<FactorDiffDrive>(f1,
@@ -242,7 +242,7 @@ TEST_F(FactorDiffDriveTest, constructor)
                                            processor);
 
     ASSERT_NE(c1, nullptr);
-    ASSERT_EQ(c1->getType(), "DIFF DRIVE");
+    ASSERT_EQ(c1->getType(), "FactorDiffDrive");
 
     // wolf: emplace
     c1 = FactorBase::emplace<FactorDiffDrive>(f1,
@@ -251,7 +251,7 @@ TEST_F(FactorDiffDriveTest, constructor)
                                               processor);
 
     ASSERT_NE(c1, nullptr);
-    ASSERT_EQ(c1->getType(), "DIFF DRIVE");
+    ASSERT_EQ(c1->getType(), "FactorDiffDrive");
     ASSERT_EQ(c1->getCaptureOther()->getSensorIntrinsic(), sensor->getIntrinsic());
 
 }
@@ -423,7 +423,7 @@ TEST(FactorDiffDrive, preintegrate_and_solve_sensor_intrinsics_gt)
     intr->wheel_separation  = 1.0; // DO NOT MODIFY THESE VALUES !!!
     intr->ticks_per_wheel_revolution = 100; // DO NOT MODIFY THESE VALUES !!!
     Vector3s extr(0, 0, 0);
-    auto sen    = problem->installSensor("DIFF DRIVE", "sensor", extr, intr);
+    auto sen    = problem->installSensor("SensorDiffDrive", "sensor", extr, intr);
     auto sensor = std::static_pointer_cast<SensorDiffDrive>(sen);
     auto calib_preint  = sensor->getIntrinsic()->getState();
     Vector3s calib_gt(1,1,1);
@@ -435,7 +435,7 @@ TEST(FactorDiffDrive, preintegrate_and_solve_sensor_intrinsics_gt)
     params->max_buff_length = 99;
     params->voting_active   = true;
     params->max_time_span   = 1.5;
-    auto prc = problem->installProcessor("DIFF DRIVE", "diff drive", sensor, params);
+    auto prc = problem->installProcessor("ProcessorDiffDrive", "diff drive", sensor, params);
     auto processor = std::static_pointer_cast<ProcessorDiffDrivePublic>(prc);
 
 
@@ -555,7 +555,7 @@ TEST(FactorDiffDrive, preintegrate_and_solve_sensor_intrinsics)
     intr->wheel_separation  = 1.05;
     intr->ticks_per_wheel_revolution = 100; // DO NOT MODIFY THESE VALUES !!!
     Vector3s extr(0, 0, 0);
-    auto sen    = problem->installSensor("DIFF DRIVE", "sensor", extr, intr);
+    auto sen    = problem->installSensor("SensorDiffDrive", "sensor", extr, intr);
     auto sensor = std::static_pointer_cast<SensorDiffDrive>(sen);
     auto calib_preint  = sensor->getIntrinsic()->getState();
     Vector3s calib_gt(1.0, 1.0, 1.0); // ground truth calib
@@ -567,7 +567,7 @@ TEST(FactorDiffDrive, preintegrate_and_solve_sensor_intrinsics)
     params->max_buff_length = 99;
     params->voting_active   = true;
     params->max_time_span   = 1.5;
-    auto prc = problem->installProcessor("DIFF DRIVE", "diff drive", sensor, params);
+    auto prc = problem->installProcessor("ProcessorDiffDrive", "diff drive", sensor, params);
     auto processor = std::static_pointer_cast<ProcessorDiffDrivePublic>(prc);
 
 
diff --git a/test/gtest_factor_odom_3D.cpp b/test/gtest_factor_odom_3D.cpp
index d6eb4ddf7ea7b07cdb675b96cb7af81e3adc3c8d..4ff27b9117808265ec8b79c0c78451a7cfbcbac8 100644
--- a/test/gtest_factor_odom_3D.cpp
+++ b/test/gtest_factor_odom_3D.cpp
@@ -41,8 +41,8 @@ FrameBasePtr frm0 = problem_ptr->emplaceFrame(KEY, problem_ptr->zeroState(), Tim
 FrameBasePtr frm1 = problem_ptr->emplaceFrame(KEY, delta, TimeStamp(1));
 
 // Capture, feature and factor from frm1 to frm0
-auto cap1 = CaptureBase::emplace<CaptureMotion>(frm1, "ODOM 3D", 1, nullptr, delta, 7, 6, nullptr);
-auto fea1 = FeatureBase::emplace<FeatureBase>(cap1, "ODOM 3D", delta, data_cov);
+auto cap1 = CaptureBase::emplace<CaptureMotion>(frm1, "CaptureOdom3D", 1, nullptr, delta, 7, 6, nullptr);
+auto fea1 = FeatureBase::emplace<FeatureBase>(cap1, "FeatureOdom3D", delta, data_cov);
 FactorOdom3DPtr ctr1 = FactorBase::emplace<FactorOdom3D>(fea1, fea1, frm0, nullptr); // create and add
 
 ////////////////////////////////////////////////////////
diff --git a/test/gtest_factor_pose_2D.cpp b/test/gtest_factor_pose_2D.cpp
index 3c88521c95ab2966b839cd6ab551ef6224b27390..6be39e3471ce81fb89ec05c6ad84cfe2d696bc49 100644
--- a/test/gtest_factor_pose_2D.cpp
+++ b/test/gtest_factor_pose_2D.cpp
@@ -33,10 +33,10 @@ CeresManager ceres_mgr(problem);
 FrameBasePtr frm0 = problem->emplaceFrame(KEY, problem->zeroState(), TimeStamp(0));
 
 // Capture, feature and factor from frm1 to frm0
-// CaptureBasePtr cap0 = frm0->addCapture(std::make_shared<CaptureMotion>("ODOM 2D", 0, nullptr, pose, 3, 3, nullptr));
-auto cap0 = CaptureBase::emplace<CaptureMotion>(frm0, "ODOM 2D", 0, nullptr, pose, 3, 3, nullptr);
-// FeatureBasePtr fea0 = cap0->addFeature(std::make_shared<FeatureBase>("ODOM 2D", pose, data_cov));
-auto fea0 = FeatureBase::emplace<FeatureBase>(cap0, "ODOM 2D", pose, data_cov);
+// CaptureBasePtr cap0 = frm0->addCapture(std::make_shared<CaptureMotion>("CaptureOdom2D", 0, nullptr, pose, 3, 3, nullptr));
+auto cap0 = CaptureBase::emplace<CaptureMotion>(frm0, "CaptureOdom2D", 0, nullptr, pose, 3, 3, nullptr);
+// FeatureBasePtr fea0 = cap0->addFeature(std::make_shared<FeatureBase>("FeatureOdom2D", pose, data_cov));
+auto fea0 = FeatureBase::emplace<FeatureBase>(cap0, "FeatureOdom2D", pose, data_cov);
 // FactorPose2DPtr ctr0 = std::static_pointer_cast<FactorPose2D>(fea0->addFactor(std::make_shared<FactorPose2D>(fea0)));
 FactorPose2DPtr ctr0 = FactorBase::emplace<FactorPose2D>(fea0, fea0);
 
diff --git a/test/gtest_factor_pose_3D.cpp b/test/gtest_factor_pose_3D.cpp
index 0b5032a27978d172432b7f68a04fdea28afc64ff..cfb89e5db2a6e1a8a6ca66d2afb83e287c5f4a73 100644
--- a/test/gtest_factor_pose_3D.cpp
+++ b/test/gtest_factor_pose_3D.cpp
@@ -39,8 +39,8 @@ CeresManager ceres_mgr(problem);
 FrameBasePtr frm0 = problem->emplaceFrame(KEY, problem->zeroState(), TimeStamp(0));
 
 // Capture, feature and factor
-auto cap0 = CaptureBase::emplace<CaptureMotion>(frm0, "ODOM 3D", 0, nullptr, pose7, 7, 6, nullptr);
-auto fea0 = FeatureBase::emplace<FeatureBase>(cap0, "ODOM 3D", pose7, data_cov);
+auto cap0 = CaptureBase::emplace<CaptureMotion>(frm0, "CaptureOdom3D", 0, nullptr, pose7, 7, 6, nullptr);
+auto fea0 = FeatureBase::emplace<FeatureBase>(cap0, "FeatureOdom3D", pose7, data_cov);
 FactorPose3DPtr ctr0 = FactorBase::emplace<FactorPose3D>(fea0, fea0);
 
 ////////////////////////////////////////////////////////
diff --git a/test/gtest_frame_base.cpp b/test/gtest_frame_base.cpp
index 03f991c07c4a144f560a3759c4c081cdd2410ed1..2f6da7f75f258e796e037032a33930e4079a05ab 100644
--- a/test/gtest_frame_base.cpp
+++ b/test/gtest_frame_base.cpp
@@ -71,7 +71,7 @@ TEST(FrameBase, LinksToTree)
     auto S = SensorBase::emplace<SensorOdom2D>(P->getHardware(), Vector3s::Zero(), intrinsics_odo);
     auto F1 = FrameBase::emplace<FrameBase>(T, 1, make_shared<StateBlock>(2), make_shared<StateBlock>(1));
     auto F2 = FrameBase::emplace<FrameBase>(T, 1, make_shared<StateBlock>(2), make_shared<StateBlock>(1));
-    auto C = CaptureBase::emplace<CaptureMotion>(F1, "MOTION", 1, S, Vector3s::Zero(), 3, 3, nullptr);
+    auto C = CaptureBase::emplace<CaptureMotion>(F1, "CaptureMotion", 1, S, Vector3s::Zero(), 3, 3, nullptr);
     /// @todo link sensor & proccessor
     ProcessorBasePtr p = std::make_shared<ProcessorOdom2D>(make_shared<ProcessorParamsOdom2D>());
     auto f = FeatureBase::emplace<FeatureBase>(C, "f", Vector1s(1), Matrix<Scalar,1,1>::Identity()*.01);
diff --git a/test/gtest_map_yaml.cpp b/test/gtest_map_yaml.cpp
index 60ac575e2a13591b22a8ce0c0217d049124cc9e2..3c04d1567ffb7ce9d3aeb05452fe0f175582c39d 100644
--- a/test/gtest_map_yaml.cpp
+++ b/test/gtest_map_yaml.cpp
@@ -36,9 +36,9 @@ TEST(MapYaml, save_2D)
     StateBlockPtr p3_sb = std::make_shared<StateBlock>(p3, true);
     StateBlockPtr o3_sb = std::make_shared<StateBlock>(o3, true);
 
-    LandmarkBase::emplace<LandmarkBase>(problem->getMap(), "BASE", p1_sb);
-    LandmarkBase::emplace<LandmarkBase>(problem->getMap(), "BASE", p2_sb, o2_sb);
-    LandmarkBase::emplace<LandmarkBase>(problem->getMap(), "BASE", p3_sb, o3_sb);
+    LandmarkBase::emplace<LandmarkBase>(problem->getMap(), "LandmarkBase", p1_sb);
+    LandmarkBase::emplace<LandmarkBase>(problem->getMap(), "LandmarkBase", p2_sb, o2_sb);
+    LandmarkBase::emplace<LandmarkBase>(problem->getMap(), "LandmarkBase", p3_sb, o3_sb);
 
     std::string wolf_root = _WOLF_ROOT_DIR;
     std::string map_path  = wolf_root + "/test/yaml";
@@ -159,9 +159,9 @@ TEST(MapYaml, save_3D)
     auto p3_sb = std::make_shared<StateBlock>(p3, true);
     auto q3_sb = std::make_shared<StateQuaternion>(q3, true);
 
-    LandmarkBase::emplace<LandmarkBase>(problem->getMap(), "BASE", p1_sb);
-    LandmarkBase::emplace<LandmarkBase>(problem->getMap(), "BASE", p2_sb, q2_sb);
-    LandmarkBase::emplace<LandmarkBase>(problem->getMap(), "BASE", p3_sb, q3_sb);
+    LandmarkBase::emplace<LandmarkBase>(problem->getMap(), "LandmarkBase", p1_sb);
+    LandmarkBase::emplace<LandmarkBase>(problem->getMap(), "LandmarkBase", p2_sb, q2_sb);
+    LandmarkBase::emplace<LandmarkBase>(problem->getMap(), "LandmarkBase", p3_sb, q3_sb);
 
     std::string wolf_root = _WOLF_ROOT_DIR;
     std::string map_path  = wolf_root + "/test/yaml";
diff --git a/test/gtest_odom_2D.cpp b/test/gtest_odom_2D.cpp
index b4647a0a83947463c8c5f8e9a975823c2f4f9fdb..54f39079573340c9395225b5aa1a6b67b6255c2c 100644
--- a/test/gtest_odom_2D.cpp
+++ b/test/gtest_odom_2D.cpp
@@ -133,15 +133,15 @@ TEST(Odom2D, FactorFix_and_FactorOdom2D)
     // KF1 and motion from KF0
     t += dt;
     FrameBasePtr        F1 = Pr->emplaceFrame(KEY, Vector3s::Zero(), t);
-    auto C1 = CaptureBase::emplace<CaptureBase>(F1, "ODOM 2D", t);
-    auto f1 = FeatureBase::emplace<FeatureBase>(C1, "ODOM 2D", delta, delta_cov);
+    auto C1 = CaptureBase::emplace<CaptureBase>(F1, "CaptureOdom2D", t);
+    auto f1 = FeatureBase::emplace<FeatureBase>(C1, "FeatureOdom2D", delta, delta_cov);
     auto c1 = FactorBase::emplace<FactorOdom2D>(f1, f1, F0, nullptr);
 
     // KF2 and motion from KF1
     t += dt;
     FrameBasePtr        F2 = Pr->emplaceFrame(KEY, Vector3s::Zero(), t);
-    auto C2 = CaptureBase::emplace<CaptureBase>(F2, "ODOM 2D", t);
-    auto f2 = FeatureBase::emplace<FeatureBase>(C2, "ODOM 2D", delta, delta_cov);
+    auto C2 = CaptureBase::emplace<CaptureBase>(F2, "CaptureOdom2D", t);
+    auto f2 = FeatureBase::emplace<FeatureBase>(C2, "FeatureOdom2D", delta, delta_cov);
     auto c2 = FactorBase::emplace<FactorOdom2D>(f2, f2, F1, nullptr);
 
     ASSERT_TRUE(Pr->check(0));
@@ -196,7 +196,7 @@ TEST(Odom2D, VoteForKfAndSolve)
 
     // Create Wolf tree nodes
     ProblemPtr problem = Problem::create("PO", 2);
-    SensorBasePtr sensor_odom2d = problem->installSensor("ODOM 2D", "odom", Vector3s(0,0,0), wolf_root + "/test/yaml/sensor_odom_2D.yaml");
+    SensorBasePtr sensor_odom2d = problem->installSensor("SensorOdom2D", "odom", Vector3s(0,0,0), wolf_root + "/test/yaml/sensor_odom_2D.yaml");
     ProcessorParamsOdom2DPtr params(std::make_shared<ProcessorParamsOdom2D>());
     params->voting_active   = true;
     params->dist_traveled   = 100;
@@ -205,7 +205,7 @@ TEST(Odom2D, VoteForKfAndSolve)
     params->cov_det         = 100;
     params->unmeasured_perturbation_std = 0.00;
     Matrix3s unmeasured_cov = params->unmeasured_perturbation_std*params->unmeasured_perturbation_std*Matrix3s::Identity();
-    ProcessorBasePtr prc_base = problem->installProcessor("ODOM 2D", "odom", sensor_odom2d, params);
+    ProcessorBasePtr prc_base = problem->installProcessor("ProcessorOdom2D", "odom", sensor_odom2d, params);
     ProcessorOdom2DPtr processor_odom2d = std::static_pointer_cast<ProcessorOdom2D>(prc_base);
 
 
@@ -336,7 +336,7 @@ TEST(Odom2D, KF_callback)
 
     // Create Wolf tree nodes
     ProblemPtr problem = Problem::create("PO", 2);
-    SensorBasePtr sensor_odom2d = problem->installSensor("ODOM 2D", "odom", Vector3s(0,0,0), wolf_root + "/test/yaml/sensor_odom_2D.yaml");
+    SensorBasePtr sensor_odom2d = problem->installSensor("SensorOdom2D", "odom", Vector3s(0,0,0), wolf_root + "/test/yaml/sensor_odom_2D.yaml");
     ProcessorParamsOdom2DPtr params(std::make_shared<ProcessorParamsOdom2D>());
     params->dist_traveled   = 100;
     params->angle_turned    = 6.28;
@@ -344,7 +344,7 @@ TEST(Odom2D, KF_callback)
     params->cov_det         = 100;
     params->unmeasured_perturbation_std = 0.000001;
     Matrix3s unmeasured_cov = params->unmeasured_perturbation_std*params->unmeasured_perturbation_std*Matrix3s::Identity();
-    ProcessorBasePtr prc_base = problem->installProcessor("ODOM 2D", "odom", sensor_odom2d, params);
+    ProcessorBasePtr prc_base = problem->installProcessor("ProcessorOdom2D", "odom", sensor_odom2d, params);
     ProcessorOdom2DPtr processor_odom2d = std::static_pointer_cast<ProcessorOdom2D>(prc_base);
     processor_odom2d->setTimeTolerance(dt/2);
 
diff --git a/test/gtest_param_prior.cpp b/test/gtest_param_prior.cpp
index 177961d922ebf117b0a696fd870cfe76f48b86ad..3329f1c7250c6e5cd961c8ee4dd18fee477cd2a5 100644
--- a/test/gtest_param_prior.cpp
+++ b/test/gtest_param_prior.cpp
@@ -22,7 +22,7 @@ Eigen::Vector7s initial_extrinsics((Eigen::Vector7s() << 1, 2, 3, 1, 0, 0, 0).fi
 Eigen::Vector7s prior_extrinsics((Eigen::Vector7s() << 10, 20, 30, 0, 0, 0, 1).finished());
 Eigen::Vector7s prior2_extrinsics((Eigen::Vector7s() << 100, 200, 300, 0, 0, 0, 1).finished());
 
-SensorOdom3DPtr odom_sensor_ptr_ = std::static_pointer_cast<SensorOdom3D>(problem_ptr->installSensor("ODOM 3D", "odometer", initial_extrinsics, std::make_shared<IntrinsicsOdom3D>()));
+SensorOdom3DPtr odom_sensor_ptr_ = std::static_pointer_cast<SensorOdom3D>(problem_ptr->installSensor("SensorOdom3D", "odometer", initial_extrinsics, std::make_shared<IntrinsicsOdom3D>()));
 
 TEST(ParameterPrior, initial_extrinsics)
 {
diff --git a/test/gtest_problem.cpp b/test/gtest_problem.cpp
index 53ebf672d6104ba4bfba1484a4a87f5424c143f0..93b2dac7b09e6a27ff7ff11d5133decc3e3cf59b 100644
--- a/test/gtest_problem.cpp
+++ b/test/gtest_problem.cpp
@@ -107,16 +107,16 @@ TEST(Problem, Installers)
     ProblemPtr P = Problem::create("PO", 3);
     Eigen::Vector7s xs;
 
-    SensorBasePtr    S = P->installSensor   ("ODOM 3D", "odometer",        xs,         wolf_root + "/test/yaml/sensor_odom_3D.yaml");
+    SensorBasePtr    S = P->installSensor   ("SensorOdom3D", "odometer",        xs,         wolf_root + "/test/yaml/sensor_odom_3D.yaml");
 
     // install processor tracker (dummy installation under an Odometry sensor -- it's OK for this test)
-    auto pt = P->installProcessor("TRACKER FEATURE DUMMY", "dummy", "odometer");
+    auto pt = P->installProcessor("ProcessorTrackerFeatureDummy", "dummy", "odometer");
 
     // check motion processor IS NOT set
     ASSERT_FALSE(P->getProcessorMotion());
 
     // install processor motion
-    ProcessorBasePtr pm = P->installProcessor("ODOM 3D", "odom integrator", "odometer", wolf_root + "/test/yaml/processor_odom_3D.yaml");
+    ProcessorBasePtr pm = P->installProcessor("ProcessorOdom3D", "odom integrator", "odometer", wolf_root + "/test/yaml/processor_odom_3D.yaml");
 
     // check motion processor is set
     ASSERT_TRUE(P->getProcessorMotion());
@@ -233,15 +233,15 @@ TEST(Problem, StateBlocks)
     Eigen::Vector3s xs2d;
 
     // 2 state blocks, fixed
-    SensorBasePtr    Sm = P->installSensor   ("ODOM 3D", "odometer",xs3d, wolf_root + "/test/yaml/sensor_odom_3D.yaml");
+    SensorBasePtr    Sm = P->installSensor   ("SensorOdom3D", "odometer",xs3d, wolf_root + "/test/yaml/sensor_odom_3D.yaml");
     ASSERT_EQ(P->getStateBlockNotificationMapSize(), (SizeStd) 2);
 
 //    // 2 state blocks, fixed
-//    SensorBasePtr    St = P->installSensor   ("ODOM 2D", "other odometer", xs2d, "");
+//    SensorBasePtr    St = P->installSensor   ("SensorOdom2D", "other odometer", xs2d, "");
 //    ASSERT_EQ(P->getStateBlockNotificationMapSize(), (SizeStd) (2 + 2));
 
-    auto pt = P->installProcessor("TRACKER FEATURE DUMMY",  "dummy",            "odometer");
-    auto pm = P->installProcessor("ODOM 3D",                "odom integrator",  "odometer", wolf_root + "/test/yaml/processor_odom_3D.yaml");
+    auto pt = P->installProcessor("ProcessorTrackerFeatureDummy",  "dummy",            "odometer");
+    auto pm = P->installProcessor("ProcessorOdom3D",                "odom integrator",  "odometer", wolf_root + "/test/yaml/processor_odom_3D.yaml");
 
     // 2 state blocks, estimated
     auto KF = P->emplaceFrame("PO", 3, KEY, xs3d, 0);
@@ -287,16 +287,16 @@ TEST(Problem, Covariances)
     Eigen::Vector7s xs3d;
     Eigen::Vector3s xs2d;
 
-    SensorBasePtr    Sm = P->installSensor   ("ODOM 3D", "odometer",       xs3d, wolf_root + "/test/yaml/sensor_odom_3D.yaml");
-    SensorBasePtr    St = P->installSensor   ("ODOM 2D", "other odometer", xs2d, wolf_root + "/test/yaml/sensor_odom_2D.yaml");
+    SensorBasePtr    Sm = P->installSensor   ("SensorOdom3D", "odometer",       xs3d, wolf_root + "/test/yaml/sensor_odom_3D.yaml");
+    SensorBasePtr    St = P->installSensor   ("SensorOdom2D", "other odometer", xs2d, wolf_root + "/test/yaml/sensor_odom_2D.yaml");
 
     ProcessorParamsTrackerFeaturePtr params = std::make_shared<ProcessorParamsTrackerFeature>();
     params->time_tolerance            = 0.1;
     params->max_new_features          = 5;
     params->min_features_for_keyframe = 10;
 
-    auto pt = P->installProcessor("TRACKER FEATURE DUMMY",  "dummy",            Sm, params);
-    auto pm = P->installProcessor("ODOM 3D",                "odom integrator",  "other odometer", wolf_root + "/test/yaml/processor_odom_3D.yaml");
+    auto pt = P->installProcessor("ProcessorTrackerFeatureDummy",  "dummy",            Sm, params);
+    auto pm = P->installProcessor("ProcessorOdom3D",                "odom integrator",  "other odometer", wolf_root + "/test/yaml/processor_odom_3D.yaml");
 
     // 4 state blocks, estimated
     St->unfixExtrinsics();
diff --git a/test/gtest_processor_base.cpp b/test/gtest_processor_base.cpp
index 36ad812454b7eb0f21c2997762e3a3ccc3096838..3567e4d0ee0b1be16fdc526ee1b928eb8d561597 100644
--- a/test/gtest_processor_base.cpp
+++ b/test/gtest_processor_base.cpp
@@ -53,13 +53,13 @@ TEST(ProcessorBase, KeyFrameCallback)
                                                     std::make_shared<StateBlock>(Eigen::VectorXs::Zero(2)),
                                                     std::make_shared<StateBlock>(Eigen::VectorXs::Zero(1)),
                                                     std::make_shared<StateBlock>(Eigen::VectorXs::Zero(2)), 2);
-    auto proc_trk = problem->installProcessor("TRACKER FEATURE DUMMY",  "dummy", sens_trk);
+    auto proc_trk = problem->installProcessor("ProcessorTrackerFeatureDummy",  "dummy", sens_trk);
 
     // Install odometer (sensor and processor)
-    SensorBasePtr sens_odo = problem->installSensor("ODOM 2D", "odometer", Vector3s(0,0,0), wolf_root + "/test/yaml/sensor_odom_2D.yaml");
+    SensorBasePtr sens_odo = problem->installSensor("SensorOdom2D", "odometer", Vector3s(0,0,0), wolf_root + "/test/yaml/sensor_odom_2D.yaml");
     ProcessorParamsOdom2DPtr proc_odo_params = make_shared<ProcessorParamsOdom2D>();
     proc_odo_params->time_tolerance = dt/2;
-    ProcessorBasePtr proc_odo = problem->installProcessor("ODOM 2D", "odom processor", sens_odo, proc_odo_params);
+    ProcessorBasePtr proc_odo = problem->installProcessor("ProcessorOdom2D", "odom processor", sens_odo, proc_odo_params);
 
     std::cout << "sensor & processor created and added to wolf problem" << std::endl;
 
diff --git a/test/gtest_processor_diff_drive.cpp b/test/gtest_processor_diff_drive.cpp
index 069f630631f03529da0d7d993f17dacb300f89a2..342f284751266099b05e358a2e09368e1fa08ff6 100644
--- a/test/gtest_processor_diff_drive.cpp
+++ b/test/gtest_processor_diff_drive.cpp
@@ -126,7 +126,7 @@ class ProcessorDiffDriveTest : public testing::Test
             intr->wheel_separation              = 1.0; // DO NOT MODIFY THESE VALUES !!!
             intr->ticks_per_wheel_revolution    = 100; // DO NOT MODIFY THESE VALUES !!!
             Vector3s extr(0,0,0);
-            sensor = std::static_pointer_cast<SensorDiffDrive>(problem->installSensor("DIFF DRIVE", "sensor diff drive", extr, intr));
+            sensor = std::static_pointer_cast<SensorDiffDrive>(problem->installSensor("SensorDiffDrive", "sensor diff drive", extr, intr));
 
             // params and processor
             params = std::make_shared<ProcessorParamsDiffDrive>();
@@ -136,7 +136,7 @@ class ProcessorDiffDriveTest : public testing::Test
             params->max_buff_length = 3;
             params->max_time_span   = 2.5;
             params->unmeasured_perturbation_std = 1e-4;
-            processor = std::static_pointer_cast<ProcessorDiffDrivePublic>(problem->installProcessor("DIFF DRIVE", "processor diff drive", sensor, params));
+            processor = std::static_pointer_cast<ProcessorDiffDrivePublic>(problem->installProcessor("ProcessorDiffDrive", "processor diff drive", sensor, params));
         }
 
         virtual void TearDown(){}
@@ -153,7 +153,7 @@ TEST(ProcessorDiffDrive, constructor)
 
     ASSERT_NE(prc, nullptr);
 
-    ASSERT_EQ(prc->getType(), "DIFF DRIVE");
+    ASSERT_EQ(prc->getType(), "ProcessorDiffDrive");
 }
 
 TEST(ProcessorDiffDrive, create)
@@ -173,7 +173,7 @@ TEST(ProcessorDiffDrive, create)
 
     ASSERT_NE(prc, nullptr);
 
-    ASSERT_EQ(prc->getType(), "DIFF DRIVE");
+    ASSERT_EQ(prc->getType(), "ProcessorDiffDrive");
 }
 
 TEST_F(ProcessorDiffDriveTest, params)
diff --git a/test/gtest_processor_motion.cpp b/test/gtest_processor_motion.cpp
index 0977b8f87f3ba2fab515098a2afd0942f8fb6714..15e8515290eefeede88469d339b98069daa61485 100644
--- a/test/gtest_processor_motion.cpp
+++ b/test/gtest_processor_motion.cpp
@@ -62,7 +62,7 @@ class ProcessorMotion_test : public testing::Test{
 
             dt                      = 1.0;
             problem = Problem::create("PO", 2);
-            sensor = static_pointer_cast<SensorOdom2D>(problem->installSensor("ODOM 2D", "odom", Vector3s(0,0,0), wolf_root + "/test/yaml/sensor_odom_2D.yaml"));
+            sensor = static_pointer_cast<SensorOdom2D>(problem->installSensor("SensorOdom2D", "odom", Vector3s(0,0,0), wolf_root + "/test/yaml/sensor_odom_2D.yaml"));
             ProcessorParamsOdom2DPtr params(std::make_shared<ProcessorParamsOdom2D>());
             params->time_tolerance  = 0.25;
             params->dist_traveled   = 100;
@@ -71,7 +71,7 @@ class ProcessorMotion_test : public testing::Test{
             params->cov_det         = 100;
             params->unmeasured_perturbation_std = 0.001;
             processor = ProcessorBase::emplace<ProcessorOdom2DPublic>(sensor, params);
-            capture = std::make_shared<CaptureMotion>("ODOM 2D", 0.0, sensor, data, data_cov, 3, 3, nullptr);
+            capture = std::make_shared<CaptureMotion>("CaptureOdom2D", 0.0, sensor, data, data_cov, 3, 3, nullptr);
 
             Vector3s x0; x0 << 0, 0, 0;
             Matrix3s P0; P0.setIdentity();
diff --git a/test/gtest_processor_tracker_feature_dummy.cpp b/test/gtest_processor_tracker_feature_dummy.cpp
index 31dee4670b60e286a55ea315a8a1507338b3022d..9f7b0305ed0a20ba10fdb09a617d4767f089cd46 100644
--- a/test/gtest_processor_tracker_feature_dummy.cpp
+++ b/test/gtest_processor_tracker_feature_dummy.cpp
@@ -82,7 +82,7 @@ class ProcessorTrackerFeatureDummyTest : public testing::Test
             problem = Problem::create("PO", 2);
 
             // Install camera
-            sensor = problem->installSensor("ODOM 2D", "auxiliar sensor", (Eigen::Vector3s() << 0,0,0).finished(), std::make_shared<IntrinsicsBase>());
+            sensor = problem->installSensor("SensorOdom2D", "auxiliar sensor", (Eigen::Vector3s() << 0,0,0).finished(), std::make_shared<IntrinsicsBase>());
 
             // Install processor
             params = std::make_shared<ProcessorParamsTrackerFeatureDummy>();
diff --git a/test/gtest_processor_tracker_landmark_dummy.cpp b/test/gtest_processor_tracker_landmark_dummy.cpp
index 779ac7de285105263ae1214e0e61463e311983e5..e9a2535fccb5e265727a78b5ed71fb46f1a46b37 100644
--- a/test/gtest_processor_tracker_landmark_dummy.cpp
+++ b/test/gtest_processor_tracker_landmark_dummy.cpp
@@ -100,7 +100,7 @@ class ProcessorTrackerLandmarkDummyTest : public testing::Test
             problem = Problem::create("PO", 2);
 
             // Install camera
-            sensor = problem->installSensor("ODOM 2D", "auxiliar sensor", (Eigen::Vector3s() << 0,0,0).finished(), std::make_shared<IntrinsicsBase>());
+            sensor = problem->installSensor("SensorOdom2D", "auxiliar sensor", (Eigen::Vector3s() << 0,0,0).finished(), std::make_shared<IntrinsicsBase>());
 
             // Install processor
             params = std::make_shared<ProcessorParamsTrackerLandmarkDummy>();
@@ -260,7 +260,7 @@ TEST_F(ProcessorTrackerLandmarkDummyTest, emplaceFactor)
     FeatureBasePtr ftr(std::make_shared<FeatureBase>("DUMMY FEATURE",
                                                      Eigen::Vector1s::Ones(),
                                                      Eigen::MatrixXs::Ones(1, 1)));
-    LandmarkBasePtr lmk(std::make_shared<LandmarkBase>("BASE",
+    LandmarkBasePtr lmk(std::make_shared<LandmarkBase>("LandmarkBase",
                                                        std::make_shared<StateBlock>(1),
                                                        std::make_shared<StateBlock>(1)));
 
diff --git a/test/gtest_sensor_base.cpp b/test/gtest_sensor_base.cpp
index 499629f8fc934eaa5853670dd7d24a69fdc8885c..ffbf013d678fd2c979d59c911c7e2f81cb92539e 100644
--- a/test/gtest_sensor_base.cpp
+++ b/test/gtest_sensor_base.cpp
@@ -13,7 +13,7 @@ using namespace wolf;
 
 TEST(SensorBase, setNoiseStd)
 {
-    SensorBasePtr S (std::make_shared<SensorBase>("BASE", nullptr, nullptr, nullptr, 2)); // noise size 2
+    SensorBasePtr S (std::make_shared<SensorBase>("SensorBase", nullptr, nullptr, nullptr, 2)); // noise size 2
 
     Eigen::Vector2s noise_std = Eigen::Vector2s::Ones()     * 0.1;
     Eigen::Matrix2s noise_cov = Eigen::Matrix2s::Identity() * 0.01;
diff --git a/test/gtest_solver_manager.cpp b/test/gtest_solver_manager.cpp
index 2616d61040d4f224cfd65020faec182d93e02376..77003a6360294f27a249c7a4e9492753c5d66997 100644
--- a/test/gtest_solver_manager.cpp
+++ b/test/gtest_solver_manager.cpp
@@ -517,7 +517,7 @@ TEST(SolverManager, AddFactor)
     // Create (and add) factor point 2d
     FrameBasePtr        F = P->emplaceFrame(KEY, P->zeroState(), TimeStamp(0));
     auto C = CaptureBase::emplace<CaptureVoid>(F, 0, nullptr);
-    auto f = FeatureBase::emplace<FeatureBase>(C, "ODOM 2D", Vector3s::Zero(), Matrix3s::Identity());
+    auto f = FeatureBase::emplace<FeatureBase>(C, "FeatureOdom2D", Vector3s::Zero(), Matrix3s::Identity());
     FactorPose2DPtr c = FactorBase::emplace<FactorPose2D>(f, f);
 
     // notification
@@ -544,7 +544,7 @@ TEST(SolverManager, RemoveFactor)
     // Create (and add) factor point 2d
     FrameBasePtr        F = P->emplaceFrame(KEY, P->zeroState(), TimeStamp(0));
     auto C = CaptureBase::emplace<CaptureVoid>(F, 0, nullptr);
-    auto f = FeatureBase::emplace<FeatureBase>(C, "ODOM 2D", Vector3s::Zero(), Matrix3s::Identity());
+    auto f = FeatureBase::emplace<FeatureBase>(C, "FeatureOdom2D", Vector3s::Zero(), Matrix3s::Identity());
     FactorPose2DPtr c = FactorBase::emplace<FactorPose2D>(f, f);
 
     // update solver
@@ -578,7 +578,7 @@ TEST(SolverManager, AddRemoveFactor)
     FrameBasePtr        F = P->emplaceFrame(KEY, P->zeroState(), TimeStamp(0));
 
     auto C = CaptureBase::emplace<CaptureVoid>(F, 0, nullptr);
-    auto f = FeatureBase::emplace<FeatureBase>(C, "ODOM 2D", Vector3s::Zero(), Matrix3s::Identity());
+    auto f = FeatureBase::emplace<FeatureBase>(C, "FeatureOdom2D", Vector3s::Zero(), Matrix3s::Identity());
     FactorPose2DPtr c = FactorBase::emplace<FactorPose2D>(f, f);
 
     // notification
@@ -613,7 +613,7 @@ TEST(SolverManager, DoubleRemoveFactor)
     FrameBasePtr        F = P->emplaceFrame(KEY, P->zeroState(), TimeStamp(0));
 
     auto C = CaptureBase::emplace<CaptureVoid>(F, 0, nullptr);
-    auto f = FeatureBase::emplace<FeatureBase>(C, "ODOM 2D", Vector3s::Zero(), Matrix3s::Identity());
+    auto f = FeatureBase::emplace<FeatureBase>(C, "FeatureOdom2D", Vector3s::Zero(), Matrix3s::Identity());
     FactorPose2DPtr c = FactorBase::emplace<FactorPose2D>(f, f);
 
     // update solver
diff --git a/test/gtest_track_matrix.cpp b/test/gtest_track_matrix.cpp
index 8d7cafc5f699abc2f0fa9d275f57d5b4b3677821..5bb8be67440f8cf15c8c37bf05c5b710906783c7 100644
--- a/test/gtest_track_matrix.cpp
+++ b/test/gtest_track_matrix.cpp
@@ -27,11 +27,11 @@ class TrackMatrixTest : public testing::Test
         {
             // unlinked captures
             // Some warnings will be thrown "linking with nullptr" for emplacing without providing frame pointer
-            C0 = CaptureBase::emplace<CaptureBase>(nullptr, "BASE", 0.0);
-            C1 = CaptureBase::emplace<CaptureBase>(nullptr, "BASE", 1.0);
-            C2 = CaptureBase::emplace<CaptureBase>(nullptr, "BASE", 2.0);
-            C3 = CaptureBase::emplace<CaptureBase>(nullptr, "BASE", 3.0);
-            C4 = CaptureBase::emplace<CaptureBase>(nullptr, "BASE", 4.0);
+            C0 = CaptureBase::emplace<CaptureBase>(nullptr, "CaptureBase", 0.0);
+            C1 = CaptureBase::emplace<CaptureBase>(nullptr, "CaptureBase", 1.0);
+            C2 = CaptureBase::emplace<CaptureBase>(nullptr, "CaptureBase", 2.0);
+            C3 = CaptureBase::emplace<CaptureBase>(nullptr, "CaptureBase", 3.0);
+            C4 = CaptureBase::emplace<CaptureBase>(nullptr, "CaptureBase", 4.0);
 
             // unlinked frames
             // Some warnings will be thrown "linking with nullptr" for emplacing without providing frame pointer
@@ -43,11 +43,11 @@ class TrackMatrixTest : public testing::Test
 
             // unlinked features
             // Some warnings will be thrown "linking with nullptr" for emplacing without providing capture pointer
-            f0 = FeatureBase::emplace<FeatureBase>(nullptr, "BASE", m, m_cov);
-            f1 = FeatureBase::emplace<FeatureBase>(nullptr, "BASE", m, m_cov);
-            f2 = FeatureBase::emplace<FeatureBase>(nullptr, "BASE", m, m_cov);
-            f3 = FeatureBase::emplace<FeatureBase>(nullptr, "BASE", m, m_cov);
-            f4 = FeatureBase::emplace<FeatureBase>(nullptr, "BASE", m, m_cov);
+            f0 = FeatureBase::emplace<FeatureBase>(nullptr, "FeatureBase", m, m_cov);
+            f1 = FeatureBase::emplace<FeatureBase>(nullptr, "FeatureBase", m, m_cov);
+            f2 = FeatureBase::emplace<FeatureBase>(nullptr, "FeatureBase", m, m_cov);
+            f3 = FeatureBase::emplace<FeatureBase>(nullptr, "FeatureBase", m, m_cov);
+            f4 = FeatureBase::emplace<FeatureBase>(nullptr, "FeatureBase", m, m_cov);
 
             // F0 and F4 are keyframes
             F0->setKey();
diff --git a/test/yaml/processor_odom_3D.yaml b/test/yaml/processor_odom_3D.yaml
index a43fb60198d51944566308f3f06b0b6f33cee8bf..25ef29e83065acfe37cff57babc06b25b3b5d57b 100644
--- a/test/yaml/processor_odom_3D.yaml
+++ b/test/yaml/processor_odom_3D.yaml
@@ -1,4 +1,4 @@
-type: "ODOM 3D"              # This must match the KEY used in the SensorFactory. Otherwise it is an error.
+type: "ProcessorOdom3D"              # This must match the KEY used in the SensorFactory. Otherwise it is an error.
 
 time_tolerance:         0.01  # seconds
 
diff --git a/test/yaml/sensor_odom_2D.yaml b/test/yaml/sensor_odom_2D.yaml
index 40677f3e1cb84d7eda527e942bd54880c0ac7e37..45271b18cfff1235f05d945c6e5f124ff33e064e 100644
--- a/test/yaml/sensor_odom_2D.yaml
+++ b/test/yaml/sensor_odom_2D.yaml
@@ -1,4 +1,4 @@
-type: "ODOM 2D"              # This must match the KEY used in the SensorFactory. Otherwise it is an error.
+type: "SensorOdom2D"              # This must match the KEY used in the SensorFactory. Otherwise it is an error.
 
 k_disp_to_disp:   0.02  # m^2   / m
 k_rot_to_rot:     0.01  # rad^2 / rad
diff --git a/test/yaml/sensor_odom_3D.yaml b/test/yaml/sensor_odom_3D.yaml
index c45adb8ca809770ff3320ec81637e7a7ea556758..9fb43d4c30c0f5c01757362f6122d0cba98b14c5 100644
--- a/test/yaml/sensor_odom_3D.yaml
+++ b/test/yaml/sensor_odom_3D.yaml
@@ -1,4 +1,4 @@
-type: "ODOM 3D"              # This must match the KEY used in the SensorFactory. Otherwise it is an error.
+type: "SensorOdom3D"              # This must match the KEY used in the SensorFactory. Otherwise it is an error.
 
 k_disp_to_disp:   0.02  # m^2   / m
 k_disp_to_rot:    0.02  # rad^2 / m
diff --git a/wolf_scripts/rename.sh b/wolf_scripts/rename.sh
index 59335743b1a5931fbd09a3c22cce8913b01ed0a6..f628c06bd9f773430db68330ff2f89b78d04e0cc 100755
--- a/wolf_scripts/rename.sh
+++ b/wolf_scripts/rename.sh
@@ -18,17 +18,40 @@ snake2camel ()
 # file2type $1
 # echo $type
 # exit 1
-for file in $(find include/ src/ -type f); do
-    name=$(echo $file | rev | cut -d '/' -f1 | rev | cut -d '.' -f1)
-    extension=$(echo $name | cut -d '_' -f2- )
-    # echo $extension
-    snake2camel $extension
-    camel_extension=$new_camel
-    snake2camel $name
-    camel_file=$new_camel
-    file2type $extension
-    # echo $file " %%% " $type " %%% " $camel_file
-    # echo "VVV "$type
-    sed -rn "s/\"${type}\"/\"${camel_file}\"/p" $file
-    # sed -ri "s/(WOLF_REGISTER_PROCESSOR[^\(]*\(\")([^\"]+)/\1${new_camel}/" $file
+getTypes ()
+{
+    for file in $(find include/ src/ test/ -type f); do
+        name=$(echo $file | rev | cut -d '/' -f1 | rev | cut -d '.' -f1)
+        extension=$(echo $name | cut -d '_' -f2- )
+        # echo $extension
+        snake2camel $extension
+        camel_extension=$new_camel
+        snake2camel $name
+        camel_file=$new_camel
+        file2type $extension
+        # echo $file " %%% " $type " %%% " $camel_file
+        # echo "VVV "$type
+        # sed -rn "s/(Feature|Capture|Landmark|Processor|Factor)(.*)\"${type}\"/\1\2\"${camel_file}\"/p" $file
+        # echo sed -rn "s/(Capture)(.*)\"${type}\"/\1\2\"${camel_file}\"/p" $file
+        # type="ODOM 3D"
+        matching=$(ag -l "\"${type}\"" --ignore "demos" . | wc -l)
+        if [ $matching -gt "0" ]; then
+            echo ${type}
+        fi
+        # sed -ri "s/\"${type}\"/\"${camel_file}\"/" $file
+    done
+}
+IFS=$'\n'
+types=$(getTypes | sort | uniq)
+# echo $types
+# for ctype in $types; do
+#     ctype=$(echo $ctype | sed -r "s/([^\ 0-9])([^\ 0-9]+)\ ?/\1\L\2/g")
+#     echo $ctype
+# done
+for target in $(find include/ src/ test/ -type f); do
+    for ctype in $types; do
+        oldtype=$ctype
+        ctype=$(echo $ctype | sed -r "s/([^\ 0-9])([^\ 0-9]+)\ ?/\1\L\2/g")
+        sed -ri "s/(Capture|Feature|Processor|Landmark|Factor|Sensor)(.*)\"${oldtype}\"/\1\2\"\1${ctype}\"/" $target
+    done
 done
\ No newline at end of file