diff --git a/CMakeLists.txt b/CMakeLists.txt
index 412fec35e5a0bac263c8544b779222342219238f..425ffc64aa4de3b73b5e5ab57f9d3eacdb1812f6 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -197,7 +197,7 @@ SET(HDRS_PROCESSOR
   include/core/processor/motion_provider.h
   include/core/processor/processor_base.h
   include/core/processor/processor_diff_drive.h
-  include/core/processor/processor_fix_wing_model.h
+  include/core/processor/processor_fixed_wing_model.h
   include/core/processor/factory_processor.h
   include/core/processor/processor_loop_closure.h
   include/core/processor/processor_motion.h
@@ -305,7 +305,7 @@ SET(SRCS_PROCESSOR
   src/processor/motion_provider.cpp
   src/processor/processor_base.cpp
   src/processor/processor_diff_drive.cpp
-  src/processor/processor_fix_wing_model.cpp
+  src/processor/processor_fixed_wing_model.cpp
   src/processor/processor_loop_closure.cpp
   src/processor/processor_motion.cpp
   src/processor/processor_odom_2d.cpp
diff --git a/include/core/processor/processor_fixed_wing_model.h b/include/core/processor/processor_fixed_wing_model.h
index 97c8ad6f3919c35744e824cde99d56c4d2b7e1b8..bccbc2317135376f7cf7dd1f70113fb933fc72b0 100644
--- a/include/core/processor/processor_fixed_wing_model.h
+++ b/include/core/processor/processor_fixed_wing_model.h
@@ -26,31 +26,31 @@
  *      Author: joanvallve
  */
 
-#ifndef INCLUDE_CORE_PROCESSOR_PROCESSOR_FIX_WING_MODEL_H_
-#define INCLUDE_CORE_PROCESSOR_PROCESSOR_FIX_WING_MODEL_H_
+#ifndef INCLUDE_CORE_PROCESSOR_PROCESSOR_FIXED_WING_MODEL_H_
+#define INCLUDE_CORE_PROCESSOR_PROCESSOR_FIXED_WING_MODEL_H_
 
 #include "core/processor/processor_base.h"
 
 namespace wolf
 {
 
-WOLF_STRUCT_PTR_TYPEDEFS(ParamsProcessorFixWingModel);
+WOLF_STRUCT_PTR_TYPEDEFS(ParamsProcessorFixedWingModel);
 
-struct ParamsProcessorFixWingModel : public ParamsProcessorBase
+struct ParamsProcessorFixedWingModel : public ParamsProcessorBase
 {
         Eigen::Vector3d velocity_local;
         double angle_stdev;
         double min_vel_norm;
 
-        ParamsProcessorFixWingModel() = default;
-        ParamsProcessorFixWingModel(std::string _unique_name, const wolf::ParamsServer & _server) :
+        ParamsProcessorFixedWingModel() = default;
+        ParamsProcessorFixedWingModel(std::string _unique_name, const wolf::ParamsServer & _server) :
             ParamsProcessorBase(_unique_name, _server)
         {
             velocity_local   = _server.getParam<Eigen::Vector3d> (prefix + _unique_name + "/velocity_local");
             angle_stdev      = _server.getParam<double>          (prefix + _unique_name + "/angle_stdev");
             min_vel_norm     = _server.getParam<double>          (prefix + _unique_name + "/min_vel_norm");
 
-            assert(std::abs(velocity_local.norm() - 1.0) < wolf::Constants::EPS && "ParamsProcessorFixWingModel: 'velocity_local' must be normalized");
+            assert(std::abs(velocity_local.norm() - 1.0) < wolf::Constants::EPS && "ParamsProcessorFixedWingModel: 'velocity_local' must be normalized");
         }
         std::string print() const override
         {
@@ -61,17 +61,17 @@ struct ParamsProcessorFixWingModel : public ParamsProcessorBase
         }
 };
 
-WOLF_PTR_TYPEDEFS(ProcessorFixWingModel);
+WOLF_PTR_TYPEDEFS(ProcessorFixedWingModel);
 
-class ProcessorFixWingModel : public ProcessorBase
+class ProcessorFixedWingModel : public ProcessorBase
 {
     public:
-        ProcessorFixWingModel(ParamsProcessorFixWingModelPtr _params);
+        ProcessorFixedWingModel(ParamsProcessorFixedWingModelPtr _params);
 
         // Factory method for high level API
-        WOLF_PROCESSOR_CREATE(ProcessorFixWingModel, ParamsProcessorFixWingModel);
+        WOLF_PROCESSOR_CREATE(ProcessorFixedWingModel, ParamsProcessorFixedWingModel);
 
-        virtual ~ProcessorFixWingModel() override;
+        virtual ~ProcessorFixedWingModel() override;
         void configure(SensorBasePtr _sensor) override;
 
     protected:
@@ -105,9 +105,9 @@ class ProcessorFixWingModel : public ProcessorBase
         virtual bool voteForKeyFrame() const override {return false;};
 
         // ATTRIBUTES
-        ParamsProcessorFixWingModelPtr params_processor_;
+        ParamsProcessorFixedWingModelPtr params_processor_;
 };
 
 } /* namespace wolf */
 
-#endif /* INCLUDE_CORE_PROCESSOR_PROCESSOR_FIX_WING_MODEL_H_ */
+#endif /* INCLUDE_CORE_PROCESSOR_PROCESSOR_FIXED_WING_MODEL_H_ */
diff --git a/src/processor/processor_fixed_wing_model.cpp b/src/processor/processor_fixed_wing_model.cpp
index 4c75926cc84925fa827f580a2d126ac294651d4b..a994d8a3cef2b93dcf0e5897392a1e9cf8d1533d 100644
--- a/src/processor/processor_fixed_wing_model.cpp
+++ b/src/processor/processor_fixed_wing_model.cpp
@@ -26,7 +26,7 @@
  *      Author: joanvallve
  */
 
-#include "core/processor/processor_fix_wing_model.h"
+#include "../../include/core/processor/processor_fixed_wing_model.h"
 
 #include "core/capture/capture_base.h"
 #include "core/feature/feature_base.h"
@@ -35,22 +35,22 @@
 namespace wolf
 {
 
-ProcessorFixWingModel::ProcessorFixWingModel(ParamsProcessorFixWingModelPtr _params) :
-        ProcessorBase("ProcessorFixWingModel", 3, _params),
+ProcessorFixedWingModel::ProcessorFixedWingModel(ParamsProcessorFixedWingModelPtr _params) :
+        ProcessorBase("ProcessorFixedWingModel", 3, _params),
         params_processor_(_params)
 {
 }
 
-ProcessorFixWingModel::~ProcessorFixWingModel()
+ProcessorFixedWingModel::~ProcessorFixedWingModel()
 {
 }
 
-void ProcessorFixWingModel::configure(SensorBasePtr _sensor)
+void ProcessorFixedWingModel::configure(SensorBasePtr _sensor)
 {
     assert(_sensor->getProblem()->getFrameStructure().find('V') != std::string::npos && "Processor only works with problems with V");
 }
 
-void ProcessorFixWingModel::processKeyFrame(FrameBasePtr _keyframe_ptr)
+void ProcessorFixedWingModel::processKeyFrame(FrameBasePtr _keyframe_ptr)
 {
     if (_keyframe_ptr->getV()->isFixed())
         return;
@@ -81,7 +81,7 @@ void ProcessorFixWingModel::processKeyFrame(FrameBasePtr _keyframe_ptr)
 // Register in the FactoryProcessor
 #include "core/processor/factory_processor.h"
 namespace wolf {
-WOLF_REGISTER_PROCESSOR(ProcessorFixWingModel);
-WOLF_REGISTER_PROCESSOR_AUTO(ProcessorFixWingModel);
+WOLF_REGISTER_PROCESSOR(ProcessorFixedWingModel);
+WOLF_REGISTER_PROCESSOR_AUTO(ProcessorFixedWingModel);
 } // namespace wolf
 
diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt
index b0396e22fd240af38382d5bcfcd058e691c1116b..f701d0fc720efe8a899d200dae7ef0798c2abf0b 100644
--- a/test/CMakeLists.txt
+++ b/test/CMakeLists.txt
@@ -225,11 +225,11 @@ target_link_libraries(gtest_map_yaml ${PLUGIN_NAME})
 wolf_add_gtest(gtest_param_prior gtest_param_prior.cpp)
 target_link_libraries(gtest_param_prior ${PLUGIN_NAME})
 
-# ProcessorDiffDriveSelfcalib class test
-wolf_add_gtest(gtest_processor_fix_wing_model gtest_processor_fix_wing_model.cpp)
-target_link_libraries(gtest_processor_fix_wing_model ${PLUGIN_NAME})
+# ProcessorFixedWingModel class test
+wolf_add_gtest(gtest_processor_fixed_wing_model gtest_processor_fixed_wing_model.cpp)
+target_link_libraries(gtest_processor_fixed_wing_model ${PLUGIN_NAME})
 
-# ProcessorFixWingModel class test
+# ProcessorDiffDrive class test
 wolf_add_gtest(gtest_processor_diff_drive gtest_processor_diff_drive.cpp)
 target_link_libraries(gtest_processor_diff_drive ${PLUGIN_NAME})
 
diff --git a/test/gtest_processor_fixed_wing_model.cpp b/test/gtest_processor_fixed_wing_model.cpp
index 41eaed71fd6bb47d2353bb6818349daad0aae326..b2bcb1990ccd266756c7f106478b79aadff3cc88 100644
--- a/test/gtest_processor_fixed_wing_model.cpp
+++ b/test/gtest_processor_fixed_wing_model.cpp
@@ -23,12 +23,12 @@
 #include "core/utils/utils_gtest.h"
 #include "core/problem/problem.h"
 #include "core/ceres_wrapper/solver_ceres.h"
-#include "core/processor/processor_fix_wing_model.h"
 #include "core/state_block/state_quaternion.h"
 
 // STL
 #include <iterator>
 #include <iostream>
+#include "../include/core/processor/processor_fixed_wing_model.h"
 
 using namespace wolf;
 using namespace Eigen;
@@ -58,11 +58,11 @@ class ProcessorFixWingModelTest : public testing::Test
                                                      2);
 
             // Emplace processor
-            ParamsProcessorFixWingModelPtr params = std::make_shared<ParamsProcessorFixWingModel>();
+            ParamsProcessorFixedWingModelPtr params = std::make_shared<ParamsProcessorFixedWingModel>();
             params->velocity_local = (Vector3d() << 1, 0, 0).finished();
             params->angle_stdev = 0.1;
             params->min_vel_norm = 0;
-            processor = ProcessorBase::emplace<ProcessorFixWingModel>(sensor, params);
+            processor = ProcessorBase::emplace<ProcessorFixedWingModel>(sensor, params);
         }
 
         FrameBasePtr emplaceFrame(TimeStamp ts, const Vector10d& x)