diff --git a/include/gnss/processor/processor_gnss_fix.h b/include/gnss/processor/processor_gnss_fix.h
index 4bd3dfe2eb36aa62ab097a9fc092db62f76b3131..ccefe606128c8fe51fe534cd3f7e9c128345f4a3 100644
--- a/include/gnss/processor/processor_gnss_fix.h
+++ b/include/gnss/processor/processor_gnss_fix.h
@@ -47,7 +47,7 @@ class ProcessorGnssFix : public ProcessorBase
         FrameBasePtr last_KF_;
 
     public:
-        ProcessorGnssFix(ProcessorParamsGnssFixPtr _params, SensorGnssPtr _sensor_gnss_ptr);
+        ProcessorGnssFix(ProcessorParamsGnssFixPtr _params);
         virtual ~ProcessorGnssFix();
         virtual void configure(SensorBasePtr _sensor) override;
 
@@ -96,7 +96,7 @@ class ProcessorGnssFix : public ProcessorBase
         bool rejectOutlier(FactorBasePtr ctr_ptr);
 
     public:
-        static ProcessorBasePtr create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, const SensorBasePtr sensor_ptr);
+        static ProcessorBasePtr create(const std::string& _unique_name, const ProcessorParamsBasePtr _params);
 
 };
 
diff --git a/include/gnss/processor/processor_gnss_single_diff.h b/include/gnss/processor/processor_gnss_single_diff.h
index b425b162d642e89328b5d2f58bb2f6f3d97e7af7..7265baca4084db602e8ea3a228b11dde973a0f4c 100644
--- a/include/gnss/processor/processor_gnss_single_diff.h
+++ b/include/gnss/processor/processor_gnss_single_diff.h
@@ -47,7 +47,7 @@ class ProcessorGnssSingleDiff : public ProcessorBase
         FrameBasePtr last_KF_;
 
     public:
-        ProcessorGnssSingleDiff(ProcessorParamsGnssSingleDiffPtr _params_gnss, SensorGnssPtr _sensor_gnss);
+        ProcessorGnssSingleDiff(ProcessorParamsGnssSingleDiffPtr _params_gnss);
         virtual ~ProcessorGnssSingleDiff();
         virtual void configure(SensorBasePtr _sensor) override;
         FrameBasePtr getLastKF();
@@ -97,7 +97,7 @@ class ProcessorGnssSingleDiff : public ProcessorBase
         FactorBasePtr emplaceFactor(FeatureBasePtr _ftr);
 
     public:
-        static ProcessorBasePtr create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, const SensorBasePtr sensor);
+        static ProcessorBasePtr create(const std::string& _unique_name, const ProcessorParamsBasePtr _params);
 
 };
 
diff --git a/src/processor/processor_gnss_fix.cpp b/src/processor/processor_gnss_fix.cpp
index f11be23a5373ee138d7ebff11a54d802258ae91b..2eee30479497af96c2a2bea1b9e00f78724f4619 100644
--- a/src/processor/processor_gnss_fix.cpp
+++ b/src/processor/processor_gnss_fix.cpp
@@ -7,9 +7,8 @@
 namespace wolf
 {
 
-ProcessorGnssFix::ProcessorGnssFix(ProcessorParamsGnssFixPtr _params_gnss, SensorGnssPtr _sensor_gnss) :
+ProcessorGnssFix::ProcessorGnssFix(ProcessorParamsGnssFixPtr _params_gnss) :
         ProcessorBase("GNSS FIX", _params_gnss),
-        sensor_gnss_(_sensor_gnss),
 
         params_gnss_(_params_gnss),
         first_capture_(nullptr)
@@ -169,10 +168,9 @@ void ProcessorGnssFix::configure(SensorBasePtr _sensor)
     sensor_gnss_ = std::static_pointer_cast<SensorGnss>(_sensor);
 };
 
-ProcessorBasePtr ProcessorGnssFix::create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, const SensorBasePtr sensor)
+ProcessorBasePtr ProcessorGnssFix::create(const std::string& _unique_name, const ProcessorParamsBasePtr _params)
 {
-    auto prc = std::make_shared<ProcessorGnssFix>(std::static_pointer_cast<ProcessorParamsGnssFix>(_params),
-                                                      std::static_pointer_cast<SensorGnss>(sensor));
+    auto prc = std::make_shared<ProcessorGnssFix>(std::static_pointer_cast<ProcessorParamsGnssFix>(_params));
     prc->setName(_unique_name);
     return prc;
 }
diff --git a/src/processor/processor_gnss_single_diff.cpp b/src/processor/processor_gnss_single_diff.cpp
index 3bc0a79c7b93175b8a56cbef27861f1204d61cca..7afcfd29d1b267bab7ca7609e18f5ef9ffc63cdd 100644
--- a/src/processor/processor_gnss_single_diff.cpp
+++ b/src/processor/processor_gnss_single_diff.cpp
@@ -6,9 +6,8 @@
 namespace wolf
 {
 
-ProcessorGnssSingleDiff::ProcessorGnssSingleDiff(ProcessorParamsGnssSingleDiffPtr _params_gnss, SensorGnssPtr _sensor_gnss) :
+ProcessorGnssSingleDiff::ProcessorGnssSingleDiff(ProcessorParamsGnssSingleDiffPtr _params_gnss) :
         ProcessorBase("GNSS SINGLE DIFFERENCES", _params_gnss),
-        sensor_gnss_(_sensor_gnss),
         params_gnss_(_params_gnss)
 {
     //
@@ -142,9 +141,9 @@ void ProcessorGnssSingleDiff::configure(SensorBasePtr _sensor)
     sensor_gnss_ = std::static_pointer_cast<SensorGnss>(_sensor);
 };
 
-ProcessorBasePtr ProcessorGnssSingleDiff::create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, const SensorBasePtr sensor)
+ProcessorBasePtr ProcessorGnssSingleDiff::create(const std::string& _unique_name, const ProcessorParamsBasePtr _params)
 {
-    ProcessorGnssSingleDiffPtr prc = std::make_shared<ProcessorGnssSingleDiff>(std::static_pointer_cast<ProcessorParamsGnssSingleDiff>(_params), std::static_pointer_cast<SensorGnss>(sensor));
+    ProcessorGnssSingleDiffPtr prc = std::make_shared<ProcessorGnssSingleDiff>(std::static_pointer_cast<ProcessorParamsGnssSingleDiff>(_params));
     prc->setName(_unique_name);
     return prc;
 }